From 22cb249309020bc4115f2a69be8a9a8d2c7fb605 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 7 Jun 2022 16:49:19 -0600 Subject: [PATCH 01/43] initial pass on removing boost --- .../collision_detection/collision_common.h | 6 +- .../collision_detection/collision_matrix.h | 2 +- .../collision_detection/occupancy_map.h | 10 +-- .../moveit/collision_detection/world.h | 2 +- moveit_core/collision_detection/src/world.cpp | 6 +- .../collision_env_distance_field.h | 4 +- .../src/collision_common_distance_field.cpp | 6 +- .../src/collision_env_distance_field.cpp | 2 +- .../moveit/kinematics_base/kinematics_base.h | 2 +- .../src/kinematics_metrics.cpp | 4 +- .../src/planning_interface.cpp | 8 +-- .../planning_request_adapter.h | 2 +- .../moveit/planning_scene/planning_scene.h | 6 +- .../moveit/robot_model/joint_model_group.h | 2 +- .../moveit/robot_state/attached_body.h | 2 +- .../include/moveit/robot_state/robot_state.h | 2 +- moveit_core/robot_state/src/attached_body.cpp | 4 +- .../kinematics_cache/kinematics_cache.h | 4 +- .../kinematics_cache/kinematics_cache.h | 4 +- .../planning_context_loader_circ.h | 4 +- .../planning_context_loader_lin.h | 4 +- .../planning_context_loader_ptp.h | 4 +- .../src/unittest_trajectory_functions.cpp | 2 +- .../moveit/benchmarks/BenchmarkExecutor.h | 12 ++-- .../moveit/pick_place/manipulation_pipeline.h | 14 ++-- .../include/moveit/pick_place/pick_place.h | 2 +- .../pick_place/src/manipulation_pipeline.cpp | 18 ++--- .../pick_place/src/pick_place.cpp | 6 +- .../src/planning_scene_monitor.cpp | 68 +++++++++---------- .../src/trajectory_monitor.cpp | 4 +- .../trajectory_execution_manager.h | 20 +++--- .../src/trajectory_execution_manager.cpp | 28 ++++---- .../src/move_group_interface.cpp | 4 +- .../src/interaction_handler.cpp | 46 ++++++------- .../src/kinematic_options_map.cpp | 12 ++-- .../src/locked_robot_state.cpp | 6 +- .../src/robot_interaction.cpp | 28 ++++---- .../test/locked_robot_state_test.cpp | 12 ++-- .../motion_planning_display.h | 2 +- .../src/motion_planning_display.cpp | 2 +- .../background_processing.hpp | 10 +-- .../planning_scene_display.h | 14 ++-- .../src/background_processing.cpp | 14 ++-- .../src/planning_scene_display.cpp | 18 ++--- .../trajectory_visualization.h | 2 +- .../src/trajectory_visualization.cpp | 4 +- .../src/tools/compute_default_collisions.cpp | 12 ++-- .../src/widgets/default_collisions_widget.cpp | 4 +- .../src/widgets/default_collisions_widget.h | 6 +- .../src/widgets/setup_assistant_widget.cpp | 2 +- .../src/widgets/setup_assistant_widget.h | 2 +- 51 files changed, 233 insertions(+), 231 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 21fd15459c..42d606d28b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -110,10 +110,10 @@ struct Contact struct CostSource { /// The minimum bound of the AABB defining the volume responsible for this partial cost - boost::array aabb_min; + std::array aabb_min; /// The maximum bound of the AABB defining the volume responsible for this partial cost - boost::array aabb_max; + std::array aabb_max; /// The partial cost (the probability of existence for the object there is a collision with) double cost; @@ -220,7 +220,7 @@ struct CollisionRequest std::size_t max_cost_sources; /** \brief Function call that decides whether collision detection should stop. */ - boost::function is_done; + std::function is_done; /** \brief Flag indicating whether information about detected collisions should be reported */ bool verbose; diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index aed91aa469..18ea04470c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -68,7 +68,7 @@ enum Type /** \brief Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type is * CONDITIONAL) */ -using DecideContactFn = boost::function; +using DecideContactFn = std::function; MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix); // Defines AllowedCollisionMatrixPtr, ConstPtr, WeakPtr... etc diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 6612bc5e10..6837e3f6cc 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -86,8 +86,8 @@ class OccMapTree : public octomap::OcTree tree_mutex_.unlock(); } - using ReadLock = boost::shared_lock; - using WriteLock = boost::unique_lock; + using ReadLock = std::shared_lock; + using WriteLock = std::unique_lock; ReadLock reading() { @@ -106,14 +106,14 @@ class OccMapTree : public octomap::OcTree } /** @brief Set the callback to trigger when updates are received */ - void setUpdateCallback(const boost::function& update_callback) + void setUpdateCallback(const std::function& update_callback) { update_callback_ = update_callback; } private: - boost::shared_mutex tree_mutex_; - boost::function update_callback_; + std::shared_mutex tree_mutex_; + std::function update_callback_; }; using OccMapTreePtr = std::shared_ptr; diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 992bb9a1db..1ae91bd64e 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -298,7 +298,7 @@ class World friend class World; }; - using ObserverCallbackFn = boost::function; + using ObserverCallbackFn = std::function; /** \brief register a callback function for notification of changes. * \e callback will be called right after any change occurs to any Object. diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 4525f91250..527c21ac99 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -139,7 +139,8 @@ bool World::knowsTransform(const std::string& name) const for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - if (boost::starts_with(name, object.first) && name[object.first.length()] == '/') + // name.rfind is in service of removing the call to boost::starts_with and does the same thing + if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { return object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)) != object.second->global_subframe_poses_.end(); @@ -173,7 +174,8 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - if (boost::starts_with(name, object.first) && name[object.first.length()] == '/') + // name.rfind is in service of removing the call to boost::starts_with and does the same thing + if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { auto it = object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)); if (it != object.second->global_subframe_poses_.end()) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 386eddea61..9aea8d645c 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -296,14 +296,14 @@ class CollisionEnvDistanceField : public CollisionEnv std::vector link_body_decomposition_vector_; std::map link_body_decomposition_index_map_; - mutable boost::mutex update_cache_lock_; + mutable std::mutex update_cache_lock_; DistanceFieldCacheEntryPtr distance_field_cache_entry_; std::map> in_group_update_map_; std::map pregenerated_group_state_representation_map_; planning_scene::PlanningScenePtr planning_scene_; - mutable boost::mutex update_cache_lock_world_; + mutable std::mutex update_cache_lock_world_; DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_; GroupStateRepresentationPtr last_gsr_; World::ObserverHandle observer_handle_; diff --git a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp index 655b5ae7fb..bc5c9b187e 100644 --- a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp @@ -59,7 +59,7 @@ struct BodyDecompositionCache static const unsigned int MAX_CLEAN_COUNT = 100; Map map_; unsigned int clean_count_; - boost::mutex lock_; + std::mutex lock_; }; BodyDecompositionCache& getBodyDecompositionCache() @@ -74,7 +74,7 @@ BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeCons BodyDecompositionCache& cache = getBodyDecompositionCache(); shapes::ShapeConstWeakPtr wptr(shape); { - boost::mutex::scoped_lock slock(cache.lock_); + std::scoped_lock slock(cache.lock_); BodyDecompositionCache::Map::const_iterator cache_it = cache.map_.find(wptr); if (cache_it != cache.map_.end()) { @@ -84,7 +84,7 @@ BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeCons BodyDecompositionConstPtr bdcp = std::make_shared(shape, resolution); { - boost::mutex::scoped_lock slock(cache.lock_); + std::scoped_lock slock(cache.lock_); cache.map_[wptr] = bdcp; cache.clean_count_++; return bdcp; diff --git a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index 13e5af29ba..a706cad2d9 100644 --- a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -166,7 +166,7 @@ void CollisionEnvDistanceField::generateCollisionCheckingStructures( // DistanceFieldCacheEntry for CollisionRobot"); DistanceFieldCacheEntryPtr new_dfce = generateDistanceFieldCacheEntry(group_name, state, acm, generate_distance_field); - boost::mutex::scoped_lock slock(update_cache_lock_); + std::scoped_lock slock(update_cache_lock_); (const_cast(this))->distance_field_cache_entry_ = new_dfce; dfce = new_dfce; } diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 1820513897..953e7bdb1a 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -150,7 +150,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase static const double DEFAULT_TIMEOUT; /* = 1.0 */ /** @brief Signature for a callback to validate an IK solution. Typically used for collision checking. */ - using IKCallbackFn = boost::function&, + using IKCallbackFn = std::function&, moveit_msgs::msg::MoveItErrorCodes&)>; /** diff --git a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp index 571059f0dc..ae3f708914 100644 --- a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp +++ b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp @@ -47,7 +47,7 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematics_metri double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& state, const moveit::core::JointModelGroup* joint_model_group) const { - if (fabs(penalty_multiplier_) <= boost::math::tools::epsilon()) + if (fabs(penalty_multiplier_) <= std::numeric_limits::min()) return 1.0; double joint_limits_multiplier(1.0); const std::vector& joint_model_vector = joint_model_group->getJointModels(); @@ -87,7 +87,7 @@ double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& double lower_bound_distance = joint_model->distance(joint_values, &lower_bounds[0]); double upper_bound_distance = joint_model->distance(joint_values, &upper_bounds[0]); double range = lower_bound_distance + upper_bound_distance; - if (range <= boost::math::tools::epsilon()) + if (range <= std::numeric_limits::min()) continue; joint_limits_multiplier *= (lower_bound_distance * upper_bound_distance / (range * range)); } diff --git a/moveit_core/planning_interface/src/planning_interface.cpp b/moveit_core/planning_interface/src/planning_interface.cpp index d8db528412..05183f1332 100644 --- a/moveit_core/planning_interface/src/planning_interface.cpp +++ b/moveit_core/planning_interface/src/planning_interface.cpp @@ -47,7 +47,7 @@ namespace // keep track of currently active contexts struct ActiveContexts { - boost::mutex mutex_; + std::mutex mutex_; std::set contexts_; }; @@ -61,14 +61,14 @@ static ActiveContexts& getActiveContexts() PlanningContext::PlanningContext(const std::string& name, const std::string& group) : name_(name), group_(group) { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); ac.contexts_.insert(this); } PlanningContext::~PlanningContext() { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); ac.contexts_.erase(this); } @@ -124,7 +124,7 @@ void PlannerManager::setPlannerConfigurations(const PlannerConfigurationMap& pcs void PlannerManager::terminate() const { ActiveContexts& ac = getActiveContexts(); - boost::mutex::scoped_lock _(ac.mutex_); + std::scoped_lock _(ac.mutex_); for (PlanningContext* context : ac.contexts_) context->terminate(); } diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index a11f2c67fe..0eb9500309 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -50,7 +50,7 @@ class PlanningRequestAdapter { public: using PlannerFn = - boost::function; PlanningRequestAdapter() diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 089f3788d6..09f9129f6e 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -68,7 +68,7 @@ MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, Wea respecting constraints and collision avoidance). The first argument is the state to check the feasibility for, the second one is whether the check should be verbose or not. */ -typedef boost::function StateFeasibilityFn; +typedef std::function StateFeasibilityFn; /** \brief This is the function signature for additional feasibility checks to be imposed on motions segments between states (in addition to respecting constraints and collision avoidance). @@ -76,7 +76,7 @@ typedef boost::function StateFeasib first state and end at the second state. The third argument indicates whether the check should be verbose or not. */ using MotionFeasibilityFn = - boost::function; + std::function; /** \brief A map from object names (e.g., attached bodies, collision objects) to their colors */ using ObjectColorMap = std::map; @@ -87,7 +87,7 @@ using ObjectTypeMap = std::map { public: diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 49bfbf1b1a..34dca32763 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -52,7 +52,7 @@ class RobotModel; class JointModelGroup; /** \brief Function type that allocates a kinematics solver for a particular group */ -typedef boost::function SolverAllocatorFn; +typedef std::function SolverAllocatorFn; /** \brief Map from group instances to allocator functions & bijections */ using SolverAllocatorMapFn = std::map; diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index d1ca3090d4..e5495078cd 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -49,7 +49,7 @@ namespace moveit namespace core { class AttachedBody; -typedef boost::function AttachedBodyCallback; +typedef std::function AttachedBodyCallback; /** @brief Object defining bodies that can be attached to robot links. * diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index d7bf0175b3..1fdb7d8d29 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -65,7 +65,7 @@ MOVEIT_CLASS_FORWARD(RobotState); // Defines RobotStatePtr, ConstPtr, WeakPtr.. joint_group_variable_values the state is valid or not. Returns true if the state is valid. This call is allowed to modify \e robot_state (e.g., set \e joint_group_variable_values) */ -typedef boost::function GroupStateValidityCallbackFn; diff --git a/moveit_core/robot_state/src/attached_body.cpp b/moveit_core/robot_state/src/attached_body.cpp index 027bfcd7be..829776fee1 100644 --- a/moveit_core/robot_state/src/attached_body.cpp +++ b/moveit_core/robot_state/src/attached_body.cpp @@ -135,7 +135,7 @@ void AttachedBody::setPadding(double padding) const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& frame_name, bool* found) const { - if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/') + if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/') { auto it = subframe_poses_.find(frame_name.substr(id_.length() + 1)); if (it != subframe_poses_.end()) @@ -153,7 +153,7 @@ const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& f const Eigen::Isometry3d& AttachedBody::getGlobalSubframeTransform(const std::string& frame_name, bool* found) const { - if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/') + if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/') { auto it = global_subframe_poses_.find(frame_name.substr(id_.length() + 1)); if (it != global_subframe_poses_.end()) diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h index 7ac5784d81..26d0461380 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h @@ -51,8 +51,8 @@ class KinematicsCache struct Options { geometry_msgs::Point origin; - boost::array workspace_size; - boost::array resolution; + std::array workspace_size; + std::array resolution; unsigned int max_solutions_per_grid_location; }; diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h index f210a0e9dc..c4778bdc4a 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h @@ -51,8 +51,8 @@ class KinematicsCache struct Options { geometry_msgs::Point origin; - boost::array workspace_size; - boost::array resolution; + std::array workspace_size; + std::array resolution; unsigned int max_solutions_per_grid_location; }; diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h index b1760aac2c..c1126b83c3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_circ.h @@ -62,7 +62,7 @@ class PlanningContextLoaderCIRC : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderCIRCPtr; -typedef boost::shared_ptr PlanningContextLoaderCIRCConstPtr; +typedef std::shared_ptr PlanningContextLoaderCIRCPtr; +typedef std::shared_ptr PlanningContextLoaderCIRCConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h index f3215fd869..14a6e74053 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_lin.h @@ -62,7 +62,7 @@ class PlanningContextLoaderLIN : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderLINPtr; -typedef boost::shared_ptr PlanningContextLoaderLINConstPtr; +typedef std::shared_ptr PlanningContextLoaderLINPtr; +typedef std::shared_ptr PlanningContextLoaderLINConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h index 52ec4f6af7..1262e62200 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_loader_ptp.h @@ -62,7 +62,7 @@ class PlanningContextLoaderPTP : public PlanningContextLoader const std::string& group) const override; }; -typedef boost::shared_ptr PlanningContextLoaderPTPPtr; -typedef boost::shared_ptr PlanningContextLoaderPTPConstPtr; +typedef std::shared_ptr PlanningContextLoaderPTPPtr; +typedef std::shared_ptr PlanningContextLoaderPTPConstPtr; } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index 220ca3832e..ae4e26395a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -151,7 +151,7 @@ class TrajectoryFunctionsTestBase : public testing::Test std::map zero_state_; // random seed - boost::uint32_t random_seed_{ 100 }; + uint32_t random_seed_{ 100 }; random_numbers::RandomNumberGenerator rng_{ random_seed_ }; }; diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 0da389c0c1..a6526f1e5f 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -67,28 +67,28 @@ class BenchmarkExecutor typedef std::vector PlannerBenchmarkData; /// Definition of a query-start benchmark event function. Invoked before a new query is benchmarked. - typedef boost::function + typedef std::function QueryStartEventFunction; /// Definition of a query-end benchmark event function. Invoked after a query has finished benchmarking. - typedef boost::function + typedef std::function QueryCompletionEventFunction; /// Definition of a planner-switch benchmark event function. Invoked before a planner starts any runs for a particular /// query. - typedef boost::function + typedef std::function PlannerStartEventFunction; /// Definition of a planner-switch benchmark event function. Invoked after a planner completes all runs for a /// particular query. - typedef boost::function + typedef std::function PlannerCompletionEventFunction; /// Definition of a pre-run benchmark event function. Invoked immediately before each planner calls solve(). - typedef boost::function PreRunEventFunction; + typedef std::function PreRunEventFunction; /// Definition of a post-run benchmark event function. Invoked immediately after each planner calls solve(). - typedef boost::function PostRunEventFunction; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index 942e8aca59..a647e2e219 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -56,12 +56,12 @@ class ManipulationPipeline return name_; } - void setSolutionCallback(const boost::function& callback) + void setSolutionCallback(const std::function& callback) { solution_callback_ = callback; } - void setEmptyQueueCallback(const boost::function& callback) + void setEmptyQueueCallback(const std::function& callback) { empty_queue_callback_ = callback; } @@ -104,13 +104,13 @@ class ManipulationPipeline std::vector success_; std::vector failed_; - std::vector processing_threads_; + std::vector processing_threads_; boost::condition_variable queue_access_cond_; - boost::mutex queue_access_lock_; - boost::mutex result_lock_; + std::mutex queue_access_lock_; + std::mutex result_lock_; - boost::function solution_callback_; - boost::function empty_queue_callback_; + std::function solution_callback_; + std::function empty_queue_callback_; unsigned int empty_queue_threads_; bool stop_processing_; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index 5783539627..f0e6bc3b55 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -88,7 +88,7 @@ class PickPlacePlanBase bool done_; bool pushed_all_poses_; boost::condition_variable done_condition_; - boost::mutex done_mutex_; + std::mutex done_mutex_; moveit_msgs::msg::MoveItErrorCodes error_code_; }; diff --git a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp index 21c2413953..39e9c896e8 100644 --- a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp +++ b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp @@ -96,11 +96,11 @@ void ManipulationPipeline::clear() { stop(); { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::mutex::scoped_lock slock(queue_access_lock_); queue_.clear(); } { - boost::mutex::scoped_lock slock(result_lock_); + std::mutex::scoped_lock slock(result_lock_); success_.clear(); failed_.clear(); } @@ -114,7 +114,7 @@ void ManipulationPipeline::start() stage->resetStopSignal(); for (std::size_t i = 0; i < processing_threads_.size(); ++i) if (!processing_threads_[i]) - processing_threads_[i] = new boost::thread([this, i] { processingThread(i); }); + processing_threads_[i] = new std::thread([this, i] { processingThread(i); }); } void ManipulationPipeline::signalStop() @@ -128,7 +128,7 @@ void ManipulationPipeline::signalStop() void ManipulationPipeline::stop() { signalStop(); - for (boost::thread*& processing_thread : processing_threads_) + for (std::thread*& processing_thread : processing_threads_) if (processing_thread) { processing_thread->join(); @@ -144,7 +144,7 @@ void ManipulationPipeline::processingThread(unsigned int index) while (!stop_processing_) { bool inc_queue = false; - boost::unique_lock ulock(queue_access_lock_); + std::unique_lock ulock(queue_access_lock_); // if the queue is empty, we trigger the corresponding event if (queue_.empty() && !stop_processing_ && empty_queue_callback_) { @@ -175,7 +175,7 @@ void ManipulationPipeline::processingThread(unsigned int index) g->processing_stage_ = i + 1; if (!res) { - boost::mutex::scoped_lock slock(result_lock_); + std::scoped_lock slock(result_lock_); failed_.push_back(g); ROS_INFO_STREAM_NAMED("manipulation", "Manipulation plan " << g->id_ << " failed at stage '" << stages_[i]->getName() << "' on thread " @@ -187,7 +187,7 @@ void ManipulationPipeline::processingThread(unsigned int index) { g->processing_stage_++; { - boost::mutex::scoped_lock slock(result_lock_); + std::scoped_lock slock(result_lock_); success_.push_back(g); } signalStop(); @@ -207,7 +207,7 @@ void ManipulationPipeline::processingThread(unsigned int index) void ManipulationPipeline::push(const ManipulationPlanPtr& plan) { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::scoped_lock slock(queue_access_lock_); queue_.push_back(plan); ROS_INFO_STREAM_NAMED("manipulation", "Added plan for pipeline '" << name_ << "'. Queue is now of size " << queue_.size()); @@ -216,7 +216,7 @@ void ManipulationPipeline::push(const ManipulationPlanPtr& plan) void ManipulationPipeline::reprocessLastFailure() { - boost::mutex::scoped_lock slock(queue_access_lock_); + std::scoped_lock slock(queue_access_lock_); if (failed_.empty()) return; ManipulationPlanPtr plan = failed_.back(); diff --git a/moveit_ros/manipulation/pick_place/src/pick_place.cpp b/moveit_ros/manipulation/pick_place/src/pick_place.cpp index 55698048d8..a633749f63 100644 --- a/moveit_ros/manipulation/pick_place/src/pick_place.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick_place.cpp @@ -59,14 +59,14 @@ PickPlacePlanBase::~PickPlacePlanBase() = default; void PickPlacePlanBase::foundSolution() { - boost::mutex::scoped_lock slock(done_mutex_); + std::scoped_lock slock(done_mutex_); done_ = true; done_condition_.notify_all(); } void PickPlacePlanBase::emptyQueue() { - boost::mutex::scoped_lock slock(done_mutex_); + std::scoped_lock slock(done_mutex_); if (pushed_all_poses_) { done_ = true; @@ -83,7 +83,7 @@ void PickPlacePlanBase::initialize() void PickPlacePlanBase::waitForPipeline(const ros::WallTime& endtime) { // wait till we're done - boost::unique_lock lock(done_mutex_); + std::unique_lock lock(done_mutex_); pushed_all_poses_ = true; while (!done_ && endtime > ros::WallTime::now()) done_condition_.timed_wait(lock, (endtime - ros::WallTime::now()).toBoost()); diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 54e8464755..d7181f8e72 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -322,7 +322,7 @@ void PlanningSceneMonitor::monitorDiffs(bool flag) { if (flag) { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); if (scene_) { scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback()); @@ -348,7 +348,7 @@ void PlanningSceneMonitor::monitorDiffs(bool flag) stopPublishingPlanningScene(); } { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); if (scene_) { scene_->decoupleParent(); @@ -369,7 +369,7 @@ void PlanningSceneMonitor::stopPublishingPlanningScene() { if (publish_planning_scene_) { - std::unique_ptr copy; + std::unique_ptr copy; copy.swap(publish_planning_scene_); new_scene_update_condition_.notify_all(); copy->join(); @@ -388,7 +388,7 @@ void PlanningSceneMonitor::startPublishingPlanningScene(SceneUpdateType update_t planning_scene_publisher_ = pnode_->create_publisher(planning_scene_topic, 100); RCLCPP_INFO(LOGGER, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str()); monitorDiffs(true); - publish_planning_scene_ = std::make_unique([this] { scenePublishingThread(); }); + publish_planning_scene_ = std::make_unique([this] { scenePublishingThread(); }); } } @@ -416,7 +416,7 @@ void PlanningSceneMonitor::scenePublishingThread() bool is_full = false; rclcpp::Rate rate(publish_planning_scene_frequency_); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); while (new_scene_update_ == UPDATE_NONE && publish_planning_scene_) new_scene_update_condition_.wait(ulock); if (new_scene_update_ != UPDATE_NONE) @@ -437,7 +437,7 @@ void PlanningSceneMonitor::scenePublishingThread() msg.robot_state.is_diff = true; } } - boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the + std::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the // transform cache to // update while we are // potentially changing @@ -527,9 +527,9 @@ bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConst void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type) { // do not modify update functions while we are calling them - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::recursive_mutex::scoped_lock lock(update_lock_); - for (boost::function& update_callback : update_callbacks_) + for (std::function& update_callback : update_callbacks_) update_callback(update_type); new_scene_update_ = (SceneUpdateType)(static_cast(new_scene_update_) | static_cast(update_type)); new_scene_update_condition_.notify_all(); @@ -599,7 +599,7 @@ void PlanningSceneMonitor::getPlanningSceneServiceCallback(moveit_msgs::srv::Get moveit_msgs::msg::PlanningSceneComponents all_components; all_components.components = UINT_MAX; // Return all scene components if nothing is specified. - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); scene_->getPlanningSceneMsg(res->scene, req->components.components ? req->components : all_components); } @@ -635,7 +635,7 @@ void PlanningSceneMonitor::clearOctomap() { bool removed = false; { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS); if (octomap_monitor_) @@ -664,9 +664,9 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann SceneUpdateType upd = UPDATE_SCENE; std::string old_scene_name; { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); // we don't want the transform cache to update while we are potentially changing attached bodies - boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); + std::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); last_update_time_ = rclcpp::Clock().now(); last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp; @@ -742,7 +742,7 @@ void PlanningSceneMonitor::newPlanningSceneWorldCallback(moveit_msgs::msg::Plann { updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); scene_->getWorldNonConst()->clearObjects(); scene_->processPlanningSceneWorldMsg(*world); @@ -767,7 +767,7 @@ void PlanningSceneMonitor::collisionObjectCallback(moveit_msgs::msg::CollisionOb updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); if (!scene_->processCollisionObjectMsg(*obj)) return; @@ -781,7 +781,7 @@ void PlanningSceneMonitor::attachObjectCallback(moveit_msgs::msg::AttachedCollis { updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); scene_->processAttachedCollisionObjectMsg(*obj); } @@ -794,7 +794,7 @@ void PlanningSceneMonitor::excludeRobotLinksFromOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); includeRobotLinksInOctree(); const std::vector& links = getRobotModel()->getLinkModelsWithCollisionGeometry(); @@ -831,7 +831,7 @@ void PlanningSceneMonitor::includeRobotLinksInOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); for (std::pair>>& link_shape_handle : @@ -846,7 +846,7 @@ void PlanningSceneMonitor::includeAttachedBodiesInOctree() if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); // clear information about any attached body, without referring to the AttachedBody* ptr (could be invalid) for (std::pair>>& @@ -887,7 +887,7 @@ void PlanningSceneMonitor::includeWorldObjectsInOctree() void PlanningSceneMonitor::excludeWorldObjectsFromOctree() { - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); includeWorldObjectsInOctree(); for (const std::pair& it : *scene_->getWorld()) @@ -899,7 +899,7 @@ void PlanningSceneMonitor::excludeAttachedBodyFromOctree(const moveit::core::Att if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i) { @@ -921,7 +921,7 @@ void PlanningSceneMonitor::includeAttachedBodyInOctree(const moveit::core::Attac if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body); if (it != attached_body_shape_handles_.end()) @@ -938,7 +938,7 @@ void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detectio if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < obj->shapes_.size(); ++i) @@ -961,7 +961,7 @@ void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection: if (!octomap_monitor_) return; - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_); if (it != collision_body_shape_handles_.end()) @@ -1040,13 +1040,13 @@ bool PlanningSceneMonitor::waitForCurrentRobotState(const rclcpp::Time& t, doubl // As publishing planning scene updates is throttled (2Hz by default), a 1s timeout is a suitable default. auto start = node_->get_clock()->now(); auto timeout = rclcpp::Duration::from_seconds(wait_time); - boost::shared_lock lock(scene_update_mutex_); + std::shared_lock lock(scene_update_mutex_); rclcpp::Time prev_robot_motion_time = last_robot_motion_time_; while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene. timeout > rclcpp::Duration(0, 0)) { RCLCPP_DEBUG(LOGGER, "last robot motion: %f ago", (t - last_robot_motion_time_).seconds()); - new_scene_update_condition_.wait_for(lock, boost::chrono::nanoseconds(timeout.nanoseconds())); + new_scene_update_condition_.wait_for(lock, std::chrono::nanoseconds(timeout.nanoseconds())); timeout = timeout - (node_->get_clock()->now() - start); // compute remaining wait_time } bool success = last_robot_motion_time_ >= t; @@ -1116,7 +1116,7 @@ bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_fram { try { - boost::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::recursive_mutex::scoped_lock _(shape_handles_lock_); for (const std::pair>>& link_shape_handle : @@ -1350,7 +1350,7 @@ void PlanningSceneMonitor::octomapUpdateCallback() updateFrameTransforms(); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = rclcpp::Clock().now(); octomap_monitor_->getOcTreePtr()->lockRead(); try @@ -1412,7 +1412,7 @@ void PlanningSceneMonitor::updateSceneWithCurrentState() } { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); last_update_time_ = last_robot_motion_time_ = current_state_monitor_->getCurrentStateTime(); RCLCPP_DEBUG(LOGGER, "robot state update %f", fmod(last_robot_motion_time_.seconds(), 10.)); current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst()); @@ -1425,16 +1425,16 @@ void PlanningSceneMonitor::updateSceneWithCurrentState() "State monitor is not active. Unable to set the planning scene state"); } -void PlanningSceneMonitor::addUpdateCallback(const boost::function& fn) +void PlanningSceneMonitor::addUpdateCallback(const std::function& fn) { - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::recursive_mutex::scoped_lock lock(update_lock_); if (fn) update_callbacks_.push_back(fn); } void PlanningSceneMonitor::clearUpdateCallbacks() { - boost::recursive_mutex::scoped_lock lock(update_lock_); + std::recursive_mutex::scoped_lock lock(update_lock_); update_callbacks_.clear(); } @@ -1480,7 +1480,7 @@ void PlanningSceneMonitor::updateFrameTransforms() std::vector transforms; getUpdatedFrameTransforms(transforms); { - boost::unique_lock ulock(scene_update_mutex_); + std::unique_lock ulock(scene_update_mutex_); scene_->getTransformsNonConst().setTransforms(transforms); last_update_time_ = rclcpp::Clock().now(); } diff --git a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp index 883e621c33..334c7b7374 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp @@ -86,7 +86,7 @@ void planning_scene_monitor::TrajectoryMonitor::startTrajectoryMonitor() { if (sampling_frequency_ > std::numeric_limits::epsilon() && !record_states_thread_) { - record_states_thread_ = std::make_unique([this] { recordStates(); }); + record_states_thread_ = std::make_unique([this] { recordStates(); }); RCLCPP_DEBUG(LOGGER, "Started trajectory monitor"); } } @@ -95,7 +95,7 @@ void planning_scene_monitor::TrajectoryMonitor::stopTrajectoryMonitor() { if (record_states_thread_) { - std::unique_ptr copy; + std::unique_ptr copy; copy.swap(record_states_thread_); copy->join(); RCLCPP_DEBUG(LOGGER, "Stopped trajectory monitor"); diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index fa783b52e5..54405b8ad2 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -66,11 +66,11 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager /// Definition of the function signature that is called when the execution of all the pushed trajectories completes. /// The status of the overall execution is passed as argument - typedef boost::function ExecutionCompleteCallback; + typedef std::function ExecutionCompleteCallback; /// Definition of the function signature that is called when the execution of a pushed trajectory completes /// successfully. - using PathSegmentCompleteCallback = boost::function; + using PathSegmentCompleteCallback = std::function; /// Data structure that represents information necessary to execute a trajectory struct TrajectoryExecutionContext @@ -324,25 +324,25 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager bool manage_controllers_; // thread used to execute trajectories using the execute() command - std::unique_ptr execution_thread_; + std::unique_ptr execution_thread_; // thread used to execute trajectories using pushAndExecute() - std::unique_ptr continuous_execution_thread_; + std::unique_ptr continuous_execution_thread_; - boost::mutex execution_state_mutex_; - boost::mutex continuous_execution_mutex_; - boost::mutex execution_thread_mutex_; + std::mutex execution_state_mutex_; + std::mutex continuous_execution_mutex_; + std::mutex execution_thread_mutex_; - boost::condition_variable continuous_execution_condition_; + std::condition_variable continuous_execution_condition_; // this condition is used to notify the completion of execution for given trajectories - boost::condition_variable execution_complete_condition_; + std::condition_variable execution_complete_condition_; moveit_controller_manager::ExecutionStatus last_execution_status_; std::vector active_handles_; int current_context_; std::vector time_index_; // used to find current expected trajectory location - mutable boost::mutex time_index_mutex_; + mutable std::mutex time_index_mutex_; bool execution_complete_; bool stop_continuous_execution_; diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 28a5070980..74e5bc431a 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -396,10 +396,10 @@ bool TrajectoryExecutionManager::pushAndExecute(const moveit_msgs::msg::RobotTra if (configure(*context, trajectory, controllers)) { { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); continuous_execution_queue_.push_back(context); if (!continuous_execution_thread_) - continuous_execution_thread_ = std::make_unique([this] { continuousExecutionThread(); }); + continuous_execution_thread_ = std::make_unique([this] { continuousExecutionThread(); }); } last_execution_status_ = moveit_controller_manager::ExecutionStatus::SUCCEEDED; continuous_execution_condition_.notify_all(); @@ -420,7 +420,7 @@ void TrajectoryExecutionManager::continuousExecutionThread() { if (!stop_continuous_execution_) { - boost::unique_lock ulock(continuous_execution_mutex_); + std::unique_lock ulock(continuous_execution_mutex_); while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_) continuous_execution_condition_.wait(ulock); } @@ -445,7 +445,7 @@ void TrajectoryExecutionManager::continuousExecutionThread() { TrajectoryExecutionContext* context = nullptr; { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); if (continuous_execution_queue_.empty()) break; context = continuous_execution_queue_.front(); @@ -1233,7 +1233,7 @@ void TrajectoryExecutionManager::stopExecution(bool auto_clear) RCLCPP_INFO(LOGGER, "Stopped trajectory execution."); // wait for the execution thread to finish - boost::mutex::scoped_lock lock(execution_thread_mutex_); + std::scoped_lock lock(execution_thread_mutex_); if (execution_thread_) { execution_thread_->join(); @@ -1249,7 +1249,7 @@ void TrajectoryExecutionManager::stopExecution(bool auto_clear) else if (execution_thread_) // just in case we have some thread waiting to be joined from some point in the past, we // join it now { - boost::mutex::scoped_lock lock(execution_thread_mutex_); + std::scoped_lock lock(execution_thread_mutex_); if (execution_thread_) { execution_thread_->join(); @@ -1281,19 +1281,19 @@ void TrajectoryExecutionManager::execute(const ExecutionCompleteCallback& callba // start the execution thread execution_complete_ = false; - execution_thread_ = std::make_unique(&TrajectoryExecutionManager::executeThread, this, callback, + execution_thread_ = std::make_unique(&TrajectoryExecutionManager::executeThread, this, callback, part_callback, auto_clear); } moveit_controller_manager::ExecutionStatus TrajectoryExecutionManager::waitForExecution() { { - boost::unique_lock ulock(execution_state_mutex_); + std::unique_lock ulock(execution_state_mutex_); while (!execution_complete_) execution_complete_condition_.wait(ulock); } { - boost::unique_lock ulock(continuous_execution_mutex_); + std::unique_lock ulock(continuous_execution_mutex_); while (!continuous_execution_queue_.empty()) continuous_execution_condition_.wait(ulock); } @@ -1312,7 +1312,7 @@ void TrajectoryExecutionManager::clear() delete trajectory; trajectories_.clear(); { - boost::mutex::scoped_lock slock(continuous_execution_mutex_); + std::scoped_lock slock(continuous_execution_mutex_); while (!continuous_execution_queue_.empty()) { delete continuous_execution_queue_.front(); @@ -1389,7 +1389,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) std::vector handles; { - boost::mutex::scoped_lock slock(execution_state_mutex_); + std::scoped_lock slock(execution_state_mutex_); if (!execution_complete_) { // time indexing uses this member too, so we lock this mutex as well @@ -1509,7 +1509,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) // construct a map from expected time to state index, for easy access to expected state location if (longest_part >= 0) { - boost::mutex::scoped_lock slock(time_index_mutex_); + std::scoped_lock slock(time_index_mutex_); if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >= context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()) @@ -1546,7 +1546,7 @@ bool TrajectoryExecutionManager::executePart(std::size_t part_index) "bound for the trajectory execution was %lf seconds). Stopping trajectory.", expected_trajectory_duration.seconds()); { - boost::mutex::scoped_lock slock(execution_state_mutex_); + std::scoped_lock slock(execution_state_mutex_); stopExecutionInternal(); // this is really tricky. we can't call stopExecution() here, so we call the // internal function only } @@ -1656,7 +1656,7 @@ bool TrajectoryExecutionManager::waitForRobotToStop(const TrajectoryExecutionCon std::pair TrajectoryExecutionManager::getCurrentExpectedTrajectoryIndex() const { - boost::mutex::scoped_lock slock(time_index_mutex_); + std::scoped_lock slock(time_index_mutex_); if (current_context_ < 0) return std::make_pair(-1, -1); if (time_index_.empty()) diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index 60521fe26d..f8b17dc597 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -1297,7 +1297,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl if (constraints_init_thread_) constraints_init_thread_->join(); constraints_init_thread_ = - std::make_unique([this, host, port] { initializeConstraintsStorageThread(host, port); }); + std::make_unique([this, host, port] { initializeConstraintsStorageThread(host, port); }); } void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz) @@ -1392,7 +1392,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl rclcpp::Client::SharedPtr cartesian_path_service_; // rclcpp::Client::SharedPtr plan_grasps_service_; std::unique_ptr constraints_storage_; - std::unique_ptr constraints_init_thread_; + std::unique_ptr constraints_init_thread_; bool initializing_constraints_; }; diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index 14f7770ef6..a492bcd04b 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -98,37 +98,37 @@ std::string InteractionHandler::fixName(std::string name) void InteractionHandler::setPoseOffset(const EndEffectorInteraction& eef, const geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_[eef.eef_group] = m; } void InteractionHandler::setPoseOffset(const JointInteraction& vj, const geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_[vj.joint_name] = m; } void InteractionHandler::clearPoseOffset(const EndEffectorInteraction& eef) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.erase(eef.eef_group); } void InteractionHandler::clearPoseOffset(const JointInteraction& vj) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.erase(vj.joint_name); } void InteractionHandler::clearPoseOffsets() { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); offset_map_.clear(); } bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); std::map::iterator it = offset_map_.find(eef.eef_group); if (it != offset_map_.end()) { @@ -140,7 +140,7 @@ bool InteractionHandler::getPoseOffset(const EndEffectorInteraction& eef, geomet bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs::msg::Pose& m) { - boost::mutex::scoped_lock slock(offset_map_lock_); + std::scoped_lock slock(offset_map_lock_); std::map::iterator it = offset_map_.find(vj.joint_name); if (it != offset_map_.end()) { @@ -153,7 +153,7 @@ bool InteractionHandler::getPoseOffset(const JointInteraction& vj, geometry_msgs bool InteractionHandler::getLastEndEffectorMarkerPose(const EndEffectorInteraction& eef, geometry_msgs::msg::PoseStamped& ps) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); std::map::iterator it = pose_map_.find(eef.eef_group); if (it != pose_map_.end()) { @@ -165,7 +165,7 @@ bool InteractionHandler::getLastEndEffectorMarkerPose(const EndEffectorInteracti bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geometry_msgs::msg::PoseStamped& ps) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); std::map::iterator it = pose_map_.find(vj.joint_name); if (it != pose_map_.end()) { @@ -177,37 +177,37 @@ bool InteractionHandler::getLastJointMarkerPose(const JointInteraction& vj, geom void InteractionHandler::clearLastEndEffectorMarkerPose(const EndEffectorInteraction& eef) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.erase(eef.eef_group); } void InteractionHandler::clearLastJointMarkerPose(const JointInteraction& vj) { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.erase(vj.joint_name); } void InteractionHandler::clearLastMarkerPoses() { - boost::mutex::scoped_lock slock(pose_map_lock_); + std::scoped_lock slock(pose_map_lock_); pose_map_.clear(); } void InteractionHandler::setMenuHandler(const std::shared_ptr& mh) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); menu_handler_ = mh; } const std::shared_ptr& InteractionHandler::getMenuHandler() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return menu_handler_; } void InteractionHandler::clearMenuHandler() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); menu_handler_.reset(); } @@ -357,7 +357,7 @@ bool InteractionHandler::inError(const JointInteraction& /*unused*/) const void InteractionHandler::clearError() { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); error_state_.clear(); } @@ -380,7 +380,7 @@ bool InteractionHandler::setErrorState(const std::string& name, bool new_error_s bool InteractionHandler::getErrorState(const std::string& name) const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return error_state_.find(name) != error_state_.end(); } @@ -422,37 +422,37 @@ bool InteractionHandler::transformFeedbackPose( void InteractionHandler::setUpdateCallback(const InteractionHandlerCallbackFn& callback) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); update_callback_ = callback; } const InteractionHandlerCallbackFn& InteractionHandler::getUpdateCallback() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return update_callback_; } void InteractionHandler::setMeshesVisible(bool visible) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); display_meshes_ = visible; } bool InteractionHandler::getMeshesVisible() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return display_meshes_; } void InteractionHandler::setControlsVisible(bool visible) { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); display_controls_ = visible; } bool InteractionHandler::getControlsVisible() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return display_controls_; } } // namespace robot_interaction diff --git a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp index 4360b5daf0..30c0d23879 100644 --- a/moveit_ros/robot_interaction/src/kinematic_options_map.cpp +++ b/moveit_ros/robot_interaction/src/kinematic_options_map.cpp @@ -48,7 +48,7 @@ robot_interaction::KinematicOptionsMap::KinematicOptionsMap() // worry about locking. robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getOptions(const std::string& key) const { - boost::mutex::scoped_lock lock(lock_); + std::scoped_lock lock(lock_); if (&key == &DEFAULT) return defaults_; @@ -62,7 +62,7 @@ robot_interaction::KinematicOptions robot_interaction::KinematicOptionsMap::getO void robot_interaction::KinematicOptionsMap::setOptions(const std::string& key, const KinematicOptions& options_delta, KinematicOptions::OptionBitmask fields) { - boost::mutex::scoped_lock lock(lock_); + std::scoped_lock lock(lock_); if (&key == &ALL) { @@ -113,12 +113,12 @@ void robot_interaction::KinematicOptionsMap::merge(const KinematicOptionsMap& ot // need to lock in consistent order to avoid deadlock. // Lock the one with lower address first. - boost::mutex* m1 = &lock_; - boost::mutex* m2 = &other.lock_; + std::mutex* m1 = &lock_; + std::mutex* m2 = &other.lock_; if (m2 < m1) std::swap(m1, m2); - boost::mutex::scoped_lock lock1(*m1); - boost::mutex::scoped_lock lock2(*m2); + std::scoped_lock lock1(*m1); + std::scoped_lock lock2(*m2); defaults_ = other.defaults_; for (const std::pair& option : other.options_) diff --git a/moveit_ros/robot_interaction/src/locked_robot_state.cpp b/moveit_ros/robot_interaction/src/locked_robot_state.cpp index 262711e45c..4ed8b27d24 100644 --- a/moveit_ros/robot_interaction/src/locked_robot_state.cpp +++ b/moveit_ros/robot_interaction/src/locked_robot_state.cpp @@ -55,14 +55,14 @@ robot_interaction::LockedRobotState::~LockedRobotState() = default; moveit::core::RobotStateConstPtr robot_interaction::LockedRobotState::getState() const { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); return state_; } void robot_interaction::LockedRobotState::setState(const moveit::core::RobotState& state) { { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); // If someone else has a reference to the state, then make a new copy. // The old state is orphaned (does not change, but is now out of date). @@ -79,7 +79,7 @@ void robot_interaction::LockedRobotState::setState(const moveit::core::RobotStat void robot_interaction::LockedRobotState::modifyState(const ModifyStateFunction& modify) { { - boost::mutex::scoped_lock lock(state_lock_); + std::scoped_lock lock(state_lock_); // If someone else has a reference to the state, then make a copy. // The old state is orphaned (does not change, but is now out of date). diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 4dad5c835d..0caebce02b 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -81,7 +81,7 @@ RobotInteraction::RobotInteraction(const moveit::core::RobotModelConstPtr& robot // spin a thread that will process feedback events run_processing_thread_ = true; - processing_thread_ = std::make_unique([this] { processingThread(); }); + processing_thread_ = std::make_unique([this] { processingThread(); }); } RobotInteraction::~RobotInteraction() @@ -114,7 +114,7 @@ void RobotInteraction::addActiveComponent(const InteractiveMarkerConstructorFn& const ProcessFeedbackFn& process, const InteractiveMarkerUpdateFn& update, const std::string& name) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); GenericInteraction g; g.construct_marker = construct; g.update_pose = update; @@ -194,7 +194,7 @@ double RobotInteraction::computeGroupMarkerSize(const std::string& group) void RobotInteraction::decideActiveJoints(const std::string& group) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_vj_.clear(); if (group.empty()) @@ -270,7 +270,7 @@ void RobotInteraction::decideActiveEndEffectors(const std::string& group) void RobotInteraction::decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_eef_.clear(); if (group.empty()) @@ -353,7 +353,7 @@ void RobotInteraction::decideActiveEndEffectors(const std::string& group, Intera void RobotInteraction::clear() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); active_eef_.clear(); active_vj_.clear(); active_generic_.clear(); @@ -363,7 +363,7 @@ void RobotInteraction::clear() void RobotInteraction::clearInteractiveMarkers() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); clearInteractiveMarkersUnsafe(); } @@ -459,7 +459,7 @@ void RobotInteraction::addInteractiveMarkers(const InteractionHandlerPtr& handle // If scale is left at default size of 0, scale will be based on end effector link size. a good value is between 0-1 std::vector ims; { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); moveit::core::RobotStateConstPtr s = handler->getState(); for (std::size_t i = 0; i < active_generic_.size(); ++i) @@ -570,7 +570,7 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable) { if (enable) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); if (int_marker_move_subscribers_.empty()) { for (size_t i = 0; i < int_marker_move_topics_.size(); ++i) @@ -589,7 +589,7 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable) } else { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); int_marker_move_subscribers_.clear(); } } @@ -628,7 +628,7 @@ void RobotInteraction::updateInteractiveMarkers(const InteractionHandlerPtr& han std::string root_link; std::map pose_updates; { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); moveit::core::RobotStateConstPtr s = handler->getState(); root_link = s->getRobotModel()->getModelFrame(); @@ -671,7 +671,7 @@ void RobotInteraction::publishInteractiveMarkers() bool RobotInteraction::showingMarkers(const InteractionHandlerPtr& handler) { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); for (const EndEffectorInteraction& eef : active_eef_) if (shown_markers_.find(getMarkerName(handler, eef)) == shown_markers_.end()) @@ -697,7 +697,7 @@ void RobotInteraction::moveInteractiveMarker(const std::string& name, const geom feedback->event_type = visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE; processInteractiveMarkerFeedback(feedback); { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); int_marker_server_->setPose(name, msg.pose, msg.header); // move the interactive marker int_marker_server_->applyChanges(); } @@ -708,7 +708,7 @@ void RobotInteraction::processInteractiveMarkerFeedback( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback) { // perform some validity checks - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); std::map::const_iterator it = shown_markers_.find(feedback->marker_name); if (it == shown_markers_.end()) { @@ -730,7 +730,7 @@ void RobotInteraction::processInteractiveMarkerFeedback( void RobotInteraction::processingThread() { - boost::unique_lock ulock(marker_access_lock_); + std::unique_lock ulock(marker_access_lock_); while (run_processing_thread_ && rclcpp::ok()) { diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index b68d611cc4..1f467d5437 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -325,7 +325,7 @@ class MyInfo void checkState(robot_interaction::LockedRobotState& locked_state); // mutex protects quit_ and counter variables - boost::mutex cnt_lock_; + std::mutex cnt_lock_; // set to true by waitThreadFunc() when all counters have reached at least // max. @@ -484,7 +484,7 @@ static void runThreads(int ncheck, int nset, int nmod) int num = ncheck + nset + nmod; typedef int* int_ptr; - typedef boost::thread* thread_ptr; + typedef std::thread* thread_ptr; int* cnt = new int[num]; int_ptr* counters = new int_ptr[num + 1]; thread_ptr* threads = new thread_ptr[num]; @@ -497,7 +497,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]); + threads[p] = new std::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]); val += 0.1; p++; } @@ -507,7 +507,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val); + threads[p] = new std::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val); val += 0.1; p++; } @@ -517,7 +517,7 @@ static void runThreads(int ncheck, int nset, int nmod) { cnt[p] = 0; counters[p] = &cnt[p]; - threads[p] = new boost::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val); + threads[p] = new std::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val); val += 0.1; p++; } @@ -527,7 +527,7 @@ static void runThreads(int ncheck, int nset, int nmod) // this thread waits for all the other threads to make progress, then stops // everything. - boost::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000); + std::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000); // wait for all threads to finish for (int i = 0; i < p; ++i) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 9d675df359..3f21f90ff7 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -294,7 +294,7 @@ private Q_SLOTS: // Metric calculations kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_; std::map dynamics_solver_; - boost::mutex update_metrics_lock_; + std::mutex update_metrics_lock_; // The trajectory playback component TrajectoryVisualizationPtr trajectory_visual_; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index 35d709e548..19d4c6e32d 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -482,7 +482,7 @@ void MotionPlanningDisplay::computeMetrics(bool start, const std::string& group, const std::vector& eef = robot_interaction_->getActiveEndEffectors(); if (eef.empty()) return; - boost::mutex::scoped_lock slock(update_metrics_lock_); + std::mutex::scoped_lock slock(update_metrics_lock_); moveit::core::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState(); for (const robot_interaction::EndEffectorInteraction& ee : eef) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp index 3ecb98b526..f1de5cc56c 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp @@ -69,10 +69,10 @@ class BackgroundProcessing : private boost::noncopyable /** \brief The signature for callback triggered when job events take place: the event that took place and the name of * the job */ - typedef boost::function JobUpdateCallback; + typedef std::function JobUpdateCallback; /** \brief The signature for job callbacks */ - typedef boost::function JobCallback; + typedef std::function JobCallback; /** \brief Constructor. The background thread is activated automatically. */ BackgroundProcessing(); @@ -96,11 +96,11 @@ class BackgroundProcessing : private boost::noncopyable void clearJobUpdateEvent(); private: - std::unique_ptr processing_thread_; + std::unique_ptr processing_thread_; bool run_processing_thread_; - mutable boost::mutex action_lock_; - boost::condition_variable new_action_condition_; + mutable std::mutex action_lock_; + std::condition_variable new_action_condition_; std::deque actions_; std::deque action_names_; diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 99449b946f..e96583f35e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -89,16 +89,16 @@ class MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_CORE_EXPORT PlanningSceneDisplay : publi /** Queue this function call for execution within the background thread All jobs are queued and processed in order by a single background thread. */ - void addBackgroundJob(const boost::function& job, const std::string& name); + void addBackgroundJob(const std::function& job, const std::string& name); /** Directly spawn a (detached) background thread for execution of this function call Should be used, when order of processing is not relevant / job can run in parallel. Must be used, when job will be blocking. Using addBackgroundJob() in this case will block other queued jobs as well */ - void spawnBackgroundJob(const boost::function& job); + void spawnBackgroundJob(const std::function& job); /// queue the execution of this function for the next time the main update() loop gets called - void addMainLoopJob(const boost::function& job); + void addMainLoopJob(const std::function& job); void waitForAllMainLoopJobs(); @@ -182,12 +182,12 @@ protected Q_SLOTS: virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type); planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_; - boost::mutex robot_model_loading_lock_; + std::mutex robot_model_loading_lock_; moveit::tools::BackgroundProcessing background_process_; - std::deque > main_loop_jobs_; - boost::mutex main_loop_jobs_lock_; - boost::condition_variable main_loop_jobs_empty_condition_; + std::deque > main_loop_jobs_; + std::mutex main_loop_jobs_lock_; + std::condition_variable main_loop_jobs_empty_condition_; Ogre::SceneNode* planning_scene_node_; ///< displays planning scene with everything in it diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp index 06485b4545..38498f1ee6 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/background_processing.cpp @@ -49,7 +49,7 @@ BackgroundProcessing::BackgroundProcessing() // spin a thread that will process user events run_processing_thread_ = true; processing_ = false; - processing_thread_ = std::make_unique([this]() { return processingThread(); }); + processing_thread_ = std::make_unique([this]() { return processingThread(); }); } BackgroundProcessing::~BackgroundProcessing() @@ -61,7 +61,7 @@ BackgroundProcessing::~BackgroundProcessing() void BackgroundProcessing::processingThread() { - boost::unique_lock ulock(action_lock_); + std::unique_lock ulock(action_lock_); while (run_processing_thread_) { @@ -96,10 +96,10 @@ void BackgroundProcessing::processingThread() } } -void BackgroundProcessing::addJob(const boost::function& job, const std::string& name) +void BackgroundProcessing::addJob(const std::function& job, const std::string& name) { { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); actions_.push_back(job); action_names_.push_back(name); new_action_condition_.notify_all(); @@ -113,7 +113,7 @@ void BackgroundProcessing::clear() bool update = false; std::deque removed; { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); update = !actions_.empty(); actions_.clear(); action_names_.swap(removed); @@ -125,13 +125,13 @@ void BackgroundProcessing::clear() std::size_t BackgroundProcessing::getJobCount() const { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); return actions_.size() + (processing_ ? 1 : 0); } void BackgroundProcessing::setJobUpdateEvent(const JobUpdateCallback& event) { - boost::mutex::scoped_lock _(action_lock_); + std::scoped_lock _(action_lock_); queue_change_event_ = event; } diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp index e8fe1cc18d..96ab38edb6 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp @@ -182,7 +182,7 @@ void PlanningSceneDisplay::clearJobs() { background_process_.clear(); { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); main_loop_jobs_.clear(); } } @@ -231,25 +231,25 @@ void PlanningSceneDisplay::reset() } } -void PlanningSceneDisplay::addBackgroundJob(const boost::function& job, const std::string& name) +void PlanningSceneDisplay::addBackgroundJob(const std::function& job, const std::string& name) { background_process_.addJob(job, name); } -void PlanningSceneDisplay::spawnBackgroundJob(const boost::function& job) +void PlanningSceneDisplay::spawnBackgroundJob(const std::function& job) { - boost::thread t(job); + std::thread t(job); } -void PlanningSceneDisplay::addMainLoopJob(const boost::function& job) +void PlanningSceneDisplay::addMainLoopJob(const std::function& job) { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); main_loop_jobs_.push_back(job); } void PlanningSceneDisplay::waitForAllMainLoopJobs() { - boost::unique_lock ulock(main_loop_jobs_lock_); + std::unique_lock ulock(main_loop_jobs_lock_); while (!main_loop_jobs_.empty()) main_loop_jobs_empty_condition_.wait(ulock); } @@ -259,7 +259,7 @@ void PlanningSceneDisplay::executeMainLoopJobs() main_loop_jobs_lock_.lock(); while (!main_loop_jobs_.empty()) { - boost::function fn = main_loop_jobs_.front(); + std::function fn = main_loop_jobs_.front(); main_loop_jobs_.pop_front(); main_loop_jobs_lock_.unlock(); try @@ -532,7 +532,7 @@ void PlanningSceneDisplay::clearRobotModel() void PlanningSceneDisplay::loadRobotModel() { // wait for other robot loadRobotModel() calls to complete; - boost::mutex::scoped_lock _(robot_model_loading_lock_); + std::scoped_lock _(robot_model_loading_lock_); // we need to make sure the clearing of the robot model is in the main thread, // so that rendering operations do not have data removed from underneath, diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index f9b3b9d345..2a9d428949 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -151,7 +151,7 @@ private Q_SLOTS: bool drop_displaying_trajectory_; int current_state_; float current_state_time_; - boost::mutex update_trajectory_message_; + std::mutex update_trajectory_message_; moveit::core::RobotModelConstPtr robot_model_; moveit::core::RobotStatePtr robot_state_; diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index c31f1d1068..7610776fbc 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -425,7 +425,7 @@ void TrajectoryVisualization::update(float wall_dt, float sim_dt) } if (!animating_path_) { // finished last animation? - boost::mutex::scoped_lock lock(update_trajectory_message_); + std::scoped_lock lock(update_trajectory_message_); // new trajectory available to display? if (trajectory_message_to_display_ && !trajectory_message_to_display_->empty()) @@ -576,7 +576,7 @@ void TrajectoryVisualization::incomingDisplayTrajectory(const moveit_msgs::msg:: if (!t->empty()) { - boost::mutex::scoped_lock lock(update_trajectory_message_); + std::scoped_lock lock(update_trajectory_message_); trajectory_message_to_display_.swap(t); if (interrupt_display_property_->getBool()) interruptCurrentDisplay(); diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 06cdd3b37a..180c61fdc1 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -48,10 +48,10 @@ namespace moveit_setup_assistant // ****************************************************************************************** // Boost mapping of reasons for disabling a link pair to strings -const boost::unordered_map REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")( +const std::unordered_map REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")( DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled"); -const boost::unordered_map REASONS_FROM_STRING = +const std::unordered_map REASONS_FROM_STRING = boost::assign::map_list_of("Never", NEVER)("Default", DEFAULT)( "Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED); @@ -65,7 +65,7 @@ typedef std::set > StringPairSet; struct ThreadComputation { ThreadComputation(planning_scene::PlanningScene& scene, const collision_detection::CollisionRequest& req, - int thread_id, int num_trials, StringPairSet* links_seen_colliding, boost::mutex* lock, + int thread_id, int num_trials, StringPairSet* links_seen_colliding, std::mutex* lock, unsigned int* progress) : scene_(scene) , req_(req) @@ -81,7 +81,7 @@ struct ThreadComputation int thread_id_; unsigned int num_trials_; StringPairSet* links_seen_colliding_; - boost::mutex* lock_; + std::mutex* lock_; unsigned int* progress_; // only to be updated by thread 0 }; @@ -557,7 +557,7 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce unsigned int num_disabled = 0; boost::thread_group bgroup; // create a group of threads - boost::mutex lock; // used for sharing the same data structures + std::mutex lock; // used for sharing the same data structures int num_threads = boost::thread::hardware_concurrency(); // how many cores does this computer have? // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " << @@ -641,7 +641,7 @@ void disableNeverInCollisionThread(ThreadComputation tc) { // Collision Matrix and links_seen_colliding is modified only if needed, based on above if statement - boost::mutex::scoped_lock slock(*tc.lock_); + std::scoped_lock slock(*tc.lock_); tc.links_seen_colliding_->insert(it->first); tc.scene_.getAllowedCollisionMatrixNonConst().setEntry(it->first.first, it->first.second, diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp index 6c8527ba23..ce3cd37044 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp @@ -815,12 +815,12 @@ bool DefaultCollisionsWidget::focusLost() return true; } -moveit_setup_assistant::MonitorThread::MonitorThread(const boost::function& f, +moveit_setup_assistant::MonitorThread::MonitorThread(const std::function& f, QProgressBar* progress_bar) : progress_(0), canceled_(false) { // start worker thread - worker_ = boost::thread([f, progress_ptr = &progress_] { f(progress_ptr); }); + worker_ = std::thread([f, progress_ptr = &progress_] { f(progress_ptr); }); // connect progress bar for updates if (progress_bar) connect(this, SIGNAL(progress(int)), progress_bar, SLOT(setValue(int))); diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.h b/moveit_setup_assistant/src/widgets/default_collisions_widget.h index 004f04e752..aa1f020ce8 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.h +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.h @@ -233,14 +233,14 @@ private Q_SLOTS: }; /** - * \brief QThread to monitor progress of a boost::thread + * \brief QThread to monitor progress of a std::thread */ class MonitorThread : public QThread { Q_OBJECT public: - MonitorThread(const boost::function& f, QProgressBar* progress_bar = nullptr); + MonitorThread(const std::function& f, QProgressBar* progress_bar = nullptr); void run() override; void cancel() { @@ -255,7 +255,7 @@ class MonitorThread : public QThread void progress(int /*_t1*/); private: - boost::thread worker_; + std::thread worker_; unsigned int progress_; bool canceled_; }; diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp index c56c454f67..b4ec5c39f4 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp @@ -200,7 +200,7 @@ void SetupAssistantWidget::navigationClicked(const QModelIndex& index) // ****************************************************************************************** void SetupAssistantWidget::moveToScreen(const int index) { - boost::mutex::scoped_lock slock(change_screen_lock_); + std::scoped_lock slock(change_screen_lock_); if (current_index_ != index) { diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h index ffae4a7924..d09c530c28 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h @@ -196,7 +196,7 @@ private Q_SLOTS: QSplitter* splitter_; QStackedWidget* main_content_; int current_index_; - boost::mutex change_screen_lock_; + std::mutex change_screen_lock_; // Rviz Panel rviz::RenderPanel* rviz_render_panel_; From a9cb84f09703511b7f8031626b0268cc091d8278 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 8 Jun 2022 10:08:08 -0600 Subject: [PATCH 02/43] removing boost filesystem usage --- moveit_core/utils/src/robot_model_test_utils.cpp | 6 +++--- .../cached_ik_kinematics_plugin.h | 2 +- .../cached_ik_kinematics_plugin/src/ik_cache.cpp | 7 ++++--- moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp | 2 +- moveit_ros/planning/rdf_loader/src/rdf_loader.cpp | 7 ++++--- .../include/moveit/robot_interaction/interaction.h | 6 +++--- .../moveit/robot_interaction/interaction_handler.h | 10 +++++----- .../moveit/robot_interaction/kinematic_options_map.h | 2 +- .../moveit/robot_interaction/locked_robot_state.h | 4 ++-- .../moveit/robot_interaction/robot_interaction.h | 4 ++-- .../src/tools/moveit_config_data.cpp | 2 +- .../src/widgets/configuration_files_widget.cpp | 2 +- .../src/widgets/start_screen_widget.cpp | 2 +- .../test/moveit_config_data_test.cpp | 5 +++-- 14 files changed, 32 insertions(+), 29 deletions(-) diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 5bfbd3b7e5..063d6eab36 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -61,7 +61,7 @@ moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name) urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name) { const std::string package_name = "moveit_resources_" + robot_name + "_description"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); std::string urdf_path; if (robot_name == "pr2") { @@ -88,13 +88,13 @@ srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name) if (robot_name == "pr2") { const std::string package_name = "moveit_resources_" + robot_name + "_description"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); srdf_path = (res_path / "srdf/robot.xml").string(); } else { const std::string package_name = "moveit_resources_" + robot_name + "_moveit_config"; - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); srdf_path = (res_path / "config" / (robot_name + ".srdf")).string(); } srdf_model->initFile(*urdf_model, srdf_path); diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 621516f76b..a3e5c14c1b 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -131,7 +131,7 @@ class IKCache /** maximum size of the cache */ unsigned int max_cache_size_; /** file name for loading / saving cache */ - boost::filesystem::path cache_file_name_; + std::filesystem::path cache_file_name_; /** the IK methods are declared const in the base class, but the diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index 6303e771c3..ee8257563b 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -36,6 +36,7 @@ #include #include +#include #include @@ -72,9 +73,9 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr // use mutex lock for rest of initialization std::lock_guard slock(lock_); // determine cache file name - boost::filesystem::path prefix(!cached_ik_path.empty() ? cached_ik_path : boost::filesystem::current_path()); + std::filesystem::path prefix(!cached_ik_path.empty() ? cached_ik_path : std::filesystem::current_path()); // create cache directory if necessary - boost::filesystem::create_directories(prefix); + std::filesystem::create_directories(prefix); cache_file_name_ = prefix / (robot_id + group_name + "_" + cache_name + "_" + std::to_string(max_cache_size_) + "_" + std::to_string(min_pose_distance_) + "_" + @@ -83,7 +84,7 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr ik_cache_.clear(); ik_nn_.clear(); last_saved_cache_size_ = 0; - if (boost::filesystem::exists(cache_file_name_)) + if (std::filesystem::exists(cache_file_name_)) { // read cache boost::filesystem::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in); diff --git a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp index 5618b98ad7..e20d28adfb 100644 --- a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp +++ b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp @@ -53,7 +53,7 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.unit_test_ void loadModelFile(std::string package_name, std::string filename, std::string& file_content) { - boost::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); + std::filesystem::path res_path(ament_index_cpp::get_package_share_directory(package_name)); std::string xml_string; std::fstream xml_file((res_path / filename).string().c_str(), std::fstream::in); while (xml_file.good()) diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index 9bff9e05fa..6fd5cc303d 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -51,6 +51,7 @@ #include #include #include +#include namespace rdf_loader { @@ -125,7 +126,7 @@ bool RDFLoader::loadFileToString(std::string& buffer, const std::string& path) return false; } - if (!boost::filesystem::exists(path)) + if (!std::filesystem::exists(path)) { RCLCPP_ERROR(LOGGER, "File does not exist"); return false; @@ -158,7 +159,7 @@ bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& pa return false; } - if (!boost::filesystem::exists(path)) + if (!std::filesystem::exists(path)) { RCLCPP_ERROR(LOGGER, "File does not exist"); return false; @@ -220,7 +221,7 @@ bool RDFLoader::loadPkgFileToString(std::string& buffer, const std::string& pack return false; } - boost::filesystem::path path(package_path); + std::filesystem::path path(package_path); // Use boost to cross-platform combine paths path = path / relative_path; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 63d3a0202c..13733a7039 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -84,7 +84,7 @@ enum InteractionStyle /// that will be used to control the interaction. /// @returns true if the function succeeds, false if the function was not able /// to fill in \e marker. -typedef boost::function +typedef std::function InteractiveMarkerConstructorFn; /// Type of function for processing marker feedback. @@ -98,7 +98,7 @@ typedef boost::function ProcessFeedbackFn; @@ -111,7 +111,7 @@ typedef boost::function InteractiveMarkerUpdateFn; +typedef std::function InteractiveMarkerUpdateFn; /// Representation of a generic interaction. /// Displays one interactive marker. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 8e798aa5b3..66c5f1520b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -63,7 +63,7 @@ struct GenericInteraction; /// whether updates to the robot state performed in the /// InteractionHandler::handle* functions have switched from failing to /// succeeding or the other way around. -typedef boost::function InteractionHandlerCallbackFn; +typedef std::function InteractionHandlerCallbackFn; /// Manage interactive markers to control a RobotState. /// @@ -227,7 +227,7 @@ class InteractionHandler : public LockedRobotState std::shared_ptr tf_buffer_; private: - typedef boost::function StateChangeCallbackFn; + typedef std::function StateChangeCallbackFn; // Update RobotState using a generic interaction feedback message. // YOU MUST LOCK state_lock_ BEFORE CALLING THIS. @@ -272,8 +272,8 @@ class InteractionHandler : public LockedRobotState // PROTECTED BY pose_map_lock_ std::map pose_map_; - boost::mutex pose_map_lock_; - boost::mutex offset_map_lock_; + std::mutex pose_map_lock_; + std::mutex offset_map_lock_; // per group options for doing kinematics. // PROTECTED BY state_lock_ - The POINTER is protected by state_lock_. The @@ -299,7 +299,7 @@ class InteractionHandler : public LockedRobotState // // PROTECTED BY state_lock_ - the function pointer is protected, but the call // is made without any lock held. - boost::function update_callback_; + std::function update_callback_; // PROTECTED BY state_lock_ bool display_meshes_; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index d00a29541a..7f3c2ea72b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -91,7 +91,7 @@ class MOVEIT_ROBOT_INTERACTION_EXPORT KinematicOptionsMap private: // this protects all members. - mutable boost::mutex lock_; + mutable std::mutex lock_; // default kinematic options. // PROTECTED BY lock_ diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index ff165ae0e0..1b72a6e985 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -78,7 +78,7 @@ class LockedRobotState void setState(const moveit::core::RobotState& state); // This is a function that can modify the maintained state. - typedef boost::function ModifyStateFunction; + typedef std::function ModifyStateFunction; // Modify the state. // @@ -99,7 +99,7 @@ class LockedRobotState protected: // this locks all accesses to the state_ member. // The lock can also be used by subclasses to lock additional fields. - mutable boost::mutex state_lock_; + mutable std::mutex state_lock_; private: // The state maintained by this class. diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 3c004546f0..62cfe88fe8 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -196,7 +196,7 @@ class RobotInteraction void processingThread(); void clearInteractiveMarkersUnsafe(); - std::unique_ptr processing_thread_; + std::unique_ptr processing_thread_; bool run_processing_thread_; boost::condition_variable new_feedback_condition_; @@ -219,7 +219,7 @@ class RobotInteraction // of Thread 1: Lock A, Lock B, Unlock B, Unloack A // Thread 2: Lock B, Lock A // => deadlock - boost::mutex marker_access_lock_; + std::mutex marker_access_lock_; interactive_markers::InteractiveMarkerServer* int_marker_server_; // ros subscribers to move the interactive markers by other ros nodes diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 227839560f..19d106bbc1 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -54,7 +54,7 @@ namespace moveit_setup_assistant { // File system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; // ****************************************************************************************** // Constructor diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index c563e043bb..575f32ea45 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -62,7 +62,7 @@ namespace moveit_setup_assistant { // Boost file system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; static const std::string SETUP_ASSISTANT_FILE = ".setup_assistant"; static const std::string CONFIG_PATH = "config"; diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index e18b1e079e..b675586fdc 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -73,7 +73,7 @@ namespace moveit_setup_assistant { // Boost file system -namespace fs = boost::filesystem; +namespace fs = std::filesystem; // ****************************************************************************************** // Start screen user interface for MoveIt Configuration Assistant diff --git a/moveit_setup_assistant/test/moveit_config_data_test.cpp b/moveit_setup_assistant/test/moveit_config_data_test.cpp index 684d9c10a1..af7b72f1d9 100644 --- a/moveit_setup_assistant/test/moveit_config_data_test.cpp +++ b/moveit_setup_assistant/test/moveit_config_data_test.cpp @@ -45,6 +45,7 @@ #include #include #include +#include // This tests writing/parsing of ros_controller.yaml class MoveItConfigData : public testing::Test @@ -104,7 +105,7 @@ TEST_F(MoveItConfigData, ReadingControllers) EXPECT_EQ(config_data->getControllers().size(), group_count); // Remove ros_controllers.yaml temp file which was used in testing - boost::filesystem::remove(test_file); + std::filesystem::remove_all(test_file); } // This tests parsing of sensors_3d.yaml @@ -114,7 +115,7 @@ TEST_F(MoveItConfigData, ReadingSensorsConfig) moveit_setup_assistant::MoveItConfigDataPtr config_data; config_data = std::make_shared(); - boost::filesystem::path setup_assistant_path(config_data->setup_assistant_path_); + std::filesystem::path setup_assistant_path(config_data->setup_assistant_path_); // Before parsing, no config available EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u); From af0fed854321f3e62c7df03e33b64690a6195fde Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 8 Jun 2022 13:36:08 -0600 Subject: [PATCH 03/43] removing boost and changing calls to work without boost --- install/.colcon_install_layout | 1 + install/COLCON_IGNORE | 0 install/_local_setup_util_ps1.py | 404 ++++ install/_local_setup_util_sh.py | 404 ++++ install/local_setup.bash | 107 + install/local_setup.ps1 | 55 + install/local_setup.sh | 137 ++ install/local_setup.zsh | 120 + .../package_run_dependencies/moveit_common | 1 + .../resource_index/packages/moveit_common | 0 .../parent_prefix_path/moveit_common | 1 + .../share/colcon-core/packages/moveit_common | 1 + .../cmake/moveit_common-extras.cmake | 30 + .../cmake/moveit_commonConfig-version.cmake | 14 + .../cmake/moveit_commonConfig.cmake | 42 + .../moveit_common/cmake/moveit_package.cmake | 81 + .../environment/ament_prefix_path.dsv | 1 + .../environment/ament_prefix_path.sh | 4 + .../share/moveit_common/environment/path.dsv | 1 + .../share/moveit_common/environment/path.sh | 5 + .../moveit_common/hook/cmake_prefix_path.dsv | 1 + .../moveit_common/hook/cmake_prefix_path.ps1 | 3 + .../moveit_common/hook/cmake_prefix_path.sh | 3 + .../share/moveit_common/local_setup.bash | 46 + .../share/moveit_common/local_setup.dsv | 2 + .../share/moveit_common/local_setup.sh | 184 ++ .../share/moveit_common/local_setup.zsh | 59 + .../share/moveit_common/package.bash | 39 + .../share/moveit_common/package.dsv | 8 + .../share/moveit_common/package.ps1 | 116 + .../share/moveit_common/package.sh | 87 + .../share/moveit_common/package.xml | 29 + .../share/moveit_common/package.zsh | 50 + .../packages/moveit_configs_utils | 0 .../colcon-core/packages/moveit_configs_utils | 1 + .../default_configs/chomp_planning.yaml | 12 + .../default_configs/ompl_defaults.yaml | 129 ++ .../default_configs/ompl_planning.yaml | 10 + ...lz_industrial_motion_planner_planning.yaml | 6 + .../default_configs/trajopt_planning.yaml | 9 + .../hook/ament_prefix_path.dsv | 1 + .../hook/ament_prefix_path.ps1 | 3 + .../hook/ament_prefix_path.sh | 3 + .../moveit_configs_utils/hook/pythonpath.dsv | 1 + .../moveit_configs_utils/hook/pythonpath.ps1 | 3 + .../moveit_configs_utils/hook/pythonpath.sh | 3 + .../share/moveit_configs_utils/package.bash | 31 + .../share/moveit_configs_utils/package.dsv | 6 + .../share/moveit_configs_utils/package.ps1 | 116 + .../share/moveit_configs_utils/package.sh | 87 + .../share/moveit_configs_utils/package.xml | 24 + .../share/moveit_configs_utils/package.zsh | 42 + .../share/colcon-core/packages/moveit_core | 1 + .../share/moveit_core/package.bash | 31 + .../moveit_core/share/moveit_core/package.dsv | 0 .../moveit_core/share/moveit_core/package.ps1 | 108 + .../moveit_core/share/moveit_core/package.sh | 52 + .../moveit_core/share/moveit_core/package.zsh | 42 + .../moveit_resources_prbt_support | 1 + .../packages/moveit_resources_prbt_support | 0 .../moveit_resources_prbt_support | 1 + .../packages/moveit_resources_prbt_support | 1 + ...resources_prbt_supportConfig-version.cmake | 14 + .../moveit_resources_prbt_supportConfig.cmake | 42 + .../config/manipulator_controller.yaml | 77 + .../config/manipulator_driver.yaml | 52 + .../config/prbt_0_1.dcf | 2052 +++++++++++++++++ .../environment/ament_prefix_path.dsv | 1 + .../environment/ament_prefix_path.sh | 4 + .../environment/path.dsv | 1 + .../environment/path.sh | 5 + .../hook/cmake_prefix_path.dsv | 1 + .../hook/cmake_prefix_path.ps1 | 3 + .../hook/cmake_prefix_path.sh | 3 + .../local_setup.bash | 46 + .../local_setup.dsv | 2 + .../local_setup.sh | 184 ++ .../local_setup.zsh | 59 + .../meshes/flange.dae | 109 + .../meshes/flange.stl | Bin 0 -> 2284 bytes .../meshes/foot.dae | 145 ++ .../meshes/foot.stl | Bin 0 -> 6284 bytes .../meshes/link_1.dae | 109 + .../meshes/link_1.stl | Bin 0 -> 17884 bytes .../meshes/link_2.dae | 181 ++ .../meshes/link_2.stl | Bin 0 -> 4284 bytes .../meshes/link_3.dae | 109 + .../meshes/link_3.stl | Bin 0 -> 18184 bytes .../meshes/link_4.dae | 145 ++ .../meshes/link_4.stl | Bin 0 -> 6884 bytes .../meshes/link_5.dae | 109 + .../meshes/link_5.stl | Bin 0 -> 10284 bytes .../package.bash | 39 + .../moveit_resources_prbt_support/package.dsv | 8 + .../moveit_resources_prbt_support/package.ps1 | 116 + .../moveit_resources_prbt_support/package.sh | 87 + .../moveit_resources_prbt_support/package.xml | 25 + .../moveit_resources_prbt_support/package.zsh | 50 + .../urdf/prbt.ros2_control.xacro | 101 + .../urdf/prbt.xacro | 73 + .../urdf/prbt_macro.xacro | 465 ++++ .../urdf/simple_gripper_brackets.urdf.xacro | 94 + install/setup.bash | 31 + install/setup.ps1 | 29 + install/setup.sh | 45 + install/setup.zsh | 31 + log/COLCON_IGNORE | 0 log/build_2022-06-08_12-52-32/events.log | 313 +++ log/build_2022-06-08_12-52-32/logger_all.log | 986 ++++++++ .../moveit_common/command.log | 6 + .../moveit_common/stderr.log | 0 .../moveit_common/stdout.log | 28 + .../moveit_common/stdout_stderr.log | 28 + .../moveit_common/streams.log | 34 + .../moveit_configs_utils/command.log | 2 + .../moveit_configs_utils/stderr.log | 2 + .../moveit_configs_utils/stdout.log | 46 + .../moveit_configs_utils/stdout_stderr.log | 48 + .../moveit_configs_utils/streams.log | 50 + .../moveit_core/command.log | 2 + .../moveit_core/stderr.log | 17 + .../moveit_core/stdout.log | 47 + .../moveit_core/stdout_stderr.log | 64 + .../moveit_core/streams.log | 66 + .../moveit_resources_prbt_support/command.log | 6 + .../moveit_resources_prbt_support/stderr.log | 0 .../moveit_resources_prbt_support/stdout.log | 57 + .../stdout_stderr.log | 57 + .../moveit_resources_prbt_support/streams.log | 63 + log/latest | 1 + log/latest_build | 1 + .../collision_detection/occupancy_map.h | 1 + .../utils/src/robot_model_test_utils.cpp | 1 + .../cached_ik_kinematics_plugin.h | 1 + .../src/ik_cache.cpp | 6 +- .../src/kdl_kinematics_plugin.cpp | 2 +- .../src/lma_kinematics_plugin.cpp | 2 +- .../src/srv_kinematics_plugin.cpp | 2 +- .../src/detail/constraints_library.cpp | 3 +- .../prbt_manipulator_ikfast_moveit_plugin.cpp | 4 +- .../benchmarks/src/BenchmarkExecutor.cpp | 3 +- .../moveit/pick_place/manipulation_pipeline.h | 2 +- .../include/moveit/pick_place/pick_place.h | 2 +- .../occupancy_map_monitor.h | 2 +- .../occupancy_map_updater.h | 2 +- .../lazy_free_space_updater.h | 14 +- .../src/lazy_free_space_updater.cpp | 10 +- .../point_containment_filter/shape_mask.h | 4 +- .../src/shape_mask.cpp | 10 +- .../moveit/semantic_world/semantic_world.h | 2 +- .../src/kinematics_plugin_loader.cpp | 8 +- .../moveit/plan_execution/plan_execution.h | 8 +- .../plan_execution/plan_representation.h | 4 +- .../moveit/plan_execution/plan_with_sensing.h | 4 +- .../src/evaluate_collision_checking_speed.cpp | 4 +- .../planning_scene_monitor.h | 14 +- .../trajectory_monitor.h | 2 +- .../src/planning_scene_monitor.cpp | 32 +- .../src/roscpp_initializer.cpp | 4 +- .../robot_interaction/robot_interaction.h | 2 +- .../src/tools/compute_default_collisions.cpp | 2 +- 161 files changed, 9413 insertions(+), 75 deletions(-) create mode 100644 install/.colcon_install_layout create mode 100644 install/COLCON_IGNORE create mode 100644 install/_local_setup_util_ps1.py create mode 100644 install/_local_setup_util_sh.py create mode 100644 install/local_setup.bash create mode 100644 install/local_setup.ps1 create mode 100644 install/local_setup.sh create mode 100644 install/local_setup.zsh create mode 100644 install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common create mode 100644 install/moveit_common/share/ament_index/resource_index/packages/moveit_common create mode 100644 install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common create mode 100644 install/moveit_common/share/colcon-core/packages/moveit_common create mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake create mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake create mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake create mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_package.cmake create mode 100644 install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv create mode 100644 install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh create mode 100644 install/moveit_common/share/moveit_common/environment/path.dsv create mode 100644 install/moveit_common/share/moveit_common/environment/path.sh create mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv create mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 create mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh create mode 100644 install/moveit_common/share/moveit_common/local_setup.bash create mode 100644 install/moveit_common/share/moveit_common/local_setup.dsv create mode 100644 install/moveit_common/share/moveit_common/local_setup.sh create mode 100644 install/moveit_common/share/moveit_common/local_setup.zsh create mode 100644 install/moveit_common/share/moveit_common/package.bash create mode 100644 install/moveit_common/share/moveit_common/package.dsv create mode 100644 install/moveit_common/share/moveit_common/package.ps1 create mode 100644 install/moveit_common/share/moveit_common/package.sh create mode 100644 install/moveit_common/share/moveit_common/package.xml create mode 100644 install/moveit_common/share/moveit_common/package.zsh create mode 100644 install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils create mode 100644 install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.bash create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.dsv create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.sh create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.xml create mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.zsh create mode 100644 install/moveit_core/share/colcon-core/packages/moveit_core create mode 100644 install/moveit_core/share/moveit_core/package.bash create mode 100644 install/moveit_core/share/moveit_core/package.dsv create mode 100644 install/moveit_core/share/moveit_core/package.ps1 create mode 100644 install/moveit_core/share/moveit_core/package.sh create mode 100644 install/moveit_core/share/moveit_core/package.zsh create mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support create mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support create mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support create mode 100644 install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro create mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro create mode 100644 install/setup.bash create mode 100644 install/setup.ps1 create mode 100644 install/setup.sh create mode 100644 install/setup.zsh create mode 100644 log/COLCON_IGNORE create mode 100644 log/build_2022-06-08_12-52-32/events.log create mode 100644 log/build_2022-06-08_12-52-32/logger_all.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_common/command.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stdout.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_common/streams.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_core/command.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stdout.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_core/streams.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log create mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log create mode 120000 log/latest create mode 120000 log/latest_build diff --git a/install/.colcon_install_layout b/install/.colcon_install_layout new file mode 100644 index 0000000000..3aad5336af --- /dev/null +++ b/install/.colcon_install_layout @@ -0,0 +1 @@ +isolated diff --git a/install/COLCON_IGNORE b/install/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/install/_local_setup_util_ps1.py b/install/_local_setup_util_ps1.py new file mode 100644 index 0000000000..98348eebcf --- /dev/null +++ b/install/_local_setup_util_ps1.py @@ -0,0 +1,404 @@ +# Copyright 2016-2019 Dirk Thomas +# Licensed under the Apache License, Version 2.0 + +import argparse +from collections import OrderedDict +import os +from pathlib import Path +import sys + + +FORMAT_STR_COMMENT_LINE = '# {comment}' +FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"' +FORMAT_STR_USE_ENV_VAR = '$env:{name}' +FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"' +FORMAT_STR_REMOVE_LEADING_SEPARATOR = '' +FORMAT_STR_REMOVE_TRAILING_SEPARATOR = '' + +DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate' +DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate' +DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists' +DSV_TYPE_SET = 'set' +DSV_TYPE_SET_IF_UNSET = 'set-if-unset' +DSV_TYPE_SOURCE = 'source' + + +def main(argv=sys.argv[1:]): # noqa: D103 + parser = argparse.ArgumentParser( + description='Output shell commands for the packages in topological ' + 'order') + parser.add_argument( + 'primary_extension', + help='The file extension of the primary shell') + parser.add_argument( + 'additional_extension', nargs='?', + help='The additional file extension to be considered') + parser.add_argument( + '--merged-install', action='store_true', + help='All install prefixes are merged into a single location') + args = parser.parse_args(argv) + + packages = get_packages(Path(__file__).parent, args.merged_install) + + ordered_packages = order_packages(packages) + for pkg_name in ordered_packages: + if _include_comments(): + print( + FORMAT_STR_COMMENT_LINE.format_map( + {'comment': 'Package: ' + pkg_name})) + prefix = os.path.abspath(os.path.dirname(__file__)) + if not args.merged_install: + prefix = os.path.join(prefix, pkg_name) + for line in get_commands( + pkg_name, prefix, args.primary_extension, + args.additional_extension + ): + print(line) + + for line in _remove_ending_separators(): + print(line) + + +def get_packages(prefix_path, merged_install): + """ + Find packages based on colcon-specific files created during installation. + + :param Path prefix_path: The install prefix path of all packages + :param bool merged_install: The flag if the packages are all installed + directly in the prefix or if each package is installed in a subdirectory + named after the package + :returns: A mapping from the package name to the set of runtime + dependencies + :rtype: dict + """ + packages = {} + # since importing colcon_core isn't feasible here the following constant + # must match colcon_core.location.get_relative_package_index_path() + subdirectory = 'share/colcon-core/packages' + if merged_install: + # return if workspace is empty + if not (prefix_path / subdirectory).is_dir(): + return packages + # find all files in the subdirectory + for p in (prefix_path / subdirectory).iterdir(): + if not p.is_file(): + continue + if p.name.startswith('.'): + continue + add_package_runtime_dependencies(p, packages) + else: + # for each subdirectory look for the package specific file + for p in prefix_path.iterdir(): + if not p.is_dir(): + continue + if p.name.startswith('.'): + continue + p = p / subdirectory / p.name + if p.is_file(): + add_package_runtime_dependencies(p, packages) + + # remove unknown dependencies + pkg_names = set(packages.keys()) + for k in packages.keys(): + packages[k] = {d for d in packages[k] if d in pkg_names} + + return packages + + +def add_package_runtime_dependencies(path, packages): + """ + Check the path and if it exists extract the packages runtime dependencies. + + :param Path path: The resource file containing the runtime dependencies + :param dict packages: A mapping from package names to the sets of runtime + dependencies to add to + """ + content = path.read_text() + dependencies = set(content.split(os.pathsep) if content else []) + packages[path.name] = dependencies + + +def order_packages(packages): + """ + Order packages topologically. + + :param dict packages: A mapping from package name to the set of runtime + dependencies + :returns: The package names + :rtype: list + """ + # select packages with no dependencies in alphabetical order + to_be_ordered = list(packages.keys()) + ordered = [] + while to_be_ordered: + pkg_names_without_deps = [ + name for name in to_be_ordered if not packages[name]] + if not pkg_names_without_deps: + reduce_cycle_set(packages) + raise RuntimeError( + 'Circular dependency between: ' + ', '.join(sorted(packages))) + pkg_names_without_deps.sort() + pkg_name = pkg_names_without_deps[0] + to_be_ordered.remove(pkg_name) + ordered.append(pkg_name) + # remove item from dependency lists + for k in list(packages.keys()): + if pkg_name in packages[k]: + packages[k].remove(pkg_name) + return ordered + + +def reduce_cycle_set(packages): + """ + Reduce the set of packages to the ones part of the circular dependency. + + :param dict packages: A mapping from package name to the set of runtime + dependencies which is modified in place + """ + last_depended = None + while len(packages) > 0: + # get all remaining dependencies + depended = set() + for pkg_name, dependencies in packages.items(): + depended = depended.union(dependencies) + # remove all packages which are not dependent on + for name in list(packages.keys()): + if name not in depended: + del packages[name] + if last_depended: + # if remaining packages haven't changed return them + if last_depended == depended: + return packages.keys() + # otherwise reduce again + last_depended = depended + + +def _include_comments(): + # skipping comment lines when COLCON_TRACE is not set speeds up the + # processing especially on Windows + return bool(os.environ.get('COLCON_TRACE')) + + +def get_commands(pkg_name, prefix, primary_extension, additional_extension): + commands = [] + package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv') + if os.path.exists(package_dsv_path): + commands += process_dsv_file( + package_dsv_path, prefix, primary_extension, additional_extension) + return commands + + +def process_dsv_file( + dsv_path, prefix, primary_extension=None, additional_extension=None +): + commands = [] + if _include_comments(): + commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path})) + with open(dsv_path, 'r') as h: + content = h.read() + lines = content.splitlines() + + basenames = OrderedDict() + for i, line in enumerate(lines): + # skip over empty or whitespace-only lines + if not line.strip(): + continue + try: + type_, remainder = line.split(';', 1) + except ValueError: + raise RuntimeError( + "Line %d in '%s' doesn't contain a semicolon separating the " + 'type from the arguments' % (i + 1, dsv_path)) + if type_ != DSV_TYPE_SOURCE: + # handle non-source lines + try: + commands += handle_dsv_types_except_source( + type_, remainder, prefix) + except RuntimeError as e: + raise RuntimeError( + "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e + else: + # group remaining source lines by basename + path_without_ext, ext = os.path.splitext(remainder) + if path_without_ext not in basenames: + basenames[path_without_ext] = set() + assert ext.startswith('.') + ext = ext[1:] + if ext in (primary_extension, additional_extension): + basenames[path_without_ext].add(ext) + + # add the dsv extension to each basename if the file exists + for basename, extensions in basenames.items(): + if not os.path.isabs(basename): + basename = os.path.join(prefix, basename) + if os.path.exists(basename + '.dsv'): + extensions.add('dsv') + + for basename, extensions in basenames.items(): + if not os.path.isabs(basename): + basename = os.path.join(prefix, basename) + if 'dsv' in extensions: + # process dsv files recursively + commands += process_dsv_file( + basename + '.dsv', prefix, primary_extension=primary_extension, + additional_extension=additional_extension) + elif primary_extension in extensions and len(extensions) == 1: + # source primary-only files + commands += [ + FORMAT_STR_INVOKE_SCRIPT.format_map({ + 'prefix': prefix, + 'script_path': basename + '.' + primary_extension})] + elif additional_extension in extensions: + # source non-primary files + commands += [ + FORMAT_STR_INVOKE_SCRIPT.format_map({ + 'prefix': prefix, + 'script_path': basename + '.' + additional_extension})] + + return commands + + +def handle_dsv_types_except_source(type_, remainder, prefix): + commands = [] + if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET): + try: + env_name, value = remainder.split(';', 1) + except ValueError: + raise RuntimeError( + "doesn't contain a semicolon separating the environment name " + 'from the value') + try_prefixed_value = os.path.join(prefix, value) if value else prefix + if os.path.exists(try_prefixed_value): + value = try_prefixed_value + if type_ == DSV_TYPE_SET: + commands += _set(env_name, value) + elif type_ == DSV_TYPE_SET_IF_UNSET: + commands += _set_if_unset(env_name, value) + else: + assert False + elif type_ in ( + DSV_TYPE_APPEND_NON_DUPLICATE, + DSV_TYPE_PREPEND_NON_DUPLICATE, + DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS + ): + try: + env_name_and_values = remainder.split(';') + except ValueError: + raise RuntimeError( + "doesn't contain a semicolon separating the environment name " + 'from the values') + env_name = env_name_and_values[0] + values = env_name_and_values[1:] + for value in values: + if not value: + value = prefix + elif not os.path.isabs(value): + value = os.path.join(prefix, value) + if ( + type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and + not os.path.exists(value) + ): + comment = f'skip extending {env_name} with not existing ' \ + f'path: {value}' + if _include_comments(): + commands.append( + FORMAT_STR_COMMENT_LINE.format_map({'comment': comment})) + elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE: + commands += _append_unique_value(env_name, value) + else: + commands += _prepend_unique_value(env_name, value) + else: + raise RuntimeError( + 'contains an unknown environment hook type: ' + type_) + return commands + + +env_state = {} + + +def _append_unique_value(name, value): + global env_state + if name not in env_state: + if os.environ.get(name): + env_state[name] = set(os.environ[name].split(os.pathsep)) + else: + env_state[name] = set() + # append even if the variable has not been set yet, in case a shell script sets the + # same variable without the knowledge of this Python script. + # later _remove_ending_separators() will cleanup any unintentional leading separator + extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': extend + value}) + if value not in env_state[name]: + env_state[name].add(value) + else: + if not _include_comments(): + return [] + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +def _prepend_unique_value(name, value): + global env_state + if name not in env_state: + if os.environ.get(name): + env_state[name] = set(os.environ[name].split(os.pathsep)) + else: + env_state[name] = set() + # prepend even if the variable has not been set yet, in case a shell script sets the + # same variable without the knowledge of this Python script. + # later _remove_ending_separators() will cleanup any unintentional trailing separator + extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value + extend}) + if value not in env_state[name]: + env_state[name].add(value) + else: + if not _include_comments(): + return [] + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +# generate commands for removing prepended underscores +def _remove_ending_separators(): + # do nothing if the shell extension does not implement the logic + if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None: + return [] + + global env_state + commands = [] + for name in env_state: + # skip variables that already had values before this script started prepending + if name in os.environ: + continue + commands += [ + FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}), + FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})] + return commands + + +def _set(name, value): + global env_state + env_state[name] = value + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value}) + return [line] + + +def _set_if_unset(name, value): + global env_state + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value}) + if env_state.get(name, os.environ.get(name)): + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +if __name__ == '__main__': # pragma: no cover + try: + rc = main() + except RuntimeError as e: + print(str(e), file=sys.stderr) + rc = 1 + sys.exit(rc) diff --git a/install/_local_setup_util_sh.py b/install/_local_setup_util_sh.py new file mode 100644 index 0000000000..35c017b255 --- /dev/null +++ b/install/_local_setup_util_sh.py @@ -0,0 +1,404 @@ +# Copyright 2016-2019 Dirk Thomas +# Licensed under the Apache License, Version 2.0 + +import argparse +from collections import OrderedDict +import os +from pathlib import Path +import sys + + +FORMAT_STR_COMMENT_LINE = '# {comment}' +FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"' +FORMAT_STR_USE_ENV_VAR = '${name}' +FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"' +FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi' +FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi' + +DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate' +DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate' +DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists' +DSV_TYPE_SET = 'set' +DSV_TYPE_SET_IF_UNSET = 'set-if-unset' +DSV_TYPE_SOURCE = 'source' + + +def main(argv=sys.argv[1:]): # noqa: D103 + parser = argparse.ArgumentParser( + description='Output shell commands for the packages in topological ' + 'order') + parser.add_argument( + 'primary_extension', + help='The file extension of the primary shell') + parser.add_argument( + 'additional_extension', nargs='?', + help='The additional file extension to be considered') + parser.add_argument( + '--merged-install', action='store_true', + help='All install prefixes are merged into a single location') + args = parser.parse_args(argv) + + packages = get_packages(Path(__file__).parent, args.merged_install) + + ordered_packages = order_packages(packages) + for pkg_name in ordered_packages: + if _include_comments(): + print( + FORMAT_STR_COMMENT_LINE.format_map( + {'comment': 'Package: ' + pkg_name})) + prefix = os.path.abspath(os.path.dirname(__file__)) + if not args.merged_install: + prefix = os.path.join(prefix, pkg_name) + for line in get_commands( + pkg_name, prefix, args.primary_extension, + args.additional_extension + ): + print(line) + + for line in _remove_ending_separators(): + print(line) + + +def get_packages(prefix_path, merged_install): + """ + Find packages based on colcon-specific files created during installation. + + :param Path prefix_path: The install prefix path of all packages + :param bool merged_install: The flag if the packages are all installed + directly in the prefix or if each package is installed in a subdirectory + named after the package + :returns: A mapping from the package name to the set of runtime + dependencies + :rtype: dict + """ + packages = {} + # since importing colcon_core isn't feasible here the following constant + # must match colcon_core.location.get_relative_package_index_path() + subdirectory = 'share/colcon-core/packages' + if merged_install: + # return if workspace is empty + if not (prefix_path / subdirectory).is_dir(): + return packages + # find all files in the subdirectory + for p in (prefix_path / subdirectory).iterdir(): + if not p.is_file(): + continue + if p.name.startswith('.'): + continue + add_package_runtime_dependencies(p, packages) + else: + # for each subdirectory look for the package specific file + for p in prefix_path.iterdir(): + if not p.is_dir(): + continue + if p.name.startswith('.'): + continue + p = p / subdirectory / p.name + if p.is_file(): + add_package_runtime_dependencies(p, packages) + + # remove unknown dependencies + pkg_names = set(packages.keys()) + for k in packages.keys(): + packages[k] = {d for d in packages[k] if d in pkg_names} + + return packages + + +def add_package_runtime_dependencies(path, packages): + """ + Check the path and if it exists extract the packages runtime dependencies. + + :param Path path: The resource file containing the runtime dependencies + :param dict packages: A mapping from package names to the sets of runtime + dependencies to add to + """ + content = path.read_text() + dependencies = set(content.split(os.pathsep) if content else []) + packages[path.name] = dependencies + + +def order_packages(packages): + """ + Order packages topologically. + + :param dict packages: A mapping from package name to the set of runtime + dependencies + :returns: The package names + :rtype: list + """ + # select packages with no dependencies in alphabetical order + to_be_ordered = list(packages.keys()) + ordered = [] + while to_be_ordered: + pkg_names_without_deps = [ + name for name in to_be_ordered if not packages[name]] + if not pkg_names_without_deps: + reduce_cycle_set(packages) + raise RuntimeError( + 'Circular dependency between: ' + ', '.join(sorted(packages))) + pkg_names_without_deps.sort() + pkg_name = pkg_names_without_deps[0] + to_be_ordered.remove(pkg_name) + ordered.append(pkg_name) + # remove item from dependency lists + for k in list(packages.keys()): + if pkg_name in packages[k]: + packages[k].remove(pkg_name) + return ordered + + +def reduce_cycle_set(packages): + """ + Reduce the set of packages to the ones part of the circular dependency. + + :param dict packages: A mapping from package name to the set of runtime + dependencies which is modified in place + """ + last_depended = None + while len(packages) > 0: + # get all remaining dependencies + depended = set() + for pkg_name, dependencies in packages.items(): + depended = depended.union(dependencies) + # remove all packages which are not dependent on + for name in list(packages.keys()): + if name not in depended: + del packages[name] + if last_depended: + # if remaining packages haven't changed return them + if last_depended == depended: + return packages.keys() + # otherwise reduce again + last_depended = depended + + +def _include_comments(): + # skipping comment lines when COLCON_TRACE is not set speeds up the + # processing especially on Windows + return bool(os.environ.get('COLCON_TRACE')) + + +def get_commands(pkg_name, prefix, primary_extension, additional_extension): + commands = [] + package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv') + if os.path.exists(package_dsv_path): + commands += process_dsv_file( + package_dsv_path, prefix, primary_extension, additional_extension) + return commands + + +def process_dsv_file( + dsv_path, prefix, primary_extension=None, additional_extension=None +): + commands = [] + if _include_comments(): + commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path})) + with open(dsv_path, 'r') as h: + content = h.read() + lines = content.splitlines() + + basenames = OrderedDict() + for i, line in enumerate(lines): + # skip over empty or whitespace-only lines + if not line.strip(): + continue + try: + type_, remainder = line.split(';', 1) + except ValueError: + raise RuntimeError( + "Line %d in '%s' doesn't contain a semicolon separating the " + 'type from the arguments' % (i + 1, dsv_path)) + if type_ != DSV_TYPE_SOURCE: + # handle non-source lines + try: + commands += handle_dsv_types_except_source( + type_, remainder, prefix) + except RuntimeError as e: + raise RuntimeError( + "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e + else: + # group remaining source lines by basename + path_without_ext, ext = os.path.splitext(remainder) + if path_without_ext not in basenames: + basenames[path_without_ext] = set() + assert ext.startswith('.') + ext = ext[1:] + if ext in (primary_extension, additional_extension): + basenames[path_without_ext].add(ext) + + # add the dsv extension to each basename if the file exists + for basename, extensions in basenames.items(): + if not os.path.isabs(basename): + basename = os.path.join(prefix, basename) + if os.path.exists(basename + '.dsv'): + extensions.add('dsv') + + for basename, extensions in basenames.items(): + if not os.path.isabs(basename): + basename = os.path.join(prefix, basename) + if 'dsv' in extensions: + # process dsv files recursively + commands += process_dsv_file( + basename + '.dsv', prefix, primary_extension=primary_extension, + additional_extension=additional_extension) + elif primary_extension in extensions and len(extensions) == 1: + # source primary-only files + commands += [ + FORMAT_STR_INVOKE_SCRIPT.format_map({ + 'prefix': prefix, + 'script_path': basename + '.' + primary_extension})] + elif additional_extension in extensions: + # source non-primary files + commands += [ + FORMAT_STR_INVOKE_SCRIPT.format_map({ + 'prefix': prefix, + 'script_path': basename + '.' + additional_extension})] + + return commands + + +def handle_dsv_types_except_source(type_, remainder, prefix): + commands = [] + if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET): + try: + env_name, value = remainder.split(';', 1) + except ValueError: + raise RuntimeError( + "doesn't contain a semicolon separating the environment name " + 'from the value') + try_prefixed_value = os.path.join(prefix, value) if value else prefix + if os.path.exists(try_prefixed_value): + value = try_prefixed_value + if type_ == DSV_TYPE_SET: + commands += _set(env_name, value) + elif type_ == DSV_TYPE_SET_IF_UNSET: + commands += _set_if_unset(env_name, value) + else: + assert False + elif type_ in ( + DSV_TYPE_APPEND_NON_DUPLICATE, + DSV_TYPE_PREPEND_NON_DUPLICATE, + DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS + ): + try: + env_name_and_values = remainder.split(';') + except ValueError: + raise RuntimeError( + "doesn't contain a semicolon separating the environment name " + 'from the values') + env_name = env_name_and_values[0] + values = env_name_and_values[1:] + for value in values: + if not value: + value = prefix + elif not os.path.isabs(value): + value = os.path.join(prefix, value) + if ( + type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and + not os.path.exists(value) + ): + comment = f'skip extending {env_name} with not existing ' \ + f'path: {value}' + if _include_comments(): + commands.append( + FORMAT_STR_COMMENT_LINE.format_map({'comment': comment})) + elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE: + commands += _append_unique_value(env_name, value) + else: + commands += _prepend_unique_value(env_name, value) + else: + raise RuntimeError( + 'contains an unknown environment hook type: ' + type_) + return commands + + +env_state = {} + + +def _append_unique_value(name, value): + global env_state + if name not in env_state: + if os.environ.get(name): + env_state[name] = set(os.environ[name].split(os.pathsep)) + else: + env_state[name] = set() + # append even if the variable has not been set yet, in case a shell script sets the + # same variable without the knowledge of this Python script. + # later _remove_ending_separators() will cleanup any unintentional leading separator + extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': extend + value}) + if value not in env_state[name]: + env_state[name].add(value) + else: + if not _include_comments(): + return [] + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +def _prepend_unique_value(name, value): + global env_state + if name not in env_state: + if os.environ.get(name): + env_state[name] = set(os.environ[name].split(os.pathsep)) + else: + env_state[name] = set() + # prepend even if the variable has not been set yet, in case a shell script sets the + # same variable without the knowledge of this Python script. + # later _remove_ending_separators() will cleanup any unintentional trailing separator + extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value + extend}) + if value not in env_state[name]: + env_state[name].add(value) + else: + if not _include_comments(): + return [] + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +# generate commands for removing prepended underscores +def _remove_ending_separators(): + # do nothing if the shell extension does not implement the logic + if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None: + return [] + + global env_state + commands = [] + for name in env_state: + # skip variables that already had values before this script started prepending + if name in os.environ: + continue + commands += [ + FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}), + FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})] + return commands + + +def _set(name, value): + global env_state + env_state[name] = value + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value}) + return [line] + + +def _set_if_unset(name, value): + global env_state + line = FORMAT_STR_SET_ENV_VAR.format_map( + {'name': name, 'value': value}) + if env_state.get(name, os.environ.get(name)): + line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) + return [line] + + +if __name__ == '__main__': # pragma: no cover + try: + rc = main() + except RuntimeError as e: + print(str(e), file=sys.stderr) + rc = 1 + sys.exit(rc) diff --git a/install/local_setup.bash b/install/local_setup.bash new file mode 100644 index 0000000000..efd5f8c9e2 --- /dev/null +++ b/install/local_setup.bash @@ -0,0 +1,107 @@ +# generated from colcon_bash/shell/template/prefix.bash.em + +# This script extends the environment with all packages contained in this +# prefix path. + +# a bash script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)" +else + _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prefix_bash_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prefix_bash_prepend_unique_value_IFS="$IFS" + IFS=":" + # start with the new value + _all_values="$_value" + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS="$_colcon_prefix_bash_prepend_unique_value_IFS" + unset _colcon_prefix_bash_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# add this prefix to the COLCON_PREFIX_PATH +_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX" +unset _colcon_prefix_bash_prepend_unique_value + +# check environment variable for custom Python executable +if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then + if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then + echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" + return 1 + fi + _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" +else + # try the Python executable known at configure time + _colcon_python_executable="/usr/bin/python3" + # if it doesn't exist try a fall back + if [ ! -f "$_colcon_python_executable" ]; then + if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then + echo "error: unable to find python3 executable" + return 1 + fi + _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` + fi +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# get all commands in topological order +_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)" +unset _colcon_python_executable +if [ -n "$COLCON_TRACE" ]; then + echo "Execute generated script:" + echo "<<<" + echo "${_colcon_ordered_commands}" + echo ">>>" +fi +eval "${_colcon_ordered_commands}" +unset _colcon_ordered_commands + +unset _colcon_prefix_sh_source_script + +unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX diff --git a/install/local_setup.ps1 b/install/local_setup.ps1 new file mode 100644 index 0000000000..6f68c8dede --- /dev/null +++ b/install/local_setup.ps1 @@ -0,0 +1,55 @@ +# generated from colcon_powershell/shell/template/prefix.ps1.em + +# This script extends the environment with all packages contained in this +# prefix path. + +# check environment variable for custom Python executable +if ($env:COLCON_PYTHON_EXECUTABLE) { + if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) { + echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist" + exit 1 + } + $_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE" +} else { + # use the Python executable known at configure time + $_colcon_python_executable="/usr/bin/python3" + # if it doesn't exist try a fall back + if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) { + if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) { + echo "error: unable to find python3 executable" + exit 1 + } + $_colcon_python_executable="python3" + } +} + +# function to source another script with conditional trace output +# first argument: the path of the script +function _colcon_prefix_powershell_source_script { + param ( + $_colcon_prefix_powershell_source_script_param + ) + # source script with conditional trace output + if (Test-Path $_colcon_prefix_powershell_source_script_param) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_prefix_powershell_source_script_param'" + } + . "$_colcon_prefix_powershell_source_script_param" + } else { + Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'" + } +} + +# get all commands in topological order +$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1 + +# execute all commands in topological order +if ($env:COLCON_TRACE) { + echo "Execute generated script:" + echo "<<<" + $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output + echo ">>>" +} +if ($_colcon_ordered_commands) { + $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression +} diff --git a/install/local_setup.sh b/install/local_setup.sh new file mode 100644 index 0000000000..8e04206e84 --- /dev/null +++ b/install/local_setup.sh @@ -0,0 +1,137 @@ +# generated from colcon_core/shell/template/prefix.sh.em + +# This script extends the environment with all packages contained in this +# prefix path. + +# since a plain shell script can't determine its own path when being sourced +# either use the provided COLCON_CURRENT_PREFIX +# or fall back to the build time prefix (if it exists) +_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install" +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then + echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 + unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX + return 1 + fi +else + _colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prefix_sh_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prefix_sh_prepend_unique_value_IFS="$IFS" + IFS=":" + # start with the new value + _all_values="$_value" + _contained_value="" + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + _contained_value=1 + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + if [ -z "$_contained_value" ]; then + if [ -n "$COLCON_TRACE" ]; then + if [ "$_all_values" = "$_value" ]; then + echo "export $_listname=$_value" + else + echo "export $_listname=$_value:\$$_listname" + fi + fi + fi + unset _contained_value + # restore the field separator + IFS="$_colcon_prefix_sh_prepend_unique_value_IFS" + unset _colcon_prefix_sh_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# add this prefix to the COLCON_PREFIX_PATH +_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" +unset _colcon_prefix_sh_prepend_unique_value + +# check environment variable for custom Python executable +if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then + if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then + echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" + return 1 + fi + _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" +else + # try the Python executable known at configure time + _colcon_python_executable="/usr/bin/python3" + # if it doesn't exist try a fall back + if [ ! -f "$_colcon_python_executable" ]; then + if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then + echo "error: unable to find python3 executable" + return 1 + fi + _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` + fi +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo "# . \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# get all commands in topological order +_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)" +unset _colcon_python_executable +if [ -n "$COLCON_TRACE" ]; then + echo "_colcon_prefix_sh_source_script() { + if [ -f \"\$1\" ]; then + if [ -n \"\$COLCON_TRACE\" ]; then + echo \"# . \\\"\$1\\\"\" + fi + . \"\$1\" + else + echo \"not found: \\\"\$1\\\"\" 1>&2 + fi + }" + echo "# Execute generated script:" + echo "# <<<" + echo "${_colcon_ordered_commands}" + echo "# >>>" + echo "unset _colcon_prefix_sh_source_script" +fi +eval "${_colcon_ordered_commands}" +unset _colcon_ordered_commands + +unset _colcon_prefix_sh_source_script + +unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX diff --git a/install/local_setup.zsh b/install/local_setup.zsh new file mode 100644 index 0000000000..f7a8d904f2 --- /dev/null +++ b/install/local_setup.zsh @@ -0,0 +1,120 @@ +# generated from colcon_zsh/shell/template/prefix.zsh.em + +# This script extends the environment with all packages contained in this +# prefix path. + +# a zsh script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)" +else + _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to convert array-like strings into arrays +# to workaround SH_WORD_SPLIT not being set +_colcon_prefix_zsh_convert_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prefix_zsh_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prefix_zsh_prepend_unique_value_IFS="$IFS" + IFS=":" + # start with the new value + _all_values="$_value" + # workaround SH_WORD_SPLIT not being set + _colcon_prefix_zsh_convert_to_array _values + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS" + unset _colcon_prefix_zsh_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# add this prefix to the COLCON_PREFIX_PATH +_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX" +unset _colcon_prefix_zsh_prepend_unique_value +unset _colcon_prefix_zsh_convert_to_array + +# check environment variable for custom Python executable +if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then + if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then + echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" + return 1 + fi + _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" +else + # try the Python executable known at configure time + _colcon_python_executable="/usr/bin/python3" + # if it doesn't exist try a fall back + if [ ! -f "$_colcon_python_executable" ]; then + if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then + echo "error: unable to find python3 executable" + return 1 + fi + _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` + fi +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# get all commands in topological order +_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)" +unset _colcon_python_executable +if [ -n "$COLCON_TRACE" ]; then + echo "Execute generated script:" + echo "<<<" + echo "${_colcon_ordered_commands}" + echo ">>>" +fi +eval "${_colcon_ordered_commands}" +unset _colcon_ordered_commands + +unset _colcon_prefix_sh_source_script + +unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common b/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common new file mode 100644 index 0000000000..cb50e1c622 --- /dev/null +++ b/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common @@ -0,0 +1 @@ +backward_ros;ament_lint_auto;ament_lint_common \ No newline at end of file diff --git a/install/moveit_common/share/ament_index/resource_index/packages/moveit_common b/install/moveit_common/share/ament_index/resource_index/packages/moveit_common new file mode 100644 index 0000000000..e69de29bb2 diff --git a/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common b/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common new file mode 100644 index 0000000000..6350bc15a2 --- /dev/null +++ b/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common @@ -0,0 +1 @@ +/opt/ros/humble \ No newline at end of file diff --git a/install/moveit_common/share/colcon-core/packages/moveit_common b/install/moveit_common/share/colcon-core/packages/moveit_common new file mode 100644 index 0000000000..64e2ddc3bc --- /dev/null +++ b/install/moveit_common/share/colcon-core/packages/moveit_common @@ -0,0 +1 @@ +backward_ros \ No newline at end of file diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake new file mode 100644 index 0000000000..b2fc2d01a0 --- /dev/null +++ b/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake @@ -0,0 +1,30 @@ +# Copyright 2021 PickNik Inc. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the PickNik Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +include("${moveit_common_DIR}/moveit_package.cmake") diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake new file mode 100644 index 0000000000..0f7d27f124 --- /dev/null +++ b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake @@ -0,0 +1,14 @@ +# generated from ament/cmake/core/templates/nameConfig-version.cmake.in +set(PACKAGE_VERSION "2.5.1") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake new file mode 100644 index 0000000000..9ff6072903 --- /dev/null +++ b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake @@ -0,0 +1,42 @@ +# generated from ament/cmake/core/templates/nameConfig.cmake.in + +# prevent multiple inclusion +if(_moveit_common_CONFIG_INCLUDED) + # ensure to keep the found flag the same + if(NOT DEFINED moveit_common_FOUND) + # explicitly set it to FALSE, otherwise CMake will set it to TRUE + set(moveit_common_FOUND FALSE) + elseif(NOT moveit_common_FOUND) + # use separate condition to avoid uninitialized variable warning + set(moveit_common_FOUND FALSE) + endif() + return() +endif() +set(_moveit_common_CONFIG_INCLUDED TRUE) + +# output package information +if(NOT moveit_common_FIND_QUIETLY) + message(STATUS "Found moveit_common: 2.5.1 (${moveit_common_DIR})") +endif() + +# warn when using a deprecated package +if(NOT "" STREQUAL "") + set(_msg "Package 'moveit_common' is deprecated") + # append custom deprecation text if available + if(NOT "" STREQUAL "TRUE") + set(_msg "${_msg} ()") + endif() + # optionally quiet the deprecation message + if(NOT ${moveit_common_DEPRECATED_QUIET}) + message(DEPRECATION "${_msg}") + endif() +endif() + +# flag package as ament-based to distinguish it after being find_package()-ed +set(moveit_common_FOUND_AMENT_PACKAGE TRUE) + +# include all config extra files +set(_extras "moveit_common-extras.cmake") +foreach(_extra ${_extras}) + include("${moveit_common_DIR}/${_extra}") +endforeach() diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake new file mode 100644 index 0000000000..1fed492e2d --- /dev/null +++ b/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake @@ -0,0 +1,81 @@ +# Copyright 2021 PickNik Inc. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the PickNik Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +macro(moveit_package) + # Set ${PROJECT_NAME}_VERSION + find_package(ament_cmake REQUIRED) + ament_package_xml() + + # Enable backward_ros on every moveit package + find_package(backward_ros QUIET) + + if(NOT "${CMAKE_CXX_STANDARD}") + set(CMAKE_CXX_STANDARD 17) + endif() + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) + + if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC") + # Enable warnings + add_compile_options(-Wall -Wextra + -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual + -Wno-unused-parameter -Wno-unused-function) + else() + # Defaults for Microsoft C++ compiler + add_compile_options(/W3 /wd4251 /wd4068 /wd4275) + + # https://blog.kitware.com/create-dlls-on-windows-without-declspec-using-new-cmake-export-all-feature/ + set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + + # Enable Math Constants + # https://docs.microsoft.com/en-us/cpp/c-runtime-library/math-constants?view=vs-2019 + add_compile_definitions( + _USE_MATH_DEFINES + ) + endif() + + option(MOVEIT_CI_WARNINGS "Enable all warnings used by CI" ON) + if(MOVEIT_CI_WARNINGS) + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") + add_compile_options(-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual) + # This too often has false-positives + add_compile_options(-Wno-maybe-uninitialized) + endif() + if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") + add_compile_options(-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual) + endif() + endif() + + set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + + if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + message("${PROJECT_NAME}: You did not request a specific build type: Choosing 'Release' for maximum performance") + set(CMAKE_BUILD_TYPE Release) + endif() +endmacro() diff --git a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv new file mode 100644 index 0000000000..79d4c95b55 --- /dev/null +++ b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh new file mode 100644 index 0000000000..02e441b753 --- /dev/null +++ b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh @@ -0,0 +1,4 @@ +# copied from +# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh + +ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/environment/path.dsv b/install/moveit_common/share/moveit_common/environment/path.dsv new file mode 100644 index 0000000000..b94426af08 --- /dev/null +++ b/install/moveit_common/share/moveit_common/environment/path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate-if-exists;PATH;bin diff --git a/install/moveit_common/share/moveit_common/environment/path.sh b/install/moveit_common/share/moveit_common/environment/path.sh new file mode 100644 index 0000000000..e59b749a89 --- /dev/null +++ b/install/moveit_common/share/moveit_common/environment/path.sh @@ -0,0 +1,5 @@ +# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh + +if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then + ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin" +fi diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv new file mode 100644 index 0000000000..e119f32cba --- /dev/null +++ b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;CMAKE_PREFIX_PATH; diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 new file mode 100644 index 0000000000..d03facc1a4 --- /dev/null +++ b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 @@ -0,0 +1,3 @@ +# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em + +colcon_prepend_unique_value CMAKE_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh new file mode 100644 index 0000000000..a948e685ba --- /dev/null +++ b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh @@ -0,0 +1,3 @@ +# generated from colcon_core/shell/template/hook_prepend_value.sh.em + +_colcon_prepend_unique_value CMAKE_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/local_setup.bash b/install/moveit_common/share/moveit_common/local_setup.bash new file mode 100644 index 0000000000..49782f2461 --- /dev/null +++ b/install/moveit_common/share/moveit_common/local_setup.bash @@ -0,0 +1,46 @@ +# generated from ament_package/template/package_level/local_setup.bash.in + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/local_setup.dsv b/install/moveit_common/share/moveit_common/local_setup.dsv new file mode 100644 index 0000000000..6aaf2a9457 --- /dev/null +++ b/install/moveit_common/share/moveit_common/local_setup.dsv @@ -0,0 +1,2 @@ +source;share/moveit_common/environment/ament_prefix_path.sh +source;share/moveit_common/environment/path.sh diff --git a/install/moveit_common/share/moveit_common/local_setup.sh b/install/moveit_common/share/moveit_common/local_setup.sh new file mode 100644 index 0000000000..818849912a --- /dev/null +++ b/install/moveit_common/share/moveit_common/local_setup.sh @@ -0,0 +1,184 @@ +# generated from ament_package/template/package_level/local_setup.sh.in + +# since this file is sourced use either the provided AMENT_CURRENT_PREFIX +# or fall back to the destination set at configure time +: ${AMENT_CURRENT_PREFIX:="/home/henry/ws_moveit2/src/moveit2/install/moveit_common"} +if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then + if [ -z "$COLCON_CURRENT_PREFIX" ]; then + echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \ + "exist. Consider sourcing a different extension than '.sh'." 1>&2 + else + AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" + fi +fi + +# function to append values to environment variables +# using colons as separators and avoiding leading separators +ament_append_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # avoid leading separator + eval _values=\"\$$_listname\" + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + _ament_append_value_IFS=$IFS + unset IFS + eval export $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + IFS=$_ament_append_value_IFS + unset _ament_append_value_IFS + fi + unset _values + + unset _value + unset _listname +} + +# function to append non-duplicate values to environment variables +# using colons as separators and avoiding leading separators +ament_append_unique_value() { + # arguments + _listname=$1 + _value=$2 + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\$$_listname + _duplicate= + _ament_append_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ $_item = $_value ]; then + _duplicate=1 + fi + done + unset _item + + # append only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid leading separator + if [ -z "$_values" ]; then + eval $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + fi + fi + IFS=$_ament_append_unique_value_IFS + unset _ament_append_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# function to prepend non-duplicate values to environment variables +# using colons as separators and avoiding trailing separators +ament_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\"\$$_listname\" + _duplicate= + _ament_prepend_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ "$_item" = "$_value" ]; then + _duplicate=1 + fi + done + unset _item + + # prepend only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid trailing separator + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval export $_listname=\"$_value:\$$_listname\" + #eval echo "prepend list \$$_listname" + fi + fi + IFS=$_ament_prepend_unique_value_IFS + unset _ament_prepend_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# list all environment hooks of this package +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_common/environment/ament_prefix_path.sh" +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_common/environment/path.sh" + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS + fi + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + if [ -f "$_hook" ]; then + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + # trace output + if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_hook\"" + fi + . "$_hook" + fi + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +# reset AMENT_CURRENT_PREFIX after each package +# allowing to source multiple package-level setup files +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/local_setup.zsh b/install/moveit_common/share/moveit_common/local_setup.zsh new file mode 100644 index 0000000000..fe161be53d --- /dev/null +++ b/install/moveit_common/share/moveit_common/local_setup.zsh @@ -0,0 +1,59 @@ +# generated from ament_package/template/package_level/local_setup.zsh.in + +AMENT_SHELL=zsh + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# function to convert array-like strings into arrays +# to wordaround SH_WORD_SPLIT not being set +ament_zsh_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +# the package-level local_setup file unsets AMENT_CURRENT_PREFIX +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.bash b/install/moveit_common/share/moveit_common/package.bash new file mode 100644 index 0000000000..15d140b8ae --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.bash @@ -0,0 +1,39 @@ +# generated from colcon_bash/shell/template/package.bash.em + +# This script extends the environment for this package. + +# a bash script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" +else + _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_bash_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh script of this package +_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_common/package.sh" + +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts +COLCON_CURRENT_PREFIX="$_colcon_package_bash_COLCON_CURRENT_PREFIX" + +# source bash hooks +_colcon_package_bash_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.bash" + +unset COLCON_CURRENT_PREFIX + +unset _colcon_package_bash_source_script +unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.dsv b/install/moveit_common/share/moveit_common/package.dsv new file mode 100644 index 0000000000..73d9cbcd41 --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.dsv @@ -0,0 +1,8 @@ +source;share/moveit_common/hook/cmake_prefix_path.ps1 +source;share/moveit_common/hook/cmake_prefix_path.dsv +source;share/moveit_common/hook/cmake_prefix_path.sh +source;share/moveit_common/local_setup.bash +source;share/moveit_common/local_setup.dsv +source;share/moveit_common/local_setup.ps1 +source;share/moveit_common/local_setup.sh +source;share/moveit_common/local_setup.zsh diff --git a/install/moveit_common/share/moveit_common/package.ps1 b/install/moveit_common/share/moveit_common/package.ps1 new file mode 100644 index 0000000000..47a325104f --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.ps1 @@ -0,0 +1,116 @@ +# generated from colcon_powershell/shell/template/package.ps1.em + +# function to append a value to a variable +# which uses colons as separators +# duplicates as well as leading separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_append_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + $_duplicate="" + # start with no values + $_all_values="" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -eq $_value) { + $_duplicate="1" + } + if ($_all_values) { + $_all_values="${_all_values};$_" + } else { + $_all_values="$_" + } + } + } + } + # append only non-duplicates + if (!$_duplicate) { + # avoid leading separator + if ($_all_values) { + $_all_values="${_all_values};${_value}" + } else { + $_all_values="${_value}" + } + } + + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_prepend_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + # start with the new value + $_all_values="$_value" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -ne $_value) { + # keep non-duplicate values + $_all_values="${_all_values};$_" + } + } + } + } + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +function colcon_package_source_powershell_script { + param ( + $_colcon_package_source_powershell_script + ) + # source script with conditional trace output + if (Test-Path $_colcon_package_source_powershell_script) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_package_source_powershell_script'" + } + . "$_colcon_package_source_powershell_script" + } else { + Write-Error "not found: '$_colcon_package_source_powershell_script'" + } +} + + +# a powershell script is able to determine its own path +# the prefix is two levels up from the package specific share directory +$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName + +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_common/hook/cmake_prefix_path.ps1" +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_common/local_setup.ps1" + +Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.sh b/install/moveit_common/share/moveit_common/package.sh new file mode 100644 index 0000000000..ea7c7d2c99 --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.sh @@ -0,0 +1,87 @@ +# generated from colcon_core/shell/template/package.sh.em + +# This script extends the environment for this package. + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prepend_unique_value_IFS=$IFS + IFS=":" + # start with the new value + _all_values="$_value" + # workaround SH_WORD_SPLIT not being set in zsh + if [ "$(command -v colcon_zsh_convert_to_array)" ]; then + colcon_zsh_convert_to_array _values + fi + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS=$_colcon_prepend_unique_value_IFS + unset _colcon_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# since a plain shell script can't determine its own path when being sourced +# either use the provided COLCON_CURRENT_PREFIX +# or fall back to the build time prefix (if it exists) +_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_common" +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then + echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 + unset _colcon_package_sh_COLCON_CURRENT_PREFIX + return 1 + fi + COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" +fi +unset _colcon_package_sh_COLCON_CURRENT_PREFIX + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo "# . \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh hooks +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/hook/cmake_prefix_path.sh" +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.sh" + +unset _colcon_package_sh_source_script +unset COLCON_CURRENT_PREFIX + +# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_common/share/moveit_common/package.xml b/install/moveit_common/share/moveit_common/package.xml new file mode 100644 index 0000000000..a015632281 --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.xml @@ -0,0 +1,29 @@ + + + + moveit_common + 2.5.1 + Common support functionality used throughout MoveIt + Henning Kayser + Tyler Weaver + MoveIt Release Team + + BSD + + http://moveit.ros.org + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Lior Lustgarten + + ament_cmake + + backward_ros + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/install/moveit_common/share/moveit_common/package.zsh b/install/moveit_common/share/moveit_common/package.zsh new file mode 100644 index 0000000000..2534236587 --- /dev/null +++ b/install/moveit_common/share/moveit_common/package.zsh @@ -0,0 +1,50 @@ +# generated from colcon_zsh/shell/template/package.zsh.em + +# This script extends the environment for this package. + +# a zsh script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" +else + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_zsh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# function to convert array-like strings into arrays +# to workaround SH_WORD_SPLIT not being set +colcon_zsh_convert_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# source sh script of this package +_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_common/package.sh" +unset convert_zsh_to_array + +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts +COLCON_CURRENT_PREFIX="$_colcon_package_zsh_COLCON_CURRENT_PREFIX" + +# source zsh hooks +_colcon_package_zsh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.zsh" + +unset COLCON_CURRENT_PREFIX + +unset _colcon_package_zsh_source_script +unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils b/install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils new file mode 100644 index 0000000000..e69de29bb2 diff --git a/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils b/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils new file mode 100644 index 0000000000..c4b091727f --- /dev/null +++ b/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils @@ -0,0 +1 @@ +ament_index_python:launch:launch_param_builder:launch_ros:srdfdom \ No newline at end of file diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml new file mode 100644 index 0000000000..47002cc036 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml @@ -0,0 +1,12 @@ +planning_plugin: chomp_interface/CHOMPPlanner +enable_failure_recovery: true +jiggle_fraction: 0.05 +request_adapters: >- + default_planner_request_adapters/AddTimeParameterization + default_planner_request_adapters/ResolveConstraintFrames + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints +ridge_factor: 0.01 +start_state_max_bounds_error: 0.1 diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml new file mode 100644 index 0000000000..dda05494b7 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml @@ -0,0 +1,129 @@ +planner_configs: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: true # Attempt to shortcut all new solution paths + hybridize: true # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml new file mode 100644 index 0000000000..a5d0ea8522 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml @@ -0,0 +1,10 @@ +planning_plugin: ompl_interface/OMPLPlanner +start_state_max_bounds_error: 0.1 +jiggle_fraction: 0.05 +request_adapters: >- + default_planner_request_adapters/AddTimeParameterization + default_planner_request_adapters/ResolveConstraintFrames + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml new file mode 100644 index 0000000000..92fd5907be --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml @@ -0,0 +1,6 @@ +planning_plugin: pilz_industrial_motion_planner/CommandPlanner +request_adapters: "" +default_planner_config: PTP +capabilities: >- + pilz_industrial_motion_planner/MoveGroupSequenceAction + pilz_industrial_motion_planner/MoveGroupSequenceService diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml new file mode 100644 index 0000000000..6565e256d4 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml @@ -0,0 +1,9 @@ +planning_plugin: trajopt_interface/TrajOptPlanner +start_state_max_bounds_error: 0.1 +jiggle_fraction: 0.05 +request_adapters: >- + default_planner_request_adapters/AddTimeParameterization + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv new file mode 100644 index 0000000000..79d4c95b55 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 new file mode 100644 index 0000000000..26b9997579 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 @@ -0,0 +1,3 @@ +# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em + +colcon_prepend_unique_value AMENT_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh new file mode 100644 index 0000000000..f3041f688a --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh @@ -0,0 +1,3 @@ +# generated from colcon_core/shell/template/hook_prepend_value.sh.em + +_colcon_prepend_unique_value AMENT_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv new file mode 100644 index 0000000000..257067d44d --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;PYTHONPATH;lib/python3.10/site-packages diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 new file mode 100644 index 0000000000..caffe83fd5 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 @@ -0,0 +1,3 @@ +# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em + +colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\lib/python3.10/site-packages" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh new file mode 100644 index 0000000000..660c34836d --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh @@ -0,0 +1,3 @@ +# generated from colcon_core/shell/template/hook_prepend_value.sh.em + +_colcon_prepend_unique_value PYTHONPATH "$COLCON_CURRENT_PREFIX/lib/python3.10/site-packages" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.bash b/install/moveit_configs_utils/share/moveit_configs_utils/package.bash new file mode 100644 index 0000000000..48f4f92f22 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.bash @@ -0,0 +1,31 @@ +# generated from colcon_bash/shell/template/package.bash.em + +# This script extends the environment for this package. + +# a bash script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" +else + _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_bash_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh script of this package +_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_configs_utils/package.sh" + +unset _colcon_package_bash_source_script +unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv new file mode 100644 index 0000000000..358282cdc6 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv @@ -0,0 +1,6 @@ +source;share/moveit_configs_utils/hook/pythonpath.ps1 +source;share/moveit_configs_utils/hook/pythonpath.dsv +source;share/moveit_configs_utils/hook/pythonpath.sh +source;share/moveit_configs_utils/hook/ament_prefix_path.ps1 +source;share/moveit_configs_utils/hook/ament_prefix_path.dsv +source;share/moveit_configs_utils/hook/ament_prefix_path.sh diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 new file mode 100644 index 0000000000..11c9459d60 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 @@ -0,0 +1,116 @@ +# generated from colcon_powershell/shell/template/package.ps1.em + +# function to append a value to a variable +# which uses colons as separators +# duplicates as well as leading separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_append_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + $_duplicate="" + # start with no values + $_all_values="" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -eq $_value) { + $_duplicate="1" + } + if ($_all_values) { + $_all_values="${_all_values};$_" + } else { + $_all_values="$_" + } + } + } + } + # append only non-duplicates + if (!$_duplicate) { + # avoid leading separator + if ($_all_values) { + $_all_values="${_all_values};${_value}" + } else { + $_all_values="${_value}" + } + } + + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_prepend_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + # start with the new value + $_all_values="$_value" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -ne $_value) { + # keep non-duplicate values + $_all_values="${_all_values};$_" + } + } + } + } + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +function colcon_package_source_powershell_script { + param ( + $_colcon_package_source_powershell_script + ) + # source script with conditional trace output + if (Test-Path $_colcon_package_source_powershell_script) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_package_source_powershell_script'" + } + . "$_colcon_package_source_powershell_script" + } else { + Write-Error "not found: '$_colcon_package_source_powershell_script'" + } +} + + +# a powershell script is able to determine its own path +# the prefix is two levels up from the package specific share directory +$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName + +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_configs_utils/hook/pythonpath.ps1" +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_configs_utils/hook/ament_prefix_path.ps1" + +Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.sh b/install/moveit_configs_utils/share/moveit_configs_utils/package.sh new file mode 100644 index 0000000000..964075e3fb --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.sh @@ -0,0 +1,87 @@ +# generated from colcon_core/shell/template/package.sh.em + +# This script extends the environment for this package. + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prepend_unique_value_IFS=$IFS + IFS=":" + # start with the new value + _all_values="$_value" + # workaround SH_WORD_SPLIT not being set in zsh + if [ "$(command -v colcon_zsh_convert_to_array)" ]; then + colcon_zsh_convert_to_array _values + fi + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS=$_colcon_prepend_unique_value_IFS + unset _colcon_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# since a plain shell script can't determine its own path when being sourced +# either use the provided COLCON_CURRENT_PREFIX +# or fall back to the build time prefix (if it exists) +_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils" +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then + echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 + unset _colcon_package_sh_COLCON_CURRENT_PREFIX + return 1 + fi + COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" +fi +unset _colcon_package_sh_COLCON_CURRENT_PREFIX + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo "# . \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh hooks +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_configs_utils/hook/pythonpath.sh" +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_configs_utils/hook/ament_prefix_path.sh" + +unset _colcon_package_sh_source_script +unset COLCON_CURRENT_PREFIX + +# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.xml b/install/moveit_configs_utils/share/moveit_configs_utils/package.xml new file mode 100644 index 0000000000..8847721002 --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.xml @@ -0,0 +1,24 @@ + + + + moveit_configs_utils + 2.5.1 + Python library for loading moveit config parameters in launch files + MoveIt Release Team + BSD + Jafar Abdi + David V. Lu!! + + ament_index_python + launch_param_builder + launch + launch_ros + srdfdom + + ament_lint_auto + ament_lint_common + + + ament_python + + diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh b/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh new file mode 100644 index 0000000000..5938d0b95e --- /dev/null +++ b/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh @@ -0,0 +1,42 @@ +# generated from colcon_zsh/shell/template/package.zsh.em + +# This script extends the environment for this package. + +# a zsh script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" +else + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_zsh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# function to convert array-like strings into arrays +# to workaround SH_WORD_SPLIT not being set +colcon_zsh_convert_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# source sh script of this package +_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_configs_utils/package.sh" +unset convert_zsh_to_array + +unset _colcon_package_zsh_source_script +unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_core/share/colcon-core/packages/moveit_core b/install/moveit_core/share/colcon-core/packages/moveit_core new file mode 100644 index 0000000000..3dbf09e4b0 --- /dev/null +++ b/install/moveit_core/share/colcon-core/packages/moveit_core @@ -0,0 +1 @@ +angles:assimp:boost:bullet:common_interfaces:eigen:eigen3_cmake_module:eigen_stl_containers:geometric_shapes:geometry_msgs:kdl_parser:libfcl-dev:moveit_common:moveit_msgs:octomap:octomap_msgs:pluginlib:pybind11_vendor:random_numbers:rclcpp:ruckig:sensor_msgs:shape_msgs:srdfdom:std_msgs:tf2:tf2_eigen:tf2_geometry_msgs:trajectory_msgs:urdf:urdfdom:urdfdom_headers:visualization_msgs \ No newline at end of file diff --git a/install/moveit_core/share/moveit_core/package.bash b/install/moveit_core/share/moveit_core/package.bash new file mode 100644 index 0000000000..fb242794b1 --- /dev/null +++ b/install/moveit_core/share/moveit_core/package.bash @@ -0,0 +1,31 @@ +# generated from colcon_bash/shell/template/package.bash.em + +# This script extends the environment for this package. + +# a bash script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" +else + _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_bash_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh script of this package +_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_core/package.sh" + +unset _colcon_package_bash_source_script +unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_core/share/moveit_core/package.dsv b/install/moveit_core/share/moveit_core/package.dsv new file mode 100644 index 0000000000..e69de29bb2 diff --git a/install/moveit_core/share/moveit_core/package.ps1 b/install/moveit_core/share/moveit_core/package.ps1 new file mode 100644 index 0000000000..4198e42ecf --- /dev/null +++ b/install/moveit_core/share/moveit_core/package.ps1 @@ -0,0 +1,108 @@ +# generated from colcon_powershell/shell/template/package.ps1.em + +# function to append a value to a variable +# which uses colons as separators +# duplicates as well as leading separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_append_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + $_duplicate="" + # start with no values + $_all_values="" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -eq $_value) { + $_duplicate="1" + } + if ($_all_values) { + $_all_values="${_all_values};$_" + } else { + $_all_values="$_" + } + } + } + } + # append only non-duplicates + if (!$_duplicate) { + # avoid leading separator + if ($_all_values) { + $_all_values="${_all_values};${_value}" + } else { + $_all_values="${_value}" + } + } + + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_prepend_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + # start with the new value + $_all_values="$_value" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -ne $_value) { + # keep non-duplicate values + $_all_values="${_all_values};$_" + } + } + } + } + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +function colcon_package_source_powershell_script { + param ( + $_colcon_package_source_powershell_script + ) + # source script with conditional trace output + if (Test-Path $_colcon_package_source_powershell_script) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_package_source_powershell_script'" + } + . "$_colcon_package_source_powershell_script" + } else { + Write-Error "not found: '$_colcon_package_source_powershell_script'" + } +} + + diff --git a/install/moveit_core/share/moveit_core/package.sh b/install/moveit_core/share/moveit_core/package.sh new file mode 100644 index 0000000000..7d7278e5f0 --- /dev/null +++ b/install/moveit_core/share/moveit_core/package.sh @@ -0,0 +1,52 @@ +# generated from colcon_core/shell/template/package.sh.em + +# This script extends the environment for this package. + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prepend_unique_value_IFS=$IFS + IFS=":" + # start with the new value + _all_values="$_value" + # workaround SH_WORD_SPLIT not being set in zsh + if [ "$(command -v colcon_zsh_convert_to_array)" ]; then + colcon_zsh_convert_to_array _values + fi + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS=$_colcon_prepend_unique_value_IFS + unset _colcon_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_core/share/moveit_core/package.zsh b/install/moveit_core/share/moveit_core/package.zsh new file mode 100644 index 0000000000..82fdae26eb --- /dev/null +++ b/install/moveit_core/share/moveit_core/package.zsh @@ -0,0 +1,42 @@ +# generated from colcon_zsh/shell/template/package.zsh.em + +# This script extends the environment for this package. + +# a zsh script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" +else + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_zsh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# function to convert array-like strings into arrays +# to workaround SH_WORD_SPLIT not being set +colcon_zsh_convert_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# source sh script of this package +_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_core/package.sh" +unset convert_zsh_to_array + +unset _colcon_package_zsh_source_script +unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support new file mode 100644 index 0000000000..476e71c3f8 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support @@ -0,0 +1 @@ +xacro \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support new file mode 100644 index 0000000000..e69de29bb2 diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support new file mode 100644 index 0000000000..6350bc15a2 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support @@ -0,0 +1 @@ +/opt/ros/humble \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support new file mode 100644 index 0000000000..476e71c3f8 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support @@ -0,0 +1 @@ +xacro \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake new file mode 100644 index 0000000000..0f7d27f124 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake @@ -0,0 +1,14 @@ +# generated from ament/cmake/core/templates/nameConfig-version.cmake.in +set(PACKAGE_VERSION "2.5.1") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake new file mode 100644 index 0000000000..fbcf5ca572 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake @@ -0,0 +1,42 @@ +# generated from ament/cmake/core/templates/nameConfig.cmake.in + +# prevent multiple inclusion +if(_moveit_resources_prbt_support_CONFIG_INCLUDED) + # ensure to keep the found flag the same + if(NOT DEFINED moveit_resources_prbt_support_FOUND) + # explicitly set it to FALSE, otherwise CMake will set it to TRUE + set(moveit_resources_prbt_support_FOUND FALSE) + elseif(NOT moveit_resources_prbt_support_FOUND) + # use separate condition to avoid uninitialized variable warning + set(moveit_resources_prbt_support_FOUND FALSE) + endif() + return() +endif() +set(_moveit_resources_prbt_support_CONFIG_INCLUDED TRUE) + +# output package information +if(NOT moveit_resources_prbt_support_FIND_QUIETLY) + message(STATUS "Found moveit_resources_prbt_support: 2.5.1 (${moveit_resources_prbt_support_DIR})") +endif() + +# warn when using a deprecated package +if(NOT "" STREQUAL "") + set(_msg "Package 'moveit_resources_prbt_support' is deprecated") + # append custom deprecation text if available + if(NOT "" STREQUAL "TRUE") + set(_msg "${_msg} ()") + endif() + # optionally quiet the deprecation message + if(NOT ${moveit_resources_prbt_support_DEPRECATED_QUIET}) + message(DEPRECATION "${_msg}") + endif() +endif() + +# flag package as ament-based to distinguish it after being find_package()-ed +set(moveit_resources_prbt_support_FOUND_AMENT_PACKAGE TRUE) + +# include all config extra files +set(_extras "") +foreach(_extra ${_extras}) + include("${moveit_resources_prbt_support_DIR}/${_extra}") +endforeach() diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml new file mode 100644 index 0000000000..9ad1cdf941 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml @@ -0,0 +1,77 @@ +# +# Copyright © 2018 Pilz GmbH & Co. KG +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# FILE DESCRIPTION: +# +# This file declares the different controller types which can then be +# instantiated by the controller manager. In this file only controllers +# for the manipulator are declared (no gripper). +# +# See also: http://wiki.ros.org/joint_trajectory_controller?distro=lunar +# + +## joint_names +joint_names: [prbt_joint_1, prbt_joint_2, prbt_joint_3, prbt_joint_4, prbt_joint_5, prbt_joint_6] + +## control_mode_adapter +max_command_silence: 0.5 + +## joint_state_controller (needed to obtain /joint_states) +manipulator_joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + +## joint trajectory controller +manipulator_joint_trajectory_controller: + type: position_controllers/PilzJointTrajectoryController + joints: + - prbt_joint_1 + - prbt_joint_2 + - prbt_joint_3 + - prbt_joint_4 + - prbt_joint_5 + - prbt_joint_6 + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 0.05 + prbt_joint_1: {trajectory: 0.157, goal: 0.01} + prbt_joint_2: {trajectory: 0.157, goal: 0.01} + prbt_joint_3: {trajectory: 0.157, goal: 0.01} + prbt_joint_4: {trajectory: 0.157, goal: 0.01} + prbt_joint_5: {trajectory: 0.157, goal: 0.01} + prbt_joint_6: {trajectory: 0.157, goal: 0.01} + stop_trajectory_duration: 0.2 + state_publish_rate: 25 + action_monitor_rate: 10 + required_drive_mode: 7 + limits: + prbt_joint_1: + has_acceleration_limits: true + max_acceleration: 6.0 + prbt_joint_2: + has_acceleration_limits: true + max_acceleration: 6.0 + prbt_joint_3: + has_acceleration_limits: true + max_acceleration: 6.0 + prbt_joint_4: + has_acceleration_limits: true + max_acceleration: 6.0 + prbt_joint_5: + has_acceleration_limits: true + max_acceleration: 6.0 + prbt_joint_6: + has_acceleration_limits: true + max_acceleration: 6.0 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml new file mode 100644 index 0000000000..4e196d3087 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml @@ -0,0 +1,52 @@ +# +# Copyright © 2018 Pilz GmbH & Co. KG +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# FILE DESCRIPTION: +# +# This file mappes the robot joints to the corresponding CAN-IDs. In this file +# only the robot joints are considered (no gripper joint). +# + +name: manipulator + +bus: + device: can0 +sync: + interval_ms: 10 + overflow: 0 + +defaults: + eds_pkg: moveit_resources_prbt_support + eds_file: "config/prbt_0_1.dcf" + +nodes: + prbt_joint_1: + id: 3 + braketest_required: true + prbt_joint_2: + id: 4 + braketest_required: true + prbt_joint_3: + id: 5 + braketest_required: true + prbt_joint_4: + id: 6 + braketest_required: true + prbt_joint_5: + id: 7 + braketest_required: true + prbt_joint_6: + id: 8 + braketest_required: true diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf new file mode 100644 index 0000000000..090290b13c --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf @@ -0,0 +1,2052 @@ +[FileInfo] +CreatedBy=Dirk Osswald, SCHUNK GmbH & Co. KG +ModifiedBy=Pilz GmbH & Co. KG +Description=PRBT Electronic Data Sheet +CreationTime=01:33PM +CreationDate=05-23-2013 +ModificationTime=00:00PM +ModificationDate=09-07-2018 +FileName=prbt_0_1.dcf +FileVersion=0x03 +FileRevision=0x01 +EDSVersion=4.0 + +[DeviceInfo] +VendorName=Pilz GmbH & Co. KG +OrderCode=0 +BaudRate_10=0 +BaudRate_20=0 +BaudRate_50=1 +BaudRate_125=1 +BaudRate_250=1 +BaudRate_500=1 +BaudRate_800=0 +BaudRate_1000=1 +SimpleBootUpMaster=0 +SimpleBootUpSlave=1 +Granularity=8 +DynamicChannelsSupported=0 +CompactPDO=0 +GroupMessaging=0 +NrOfRXPDO=2 +NrOfTXPDO=4 +LSS_Supported=1 + +[DummyUsage] +Dummy0001=0 +Dummy0002=1 +Dummy0003=1 +Dummy0004=1 +Dummy0005=1 +Dummy0006=1 +Dummy0007=1 + +[Comments] +Lines=0 + +[MandatoryObjects] +SupportedObjects=3 +1=0x1000 +2=0x1001 +3=0x1018 + +[1000] +ParameterName=Device type +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 +ObjFlags=0x0 + +[1001] +ParameterName=Error register +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +PDOMapping=0 +ObjFlags=0x0 + +[1018] +ParameterName=Identity Object +ObjectType=0x9 +SubNumber=5 +ObjFlags=0x0 + +[1018sub0] +ParameterName=number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=4 +PDOMapping=0 +LowLimit=1 +HighLimit=4 +ObjFlags=0 + +[1018sub1] +ParameterName=Vendor ID +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 +ObjFlags=0 + +[1018sub2] +ParameterName=Product code +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 +ObjFlags=0 + +[1018sub3] +ParameterName=Revision number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 +ObjFlags=0 + +[1018sub4] +ParameterName=Serial number +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 +ObjFlags=0 + +[OptionalObjects] +SupportedObjects=62 +1=0x1002 +2=0x1003 +3=0x1005 +4=0x1008 +5=0x1009 +6=0x100A +7=0x100C +8=0x100D +9=0x1014 +10=0x1016 +11=0x1017 +12=0x1200 +13=0x1400 +14=0x1401 +15=0x1600 +16=0x1601 +17=0x1800 +18=0x1801 +19=0x1802 +20=0x1803 +21=0x1A00 +22=0x1A01 +23=0x1A02 +24=0x1A03 +25=0x20A0 +26=0x6040 +27=0x6041 +28=0x6042 +29=0x6043 +30=0x6044 +31=0x6046 +32=0x6048 +33=0x6049 +34=0x604C +35=0x6060 +36=0x6061 +37=0x6062 +38=0x6064 +39=0x6065 +40=0x606B +41=0x606C +42=0x6073 +43=0x6075 +44=0x6077 +45=0x607A +46=0x607C +47=0x607D +48=0x6081 +49=0x6083 +50=0x6086 +51=0x6098 +52=0x60B2 +53=0x60C0 +54=0x60C1 +55=0x60C2 +56=0x60C3 +57=0x60C4 +58=0x60F4 +59=0x60FD +60=0x60FE +61=0x6502 +62=0x2060 + +[1002] +ParameterName=Manufacturer Status Register +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=0 + +[1003] +ParameterName=Pre-defined Error Field +ObjectType=0x8 +SubNumber=3 +ObjFlags=0x0 + +[1003sub0] +ParameterName=Number of Errors +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0 + +[1003sub1] +ParameterName=Standard Error Field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 +ObjFlags=2 + +[1003sub2] +ParameterName=Standard Error Field +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0 +PDOMapping=0 +ObjFlags=2 + +[1005] +ParameterName=COB-ID SYNC message +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x00000080 +PDOMapping=0 +ObjFlags=0x0 + +[1008] +ParameterName=Manufacturer device name +ObjectType=0x7 +DataType=0x0009 +AccessType=const +PDOMapping=0 +ObjFlags=0x0 + +[1009] +ParameterName=Manufacturer hardware version +ObjectType=0x7 +DataType=0x0009 +AccessType=const +PDOMapping=0 +ObjFlags=0x0 + +[100A] +ParameterName=Manufacturer software version +ObjectType=0x7 +DataType=0x0009 +AccessType=const +PDOMapping=0 +ObjFlags=0x0 + +[100C] +ParameterName=Guard time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x00000000 +PDOMapping=0 +ObjFlags=0x0 + +[100D] +ParameterName=Life time factor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0x00000000 +PDOMapping=0 +ObjFlags=0x0 + +[1014] +ParameterName=COB-ID EMCY message +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x80 +PDOMapping=0 +ObjFlags=0x0 + +[1016] +ParameterName=Consumer Heartbeat Time +ObjectType=0x8 +SubNumber=4 +ObjFlags=0x0 + +[1016sub0] +ParameterName=Number of Entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=3 +PDOMapping=0 +LowLimit=1 +HighLimit=127 +ObjFlags=0 + +[1016sub1] +ParameterName=Consumer Heartbeat Time of Node-ID 1 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0 + +[1016sub2] +ParameterName=Consumer Heartbeat Time of Node-ID 2 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0 + +[1016sub3] +ParameterName=Consumer Heartbeat Time of Node-ID 3 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0 + +[1017] +ParameterName=Producer heartbeat time +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x00000000 +PDOMapping=0 +LowLimit=0 +HighLimit=32767 +ObjFlags=0x0 +ParameterValue=100 + +[1200] +ParameterName=1. Server SDO parameter +ObjectType=0x9 +SubNumber=3 +ObjFlags=0x0 + +[1200sub0] +ParameterName=Number of supported Entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=2 +PDOMapping=0 +ObjFlags=0 + +[1200sub1] +ParameterName=COB-ID Client -> Server (rx) +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=$NodeID + 0x600 +PDOMapping=0 +ObjFlags=0 + +[1200sub2] +ParameterName=COB-ID Server -> Client (tx) +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=$NodeID + 0x580 +PDOMapping=0 +ObjFlags=0 + +[1400] +ParameterName=1. Receive PDO parameter +ObjectType=0x9 +SubNumber=3 +ObjFlags=0x0 + +[1400sub0] +ParameterName=Largest Sub-Index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=2 +PDOMapping=0 +ObjFlags=0 + +[1400sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x200 +PDOMapping=0 +ObjFlags=0 +ParameterValue=$NODEID+0x200 + +[1400sub2] +ParameterName=Transmission Type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=255 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x1 + +[1401] +ParameterName=2. Receive PDO Parameter +ObjectType=0x9 +SubNumber=3 +ObjFlags=0x0 + +[1401sub0] +ParameterName=Largest Sub-Index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=2 +PDOMapping=0 +ObjFlags=0 + +[1401sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x300 +PDOMapping=0 +ObjFlags=0 +ParameterValue=$NODEID+0x300 + +[1401sub2] +ParameterName=Transmission Type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=255 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x1 + +[1600] +ParameterName=1. Receive PDO Mapping +ObjectType=0x9 +SubNumber=9 +ObjFlags=0x0 + +[1600sub0] +ParameterName=Number of mapped Application Objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=2 +PDOMapping=0 +LowLimit=0 +HighLimit=8 +ObjFlags=0 +ParameterValue=3 + +[1600sub1] +ParameterName=1. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60400010 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60400010 + +[1600sub2] +ParameterName=2. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60c10120 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60420010 + +[1600sub3] +ParameterName=3. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60c10120 + +[1600sub4] +ParameterName=4. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1600sub5] +ParameterName=5. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1600sub6] +ParameterName=6. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1600sub7] +ParameterName=7. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1600sub8] +ParameterName=8. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601] +ParameterName=2. Receive PDO mapping +ObjectType=0x9 +SubNumber=9 +ObjFlags=0x0 + +[1601sub0] +ParameterName=Number of mapped Application Objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=0 +HighLimit=8 +ObjFlags=0 +ParameterValue=2 + +[1601sub1] +ParameterName=1. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x607a0020 + +[1601sub2] +ParameterName=2. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60810020 + +[1601sub3] +ParameterName=3. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601sub4] +ParameterName=4. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601sub5] +ParameterName=5. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601sub6] +ParameterName=6. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601sub7] +ParameterName=7. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1601sub8] +ParameterName=8. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1800] +ParameterName=1. Transmit PDO Parameter +ObjectType=0x9 +SubNumber=4 +ObjFlags=0x0 + +[1800sub0] +ParameterName=Largest Sub-Index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=5 +PDOMapping=0 +ObjFlags=0 + +[1800sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x180 +PDOMapping=0 +ObjFlags=0 +ParameterValue=$NODEID+0x180 + +[1800sub2] +ParameterName=transmission type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=1 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x1 + +[1800sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=0 +HighLimit=32767 +ObjFlags=0 + +[1801] +ParameterName=2. Transmit PDO Parameter +ObjectType=0x9 +SubNumber=4 +ObjFlags=0x0 + +[1801sub0] +ParameterName=Largest Sub-Index supported +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=5 +PDOMapping=0 +ObjFlags=0 + +[1801sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x280 +PDOMapping=0 +ObjFlags=0 + +[1801sub2] +ParameterName=Transmission Type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=1 +PDOMapping=0 +ObjFlags=0 + +[1801sub5] +ParameterName=event timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0 + +[1802] +ParameterName=3. Transmit PDO Parameter +ObjectType=0x9 +SubNumber=4 + +[1802sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=5 +PDOMapping=0 +LowLimit=0x02 +HighLimit=0x06 + +[1802sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x380 +PDOMapping=0 +ObjFlags=0 +ParameterValue=$NODEID+0x380 + +[1802sub2] +ParameterName=Transmission Type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=1 +PDOMapping=0 +ParameterValue=0x1 + +[1802sub5] +ParameterName=Event Timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[1803] +ParameterName=4. Transmit PDO Parameter +ObjectType=0x9 +SubNumber=4 + +[1803sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=5 +PDOMapping=0 +LowLimit=0x02 +HighLimit=0x06 + +[1803sub1] +ParameterName=COB-ID used by PDO +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=$NodeID + 0x480 +PDOMapping=0 +ObjFlags=0 + +[1803sub2] +ParameterName=Transmission Type +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=254 +PDOMapping=0 + +[1803sub5] +ParameterName=Event Timer +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[1A00] +ParameterName=1. Transmit PDO Mapping +ObjectType=0x9 +SubNumber=9 +ObjFlags=0x0 + +[1A00sub0] +ParameterName=Number of mapped Application Objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=3 +PDOMapping=0 +LowLimit=0 +HighLimit=8 +ObjFlags=0 +ParameterValue=2 + +[1A00sub1] +ParameterName=1. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60410010 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60410010 + +[1A00sub2] +ParameterName=2. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60770010 +PDOMapping=0 +ObjFlags=0 +ParameterValue=0x60610008 + +[1A00sub3] +ParameterName=3. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x60640020 +PDOMapping=0 +ObjFlags=0 + +[1A00sub4] +ParameterName=4. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A00sub5] +ParameterName=5. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A00sub6] +ParameterName=6. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A00sub7] +ParameterName=7. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A00sub8] +ParameterName=8. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01] +ParameterName=2. Transmit PDO Mapping +ObjectType=0x9 +SubNumber=9 +ObjFlags=0x0 + +[1A01sub0] +ParameterName=Number of mapped Application Objects +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=2 +PDOMapping=0 +LowLimit=0 +HighLimit=8 +ObjFlags=0 + +[1A01sub1] +ParameterName=1. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x606b0020 +PDOMapping=0 +ObjFlags=0 + +[1A01sub2] +ParameterName=2. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0x606c0020 +PDOMapping=0 +ObjFlags=0 + +[1A01sub3] +ParameterName=3. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01sub4] +ParameterName=4. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01sub5] +ParameterName=5. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01sub6] +ParameterName=6. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01sub7] +ParameterName=7. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A01sub8] +ParameterName=8. mapped Object +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ObjFlags=0 + +[1A02] +ParameterName=3. Transmit PDO Mapping +ObjectType=0x9 +SubNumber=9 + +[1A02sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=0 +HighLimit=8 +ParameterValue=2 + +[1A02sub1] +ParameterName=PDO Mapping Entry +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ParameterValue=0x60640020 + +[1A02sub2] +ParameterName=PDO Mapping Entry_2 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 +ParameterValue=0x606c0020 + +[1A02sub3] +ParameterName=PDO Mapping Entry_3 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A02sub4] +ParameterName=PDO Mapping Entry_4 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A02sub5] +ParameterName=PDO Mapping Entry_5 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A02sub6] +ParameterName=PDO Mapping Entry_6 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A02sub7] +ParameterName=PDO Mapping Entry_7 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A02sub8] +ParameterName=PDO Mapping Entry_8 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03] +ParameterName=4. Transmit PDO Mapping +ObjectType=0x9 +SubNumber=9 + +[1A03sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=0 +HighLimit=8 + +[1A03sub1] +ParameterName=PDO Mapping Entry +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub2] +ParameterName=PDO Mapping Entry_2 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub3] +ParameterName=PDO Mapping Entry_3 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub4] +ParameterName=PDO Mapping Entry_4 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub5] +ParameterName=PDO Mapping Entry_5 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub6] +ParameterName=PDO Mapping Entry_6 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub7] +ParameterName=PDO Mapping Entry_7 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[1A03sub8] +ParameterName=PDO Mapping Entry_8 +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[6040] +ParameterName=controlword +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +PDOMapping=1 + +[6041] +ParameterName=statusword +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=1 + +[6042] +ParameterName=vl_target_velocity +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +DefaultValue=0 +PDOMapping=1 + +[6043] +ParameterName=vl_velocity_demand +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=1 + +[6044] +ParameterName=vl_velocity_actual_value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=1 + +[6046] +ParameterName=vl_velocity_min_max_amount +ObjectType=0x8 +SubNumber=3 + +[6046sub0] +ParameterName=vl_velocity_min_max_amount_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[6046sub1] +ParameterName=vl_velocity_min_max_amount_vl_velocity_min_amount +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +PDOMapping=1 + +[6046sub2] +ParameterName=vl_velocity_min_max_amount_vl_velocity_max_amount +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +PDOMapping=1 + +[6048] +ParameterName=vl_velocity_acceleration +ObjectType=0x9 +SubNumber=3 + +[6048sub0] +ParameterName=vl_velocity_acceleration_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[6048sub1] +ParameterName=vl_velocity_acceleration_delta_speed +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +PDOMapping=1 + +[6048sub2] +ParameterName=vl_velocity_acceleration_delta_time +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +PDOMapping=1 + +[6049] +ParameterName=vl_velocity_deceleration +ObjectType=0x9 +SubNumber=3 + +[6049sub0] +ParameterName=vl_velocity_deceleration_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[6049sub1] +ParameterName=vl_velocity_deceleration_delta_speed +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +PDOMapping=1 + +[6049sub2] +ParameterName=vl_velocity_deceleration_delta_time +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +PDOMapping=1 + +[604C] +ParameterName=vl_dimension_factor +ObjectType=0x8 +SubNumber=3 + +[604Csub0] +ParameterName=vl_dimension_factor_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[604Csub1] +ParameterName=vl_dimension_factor_numerator +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=1 +PDOMapping=0 + +[604Csub2] +ParameterName=vl_dimension_factor_denominator +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=6000 +PDOMapping=0 + +[6060] +ParameterName=modes_of_operation +ObjectType=0x7 +DataType=0x0002 +AccessType=rw +PDOMapping=1 +ParameterValue=7 + +[6061] +ParameterName=modes_of_operation_display +ObjectType=0x7 +DataType=0x0002 +AccessType=ro +PDOMapping=1 +ObjFlags=0x1 + +[6062] +ParameterName=position_demand_value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=1 + +[6064] +ParameterName=position_actual_value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=1 + +[6065] +ParameterName=following_error_window +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[606B] +ParameterName=velocity_demand_value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=1 + +[606C] +ParameterName=velocity_actual_value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=1 + +[6073] +ParameterName=max_current +ObjectType=0x7 +DataType=0x0006 +AccessType=rww +PDOMapping=1 + +[6075] +ParameterName=motor_rated_current +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[6077] +ParameterName=torque_actual_value +ObjectType=0x7 +DataType=0x0003 +AccessType=ro +PDOMapping=1 + +[607A] +ParameterName=target_position +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +PDOMapping=1 + +[607C] +ParameterName=home_offset +ObjectType=0x7 +DataType=0x0004 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[607D] +ParameterName=software_position_limit +ObjectType=0x8 +SubNumber=3 + +[607Dsub0] +ParameterName=software_position_limit_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[607Dsub1] +ParameterName=software_position_limit_min_position_limit +ObjectType=0x7 +DataType=0x0004 +AccessType=rw + +[607Dsub2] +ParameterName=software_position_limit_max_position_limit +ObjectType=0x7 +DataType=0x0004 +AccessType=rw + +[6081] +ParameterName=profile_velocity +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=1 +DefaultValue=0x2710 + +[6083] +ParameterName=profile_acceleration +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=1 + +[6086] +ParameterName=motion_profile_type +ObjectType=0x7 +DataType=0x0003 +AccessType=rw +PDOMapping=0 + +[6098] +ParameterName=homing_method +ObjectType=0x7 +DataType=0x0002 +AccessType=const +DefaultValue=0 +PDOMapping=0 +LowLimit=-128 +HighLimit=35 +ParameterValue=0 + +[60B2] +ParameterName=torque_offset +ObjectType=0x7 +DataType=0x0003 +AccessType=rww +PDOMapping=1 + +[60C0] +ParameterName=interpolation_sub_mode_select +ObjectType=0x7 +DataType=0x0003 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=-1 +HighLimit=0 +ParameterValue=0 + +[60C1] +ParameterName=interpolation_data_record +ObjectType=0x8 +SubNumber=2 + +[60C1sub0] +ParameterName=interpolation_data_record_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=1 +PDOMapping=0 + +[60C1sub1] +ParameterName=interpolation_data_record_setpoint_1 +ObjectType=0x7 +DataType=0x0004 +AccessType=rww +PDOMapping=1 + +[60C2] +ParameterName=interpolation_time_period +ObjectType=0x9 +SubNumber=3 + +[60C2sub0] +ParameterName=interpolation_time_period_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[60C2sub1] +ParameterName=interpolation_time_period_value +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=8 +PDOMapping=0 +ParameterValue=10 + +[60C2sub2] +ParameterName=interpolation_time_period_index +ObjectType=0x7 +DataType=0x0002 +AccessType=rw +DefaultValue=-3 +PDOMapping=0 + +[60C3] +ParameterName=interpolation_sync_definition +ObjectType=0x8 +SubNumber=3 + +[60C3sub0] +ParameterName=interpolation_sync_definition_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[60C3sub1] +ParameterName=syncronize_on_group +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[60C3sub2] +ParameterName=ip_sync_every_n_event +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=1 +PDOMapping=0 +LowLimit=0 +HighLimit=255 + +[60C4] +ParameterName=interpolation_data_configuration +ObjectType=0x9 +SubNumber=7 + +[60C4sub0] +ParameterName=interpolation_data_configuration_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=6 +PDOMapping=0 + +[60C4sub1] +ParameterName=interpolation_data_configuration_maximum_buffer_size +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=1 +PDOMapping=0 + +[60C4sub2] +ParameterName=interpolation_data_configuration_actual_buffer_size +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[60C4sub3] +ParameterName=interpolation_data_configuration_buffer_organization +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +LowLimit=0 +HighLimit=1 + +[60C4sub4] +ParameterName=interpolation_data_configuration_buffer_position +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0 +PDOMapping=0 + +[60C4sub5] +ParameterName=interpolation_data_configuration_size_of_data_record +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=1 +PDOMapping=0 + +[60C4sub6] +ParameterName=interpolation_data_configuration_buffer_clear +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +DefaultValue=0 +PDOMapping=0 + +[60F4] +ParameterName=following_error_actual_value +ObjectType=0x7 +DataType=0x0004 +AccessType=ro +PDOMapping=1 +ObjFlags=0x0 + +[60FD] +ParameterName=digital_inputs +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +PDOMapping=1 +ObjFlags=0x2 + +[60FE] +ParameterName=digital_outputs +ObjectType=0x8 +SubNumber=3 + +[60FEsub0] +ParameterName=digital_outputs_highest_subindex +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 + +[60FEsub1] +ParameterName=digital_outputs_physical_outputs +ObjectType=0x7 +DataType=0x0007 +AccessType=rww +PDOMapping=1 +ObjFlags=2 + +[60FEsub2] +ParameterName=digital_outputs_bit_mask +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +PDOMapping=0 + +[6502] +ParameterName=supported_drive_modes +ObjectType=0x7 +DataType=0x0007 +AccessType=ro +DefaultValue=0x00000043 +PDOMapping=0 + +[ManufacturerObjects] +SupportedObjects=29 +1=0x2000 +2=0x2001 +3=0x2002 +4=0x2003 +5=0x2004 +6=0x2007 +7=0x2008 +8=0x2009 +9=0x200A +10=0x200B +11=0x200C +12=0x200D +13=0x200E +14=0x2010 +15=0x2011 +16=0x2012 +17=0x2013 +18=0x2020 +19=0x2021 +20=0x2022 +21=0x2023 +22=0x2024 +23=0x2030 +24=0x2031 +25=0x2032 +26=0x2033 +27=0x2034 +28=0x2041 +29=0x2050 + +[2000] +ParameterName=manufacturer_debug_flags +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ObjFlags=0x0 + +[2001] +ParameterName=debug_values_int32 +ObjectType=0x8 +SubNumber=5 + +[2001sub0] +ParameterName=nb_debug_values_int32 +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=4 +PDOMapping=0 + +[2001sub1] +ParameterName=debug_value_int32_1 +ObjectType=0x7 +DataType=0x0004 +AccessType=rwr +PDOMapping=1 + +[2001sub2] +ParameterName=debug_value_int32_2 +ObjectType=0x7 +DataType=0x0004 +AccessType=rwr +PDOMapping=1 + +[2001sub3] +ParameterName=debug_value_int32_3 +ObjectType=0x7 +DataType=0x0004 +AccessType=rwr +PDOMapping=1 + +[2001sub4] +ParameterName=debug_value_int32_4 +ObjectType=0x7 +DataType=0x0004 +AccessType=rwr +PDOMapping=1 + +[2002] +ParameterName=debug_values_float +ObjectType=0x8 +SubNumber=5 + +[2002sub0] +ParameterName=nb_debug_values_float +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=4 +PDOMapping=0 + +[2002sub1] +ParameterName=debug_value_float_1 +ObjectType=0x7 +DataType=0x0008 +AccessType=rwr +PDOMapping=1 + +[2002sub2] +ParameterName=debug_value_float_2 +ObjectType=0x7 +DataType=0x0008 +AccessType=rwr +PDOMapping=1 + +[2002sub3] +ParameterName=debug_value_float_3 +ObjectType=0x7 +DataType=0x0008 +AccessType=rwr +PDOMapping=1 + +[2002sub4] +ParameterName=debug_value_float_4 +ObjectType=0x7 +DataType=0x0008 +AccessType=rwr +PDOMapping=1 + +[2003] +ParameterName=debug_message +ObjectType=0x7 +DataType=0x0009 +AccessType=ro +PDOMapping=1 + +[2004] +ParameterName=logging +ObjectType=0x9 +SubNumber=3 +ObjFlags=0x3 + +[2004sub0] +ParameterName=nb_logging +ObjectType=0x7 +DataType=0x0005 +AccessType=const +DefaultValue=2 +PDOMapping=0 +ObjFlags=3 + +[2004sub1] +ParameterName=logging_state +ObjectType=0x7 +DataType=0x0006 +AccessType=rw +DefaultValue=0x8001 +PDOMapping=0 +ObjFlags=3 + +[2004sub2] +ParameterName=logging_trigger_time +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 +ObjFlags=3 + +[2007] +ParameterName=EEPROM_Parameters +ObjectType=0x9 +SubNumber=2 + +[2007sub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=1 +PDOMapping=0 + +[2007sub1] +ParameterName=SECT_CONFIG +ObjectType=0x7 +DataType=0x000a +AccessType=ro +PDOMapping=0 +ObjFlags=3 + +[2008] +ParameterName=Password +ObjectType=0x7 +DataType=0x0009 +AccessType=wo +PDOMapping=0 +ObjFlags=0x1 + +[2009] +ParameterName=User +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0 +PDOMapping=0 + +[200A] +ParameterName=Disconnect_Reset +ObjectType=0x7 +DataType=0x0005 +AccessType=wo +PDOMapping=0 +ObjFlags=0x3 + +[200B] +ParameterName=error_details +ObjectType=0x9 +SubNumber=4 +DataType=0x0008 +AccessType=ro + +[200Bsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=3 +PDOMapping=0 + +[200Bsub1] +ParameterName=detail +ObjectType=0x7 +DataType=0x0008 +AccessType=ro +PDOMapping=0 + +[200Bsub2] +ParameterName=file +ObjectType=0x7 +DataType=0x0009 +AccessType=ro +PDOMapping=0 +ObjFlags=2 + +[200Bsub3] +ParameterName=line +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +PDOMapping=0 + +[200C] +ParameterName=communication_mode +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +PDOMapping=0 + +[200D] +ParameterName=pcb_temperature +ObjectType=0x9 +SubNumber=3 + +[200Dsub0] +ParameterName=Number of entries +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=2 +PDOMapping=0 + +[200Dsub1] +ParameterName=actual_pcb_temperature +ObjectType=0x7 +DataType=0x0008 +AccessType=ro +PDOMapping=1 + +[200Dsub2] +ParameterName=pcb_temperature_update_period_ms +ObjectType=0x7 +DataType=0x0007 +AccessType=rw +DefaultValue=20000 +PDOMapping=0 +LowLimit=1000 +HighLimit=3600000 + +[200E] +ParameterName=sync_timeout_factor +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=6 +PDOMapping=0 + +[2010] +ParameterName=KR_Current +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2011] +ParameterName=TN_Current +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2012] +ParameterName=TD_Current +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2013] +ParameterName=KC_Current +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2020] +ParameterName=KR_Speed +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2021] +ParameterName=TN_Speed +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2022] +ParameterName=TD_Speed +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2023] +ParameterName=KC_Speed +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2024] +ParameterName=KS_FeedForward +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2030] +ParameterName=KR_Pos +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2031] +ParameterName=TN_Pos +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2032] +ParameterName=TD_Pos +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2033] +ParameterName=KC_Pos +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2034] +ParameterName=KP_FeedForward +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2041] +ParameterName=Delta_Position +ObjectType=0x7 +DataType=0x0008 +AccessType=rw +PDOMapping=0 + +[2050] +ParameterName=extended_status +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0 +PDOMapping=1 +ObjFlags=0x1 + +[20A0] +ParameterName=vendor_parameters_and_status +ObjectType=0x9 +SubNumber=8 + +[20A0sub7] +ParameterName=run_permitted_status +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0 +PDOMapping=1 +ObjFlags=0x1 + +[2060] +ParameterName=brake_test +ObjectType=0x9 +SubNumber=4 + +[2060sub1] +ParameterName=brake_test_duration +ObjectType=0x7 +DataType=0x0006 +AccessType=ro +DefaultValue=2500 +PDOMapping=0 +ObjFlags=1 +ParameterValue=2500 + + +[2060sub2] +ParameterName=start_brake_test +ObjectType=0x7 +DataType=0x0005 +AccessType=rw +DefaultValue=0 +PDOMapping=0 +ParameterValue=0 + +[2060sub3] +ParameterName=brake_test_status +ObjectType=0x7 +DataType=0x0005 +AccessType=ro +DefaultValue=0 +PDOMapping=0 +ParameterValue=0 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv new file mode 100644 index 0000000000..79d4c95b55 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh new file mode 100644 index 0000000000..02e441b753 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh @@ -0,0 +1,4 @@ +# copied from +# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh + +ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv new file mode 100644 index 0000000000..b94426af08 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate-if-exists;PATH;bin diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh new file mode 100644 index 0000000000..e59b749a89 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh @@ -0,0 +1,5 @@ +# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh + +if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then + ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin" +fi diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv new file mode 100644 index 0000000000..e119f32cba --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;CMAKE_PREFIX_PATH; diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 new file mode 100644 index 0000000000..d03facc1a4 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 @@ -0,0 +1,3 @@ +# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em + +colcon_prepend_unique_value CMAKE_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh new file mode 100644 index 0000000000..a948e685ba --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh @@ -0,0 +1,3 @@ +# generated from colcon_core/shell/template/hook_prepend_value.sh.em + +_colcon_prepend_unique_value CMAKE_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash new file mode 100644 index 0000000000..49782f2461 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash @@ -0,0 +1,46 @@ +# generated from ament_package/template/package_level/local_setup.bash.in + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv new file mode 100644 index 0000000000..36167c5b9a --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv @@ -0,0 +1,2 @@ +source;share/moveit_resources_prbt_support/environment/ament_prefix_path.sh +source;share/moveit_resources_prbt_support/environment/path.sh diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh new file mode 100644 index 0000000000..cce3209152 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh @@ -0,0 +1,184 @@ +# generated from ament_package/template/package_level/local_setup.sh.in + +# since this file is sourced use either the provided AMENT_CURRENT_PREFIX +# or fall back to the destination set at configure time +: ${AMENT_CURRENT_PREFIX:="/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support"} +if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then + if [ -z "$COLCON_CURRENT_PREFIX" ]; then + echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \ + "exist. Consider sourcing a different extension than '.sh'." 1>&2 + else + AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" + fi +fi + +# function to append values to environment variables +# using colons as separators and avoiding leading separators +ament_append_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # avoid leading separator + eval _values=\"\$$_listname\" + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + _ament_append_value_IFS=$IFS + unset IFS + eval export $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + IFS=$_ament_append_value_IFS + unset _ament_append_value_IFS + fi + unset _values + + unset _value + unset _listname +} + +# function to append non-duplicate values to environment variables +# using colons as separators and avoiding leading separators +ament_append_unique_value() { + # arguments + _listname=$1 + _value=$2 + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\$$_listname + _duplicate= + _ament_append_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ $_item = $_value ]; then + _duplicate=1 + fi + done + unset _item + + # append only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid leading separator + if [ -z "$_values" ]; then + eval $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + fi + fi + IFS=$_ament_append_unique_value_IFS + unset _ament_append_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# function to prepend non-duplicate values to environment variables +# using colons as separators and avoiding trailing separators +ament_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\"\$$_listname\" + _duplicate= + _ament_prepend_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ "$_item" = "$_value" ]; then + _duplicate=1 + fi + done + unset _item + + # prepend only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid trailing separator + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval export $_listname=\"$_value:\$$_listname\" + #eval echo "prepend list \$$_listname" + fi + fi + IFS=$_ament_prepend_unique_value_IFS + unset _ament_prepend_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# list all environment hooks of this package +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh" +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_resources_prbt_support/environment/path.sh" + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS + fi + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + if [ -f "$_hook" ]; then + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + # trace output + if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_hook\"" + fi + . "$_hook" + fi + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +# reset AMENT_CURRENT_PREFIX after each package +# allowing to source multiple package-level setup files +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh new file mode 100644 index 0000000000..fe161be53d --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh @@ -0,0 +1,59 @@ +# generated from ament_package/template/package_level/local_setup.zsh.in + +AMENT_SHELL=zsh + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# function to convert array-like strings into arrays +# to wordaround SH_WORD_SPLIT not being set +ament_zsh_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +# the package-level local_setup file unsets AMENT_CURRENT_PREFIX +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae new file mode 100644 index 0000000000..48d7f2088b --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae @@ -0,0 +1,109 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T14:46:40 + 2019-01-15T14:46:40 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + -25.4994 1001.4 -2.59834 -31.78964 1001.4 -6.756204 -32.5 1001.4 0 -32.5 998.9 0 -32.5 1001.4 0 -31.78964 1001.4 -6.756204 -26.99976 1001.4 0 -31.78964 1001.4 6.756204 -31.7898 998.9 6.75713 -31.78964 1001.4 6.756204 -32.5 1001.4 0 -26.59765 1001.4 -1.500361 -32.5 998.9 0 29.68938 1001.4 -13.22047 -29.68938 1001.4 -13.22047 -31.7898 998.9 -6.75713 -29.68938 1001.4 -13.22047 31.78964 1001.4 -6.756204 -24 1001.4 -3 26.29395 1001.4 -19.10152 -26.29395 1001.4 -19.10152 -29.69023 998.9 -13.21894 -26.29395 1001.4 -19.10152 21.74586 1001.4 -24.15253 -21.74586 1001.4 -24.15253 -26.29305 998.9 -19.10302 -21.74586 1001.4 -24.15253 16.25 1001.4 -28.14583 -16.25 1001.4 -28.14583 -21.74674 998.9 -24.15221 -16.25 1001.4 -28.14583 10.04377 1001.4 -30.90873 -10.04377 1001.4 -30.90873 -16.25 998.9 -28.14583 -10.04377 1001.4 -30.90873 3.395426 1001.4 -32.32199 -3.395426 1001.4 -32.32199 -10.04305 998.9 -30.90934 -3.395426 1001.4 -32.32199 -3.397175 998.9 -32.32196 3.395426 1001.4 -32.32199 3.397175 998.9 -32.32196 10.04377 1001.4 -30.90873 10.04305 998.9 -30.90934 16.25 1001.4 -28.14583 16.25 998.9 -28.14583 21.74586 1001.4 -24.15253 21.74674 998.9 -24.15221 26.29395 1001.4 -19.10152 26.29305 998.9 -19.10302 29.68938 1001.4 -13.22047 29.69023 998.9 -13.21894 31.78964 1001.4 -6.756204 -21.00024 1001.4 0 32.5 1001.4 0 31.7898 998.9 -6.75713 32.5 1001.4 0 -22.50061 1001.4 -2.59834 -21.40235 1001.4 -1.500361 31.78964 1001.4 6.756204 32.5 998.9 0 32.5 1001.4 0 31.78964 1001.4 6.756204 -24 1001.4 3 -22.50061 1001.4 2.59834 -21.40235 1001.4 1.500361 32.5 998.9 0 -29.68938 1001.4 13.22047 29.68938 1001.4 13.22047 31.7898 998.9 6.75713 29.68938 1001.4 13.22047 -26.29395 1001.4 19.10152 26.29395 1001.4 19.10152 29.69023 998.9 13.21894 26.29395 1001.4 19.10152 -21.74586 1001.4 24.15253 21.74586 1001.4 24.15253 26.29305 998.9 19.10302 21.74586 1001.4 24.15253 -16.25 1001.4 28.14583 16.25 1001.4 28.14583 21.74674 998.9 24.15221 16.25 1001.4 28.14583 -10.04377 1001.4 30.90873 10.04377 1001.4 30.90873 16.25 998.9 28.14583 10.04377 1001.4 30.90873 -3.395426 1001.4 32.32199 3.395426 1001.4 32.32199 10.04305 998.9 30.90934 3.395426 1001.4 32.32199 3.397175 998.9 32.32196 -3.395426 1001.4 32.32199 -3.397175 998.9 32.32196 -10.04377 1001.4 30.90873 -10.04305 998.9 30.90934 -16.25 1001.4 28.14583 -16.25 998.9 28.14583 -21.74586 1001.4 24.15253 -21.74674 998.9 24.15221 -26.29395 1001.4 19.10152 -26.29305 998.9 19.10302 -29.68938 1001.4 13.22047 -29.69023 998.9 13.21894 -26.59765 1001.4 1.500361 -25.4994 1001.4 2.59834 -24 1007.9 -3 -24 1001.4 -3 -25.4994 1001.4 -2.59834 -22.5 1007.9 -2.598076 -22.50061 1001.4 -2.59834 -24 1001.4 -3 -24 1007.9 -3 -25.5 1007.9 -2.598076 -26.59765 1001.4 -1.500361 -26.59808 1007.9 -1.5 -26.99976 1001.4 0 -27 1007.9 0 -26.59765 1001.4 1.500361 -26.59808 1007.9 1.5 -25.4994 1001.4 2.59834 -25.5 1007.9 2.598076 -24 1001.4 3 -24 1007.9 3 -24 1001.4 3 -22.50061 1001.4 2.59834 -24 1007.9 3 -22.5 1007.9 2.598076 -21.40235 1001.4 1.500361 -21.40192 1007.9 1.5 -21.00024 1001.4 0 -21 1007.9 0 -21.40235 1001.4 -1.500361 -21.40192 1007.9 -1.5 -28.5 994.4 0 -32.5 998.9 0 -31.7898 998.9 -6.75713 -27.78544 994.4 6.341847 -32.5 998.9 0 -28.5 994.4 0 -31.7898 998.9 6.75713 -27.78544 994.4 -6.341847 -29.69023 998.9 -13.21894 -25.67761 994.4 -12.36569 -26.29305 998.9 -19.10302 -22.2822 994.4 -17.76946 -21.74674 998.9 -24.15221 -17.76946 994.4 -22.2822 -16.25 998.9 -28.14583 -12.36569 994.4 -25.67761 -10.04305 998.9 -30.90934 -6.341847 994.4 -27.78544 -3.397175 998.9 -32.32196 0 994.4 -28.5 3.397175 998.9 -32.32196 6.341847 994.4 -27.78544 10.04305 998.9 -30.90934 12.36569 994.4 -25.67761 16.25 998.9 -28.14583 17.76946 994.4 -22.2822 21.74674 998.9 -24.15221 22.2822 994.4 -17.76946 26.29305 998.9 -19.10302 25.67761 994.4 -12.36569 29.69023 998.9 -13.21894 27.78544 994.4 -6.341847 31.7898 998.9 -6.75713 32.5 998.9 0 28.5 994.4 0 31.7898 998.9 6.75713 28.5 994.4 0 32.5 998.9 0 -28.5 991.9 0 -28.5 994.4 0 -27.78544 994.4 -6.341847 -27.78535 991.9 6.340377 -28.5 994.4 0 -28.5 991.9 0 -27.78544 994.4 6.341847 -27.78535 991.9 -6.340377 -25.67761 994.4 -12.36569 -25.6765 991.9 -12.36724 -22.2822 994.4 -17.76946 -22.28293 991.9 -17.76848 -17.76946 994.4 -22.2822 -17.76975 991.9 -22.28136 -12.36569 994.4 -25.67761 -12.36372 991.9 -25.67831 -6.341847 994.4 -27.78544 -6.343652 991.9 -27.78491 0 994.4 -28.5 0 991.9 -28.4995 6.341847 994.4 -27.78544 6.343652 991.9 -27.78491 12.36569 994.4 -25.67761 12.36372 991.9 -25.67831 17.76946 994.4 -22.2822 17.76975 991.9 -22.28136 22.2822 994.4 -17.76946 22.28293 991.9 -17.76848 25.67761 994.4 -12.36569 25.6765 991.9 -12.36724 27.78544 994.4 -6.341847 27.78535 991.9 -6.340377 28.5 994.4 0 28.5 991.9 0 27.78544 994.4 6.341847 28.5 991.9 0 28.5 994.4 0 27.78544 994.4 6.341847 28.5 991.9 0 -28.5 991.9 0 -27.78535 991.9 -6.340377 27.78535 991.9 6.340377 -27.78535 991.9 6.340377 27.78535 991.9 -6.340377 -25.6765 991.9 -12.36724 25.6765 991.9 -12.36724 -22.28293 991.9 -17.76848 22.28293 991.9 -17.76848 -17.76975 991.9 -22.28136 17.76975 991.9 -22.28136 -12.36372 991.9 -25.67831 12.36372 991.9 -25.67831 -6.343652 991.9 -27.78491 6.343652 991.9 -27.78491 0 991.9 -28.4995 27.78535 991.9 6.340377 25.6765 991.9 12.36724 -25.6765 991.9 12.36724 -25.6765 991.9 12.36724 22.28293 991.9 17.76848 -22.28293 991.9 17.76848 -25.67761 994.4 12.36569 -22.28293 991.9 17.76848 17.76975 991.9 22.28136 -17.76975 991.9 22.28136 -22.2822 994.4 17.76946 -17.76975 991.9 22.28136 12.36372 991.9 25.67831 -12.36372 991.9 25.67831 -17.76946 994.4 22.2822 -12.36372 991.9 25.67831 6.343652 991.9 27.78491 -6.343652 991.9 27.78491 -12.36569 994.4 25.67761 -6.343652 991.9 27.78491 0 991.9 28.4995 -6.341847 994.4 27.78544 0 991.9 28.4995 0 994.4 28.5 6.343652 991.9 27.78491 6.341847 994.4 27.78544 12.36372 991.9 25.67831 12.36569 994.4 25.67761 17.76975 991.9 22.28136 17.76946 994.4 22.2822 22.28293 991.9 17.76848 22.2822 994.4 17.76946 25.6765 991.9 12.36724 25.67761 994.4 12.36569 29.69023 998.9 13.21894 25.67761 994.4 12.36569 26.29305 998.9 19.10302 22.2822 994.4 17.76946 21.74674 998.9 24.15221 17.76946 994.4 22.2822 16.25 998.9 28.14583 12.36569 994.4 25.67761 10.04305 998.9 30.90934 6.341847 994.4 27.78544 3.397175 998.9 32.32196 0 994.4 28.5 -3.397175 998.9 32.32196 -6.341847 994.4 27.78544 -10.04305 998.9 30.90934 -12.36569 994.4 25.67761 -16.25 998.9 28.14583 -17.76946 994.4 22.2822 -21.74674 998.9 24.15221 -22.2822 994.4 17.76946 -26.29305 998.9 19.10302 -25.67761 994.4 12.36569 -29.69023 998.9 13.21894 -22.5 1007.9 2.598076 -22.5 1007.9 -2.598076 -24 1007.9 -3 -24 1007.9 3 -25.5 1007.9 -2.598076 -21.40192 1007.9 1.5 -21.40192 1007.9 -1.5 -21 1007.9 0 -25.5 1007.9 2.598076 -26.59808 1007.9 -1.5 -26.59808 1007.9 1.5 -27 1007.9 0 + + + + + + + + + + 0 1 2.68571e-6 -0.9945221 0 -0.1045275 -0.9945189 0 -0.1045576 -0.9781579 1.22075e-4 -0.2078635 0 1 -3.28492e-6 -0.9781441 1.22077e-4 0.2079281 -0.9781517 1.22074e-4 0.2078927 -0.9945221 0 0.1045275 0 1 0 0 1 -1.18338e-4 0 1 2.54419e-5 -0.9781441 1.22077e-4 -0.2079281 -0.9135232 6.10379e-5 -0.4067869 0 1 -1.90088e-5 0 1 -3.27134e-5 0 1 -1.11469e-4 0 1 1.10517e-5 -0.9135622 6.10384e-5 -0.4066991 -0.8090448 6.10393e-5 -0.587747 0 1 -2.2372e-5 0 1 4.44544e-6 -0.8089907 6.10375e-5 -0.5878214 -0.6691013 1.22077e-4 -0.7431712 0 1 4.51477e-5 -0.6691334 1.22077e-4 -0.7431423 -0.4999665 0 -0.8660449 0 1 -4.49833e-5 0 1 -3.51915e-5 -0.3090316 1.22074e-4 -0.9510518 0 1 1.01754e-4 -0.3089764 1.22077e-4 -0.9510697 -0.1044671 6.10383e-5 -0.9945284 0 1 6.87988e-5 -0.1045576 3.05189e-5 -0.9945189 0.1044671 3.05192e-5 -0.9945284 0.1045576 6.10378e-5 -0.9945189 0.309004 1.22076e-4 -0.9510608 0.3089764 1.22077e-4 -0.9510697 0.4999893 0 -0.8660317 0.6691013 1.22077e-4 -0.7431712 0.6691334 1.22077e-4 -0.7431423 0.8090303 6.10382e-5 -0.587767 0.8089802 6.1039e-5 -0.5878359 0.9135345 6.10386e-5 -0.4067614 0.9135735 6.10392e-5 -0.4066736 0.9781517 1.22074e-4 -0.2078927 0 1 -7.76747e-6 0.9781441 1.22077e-4 -0.2079281 0.9945221 0 -0.1045275 0 1 9.53667e-5 0 1 1.21736e-4 0 1 6.53611e-6 0.9945221 0 0.1045275 0.9945189 0 0.1045576 0.9781579 1.22075e-4 0.2078635 0 1 -9.73282e-5 0 1 -2.54419e-5 0.9781441 1.22077e-4 0.2079281 0.9135232 6.10379e-5 0.4067869 0 1 1.90088e-5 0 1 -1.10517e-5 0.9135622 6.10384e-5 0.4066991 0.8090448 6.10393e-5 0.587747 0 1 2.2372e-5 0 1 -4.44544e-6 0.8089907 6.10375e-5 0.5878214 0.6691013 1.22077e-4 0.7431712 0 1 -4.51477e-5 0.6691334 1.22077e-4 0.7431423 0.4999665 0 0.8660449 0 1 4.49833e-5 0 1 3.51915e-5 0.3090316 1.22074e-4 0.9510518 0 1 -1.01754e-4 0.3089764 1.22077e-4 0.9510697 0.1044671 6.10383e-5 0.9945284 0 1 -6.87988e-5 0.1045576 3.05189e-5 0.9945189 -0.1044671 3.05192e-5 0.9945284 -0.1045576 6.10378e-5 0.9945189 -0.309004 1.22076e-4 0.9510608 -0.3089764 1.22077e-4 0.9510697 -0.4999893 0 0.8660317 -0.6691013 1.22077e-4 0.7431712 -0.6691334 1.22077e-4 0.7431423 -0.8090303 6.10382e-5 0.587767 -0.8089802 6.1039e-5 0.5878359 -0.9135345 6.10386e-5 0.4067614 -0.9135735 6.10392e-5 0.4066736 0 1 1.11469e-4 -0.2588022 0 -0.9659304 -0.2587376 0 -0.9659477 -0.4999074 0 -0.8660789 0.5000025 0 -0.866024 0.4999074 0 -0.8660789 0.2587453 0 -0.9659456 0.2588022 0 -0.9659304 -0.5000025 0 -0.866024 -0.8659768 -3.0519e-5 -0.5000844 -0.8660317 0 -0.4999893 -1 -3.05185e-5 0 -0.8659768 0 0.5000844 -0.8660317 -3.05188e-5 0.4999893 -0.4999074 0 0.8660789 -0.5000025 0 0.866024 -0.2587737 0 0.965938 0.2588022 0 0.9659304 0.2587376 0 0.9659477 0.4999074 0 0.8660789 -0.2588022 0 0.9659304 0.5000025 0 0.866024 0.8659768 -3.0519e-5 0.5000844 0.8660317 0 0.4999893 1 -3.05185e-5 0 0.8659768 0 -0.5000844 0.8660317 -3.05188e-5 -0.4999893 -0.7430429 -0.6643653 -0.08066135 -0.7451192 -0.6623214 -0.07828098 -0.7320972 -0.6636424 -0.1536647 -0.7272366 -0.6665344 0.1638869 -0.7430528 -0.6643131 0.08099812 -0.7447675 -0.6620292 0.08389812 -0.7313593 -0.6648277 0.152046 -0.7260594 -0.6674925 -0.1652022 -0.6853744 -0.6622712 -0.3027525 -0.6695508 -0.6690015 -0.3227052 -0.6081908 -0.6612336 -0.4391744 -0.5799239 -0.6700773 -0.4633409 -0.5038744 -0.6604997 -0.5566424 -0.4617599 -0.6708183 -0.5803281 -0.3770033 -0.6600076 -0.6498143 -0.3209741 -0.671308 -0.6680729 -0.2331983 -0.6597061 -0.7144273 -0.1645012 -0.6715557 -0.7224626 -0.07889223 -0.6595514 -0.7475079 0 -0.6716346 -0.7408825 0.07889223 -0.6595514 -0.7475079 0.1645012 -0.6715557 -0.7224626 0.2331983 -0.6597061 -0.7144273 0.3209675 -0.6712943 -0.6680898 0.3770033 -0.6600076 -0.6498143 0.4617599 -0.6708183 -0.5803281 0.5038744 -0.6604997 -0.5566424 0.5799239 -0.6700773 -0.4633409 0.6081908 -0.6612336 -0.4391744 0.6695508 -0.6690015 -0.3227052 0.6853744 -0.6622712 -0.3027525 0.7272366 -0.6665344 -0.1638869 0.7313593 -0.6648277 -0.152046 0.7430528 -0.6643131 -0.08099812 0.7447675 -0.6620292 -0.08389812 0.7320972 -0.6636424 0.1536647 0.7430429 -0.6643653 0.08066135 0.7451174 -0.6623198 0.07831132 -0.993711 0 -0.1119756 -0.9937145 0 -0.1119455 -0.9749163 -1.52593e-4 -0.222572 -0.9749362 -1.52596e-4 0.222485 -0.993711 0 0.1119756 -0.9937075 0 0.1120057 -0.974923 -1.52594e-4 0.2225431 -0.9749362 -1.52596e-4 -0.222485 -0.9009933 -1.22078e-4 -0.4338331 -0.9009518 -9.1557e-5 -0.4339193 -0.7818266 0 -0.6234959 -0.7818683 0 -0.6234438 -0.6234437 -1.52595e-4 -0.7818682 -0.6234773 -1.83115e-4 -0.7818415 -0.4339441 -9.15558e-5 -0.9009398 -0.4338331 -6.10388e-5 -0.9009933 -0.222456 -3.05194e-5 -0.9749428 -0.2225431 -3.05188e-5 -0.974923 0 -1.83111e-4 -1 0.222456 -3.05194e-5 -0.9749428 0.2225431 -3.05188e-5 -0.974923 0.4339193 -6.1038e-5 -0.9009518 0.4338331 -9.15582e-5 -0.9009933 0.6234773 -1.83115e-4 -0.7818415 0.6235108 -1.52597e-4 -0.7818148 0.7818148 0 -0.6235108 0.7818415 0 -0.6234773 0.9009933 -9.15582e-5 -0.4338331 0.9009518 -1.22076e-4 -0.4339193 0.974923 -1.52594e-4 -0.2225431 0.9749362 -1.52596e-4 -0.222485 0.993711 0 -0.1119756 0.9937075 0 -0.1120057 0.9749163 -1.52593e-4 0.222572 0.993711 0 0.1119756 0.9937145 0 0.1119455 0.7260594 -0.6674925 0.1652022 0 -1 -6.41762e-6 0 -1 0 0 -1 6.58268e-6 0 -1 4.37375e-6 0 -1 1.94224e-5 0 -1 8.08909e-6 0 -1 3.74946e-5 0 -1 -7.30767e-5 0.9749362 -1.52596e-4 0.222485 0 -1 -4.73297e-6 -0.9009518 -1.22076e-4 0.4339193 -0.9009933 -9.15582e-5 0.4338331 -0.7818415 0 0.6234773 0 -1 2.43554e-5 -0.7817999 0 0.6235294 -0.6235108 -1.52597e-4 0.7818148 0 -1 -3.88449e-5 0 -1 -1.1626e-5 -0.6234773 -1.83115e-4 0.7818415 -0.4338331 -9.15582e-5 0.9009933 0 -1 7.30767e-5 -0.4339441 -6.10372e-5 0.9009398 -0.2225431 -3.05188e-5 0.974923 0 -1 -7.49892e-5 -0.222456 -3.05194e-5 0.9749428 0 -1.83111e-4 1 0.222572 -3.05186e-5 0.9749163 0.222456 -3.05194e-5 0.9749428 0.4338331 -6.10388e-5 0.9009933 0.4339193 -9.1557e-5 0.9009518 0.6234773 -1.83115e-4 0.7818415 0.6234586 -1.52599e-4 0.7818564 0.7818683 0 0.6234438 0.7818415 0 0.6234773 0.9009518 -9.1557e-5 0.4339193 0.9009933 -1.22078e-4 0.4338331 0.6853744 -0.6622712 0.3027525 0.6695508 -0.6690015 0.3227052 0.6081908 -0.6612336 0.4391744 0.5799239 -0.6700773 0.4633409 0.5038744 -0.6604997 0.5566424 0.4617599 -0.6708183 0.5803281 0.3770033 -0.6600076 0.6498143 0.3209741 -0.671308 0.6680729 0.2331983 -0.6597061 0.7144273 0.1645012 -0.6715557 0.7224626 0.07889223 -0.6595514 0.7475079 0 -0.6716346 0.7408825 -0.07889223 -0.6595514 0.7475079 -0.1645012 -0.6715557 0.7224626 -0.2331983 -0.6597061 0.7144273 -0.3209675 -0.6712943 0.6680898 -0.3770033 -0.6600076 0.6498143 -0.4617599 -0.6708183 0.5803281 -0.5038744 -0.6604997 0.5566424 -0.5799239 -0.6700773 0.4633409 -0.6081908 -0.6612336 0.4391744 -0.6695508 -0.6690015 0.3227052 -0.6853744 -0.6622712 0.3027525 + + + + + + + + + + 0.05798298 0.02975195 0.06425899 0.02560299 0.06496697 0.03234595 0.06504899 0.03234595 0.06496697 0.03234595 0.06425899 0.02560299 0.05947995 0.03234595 0.06496697 0.03234595 0.06425899 0.03908896 0.06433796 0.03910696 0.06425899 0.03908896 0.06496697 0.03234595 0.05907899 0.0308479 0.05798298 0.02975195 0.06496697 0.03234595 0.05947995 0.03234595 0.05907899 0.0308479 0.06496697 0.03234595 0.06433796 0.03910696 0.06496697 0.03234595 0.06504899 0.03234595 0.002884984 0.01915097 0.06216388 0.01915097 0.06425899 0.02560299 0.06433796 0.02558499 0.06425899 0.02560299 0.06216388 0.01915097 7.9e-4 0.02560299 0.002884984 0.01915097 0.06425899 0.02560299 0.05648595 0.02935099 7.9e-4 0.02560299 0.06425899 0.02560299 0.05798298 0.02975195 0.05648595 0.02935099 0.06425899 0.02560299 0.06433796 0.02558499 0.06504899 0.03234595 0.06425899 0.02560299 0.006272971 0.01327997 0.05877488 0.01327997 0.06216388 0.01915097 0.06223791 0.01911896 0.06216388 0.01915097 0.05877488 0.01327997 0.002884984 0.01915097 0.006272971 0.01327997 0.06216388 0.01915097 0.06223791 0.01911896 0.06433796 0.02558499 0.06216388 0.01915097 0.01081198 0.008237957 0.05423599 0.008237957 0.05877488 0.01327997 0.05883991 0.01323091 0.05877488 0.01327997 0.05423599 0.008237957 0.006272971 0.01327997 0.01081198 0.008237957 0.05877488 0.01327997 0.05883991 0.01323091 0.06223791 0.01911896 0.05877488 0.01327997 0.01629799 0.004250943 0.04874998 0.004250943 0.05423599 0.008237957 0.05429196 0.008177995 0.05423599 0.008237957 0.04874998 0.004250943 0.01081198 0.008237957 0.01629799 0.004250943 0.05423599 0.008237957 0.05429196 0.008177995 0.05883991 0.01323091 0.05423599 0.008237957 0.02249497 0.001491904 0.04255396 0.001491904 0.04874998 0.004250943 0.04879099 0.004179954 0.04874998 0.004250943 0.04255396 0.001491904 0.01629799 0.004250943 0.02249497 0.001491904 0.04874998 0.004250943 0.04879099 0.004179954 0.05429196 0.008177995 0.04874998 0.004250943 0.02913397 8.1e-5 0.03591489 8.1e-5 0.04255396 0.001491904 0.04257798 0.001413941 0.04255396 0.001491904 0.03591489 8.1e-5 0.02249497 0.001491904 0.02913397 8.1e-5 0.04255396 0.001491904 0.04257798 0.001413941 0.04879099 0.004179954 0.04255396 0.001491904 0.03592497 0 0.03591489 8.1e-5 0.02913397 8.1e-5 0.03592497 0 0.04257798 0.001413941 0.03591489 8.1e-5 0.02912288 0 0.02913397 8.1e-5 0.02249497 0.001491904 0.02912288 0 0.03592497 0 0.02913397 8.1e-5 0.02247095 0.001413941 0.02249497 0.001491904 0.01629799 0.004250943 0.02247095 0.001413941 0.02912288 0 0.02249497 0.001491904 0.016258 0.004179954 0.01629799 0.004250943 0.01081198 0.008237957 0.016258 0.004179954 0.02247095 0.001413941 0.01629799 0.004250943 0.0107569 0.008177995 0.01081198 0.008237957 0.006272971 0.01327997 0.0107569 0.008177995 0.016258 0.004179954 0.01081198 0.008237957 0.006207883 0.01323091 0.006272971 0.01327997 0.002884984 0.01915097 0.006207883 0.01323091 0.0107569 0.008177995 0.006272971 0.01327997 0.002809882 0.01911896 0.002884984 0.01915097 7.9e-4 0.02560299 0.002809882 0.01911896 0.006207883 0.01323091 0.002884984 0.01915097 0.05349195 0.03234595 8.1e-5 0.03234595 7.9e-4 0.02560299 7.1e-4 0.02558499 7.9e-4 0.02560299 8.1e-5 0.03234595 0.05498999 0.02975195 7.9e-4 0.02560299 0.05648595 0.02935099 0.05389297 0.0308479 0.05349195 0.03234595 7.9e-4 0.02560299 0.05498999 0.02975195 0.05389297 0.0308479 7.9e-4 0.02560299 7.1e-4 0.02558499 0.002809882 0.01911896 7.9e-4 0.02560299 0.06425899 0.03908896 7.9e-4 0.03908896 8.1e-5 0.03234595 0 0.03234595 8.1e-5 0.03234595 7.9e-4 0.03908896 0.05648595 0.03534096 0.06425899 0.03908896 8.1e-5 0.03234595 0.05498999 0.03494 0.05648595 0.03534096 8.1e-5 0.03234595 0.05389297 0.03384399 0.05498999 0.03494 8.1e-5 0.03234595 0.05349195 0.03234595 0.05389297 0.03384399 8.1e-5 0.03234595 0 0.03234595 7.1e-4 0.02558499 8.1e-5 0.03234595 0.06216388 0.045542 0.002884984 0.045542 7.9e-4 0.03908896 7.1e-4 0.03910696 7.9e-4 0.03908896 0.002884984 0.045542 0.06425899 0.03908896 0.06216388 0.045542 7.9e-4 0.03908896 7.1e-4 0.03910696 0 0.03234595 7.9e-4 0.03908896 0.05877488 0.05141192 0.006272971 0.05141192 0.002884984 0.045542 0.002809882 0.04557293 0.002884984 0.045542 0.006272971 0.05141192 0.06216388 0.045542 0.05877488 0.05141192 0.002884984 0.045542 0.002809882 0.04557293 7.1e-4 0.03910696 0.002884984 0.045542 0.05423599 0.056454 0.01081198 0.056454 0.006272971 0.05141192 0.006207883 0.05146098 0.006272971 0.05141192 0.01081198 0.056454 0.05877488 0.05141192 0.05423599 0.056454 0.006272971 0.05141192 0.006207883 0.05146098 0.002809882 0.04557293 0.006272971 0.05141192 0.04874998 0.06044089 0.01629799 0.06044089 0.01081198 0.056454 0.0107569 0.05651396 0.01081198 0.056454 0.01629799 0.06044089 0.05423599 0.056454 0.04874998 0.06044089 0.01081198 0.056454 0.0107569 0.05651396 0.006207883 0.05146098 0.01081198 0.056454 0.04255396 0.06319999 0.02249497 0.06319999 0.01629799 0.06044089 0.016258 0.06051188 0.01629799 0.06044089 0.02249497 0.06319999 0.04874998 0.06044089 0.04255396 0.06319999 0.01629799 0.06044089 0.016258 0.06051188 0.0107569 0.05651396 0.01629799 0.06044089 0.03591489 0.06461095 0.02913397 0.06461095 0.02249497 0.06319999 0.02247095 0.06327795 0.02249497 0.06319999 0.02913397 0.06461095 0.04255396 0.06319999 0.03591489 0.06461095 0.02249497 0.06319999 0.02247095 0.06327795 0.016258 0.06051188 0.02249497 0.06319999 0.02912288 0.06469196 0.02913397 0.06461095 0.03591489 0.06461095 0.02912288 0.06469196 0.02247095 0.06327795 0.02913397 0.06461095 0.03592497 0.06469196 0.03591489 0.06461095 0.04255396 0.06319999 0.03592497 0.06469196 0.02912288 0.06469196 0.03591489 0.06461095 0.04257798 0.06327795 0.04255396 0.06319999 0.04874998 0.06044089 0.04257798 0.06327795 0.03592497 0.06469196 0.04255396 0.06319999 0.04879099 0.06051188 0.04874998 0.06044089 0.05423599 0.056454 0.04879099 0.06051188 0.04257798 0.06327795 0.04874998 0.06044089 0.05429196 0.05651396 0.05423599 0.056454 0.05877488 0.05141192 0.05429196 0.05651396 0.04879099 0.06051188 0.05423599 0.056454 0.05883991 0.05146098 0.05877488 0.05141192 0.06216388 0.045542 0.05883991 0.05146098 0.05429196 0.05651396 0.05877488 0.05141192 0.06223791 0.04557293 0.06216388 0.045542 0.06425899 0.03908896 0.06223791 0.04557293 0.05883991 0.05146098 0.06216388 0.045542 0.05907899 0.03384399 0.05947995 0.03234595 0.06425899 0.03908896 0.05798298 0.03494 0.05907899 0.03384399 0.06425899 0.03908896 0.05648595 0.03534096 0.05798298 0.03494 0.06425899 0.03908896 0.06433796 0.03910696 0.06223791 0.04557293 0.06425899 0.03908896 0.05633199 0.02936995 0.05648595 0.02935099 0.05798298 0.02975195 0.05484396 0.029769 0.05498999 0.02975195 0.05648595 0.02935099 0.05484396 0.029769 0.05648595 0.02935099 0.05633199 0.02936995 0.05781888 0.029769 0.05798298 0.02975195 0.05907899 0.0308479 0.05781888 0.029769 0.05633199 0.02936995 0.05798298 0.02975195 0.05890792 0.03085798 0.05907899 0.0308479 0.05947995 0.03234595 0.05781888 0.029769 0.05907899 0.0308479 0.05890792 0.03085798 0.0593059 0.03234595 0.05947995 0.03234595 0.05907899 0.03384399 0.05890792 0.03085798 0.05947995 0.03234595 0.0593059 0.03234595 0.05890792 0.03383398 0.05907899 0.03384399 0.05798298 0.03494 0.0593059 0.03234595 0.05907899 0.03384399 0.05890792 0.03383398 0.05781888 0.03492289 0.05798298 0.03494 0.05648595 0.03534096 0.05890792 0.03383398 0.05798298 0.03494 0.05781888 0.03492289 0.05633199 0.03532195 0.05648595 0.03534096 0.05498999 0.03494 0.05781888 0.03492289 0.05648595 0.03534096 0.05633199 0.03532195 0.05484396 0.03492289 0.05498999 0.03494 0.05389297 0.03384399 0.05633199 0.03532195 0.05498999 0.03494 0.05484396 0.03492289 0.05375498 0.03383398 0.05389297 0.03384399 0.05349195 0.03234595 0.05484396 0.03492289 0.05389297 0.03384399 0.05375498 0.03383398 0.053357 0.03234595 0.05349195 0.03234595 0.05389297 0.0308479 0.05375498 0.03383398 0.05349195 0.03234595 0.053357 0.03234595 0.05375498 0.03085798 0.05389297 0.0308479 0.05498999 0.02975195 0.053357 0.03234595 0.05389297 0.0308479 0.05375498 0.03085798 0.05375498 0.03085798 0.05498999 0.02975195 0.05484396 0.029769 0.06117689 0.03234595 0.06504899 0.03234595 0.06433796 0.02558499 0.06045889 0.03872096 0.06504899 0.03234595 0.06117689 0.03234595 0.06045889 0.03872096 0.06433796 0.03910696 0.06504899 0.03234595 0.06045889 0.02597099 0.06433796 0.02558499 0.06223791 0.01911896 0.06045889 0.02597099 0.06117689 0.03234595 0.06433796 0.02558499 0.0583409 0.01991593 0.06223791 0.01911896 0.05883991 0.01323091 0.0583409 0.01991593 0.06045889 0.02597099 0.06223791 0.01911896 0.054928 0.01448297 0.05883991 0.01323091 0.05429196 0.008177995 0.054928 0.01448297 0.0583409 0.01991593 0.05883991 0.01323091 0.05039197 0.009945988 0.05429196 0.008177995 0.04879099 0.004179954 0.05039197 0.009945988 0.054928 0.01448297 0.05429196 0.008177995 0.04495888 0.006531894 0.04879099 0.004179954 0.04257798 0.001413941 0.04495888 0.006531894 0.05039197 0.009945988 0.04879099 0.004179954 0.03890198 0.004411995 0.04257798 0.001413941 0.03592497 0 0.03890198 0.004411995 0.04495888 0.006531894 0.04257798 0.001413941 0.03252393 0.003692984 0.03592497 0 0.02912288 0 0.03252393 0.003692984 0.03890198 0.004411995 0.03592497 0 0.02614688 0.004411995 0.02912288 0 0.02247095 0.001413941 0.02614688 0.004411995 0.03252393 0.003692984 0.02912288 0 0.02008998 0.006531894 0.02247095 0.001413941 0.016258 0.004179954 0.02008998 0.006531894 0.02614688 0.004411995 0.02247095 0.001413941 0.01465696 0.009945988 0.016258 0.004179954 0.0107569 0.008177995 0.01465696 0.009945988 0.02008998 0.006531894 0.016258 0.004179954 0.01011997 0.01448297 0.0107569 0.008177995 0.006207883 0.01323091 0.01011997 0.01448297 0.01465696 0.009945988 0.0107569 0.008177995 0.006707966 0.01991593 0.006207883 0.01323091 0.002809882 0.01911896 0.006707966 0.01991593 0.01011997 0.01448297 0.006207883 0.01323091 0.004589915 0.02597099 0.002809882 0.01911896 7.1e-4 0.02558499 0.004589915 0.02597099 0.006707966 0.01991593 0.002809882 0.01911896 0.004589915 0.02597099 7.1e-4 0.02558499 0 0.03234595 0.003871977 0.03234595 0.004589915 0.02597099 0 0.03234595 7.1e-4 0.03910696 0.003871977 0.03234595 0 0.03234595 0.06124889 0.03234595 0.06117689 0.03234595 0.06045889 0.02597099 0.06052899 0.03873592 0.06117689 0.03234595 0.06124889 0.03234595 0.06045889 0.03872096 0.06117689 0.03234595 0.06052899 0.03873592 0.06052899 0.02595692 0.06045889 0.02597099 0.0583409 0.01991593 0.06052899 0.02595692 0.06124889 0.03234595 0.06045889 0.02597099 0.05840498 0.01988291 0.0583409 0.01991593 0.054928 0.01448297 0.05840498 0.01988291 0.06052899 0.02595692 0.0583409 0.01991593 0.05498492 0.01443892 0.054928 0.01448297 0.05039197 0.009945988 0.05498492 0.01443892 0.05840498 0.01988291 0.054928 0.01448297 0.05043697 0.00988996 0.05039197 0.009945988 0.04495888 0.006531894 0.05043697 0.00988996 0.05498492 0.01443892 0.05039197 0.009945988 0.04498791 0.006465971 0.04495888 0.006531894 0.03890198 0.004411995 0.04498791 0.006465971 0.05043697 0.00988996 0.04495888 0.006531894 0.03891998 0.0043419 0.03890198 0.004411995 0.03252393 0.003692984 0.03891998 0.0043419 0.04498791 0.006465971 0.03890198 0.004411995 0.03252393 0.003621995 0.03252393 0.003692984 0.02614688 0.004411995 0.03252393 0.003621995 0.03891998 0.0043419 0.03252393 0.003692984 0.02612888 0.0043419 0.02614688 0.004411995 0.02008998 0.006531894 0.02612888 0.0043419 0.03252393 0.003621995 0.02614688 0.004411995 0.02006 0.006465971 0.02008998 0.006531894 0.01465696 0.009945988 0.02006 0.006465971 0.02612888 0.0043419 0.02008998 0.006531894 0.01461088 0.00988996 0.01465696 0.009945988 0.01011997 0.01448297 0.01461088 0.00988996 0.02006 0.006465971 0.01465696 0.009945988 0.01006299 0.01443892 0.01011997 0.01448297 0.006707966 0.01991593 0.01006299 0.01443892 0.01461088 0.00988996 0.01011997 0.01448297 0.006643891 0.01988291 0.006707966 0.01991593 0.004589915 0.02597099 0.006643891 0.01988291 0.01006299 0.01443892 0.006707966 0.01991593 0.004518926 0.02595692 0.004589915 0.02597099 0.003871977 0.03234595 0.004518926 0.02595692 0.006643891 0.01988291 0.004589915 0.02597099 0.003798902 0.03234595 0.004518926 0.02595692 0.003871977 0.03234595 0.004589915 0.03872096 0.003798902 0.03234595 0.003871977 0.03234595 0.004589915 0.03872096 0.003871977 0.03234595 7.1e-4 0.03910696 0.003798902 0.03234595 0.06124889 0.03234595 0.06052899 0.02595692 0.004518926 0.03873592 0.06124889 0.03234595 0.003798902 0.03234595 0.004518926 0.03873592 0.06052899 0.03873592 0.06124889 0.03234595 0.004518926 0.02595692 0.06052899 0.02595692 0.05840498 0.01988291 0.003798902 0.03234595 0.06052899 0.02595692 0.004518926 0.02595692 0.006643891 0.01988291 0.05840498 0.01988291 0.05498492 0.01443892 0.004518926 0.02595692 0.05840498 0.01988291 0.006643891 0.01988291 0.01006299 0.01443892 0.05498492 0.01443892 0.05043697 0.00988996 0.006643891 0.01988291 0.05498492 0.01443892 0.01006299 0.01443892 0.01461088 0.00988996 0.05043697 0.00988996 0.04498791 0.006465971 0.01006299 0.01443892 0.05043697 0.00988996 0.01461088 0.00988996 0.02006 0.006465971 0.04498791 0.006465971 0.03891998 0.0043419 0.01461088 0.00988996 0.04498791 0.006465971 0.02006 0.006465971 0.02612888 0.0043419 0.03891998 0.0043419 0.03252393 0.003621995 0.02006 0.006465971 0.03891998 0.0043419 0.02612888 0.0043419 0.004589915 0.03872096 0.004518926 0.03873592 0.003798902 0.03234595 0.006643891 0.04480898 0.05840498 0.04480898 0.06052899 0.03873592 0.06045889 0.03872096 0.06052899 0.03873592 0.05840498 0.04480898 0.004518926 0.03873592 0.006643891 0.04480898 0.06052899 0.03873592 0.01006299 0.05025297 0.05498492 0.05025297 0.05840498 0.04480898 0.0583409 0.04477691 0.05840498 0.04480898 0.05498492 0.05025297 0.006643891 0.04480898 0.01006299 0.05025297 0.05840498 0.04480898 0.06045889 0.03872096 0.05840498 0.04480898 0.0583409 0.04477691 0.01461088 0.054802 0.05043697 0.054802 0.05498492 0.05025297 0.054928 0.05020892 0.05498492 0.05025297 0.05043697 0.054802 0.01006299 0.05025297 0.01461088 0.054802 0.05498492 0.05025297 0.0583409 0.04477691 0.05498492 0.05025297 0.054928 0.05020892 0.02006 0.05822592 0.04498791 0.05822592 0.05043697 0.054802 0.05039197 0.05474597 0.05043697 0.054802 0.04498791 0.05822592 0.01461088 0.054802 0.02006 0.05822592 0.05043697 0.054802 0.054928 0.05020892 0.05043697 0.054802 0.05039197 0.05474597 0.02612888 0.06035 0.03891998 0.06035 0.04498791 0.05822592 0.04495888 0.05816096 0.04498791 0.05822592 0.03891998 0.06035 0.02006 0.05822592 0.02612888 0.06035 0.04498791 0.05822592 0.05039197 0.05474597 0.04498791 0.05822592 0.04495888 0.05816096 0.02612888 0.06035 0.03252393 0.06106996 0.03891998 0.06035 0.03890198 0.06027996 0.03891998 0.06035 0.03252393 0.06106996 0.04495888 0.05816096 0.03891998 0.06035 0.03890198 0.06027996 0.03252393 0.06099891 0.03252393 0.06106996 0.02612888 0.06035 0.03890198 0.06027996 0.03252393 0.06106996 0.03252393 0.06099891 0.02614688 0.06027996 0.02612888 0.06035 0.02006 0.05822592 0.03252393 0.06099891 0.02612888 0.06035 0.02614688 0.06027996 0.02008998 0.05816096 0.02006 0.05822592 0.01461088 0.054802 0.02614688 0.06027996 0.02006 0.05822592 0.02008998 0.05816096 0.01465696 0.05474597 0.01461088 0.054802 0.01006299 0.05025297 0.02008998 0.05816096 0.01461088 0.054802 0.01465696 0.05474597 0.01011997 0.05020892 0.01006299 0.05025297 0.006643891 0.04480898 0.01465696 0.05474597 0.01006299 0.05025297 0.01011997 0.05020892 0.006707966 0.04477691 0.006643891 0.04480898 0.004518926 0.03873592 0.01011997 0.05020892 0.006643891 0.04480898 0.006707966 0.04477691 0.006707966 0.04477691 0.004518926 0.03873592 0.004589915 0.03872096 0.004589915 0.03872096 7.1e-4 0.03910696 0.002809882 0.04557293 0.006707966 0.04477691 0.002809882 0.04557293 0.006207883 0.05146098 0.006707966 0.04477691 0.004589915 0.03872096 0.002809882 0.04557293 0.01011997 0.05020892 0.006207883 0.05146098 0.0107569 0.05651396 0.01011997 0.05020892 0.006707966 0.04477691 0.006207883 0.05146098 0.01465696 0.05474597 0.0107569 0.05651396 0.016258 0.06051188 0.01465696 0.05474597 0.01011997 0.05020892 0.0107569 0.05651396 0.02008998 0.05816096 0.016258 0.06051188 0.02247095 0.06327795 0.02008998 0.05816096 0.01465696 0.05474597 0.016258 0.06051188 0.02614688 0.06027996 0.02247095 0.06327795 0.02912288 0.06469196 0.02614688 0.06027996 0.02008998 0.05816096 0.02247095 0.06327795 0.03252393 0.06099891 0.02912288 0.06469196 0.03592497 0.06469196 0.03252393 0.06099891 0.02614688 0.06027996 0.02912288 0.06469196 0.03890198 0.06027996 0.03592497 0.06469196 0.04257798 0.06327795 0.03890198 0.06027996 0.03252393 0.06099891 0.03592497 0.06469196 0.04495888 0.05816096 0.04257798 0.06327795 0.04879099 0.06051188 0.04495888 0.05816096 0.03890198 0.06027996 0.04257798 0.06327795 0.05039197 0.05474597 0.04879099 0.06051188 0.05429196 0.05651396 0.05039197 0.05474597 0.04495888 0.05816096 0.04879099 0.06051188 0.054928 0.05020892 0.05429196 0.05651396 0.05883991 0.05146098 0.054928 0.05020892 0.05039197 0.05474597 0.05429196 0.05651396 0.0583409 0.04477691 0.05883991 0.05146098 0.06223791 0.04557293 0.0583409 0.04477691 0.054928 0.05020892 0.05883991 0.05146098 0.06045889 0.03872096 0.06223791 0.04557293 0.06433796 0.03910696 0.06045889 0.03872096 0.0583409 0.04477691 0.06223791 0.04557293 0.05484396 0.03492289 0.05484396 0.029769 0.05633199 0.02936995 0.05633199 0.03532195 0.05484396 0.03492289 0.05633199 0.02936995 0.05781888 0.029769 0.05633199 0.03532195 0.05633199 0.02936995 0.05375498 0.03383398 0.05375498 0.03085798 0.05484396 0.029769 0.05484396 0.03492289 0.05375498 0.03383398 0.05484396 0.029769 0.05375498 0.03383398 0.053357 0.03234595 0.05375498 0.03085798 0.05781888 0.029769 0.05781888 0.03492289 0.05633199 0.03532195 0.05890792 0.03085798 0.05890792 0.03383398 0.05781888 0.03492289 0.05781888 0.029769 0.05890792 0.03085798 0.05781888 0.03492289 0.05890792 0.03085798 0.0593059 0.03234595 0.05890792 0.03383398 + + + + + + + + + + + + + + +

0 0 0 1 0 1 2 0 2 3 1 3 4 2 4 5 3 5 6 4 6 2 4 7 7 4 8 8 5 9 9 6 10 10 7 11 11 8 12 0 8 13 2 8 14 6 9 15 11 9 16 2 9 17 8 5 18 10 7 19 12 7 20 13 10 21 14 10 22 1 10 23 15 11 24 5 3 25 16 12 26 17 13 27 13 13 28 1 13 29 18 14 30 17 14 31 1 14 32 0 15 33 18 15 34 1 15 35 15 11 36 3 1 37 5 3 38 19 16 39 20 16 40 14 16 41 21 17 42 16 12 43 22 18 44 13 19 45 19 19 46 14 19 47 21 17 48 15 11 49 16 12 50 23 20 51 24 20 52 20 20 53 25 21 54 22 18 55 26 22 56 19 8 57 23 8 58 20 8 59 25 21 60 21 17 61 22 18 62 27 23 63 28 23 64 24 23 65 29 24 66 26 22 67 30 25 68 23 26 69 27 26 70 24 26 71 29 24 72 25 21 73 26 22 74 31 27 75 32 27 76 28 27 77 33 25 78 30 25 79 34 28 80 27 8 81 31 8 82 28 8 83 33 25 84 29 24 85 30 25 86 35 29 87 36 29 88 32 29 89 37 30 90 34 28 91 38 31 92 31 32 93 35 32 94 32 32 95 37 30 96 33 25 97 34 28 98 39 33 99 38 31 100 40 34 101 39 33 102 37 30 103 38 31 104 41 35 105 40 34 106 42 36 107 41 35 108 39 33 109 40 34 110 43 37 111 42 36 112 44 38 113 43 37 114 41 35 115 42 36 116 45 38 117 44 38 118 46 39 119 45 38 120 43 37 121 44 38 122 47 40 123 46 39 124 48 41 125 47 40 126 45 38 127 46 39 128 49 42 129 48 41 130 50 43 131 49 42 132 47 40 133 48 41 134 51 44 135 50 43 136 52 45 137 51 44 138 49 42 139 50 43 140 53 46 141 54 46 142 17 46 143 55 47 144 52 45 145 56 48 146 57 8 147 17 8 148 18 8 149 58 49 150 53 49 151 17 49 152 57 50 153 58 50 154 17 50 155 55 47 156 51 44 157 52 45 158 7 51 159 59 51 160 54 51 161 60 52 162 61 53 163 62 54 164 63 8 165 7 8 166 54 8 167 64 8 168 63 8 169 54 8 170 65 8 171 64 8 172 54 8 173 53 55 174 65 55 175 54 55 176 66 48 177 55 47 178 56 48 179 67 56 180 68 56 181 59 56 182 69 57 183 62 54 184 70 58 185 7 59 186 67 59 187 59 59 188 69 57 189 60 52 190 62 54 191 71 60 192 72 60 193 68 60 194 73 61 195 70 58 196 74 62 197 67 63 198 71 63 199 68 63 200 73 61 201 69 57 202 70 58 203 75 64 204 76 64 205 72 64 206 77 65 207 74 62 208 78 66 209 71 8 210 75 8 211 72 8 212 77 65 213 73 61 214 74 62 215 79 67 216 80 67 217 76 67 218 81 68 219 78 66 220 82 69 221 75 70 222 79 70 223 76 70 224 81 68 225 77 65 226 78 66 227 83 71 228 84 71 229 80 71 230 85 69 231 82 69 232 86 72 233 79 8 234 83 8 235 80 8 236 85 69 237 81 68 238 82 69 239 87 73 240 88 73 241 84 73 242 89 74 243 86 72 244 90 75 245 83 76 246 87 76 247 84 76 248 89 74 249 85 69 250 86 72 251 91 77 252 90 75 253 92 78 254 91 77 255 89 74 256 90 75 257 93 79 258 92 78 259 94 80 260 93 79 261 91 77 262 92 78 263 95 81 264 94 80 265 96 82 266 95 81 267 93 79 268 94 80 269 97 82 270 96 82 271 98 83 272 97 82 273 95 81 274 96 82 275 99 84 276 98 83 277 100 85 278 99 84 279 97 82 280 98 83 281 101 86 282 100 85 283 102 87 284 101 86 285 99 84 286 100 85 287 103 88 288 102 87 289 9 6 290 103 88 291 101 86 292 102 87 293 104 8 294 6 8 295 7 8 296 105 8 297 104 8 298 7 8 299 63 89 300 105 89 301 7 89 302 8 5 303 103 88 304 9 6 305 106 90 306 107 91 307 108 92 308 109 93 309 110 94 310 111 95 311 109 93 312 111 95 313 112 96 314 113 97 315 108 92 316 114 98 317 113 97 318 106 90 319 108 92 320 115 99 321 114 98 322 116 100 323 113 97 324 114 98 325 115 99 326 117 100 327 116 100 328 118 101 329 115 99 330 116 100 331 117 100 332 119 102 333 118 101 334 120 103 335 117 100 336 118 101 337 119 102 338 121 104 339 120 103 340 122 105 341 119 102 342 120 103 343 121 104 344 123 106 345 124 107 346 125 108 347 121 104 348 122 105 349 126 109 350 127 110 351 125 108 352 128 111 353 123 106 354 125 108 355 127 110 356 129 112 357 128 111 358 130 113 359 127 110 360 128 111 361 129 112 362 131 113 363 130 113 364 132 114 365 129 112 366 130 113 367 131 113 368 133 115 369 132 114 370 110 94 371 131 113 372 132 114 373 133 115 374 133 115 375 110 94 376 109 93 377 134 116 378 135 117 379 136 118 380 137 119 381 138 120 382 139 121 383 137 119 384 140 122 385 138 120 386 141 123 387 136 118 388 142 124 389 141 123 390 134 116 391 136 118 392 143 125 393 142 124 394 144 126 395 143 125 396 141 123 397 142 124 398 145 127 399 144 126 400 146 128 401 145 127 402 143 125 403 144 126 404 147 129 405 146 128 406 148 130 407 147 129 408 145 127 409 146 128 410 149 131 411 148 130 412 150 132 413 149 131 414 147 129 415 148 130 416 151 133 417 150 132 418 152 134 419 151 133 420 149 131 421 150 132 422 153 135 423 152 134 424 154 136 425 153 135 426 151 133 427 152 134 428 155 137 429 154 136 430 156 138 431 155 137 432 153 135 433 154 136 434 157 139 435 156 138 436 158 140 437 157 139 438 155 137 439 156 138 440 159 141 441 158 140 442 160 142 443 159 141 444 157 139 445 158 140 446 161 143 447 160 142 448 162 144 449 161 143 450 159 141 451 160 142 452 163 145 453 162 144 454 164 146 455 163 145 456 161 143 457 162 144 458 165 147 459 164 146 460 166 148 461 165 147 462 163 145 463 164 146 464 165 147 465 166 148 466 167 149 467 168 150 468 165 147 469 167 149 470 169 151 471 170 152 472 171 153 473 172 154 474 173 155 475 174 156 476 175 157 477 176 158 478 177 159 479 178 160 480 176 158 481 175 157 482 179 161 483 174 156 484 180 162 485 179 161 486 172 154 487 174 156 488 181 163 489 180 162 490 182 164 491 181 163 492 179 161 493 180 162 494 183 165 495 182 164 496 184 166 497 183 165 498 181 163 499 182 164 500 185 167 501 184 166 502 186 168 503 185 167 504 183 165 505 184 166 506 187 169 507 186 168 508 188 170 509 187 169 510 185 167 511 186 168 512 189 171 513 188 170 514 190 172 515 189 171 516 187 169 517 188 170 518 191 172 519 190 172 520 192 173 521 191 172 522 189 171 523 190 172 524 193 174 525 192 173 526 194 175 527 193 174 528 191 172 529 192 173 530 195 176 531 194 175 532 196 177 533 195 176 534 193 174 535 194 175 536 197 178 537 196 177 538 198 179 539 197 178 540 195 176 541 196 177 542 199 180 543 198 179 544 200 181 545 199 180 546 197 178 547 198 179 548 201 182 549 200 181 550 202 183 551 201 182 552 199 180 553 200 181 554 203 184 555 202 183 556 204 185 557 203 184 558 201 182 559 202 183 560 205 186 561 203 184 562 204 185 563 206 187 564 207 188 565 208 189 566 209 190 567 170 152 568 169 151 569 210 191 570 211 191 571 212 191 572 213 192 573 211 192 574 210 192 575 213 193 576 214 193 577 211 193 578 215 194 579 212 194 580 216 194 581 210 192 582 212 192 583 215 192 584 217 192 585 216 192 586 218 192 587 215 192 588 216 192 589 217 192 590 219 195 591 218 195 592 220 195 593 217 192 594 218 192 595 219 192 596 221 196 597 220 196 598 222 196 599 219 192 600 220 192 601 221 192 602 223 197 603 222 197 604 224 197 605 221 192 606 222 192 607 223 192 608 225 192 609 224 192 610 226 192 611 223 198 612 224 198 613 225 198 614 206 187 615 227 199 616 207 188 617 228 200 618 229 200 619 214 200 620 178 160 621 175 157 622 230 201 623 213 192 624 228 192 625 214 192 626 231 192 627 232 192 628 229 192 629 233 202 630 230 201 631 234 203 632 228 192 633 231 192 634 229 192 635 178 160 636 230 201 637 233 202 638 235 204 639 236 204 640 232 204 641 237 205 642 234 203 643 238 206 644 231 207 645 235 207 646 232 207 647 233 202 648 234 203 649 237 205 650 239 208 651 240 208 652 236 208 653 241 209 654 238 206 655 242 210 656 235 192 657 239 192 658 236 192 659 237 205 660 238 206 661 241 209 662 243 211 663 244 211 664 240 211 665 245 212 666 242 210 667 246 213 668 239 214 669 243 214 670 240 214 671 241 209 672 242 210 673 245 212 674 243 192 675 247 192 676 244 192 677 248 215 678 246 213 679 249 216 680 245 212 681 246 213 682 248 215 683 250 216 684 249 216 685 251 217 686 248 215 687 249 216 688 250 216 689 252 218 690 251 217 691 253 219 692 250 216 693 251 217 694 252 218 695 254 220 696 253 219 697 255 221 698 252 218 699 253 219 700 254 220 701 256 222 702 255 221 703 257 223 704 254 220 705 255 221 706 256 222 707 258 224 708 257 223 709 259 225 710 256 222 711 257 223 712 258 224 713 260 226 714 259 225 715 227 199 716 258 224 717 259 225 718 260 226 719 260 226 720 227 199 721 206 187 722 209 190 723 169 151 724 261 227 725 262 228 726 261 227 727 263 229 728 262 228 729 209 190 730 261 227 731 264 230 732 263 229 733 265 231 734 264 230 735 262 228 736 263 229 737 266 232 738 265 231 739 267 233 740 266 232 741 264 230 742 265 231 743 268 234 744 267 233 745 269 235 746 268 234 747 266 232 748 267 233 749 270 236 750 269 235 751 271 237 752 270 236 753 268 234 754 269 235 755 272 238 756 271 237 757 273 239 758 272 238 759 270 236 760 271 237 761 274 240 762 273 239 763 275 241 764 274 240 765 272 238 766 273 239 767 276 242 768 275 241 769 277 243 770 276 242 771 274 240 772 275 241 773 278 244 774 277 243 775 279 245 776 278 244 777 276 242 778 277 243 779 280 246 780 279 245 781 281 247 782 280 246 783 278 244 784 279 245 785 282 248 786 281 247 787 283 249 788 282 248 789 280 246 790 281 247 791 137 119 792 283 249 793 140 122 794 137 119 795 282 248 796 283 249 797 284 8 798 285 8 799 286 8 800 287 8 801 284 8 802 286 8 803 288 8 804 287 8 805 286 8 806 289 8 807 290 8 808 285 8 809 284 8 810 289 8 811 285 8 812 289 8 813 291 8 814 290 8 815 288 8 816 292 8 817 287 8 818 293 8 819 294 8 820 292 8 821 288 8 822 293 8 823 292 8 824 293 8 825 295 8 826 294 8 827

+
+
+
+
+ + + + + -4.37108e-11 1.62919e-10 9.99987e-4 0 9.99987e-4 -2.98019e-11 4.37108e-11 0 2.98019e-11 9.99987e-4 -1.62919e-10 -1.0014 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl new file mode 100644 index 0000000000000000000000000000000000000000..7c86d6e49b328ba00517a57b80c70b5823081360 GIT binary patch literal 2284 zcmb7_PfJu`6vkhojeUv;r_;%2cMJmX{m?w=IW0KqN|;1%Wxc zAc*h}7-fqV6;`Hc5lTdz=brbu_j#2T4d@(w&hI?uocFymXKsv+G_N)WYnPfMmusho z8pDH)=8@i`{U>YPSFT;G9qS4I^*U_X-^N;}zMQ?D5nO3^4NTrWG>g9x4;?&EUulom zXD+PQ5r?oLger`c_IPW5U-rX(yr$QJLIQOkS^YQW;~vQV9tl+#EA1YiZH9I03?7=r z*yrdPxU=;9zI&`0@jeomlnP_iC7pQ8`5aDoCl!r7y={-rCLRT$3S*_+15?}d9e8LK zW7M_!IFINNcU2IoFh*U{?h(&CA)t_e$LhJM~J>`V#|&0>tY zuWV0`%Q-;UnG}R7j8T`gdu-aCe#TvC7Groku=?-H^VqQL?MSG?7-j6x)IKR_jFhI54WK6g|PYTPcKvus_0DGt>^mhJX1wGOuK5g z?oE?W52aJ$m)-QW_$f*Pw}CPCqo)~y5~?s(+V9nl-SpL6-yhsNc7-gZLr_8$#!55h zzVZ&U+}+OuF~3Xr|B6tB`*EWB1P{TUj}vjb9o`IN@jMXoj_vhOh3A1R-eV``#X}X| z5@eZo`TTPRyyxhuRCt0Qc5j4Kx+~p+&KJVIo40wdlF4-@?UwbuD^;|^e|M$sN~gqM DKkB`Q literal 0 HcmV?d00001 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae new file mode 100644 index 0000000000..3fd9152677 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae @@ -0,0 +1,145 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T14:47:26 + 2019-01-15T14:47:26 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.31 0.33 0.33 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + + + + 26.12602 99.69651 66.13459 42.55324 95 58 34.5009 97.64975 62.5895 32.92695 129.5 57.02968 34.5009 97.64975 62.5895 42.55324 95 58 17.52961 101.1482 68.64896 8.79768 102.0146 70.14962 0 102.3025 70.64831 -8.797612 102.0146 70.14963 37.09656 129.5 54.40962 41.05839 129.5 51.4856 50.89944 65.33378 58 60.35892 28.24008 58 50.89944 65.33378 58 42.55324 95 58 -17.52952 101.1482 68.64897 -26.12594 99.69652 66.13462 -34.50087 97.64976 62.58951 -42.55324 95 58 -20.17238 90.05471 58 -42.55324 95 58 -20 85.97177 58 28.5724 129.5 59.33119 26.12602 99.69651 66.13459 19.40983 129.5 62.9271 17.52961 101.1482 68.64896 24.05798 129.5 61.30075 9.815401 129.5 65.11697 8.79768 102.0146 70.14962 14.65357 129.5 64.20149 0 129.5 65.85266 0 102.3025 70.64831 4.922456 129.5 65.66841 -4.922456 129.5 65.66841 0 102.3025 70.64831 0 129.5 65.85266 -8.797612 102.0146 70.14963 0 129.5 61.5 0 129.5 65.85266 4.922456 129.5 65.66841 -9.621398 129.5 60.74267 -4.922456 129.5 65.66841 9.621398 129.5 60.74267 9.815401 129.5 65.11697 14.65357 129.5 64.20149 19.00452 129.5 58.48989 19.40983 129.5 62.9271 24.05798 129.5 61.30075 27.91977 129.5 54.79717 28.5724 129.5 59.33119 32.92695 129.5 57.02968 36.14879 129.5 49.75454 37.09656 129.5 54.40962 41.05839 129.5 51.4856 44.79069 129.5 48.27375 43.48752 129.5 43.48654 44.79069 129.5 48.27375 60.29818 28.47987 58 48.27289 129.5 44.7917 48.27289 129.5 44.7917 64.28165 28.47987 53.55129 51.48568 129.5 41.05846 49.75447 129.5 36.14874 51.48568 129.5 41.05846 58.44707 101.1704 40.04206 54.4104 129.5 37.0955 54.4104 129.5 37.0955 58.50773 99.33776 40.52366 58.5972 97.30286 41.02306 58.71929 95.04547 41.54118 58.87856 92.54319 42.07857 59.0805 89.76996 42.63568 59.33171 86.69617 43.21257 59.64018 83.28813 43.80873 60.01565 79.50714 44.4229 60.4699 75.3105 45.05237 61.01741 70.64891 45.69291 61.67665 65.46395 46.33765 62.47172 59.68569 46.97561 63.43516 53.22743 47.58906 59.64444 112.3794 34.43574 57.0303 129.5 32.92578 54.79654 129.5 27.92101 57.0303 129.5 32.92578 59.45811 112.327 34.77478 59.27178 112.1529 35.15167 59.10295 111.8574 35.53603 58.95536 111.4522 35.91783 58.82619 110.9408 36.30103 58.71517 110.3289 36.68436 58.62092 109.6142 37.07111 58.54294 108.7934 37.46332 58.48117 107.8602 37.86329 58.43608 106.8069 38.2729 58.40855 105.6228 38.69424 58.39995 104.2973 39.12866 58.41205 102.8183 39.57741 63.48478 102.8041 30.79572 59.3311 129.5 28.57235 58.48997 129.5 19.00455 59.3311 129.5 28.57235 63.08979 104.2849 31.00957 62.71754 105.6121 31.23422 62.3661 106.7978 31.46875 62.03363 107.8526 31.71264 61.71778 108.7874 31.96623 61.4167 109.6097 32.23007 61.12855 110.3256 32.50528 60.85177 110.9386 32.7933 60.58418 111.4509 33.09705 60.32679 111.857 33.41637 60.07841 112.1526 33.75463 59.84508 112.3269 34.10456 68.485 79.47608 29.76399 61.30022 129.5 24.0592 60.74289 129.5 9.620025 61.30022 129.5 24.0592 67.76525 83.25878 29.74548 67.09452 86.66883 29.77605 66.46907 89.74466 29.84662 65.88543 92.5197 29.94999 65.34017 95.02383 30.08051 64.83016 97.28314 30.23363 64.35267 99.31984 30.40568 63.90499 101.1544 30.59381 79.85744 28.47987 24.95315 62.92676 129.5 19.4111 61.4999 129.5 0 62.92676 129.5 19.4111 71.92422 59.64659 30.61713 70.97407 65.42729 30.24676 70.08599 70.6142 29.99756 69.2574 75.27765 29.84313 62.92676 129.5 -19.4111 64.20159 129.5 14.65359 82.2877 28.47987 15.11971 64.20159 129.5 14.65359 61.30022 129.5 -24.0592 64.20159 129.5 -14.65359 65.11721 129.5 9.814099 65.11721 129.5 9.814099 65.11721 129.5 -9.814099 65.66848 129.5 4.920582 83.51181 28.47987 5.064649 65.66848 129.5 4.920582 65.66848 129.5 -4.920582 65.85256 129.5 0 65.85256 129.5 0 83.51181 28.47987 -5.064649 65.66848 129.5 -4.920582 82.2877 28.47987 -15.11971 65.11721 129.5 -9.814099 64.20159 129.5 -14.65359 79.85744 28.47987 -24.95315 62.92676 129.5 -19.4111 61.30022 129.5 -24.0592 63.90098 101.1704 -30.59562 59.3311 129.5 -28.57235 60.74289 129.5 -9.620025 59.3311 129.5 -28.57235 64.34839 99.33776 -30.40735 64.82563 97.30286 -30.23513 65.33538 95.04547 -30.08181 65.8804 92.54319 -29.95104 66.46384 89.76996 -29.84738 67.08905 86.69617 -29.77649 67.75957 83.28813 -29.74555 68.47919 79.50714 -29.76363 69.25145 75.3105 -29.84229 70.07994 70.64891 -29.99617 70.96791 65.46395 -30.24472 71.91793 59.68569 -30.61429 72.93093 53.22743 -31.14193 59.64444 112.3794 -34.43574 57.0303 129.5 -32.92578 58.48997 129.5 -19.00455 57.0303 129.5 -32.92578 59.8449 112.327 -34.10485 60.07813 112.1529 -33.75503 60.32658 111.8574 -33.41664 60.58344 111.4522 -33.09793 60.85071 110.9408 -32.79446 61.12717 110.3289 -32.50665 61.41498 109.6142 -32.23165 61.71566 108.7934 -31.96801 62.03116 107.8602 -31.71454 62.36334 106.8069 -31.47068 62.71448 105.6228 -31.23617 63.08639 104.2973 -31.01151 63.48107 102.8183 -30.79761 58.41226 102.8041 -39.58157 54.4104 129.5 -37.0955 54.79654 129.5 -27.92101 54.4104 129.5 -37.0955 58.39997 104.2849 -39.13258 58.4084 105.6121 -38.69787 58.43579 106.7978 -38.27625 58.48076 107.8526 -37.86638 58.54246 108.7874 -37.46606 58.62041 109.6097 -37.07339 58.71467 110.3256 -36.68623 58.82572 110.9386 -36.30252 58.95497 111.4509 -35.91892 59.10282 111.857 -35.53635 59.27157 112.1526 -35.15211 59.45796 112.3269 -34.77508 60.01887 79.47608 -44.42775 51.48568 129.5 -41.05846 51.48568 129.5 -41.05846 59.64296 83.25878 -43.81369 59.33407 86.66883 -43.21752 59.08246 89.74466 -42.64059 58.88017 92.5197 -42.08345 58.72057 95.02383 -41.54599 58.59817 97.28314 -41.02774 58.50842 99.31984 -40.5282 58.44751 101.1544 -40.04644 61.53878 28.47987 -56.68199 48.27289 129.5 -44.7917 49.75447 129.5 -36.14874 48.27289 129.5 -44.7917 62.47731 59.64659 -46.97964 61.68149 65.42729 -46.34197 61.02164 70.6142 -45.69746 60.4736 75.27765 -45.05709 54.2379 28.47987 -63.70338 44.79069 129.5 -48.27375 44.79069 129.5 -48.27375 41.05839 129.5 -51.4856 43.48752 129.5 -43.48654 41.05839 129.5 -51.4856 46.14201 28.47987 -69.79101 37.09656 129.5 -54.40962 37.09656 129.5 -54.40962 32.92695 129.5 -57.02968 36.14879 129.5 -49.75454 32.92695 129.5 -57.02968 37.36978 28.47987 -74.85566 28.5724 129.5 -59.33119 28.5724 129.5 -59.33119 28.04979 28.47987 -78.82309 24.05798 129.5 -61.30075 27.91977 129.5 -54.79717 24.05798 129.5 -61.30075 19.40983 129.5 -62.9271 19.40983 129.5 -62.9271 18.31866 28.47987 -81.63515 14.65357 129.5 -64.20149 19.00452 129.5 -58.48989 14.65357 129.5 -64.20149 9.815401 129.5 -65.11697 9.815401 129.5 -65.11697 5.453908 101.1704 -70.63769 4.922456 129.5 -65.66841 9.621398 129.5 -60.74267 4.922456 129.5 -65.66841 5.840654 99.33776 -70.93103 6.228416 97.30286 -71.2582 6.616074 95.04547 -71.623 7.001833 92.54319 -72.02962 7.383331 89.76996 -72.48307 7.757323 86.69617 -72.98906 8.119386 83.28813 -73.55429 8.463538 79.50714 -74.18653 8.781544 75.3105 -74.89466 9.062521 70.64891 -75.68908 9.291265 65.46395 -76.58237 9.446212 59.68569 -77.5899 9.495759 53.22743 -78.73101 0 112.3794 -68.87149 0 129.5 -65.85266 0 129.5 -65.85266 0.386784 112.327 -68.87963 0.80635 112.1529 -68.90671 1.223627 111.8574 -68.95269 1.628072 111.4522 -69.01576 2.024522 110.9408 -69.09549 2.412002 110.3289 -69.19101 2.794067 109.6142 -69.30276 3.172716 108.7934 -69.43135 3.549988 107.8602 -69.57783 3.927262 106.8069 -69.74359 4.305922 105.6228 -69.93041 4.686441 104.2973 -70.14019 5.069021 102.8183 -70.37503 -0.387123 112.3269 -68.87965 0 129.5 -65.85266 0 112.3794 -68.87149 -4.689824 104.2849 -70.14215 -5.072514 102.8041 -70.37729 -4.922456 129.5 -65.66841 -4.309144 105.6121 -69.9321 -3.930311 106.7978 -69.74501 -3.552864 107.8526 -69.57902 -3.17533 108.7874 -69.43228 -2.796289 109.6097 -69.30346 -2.413873 110.3256 -69.19152 -2.026049 110.9386 -69.09584 -1.629207 111.4509 -69.01597 -1.22397 111.857 -68.95272 -0.806836 112.1526 -68.90676 0 129.5 -61.5 -4.922456 129.5 -65.66841 0 12 -71.5 0 112.3794 -68.87149 0.386784 112.327 -68.87963 -1.329693 12 -71.60466 -0.387123 112.3269 -68.87965 0 112.3794 -68.87149 0 12 -71.5 0.80635 112.1529 -68.90671 1.223627 111.8574 -68.95269 1.628072 111.4522 -69.01576 1.329693 12 -71.60466 2.024522 110.9408 -69.09549 2.412002 110.3289 -69.19101 2.794067 109.6142 -69.30276 3.172716 108.7934 -69.43135 2.626644 12 -71.91603 3.549988 107.8602 -69.57783 3.927262 106.8069 -69.74359 4.305922 105.6228 -69.93041 4.686441 104.2973 -70.14019 3.858919 12 -72.42646 5.069021 102.8183 -70.37503 5.453908 101.1704 -70.63769 5.840654 99.33776 -70.93103 6.228416 97.30286 -71.2582 4.996175 12 -73.12336 6.616074 95.04547 -71.623 7.001833 92.54319 -72.02962 7.383331 89.76996 -72.48307 6.010408 12 -73.9896 7.757323 86.69617 -72.98906 8.119386 83.28813 -73.55429 6.876644 12 -75.00382 8.463538 79.50714 -74.18653 8.781544 75.3105 -74.89466 7.573555 12 -76.14109 9.062521 70.64891 -75.68908 9.291265 65.46395 -76.58237 8.08398 12 -77.37336 9.446212 59.68569 -77.5899 8.395353 12 -78.67031 9.495759 53.22743 -78.73101 9.391167 45.9834 -80.02976 8.5 12 -80 9.391167 45.9834 -80.02976 9.050388 37.79684 -81.52156 8.395353 12 -81.3297 9.050388 37.79684 -81.52156 8.31901 28.47987 -83.25061 8.08398 12 -82.62664 8.31901 28.47987 -83.25061 17.95494 24.46426 -82.89403 8.31901 28.47987 -83.25061 18.31866 28.47987 -81.63515 7.828858 25.33502 -84.12519 7.573555 12 -83.85892 7.828858 25.33502 -84.12519 28.07899 24.46426 -80.03356 28.04979 28.47987 -78.82309 37.77103 24.46426 -75.94175 37.36978 28.47987 -74.85566 46.14201 28.47987 -69.79101 46.88196 24.46426 -70.68155 54.2379 28.47987 -63.70338 55.2716 24.46426 -64.3339 61.53878 28.47987 -56.68199 66.07898 37.77328 -48.59962 67.93764 28.47987 -48.82978 62.81087 24.46426 -56.99645 67.93764 28.47987 -48.82978 64.61872 45.94526 -48.15041 63.44156 53.18627 -47.59262 67.5148 12 -48.31425 67.93764 28.47987 -48.82978 66.07898 37.77328 -48.59962 68.94012 25.33501 -48.84258 68.83718 12 -48.48835 68.94012 25.33501 -48.84258 66.23591 12 -47.93543 64.61872 45.94526 -48.15041 65.03203 12 -47.36122 63.44156 53.18627 -47.59262 63.93281 12 -46.60574 62.47731 59.64659 -46.97964 62.9653 12 -45.68761 61.68149 65.42729 -46.34197 61.02164 70.6142 -45.69746 62.15333 12 -44.62943 60.4736 75.27765 -45.05709 60.01887 79.47608 -44.42775 61.51689 12 -43.45726 59.64296 83.25878 -43.81369 59.33407 86.66883 -43.21752 61.07166 12 -42.19996 59.08246 89.74466 -42.64059 58.88017 92.5197 -42.08345 58.72057 95.02383 -41.54599 60.82859 12 -40.88849 58.59817 97.28314 -41.02774 58.50842 99.31984 -40.5282 58.44751 101.1544 -40.04644 58.41226 102.8041 -39.58157 60.79368 12 -39.55514 58.39997 104.2849 -39.13258 58.4084 105.6121 -38.69787 58.43579 106.7978 -38.27625 58.48076 107.8526 -37.86638 60.96778 12 -38.23275 58.54246 108.7874 -37.46606 58.62041 109.6097 -37.07339 58.71467 110.3256 -36.68623 58.82572 110.9386 -36.30252 61.3466 12 -36.95387 58.95497 111.4509 -35.91892 59.10282 111.857 -35.53635 59.27157 112.1526 -35.15211 59.45796 112.3269 -34.77508 59.64444 112.3794 -34.43574 61.92081 12 -35.75 59.64444 112.3794 -34.43574 59.8449 112.327 -34.10485 61.92081 12 -35.75 60.07813 112.1529 -33.75503 60.32658 111.8574 -33.41664 60.58344 111.4522 -33.09793 62.67629 12 -34.65077 60.85071 110.9408 -32.79446 61.12717 110.3289 -32.50665 61.41498 109.6142 -32.23165 61.71566 108.7934 -31.96801 63.59442 12 -33.68327 62.03116 107.8602 -31.71454 62.36334 106.8069 -31.47068 62.71448 105.6228 -31.23617 63.08639 104.2973 -31.01151 64.65261 12 -32.8713 63.48107 102.8183 -30.79761 63.90098 101.1704 -30.59562 64.34839 99.33776 -30.40735 64.82563 97.30286 -30.23513 65.82477 12 -32.23486 65.33538 95.04547 -30.08181 65.8804 92.54319 -29.95104 66.46384 89.76996 -29.84738 67.08207 12 -31.78963 67.08905 86.69617 -29.77649 67.75957 83.28813 -29.74555 68.39354 12 -31.54656 68.47919 79.50714 -29.76363 69.25145 75.3105 -29.84229 69.72689 12 -31.51165 70.07994 70.64891 -29.99617 70.96791 65.46395 -30.24472 71.04928 12 -31.68575 71.91793 59.68569 -30.61429 72.32817 12 -32.06457 72.93093 53.22743 -31.14193 74.00339 45.9834 -31.88189 73.53203 12 -32.63878 74.00339 45.9834 -31.88189 75.12493 37.79684 -32.92291 74.63127 12 -33.39426 75.12493 37.79684 -32.92291 76.25666 28.47987 -34.42083 75.59877 12 -34.31239 76.25666 28.47987 -34.42083 80.7658 24.46426 -25.89758 76.25666 28.47987 -34.42083 79.85744 28.47987 -24.95315 76.76898 25.33502 -35.2826 76.41073 12 -35.37057 76.76898 25.33502 -35.2826 83.3506 24.46426 -15.69966 82.2877 28.47987 -15.11971 84.653 24.46426 -5.260197 83.51181 28.47987 -5.064649 83.51181 28.47987 5.064649 84.653 24.46426 5.260197 82.2877 28.47987 15.11971 83.3506 24.46426 15.69966 79.85744 28.47987 24.95315 75.128 37.77328 32.92626 76.25666 28.47987 34.42083 80.7658 24.46426 25.89758 76.25666 28.47987 34.42083 74.00885 45.94526 31.88624 72.93721 53.18627 31.1457 75.59877 12 34.31239 76.25666 28.47987 34.42083 75.128 37.77328 32.92626 76.76898 25.33501 35.2826 76.41073 12 35.37057 76.76898 25.33501 35.2826 74.63127 12 33.39426 74.00885 45.94526 31.88624 73.53203 12 32.63878 72.93721 53.18627 31.1457 72.32817 12 32.06457 71.92422 59.64659 30.61713 71.04928 12 31.68575 70.97407 65.42729 30.24676 70.08599 70.6142 29.99756 69.72689 12 31.51165 69.2574 75.27765 29.84313 68.485 79.47608 29.76399 68.39354 12 31.54656 67.76525 83.25878 29.74548 67.09452 86.66883 29.77605 67.08207 12 31.78963 66.46907 89.74466 29.84662 65.88543 92.5197 29.94999 65.34017 95.02383 30.08051 65.82477 12 32.23486 64.83016 97.28314 30.23363 64.35267 99.31984 30.40568 63.90499 101.1544 30.59381 63.48478 102.8041 30.79572 64.65261 12 32.8713 63.08979 104.2849 31.00957 62.71754 105.6121 31.23422 62.3661 106.7978 31.46875 62.03363 107.8526 31.71264 63.59442 12 33.68327 61.71778 108.7874 31.96623 61.4167 109.6097 32.23007 61.12855 110.3256 32.50528 60.85177 110.9386 32.7933 62.67629 12 34.65077 60.58418 111.4509 33.09705 60.32679 111.857 33.41637 60.07841 112.1526 33.75463 59.84508 112.3269 34.10456 59.64444 112.3794 34.43574 61.92081 12 35.75 59.64444 112.3794 34.43574 59.45811 112.327 34.77478 61.92081 12 35.75 59.27178 112.1529 35.15167 59.10295 111.8574 35.53603 58.95536 111.4522 35.91783 61.3466 12 36.95387 58.82619 110.9408 36.30103 58.71517 110.3289 36.68436 58.62092 109.6142 37.07111 58.54294 108.7934 37.46332 60.96778 12 38.23275 58.48117 107.8602 37.86329 58.43608 106.8069 38.2729 58.40855 105.6228 38.69424 58.39995 104.2973 39.12866 60.79368 12 39.55514 58.41205 102.8183 39.57741 58.44707 101.1704 40.04206 58.50773 99.33776 40.52366 58.5972 97.30286 41.02306 60.82859 12 40.88849 58.71929 95.04547 41.54118 58.87856 92.54319 42.07857 59.0805 89.76996 42.63568 61.07166 12 42.19996 59.33171 86.69617 43.21257 59.64018 83.28813 43.80873 61.51689 12 43.45726 60.01565 79.50714 44.4229 60.4699 75.3105 45.05237 62.15333 12 44.62943 61.01741 70.64891 45.69291 61.67665 65.46395 46.33765 62.9653 12 45.68761 62.47172 59.68569 46.97561 63.93281 12 46.60574 63.43516 53.22743 47.58906 64.61222 45.9834 48.14787 65.03203 12 47.36122 64.61222 45.9834 48.14787 66.07455 37.79684 48.59864 66.23591 12 47.93543 66.07455 37.79684 48.59864 67.93764 28.47987 48.82978 67.5148 12 48.31425 67.93764 28.47987 48.82978 68.94012 25.33502 48.84258 67.93764 28.47987 48.82978 64.28165 28.47987 53.55129 68.83718 12 48.48835 68.94012 25.33502 48.84258 62.57725 24.46426 57.25284 60.29818 28.47987 58 69.38591 24.39945 48.82408 60.29818 28.47987 58 60.35892 28.24008 58 60.42392 28 58 12.1063 15 -91.95652 12.10664 0 -91.95637 0 0 -92.75 -12.10664 0 -91.95637 0 0 -92.75 12.10664 0 -91.95637 0 15 -92.75 -12.10664 0 -91.95637 0 15 -92.75 0 0 -92.75 24.00547 15 -89.58963 24.00468 0 -89.5898 24.00468 0 -89.5898 35.49389 15 -85.68983 35.49462 0 -85.68946 -24.00468 0 -89.5898 35.49462 0 -85.68946 46.375 15 -80.32386 46.3744 0 -80.32411 0 0 -84.25 46.3744 0 -80.32411 -35.49462 0 -85.68946 56.46262 15 -73.58352 56.46306 0 -73.58319 4.185433 0 -79.262 56.46306 0 -73.58319 1.453586 0 -83.99369 2.731847 0 -83.25569 3.680608 0 -82.125 4.185433 0 -80.73801 65.58415 15 -65.58415 65.58409 0 -65.58409 23.33038 0 -73.15058 65.58409 0 -65.58409 3.680608 0 -77.875 19.49515 0 -75.96544 21.09926 0 -75.53565 22.43872 0 -74.55274 73.58352 15 -56.46262 73.58319 0 -56.46306 34.91143 0 -65.24713 73.58319 0 -56.46306 23.65241 0 -71.52102 23.82219 0 -70.73329 24.28907 0 -70.0765 24.97726 0 -69.65728 30.02434 0 -67.63536 80.32386 15 -46.375 80.32411 0 -46.3744 48.34083 0 -56.02815 80.32411 0 -46.3744 39.61006 0 -62.50629 44.09458 0 -59.42776 85.68983 15 -35.49389 85.68946 0 -35.49462 70.73562 0 -43.99369 85.68946 0 -35.49462 69.28203 0 -44.25 56.02824 0 -48.34072 52.3259 0 -52.3258 89.58963 15 -24.00547 89.5898 0 -24.00468 65.24717 0 -34.91135 89.5898 0 -24.00468 73.46747 0 -40.73801 72.96264 0 -42.125 72.01388 0 -43.25569 73.46747 0 -39.26199 72.96264 0 -37.875 72.01388 0 -36.74431 70.73562 0 -36.0063 69.28203 0 -35.75 91.95652 15 -12.1063 91.95637 0 -12.10664 73.15052 0 -23.33041 91.95637 0 -12.10664 67.63537 0 -30.0243 69.65728 0 -24.97726 70.0765 0 -24.28907 70.73329 0 -23.82219 92.75 15 0 92.75 0 0 73.58609 0 -7.815966 92.75 0 0 74.55265 0 -22.43881 75.53559 0 -21.09942 75.96543 0 -19.49533 75.78392 0 -17.84387 75.01544 0 -16.37059 73.76522 0 -15.27692 73.16793 0 -14.73602 72.83258 0 -14.0033 72.81361 0 -13.1977 91.95652 15 12.1063 91.95637 0 12.10664 85.18923 0 0.694593 91.95637 0 12.10664 83.82115 0 -3.064178 82.61808 0 -3.75877 84.71411 0 -2 85.18923 0 -0.694593 89.58963 15 24.00547 89.5898 0 24.00468 72.69229 0 13.84998 89.5898 0 24.00468 84.71411 0 2 83.82115 0 3.064178 82.61808 0 3.75877 81.25 0 4 73.51329 0 8.472822 85.68983 15 35.49389 85.68946 0 35.49462 69.87854 0 24.35123 85.68946 0 35.49462 71.47851 0 19.15234 80.32386 15 46.375 80.32411 0 46.3744 72.01388 0 36.74431 80.32411 0 46.3744 70.73562 0 36.0063 69.28203 0 35.75 65.55654 0 34.32689 67.90097 0 29.41852 73.58352 15 56.46262 73.58319 0 56.46306 56.45958 0 47.83634 73.58319 0 56.46306 72.01388 0 43.25569 72.96264 0 42.125 73.46747 0 40.73801 70.73562 0 43.99369 69.28203 0 44.25 59.81955 0 43.56171 72.96264 0 37.875 73.46747 0 39.26199 65.58415 15 65.58415 65.58409 0 65.58409 53.3452 0 56.70886 65.58409 0 65.58409 56.0732 0 48.54349 55.99727 0 49.34572 56.24409 0 50.11281 56.77998 0 51.685 56.7089 0 53.34508 56.04042 0 54.86601 54.86616 0 56.04032 56.46262 15 73.58352 56.46306 0 73.58319 29.41893 0 67.90081 56.46306 0 73.58319 51.68506 0 56.77999 43.56184 0 59.81946 39.05011 0 62.85765 34.32722 0 65.55636 46.375 15 80.32386 46.3744 0 80.32411 3.050353 0 73.93708 46.3744 0 80.32411 24.3517 0 69.87836 19.15286 0 71.47837 13.85052 0 72.69219 8.473347 0 73.51322 35.49389 15 85.68983 35.49462 0 85.68946 -46.3744 0 80.32411 35.49462 0 85.68946 -56.46306 0 73.58319 -19.49515 0 75.96544 -2.389251 0 73.96141 -16.37053 0 75.01541 -17.84374 0 75.78388 24.00547 15 89.58963 24.00468 0 89.5898 -35.49462 0 85.68946 24.00468 0 89.5898 12.1063 15 91.95652 12.10664 0 91.95637 -24.00468 0 89.5898 12.10664 0 91.95637 0 15 92.75 0 0 92.75 -12.10664 0 91.95637 0 0 92.75 -12.1063 15 91.95652 0 0 92.75 0 15 92.75 -12.10664 0 91.95637 0 17.32252 89.72489 0 15 92.75 12.1063 15 91.95652 -11.21306 17.56821 88.7605 -12.1063 15 91.95652 0 15 92.75 0 17.32252 89.72489 22.24928 17.56821 86.65523 24.00547 15 89.58963 11.21306 17.56821 88.7605 0 17.56821 89.46598 32.93462 17.56821 83.18335 35.49389 15 85.68983 43.10056 17.56821 78.39963 46.375 15 80.32386 52.58678 17.56821 72.3795 56.46262 15 73.58352 61.24367 17.56821 65.21788 65.58415 15 65.58415 68.93473 17.56821 57.02775 73.58352 15 56.46262 75.53861 17.56821 47.93826 80.32386 15 46.375 80.95124 17.56821 38.09275 85.68983 15 35.49389 85.08719 17.56821 27.6465 89.58963 15 24.00547 87.88128 17.56821 16.76425 91.95652 15 12.1063 89.28943 17.56821 5.617614 92.75 15 0 89.28943 17.56821 -5.617614 91.95652 15 -12.1063 87.88128 17.56821 -16.76425 89.58963 15 -24.00547 85.08719 17.56821 -27.6465 85.68983 15 -35.49389 80.95124 17.56821 -38.09275 80.32386 15 -46.375 75.53861 17.56821 -47.93826 73.58352 15 -56.46262 68.93473 17.56821 -57.02775 65.58415 15 -65.58415 61.24367 17.56821 -65.21788 56.46262 15 -73.58352 52.58678 17.56821 -72.3795 46.375 15 -80.32386 43.10056 17.56821 -78.39963 35.49389 15 -85.68983 32.93462 17.56821 -83.18335 24.00547 15 -89.58963 22.24928 17.56821 -86.65523 12.1063 15 -91.95652 11.21306 17.56821 -88.7605 0 15 -92.75 -12.1063 15 -91.95652 0 16.55666 -90.5959 0 15 -92.75 -12.1063 15 -91.95652 0 16.55666 -90.5959 -48.27289 129.5 44.7917 -64.28165 28.47987 53.55129 -60.29818 28.47987 58 -60.35892 28.24008 58 -60.29818 28.47987 58 -64.28165 28.47987 53.55129 -44.79069 129.5 48.27375 -50.89953 65.33341 58 -56.43347 39.79531 58 -50.89953 65.33341 58 -60.29818 28.47987 58 -60.35892 28.24008 58 60.42392 28 58 -52.41174 32.82986 58 -56.75 38 58 -56.43347 36.20468 58 -55.52194 34.62569 58 -54.12522 33.45357 58 -66.07898 37.77328 48.59962 -67.93764 28.47987 48.82978 -62.57725 24.46426 57.25284 -67.93764 28.47987 48.82978 -64.61872 45.94526 48.15041 -63.44156 53.18627 47.59262 -62.47731 59.64659 46.97964 -51.48568 129.5 41.05846 -60.42392 28 58 -67.5148 12 48.31425 -67.93764 28.47987 48.82978 -66.07898 37.77328 48.59962 -68.94012 25.33501 48.84258 -68.83718 12 48.48835 -68.94012 25.33501 48.84258 -66.23591 12 47.93543 -64.61872 45.94526 48.15041 -65.03203 12 47.36122 -63.44156 53.18627 47.59262 -63.93281 12 46.60574 -62.47731 59.64659 46.97964 -61.68149 65.42729 46.34197 -62.9653 12 45.68761 -61.68149 65.42729 46.34197 -61.02164 70.6142 45.69746 -61.02164 70.6142 45.69746 -60.4736 75.27765 45.05709 -62.15333 12 44.62943 -60.4736 75.27765 45.05709 -60.01887 79.47608 44.42775 -60.01887 79.47608 44.42775 -54.4104 129.5 37.0955 -59.64296 83.25878 43.81369 -61.51689 12 43.45726 -59.64296 83.25878 43.81369 -59.33407 86.66883 43.21752 -59.33407 86.66883 43.21752 -59.08246 89.74466 42.64059 -61.07166 12 42.19996 -59.08246 89.74466 42.64059 -58.88017 92.5197 42.08345 -58.88017 92.5197 42.08345 -58.72057 95.02383 41.54599 -58.72057 95.02383 41.54599 -58.59817 97.28314 41.02774 -60.82859 12 40.88849 -58.59817 97.28314 41.02774 -58.50842 99.31984 40.5282 -58.50842 99.31984 40.5282 -58.44751 101.1544 40.04644 -58.44751 101.1544 40.04644 -58.41226 102.8041 39.58157 -58.41226 102.8041 39.58157 -57.0303 129.5 32.92578 -58.39997 104.2849 39.13258 -60.79368 12 39.55514 -58.39997 104.2849 39.13258 -58.4084 105.6121 38.69787 -58.4084 105.6121 38.69787 -58.43579 106.7978 38.27625 -58.43579 106.7978 38.27625 -58.48076 107.8526 37.86638 -58.48076 107.8526 37.86638 -58.54246 108.7874 37.46606 -60.96778 12 38.23275 -58.54246 108.7874 37.46606 -58.62041 109.6097 37.07339 -58.62041 109.6097 37.07339 -58.71467 110.3256 36.68623 -58.71467 110.3256 36.68623 -58.82572 110.9386 36.30252 -58.82572 110.9386 36.30252 -58.95497 111.4509 35.91892 -61.3466 12 36.95387 -58.95497 111.4509 35.91892 -59.10282 111.857 35.53635 -59.10282 111.857 35.53635 -59.27157 112.1526 35.15211 -59.27157 112.1526 35.15211 -59.45796 112.3269 34.77508 -59.45796 112.3269 34.77508 -59.64444 112.3794 34.43574 -59.64444 112.3794 34.43574 -59.3311 129.5 28.57235 -59.8449 112.327 34.10485 -61.92081 12 35.75 -59.64444 112.3794 34.43574 -59.8449 112.327 34.10485 -61.92081 12 35.75 -60.07813 112.1529 33.75503 -60.07813 112.1529 33.75503 -60.32658 111.8574 33.41664 -60.32658 111.8574 33.41664 -60.58344 111.4522 33.09793 -60.58344 111.4522 33.09793 -60.85071 110.9408 32.79446 -62.67629 12 34.65077 -60.85071 110.9408 32.79446 -61.12717 110.3289 32.50665 -61.12717 110.3289 32.50665 -61.41498 109.6142 32.23165 -61.41498 109.6142 32.23165 -61.71566 108.7934 31.96801 -61.71566 108.7934 31.96801 -62.03116 107.8602 31.71454 -63.59442 12 33.68327 -62.03116 107.8602 31.71454 -62.36334 106.8069 31.47068 -62.36334 106.8069 31.47068 -62.71448 105.6228 31.23617 -62.71448 105.6228 31.23617 -63.08639 104.2973 31.01151 -63.08639 104.2973 31.01151 -63.48107 102.8183 30.79761 -64.65261 12 32.8713 -63.48107 102.8183 30.79761 -63.90098 101.1704 30.59562 -63.90098 101.1704 30.59562 -61.30022 129.5 24.0592 -64.34839 99.33776 30.40735 -64.34839 99.33776 30.40735 -64.82563 97.30286 30.23513 -64.82563 97.30286 30.23513 -65.33538 95.04547 30.08181 -65.82477 12 32.23486 -65.33538 95.04547 30.08181 -65.8804 92.54319 29.95104 -65.8804 92.54319 29.95104 -66.46384 89.76996 29.84738 -66.46384 89.76996 29.84738 -67.08905 86.69617 29.77649 -67.08207 12 31.78963 -67.08905 86.69617 29.77649 -67.75957 83.28813 29.74555 -67.75957 83.28813 29.74555 -68.47919 79.50714 29.76363 -68.39354 12 31.54656 -68.47919 79.50714 29.76363 -69.25145 75.3105 29.84229 -69.25145 75.3105 29.84229 -70.07994 70.64891 29.99617 -69.72689 12 31.51165 -70.07994 70.64891 29.99617 -70.96791 65.46395 30.24472 -70.96791 65.46395 30.24472 -71.91793 59.68569 30.61429 -71.04928 12 31.68575 -71.91793 59.68569 30.61429 -72.93093 53.22743 31.14193 -72.32817 12 32.06457 -72.93093 53.22743 31.14193 -79.85744 28.47987 24.95315 -74.00339 45.9834 31.88189 -73.53203 12 32.63878 -74.00339 45.9834 31.88189 -75.12493 37.79684 32.92291 -74.63127 12 33.39426 -75.12493 37.79684 32.92291 -76.25666 28.47987 34.42083 -75.59877 12 34.31239 -76.25666 28.47987 34.42083 -80.7658 24.46426 25.89758 -76.25666 28.47987 34.42083 -79.85744 28.47987 24.95315 -76.76898 25.33502 35.2826 -76.41073 12 35.37057 -76.76898 25.33502 35.2826 -64.20159 129.5 14.65359 -82.2877 28.47987 15.11971 -83.3506 24.46426 15.69966 -82.2877 28.47987 15.11971 -62.92676 129.5 19.4111 -65.66848 129.5 4.920582 -83.51181 28.47987 5.064649 -84.653 24.46426 5.260197 -83.51181 28.47987 5.064649 -65.11721 129.5 9.814099 -65.85256 129.5 0 -83.51181 28.47987 -5.064649 -83.51181 28.47987 -5.064649 -65.11721 129.5 -9.814099 -82.2877 28.47987 -15.11971 -84.653 24.46426 -5.260197 -82.2877 28.47987 -15.11971 -65.66848 129.5 -4.920582 -62.92676 129.5 -19.4111 -79.85744 28.47987 -24.95315 -83.3506 24.46426 -15.69966 -79.85744 28.47987 -24.95315 -64.20159 129.5 -14.65359 -75.128 37.77328 -32.92626 -76.25666 28.47987 -34.42083 -80.7658 24.46426 -25.89758 -76.25666 28.47987 -34.42083 -74.00885 45.94526 -31.88624 -72.93721 53.18627 -31.1457 -71.92422 59.64659 -30.61713 -61.30022 129.5 -24.0592 -75.59877 12 -34.31239 -76.25666 28.47987 -34.42083 -75.128 37.77328 -32.92626 -76.76898 25.33501 -35.2826 -76.41073 12 -35.37057 -76.76898 25.33501 -35.2826 -74.63127 12 -33.39426 -74.00885 45.94526 -31.88624 -73.53203 12 -32.63878 -72.93721 53.18627 -31.1457 -72.32817 12 -32.06457 -71.92422 59.64659 -30.61713 -70.97407 65.42729 -30.24676 -71.04928 12 -31.68575 -70.97407 65.42729 -30.24676 -70.08599 70.6142 -29.99756 -70.08599 70.6142 -29.99756 -69.2574 75.27765 -29.84313 -69.72689 12 -31.51165 -69.2574 75.27765 -29.84313 -68.485 79.47608 -29.76399 -68.485 79.47608 -29.76399 -59.3311 129.5 -28.57235 -67.76525 83.25878 -29.74548 -68.39354 12 -31.54656 -67.76525 83.25878 -29.74548 -67.09452 86.66883 -29.77605 -67.09452 86.66883 -29.77605 -66.46907 89.74466 -29.84662 -67.08207 12 -31.78963 -66.46907 89.74466 -29.84662 -65.88543 92.5197 -29.94999 -65.88543 92.5197 -29.94999 -65.34017 95.02383 -30.08051 -65.34017 95.02383 -30.08051 -64.83016 97.28314 -30.23363 -65.82477 12 -32.23486 -64.83016 97.28314 -30.23363 -64.35267 99.31984 -30.40568 -64.35267 99.31984 -30.40568 -63.90499 101.1544 -30.59381 -63.90499 101.1544 -30.59381 -63.48478 102.8041 -30.79572 -63.48478 102.8041 -30.79572 -57.0303 129.5 -32.92578 -63.08979 104.2849 -31.00957 -64.65261 12 -32.8713 -63.08979 104.2849 -31.00957 -62.71754 105.6121 -31.23422 -62.71754 105.6121 -31.23422 -62.3661 106.7978 -31.46875 -62.3661 106.7978 -31.46875 -62.03363 107.8526 -31.71264 -62.03363 107.8526 -31.71264 -61.71778 108.7874 -31.96623 -63.59442 12 -33.68327 -61.71778 108.7874 -31.96623 -61.4167 109.6097 -32.23007 -61.4167 109.6097 -32.23007 -61.12855 110.3256 -32.50528 -61.12855 110.3256 -32.50528 -60.85177 110.9386 -32.7933 -60.85177 110.9386 -32.7933 -60.58418 111.4509 -33.09705 -62.67629 12 -34.65077 -60.58418 111.4509 -33.09705 -60.32679 111.857 -33.41637 -60.32679 111.857 -33.41637 -60.07841 112.1526 -33.75463 -60.07841 112.1526 -33.75463 -59.84508 112.3269 -34.10456 -59.84508 112.3269 -34.10456 -59.64444 112.3794 -34.43574 -59.64444 112.3794 -34.43574 -54.4104 129.5 -37.0955 -59.45811 112.327 -34.77478 -61.92081 12 -35.75 -59.64444 112.3794 -34.43574 -59.45811 112.327 -34.77478 -61.92081 12 -35.75 -59.27178 112.1529 -35.15167 -59.27178 112.1529 -35.15167 -59.10295 111.8574 -35.53603 -59.10295 111.8574 -35.53603 -58.95536 111.4522 -35.91783 -58.95536 111.4522 -35.91783 -58.82619 110.9408 -36.30103 -61.3466 12 -36.95387 -58.82619 110.9408 -36.30103 -58.71517 110.3289 -36.68436 -58.71517 110.3289 -36.68436 -58.62092 109.6142 -37.07111 -58.62092 109.6142 -37.07111 -58.54294 108.7934 -37.46332 -58.54294 108.7934 -37.46332 -58.48117 107.8602 -37.86329 -60.96778 12 -38.23275 -58.48117 107.8602 -37.86329 -58.43608 106.8069 -38.2729 -58.43608 106.8069 -38.2729 -58.40855 105.6228 -38.69424 -58.40855 105.6228 -38.69424 -58.39995 104.2973 -39.12866 -58.39995 104.2973 -39.12866 -58.41205 102.8183 -39.57741 -60.79368 12 -39.55514 -58.41205 102.8183 -39.57741 -58.44707 101.1704 -40.04206 -58.44707 101.1704 -40.04206 -51.48568 129.5 -41.05846 -58.50773 99.33776 -40.52366 -58.50773 99.33776 -40.52366 -58.5972 97.30286 -41.02306 -58.5972 97.30286 -41.02306 -58.71929 95.04547 -41.54118 -60.82859 12 -40.88849 -58.71929 95.04547 -41.54118 -58.87856 92.54319 -42.07857 -58.87856 92.54319 -42.07857 -59.0805 89.76996 -42.63568 -59.0805 89.76996 -42.63568 -59.33171 86.69617 -43.21257 -61.07166 12 -42.19996 -59.33171 86.69617 -43.21257 -59.64018 83.28813 -43.80873 -59.64018 83.28813 -43.80873 -60.01565 79.50714 -44.4229 -61.51689 12 -43.45726 -60.01565 79.50714 -44.4229 -60.4699 75.3105 -45.05237 -60.4699 75.3105 -45.05237 -61.01741 70.64891 -45.69291 -62.15333 12 -44.62943 -61.01741 70.64891 -45.69291 -61.67665 65.46395 -46.33765 -61.67665 65.46395 -46.33765 -62.47172 59.68569 -46.97561 -62.9653 12 -45.68761 -62.47172 59.68569 -46.97561 -63.43516 53.22743 -47.58906 -63.93281 12 -46.60574 -63.43516 53.22743 -47.58906 -61.53878 28.47987 -56.68199 -64.61222 45.9834 -48.14787 -65.03203 12 -47.36122 -64.61222 45.9834 -48.14787 -66.07455 37.79684 -48.59864 -66.23591 12 -47.93543 -66.07455 37.79684 -48.59864 -67.93764 28.47987 -48.82978 -67.5148 12 -48.31425 -67.93764 28.47987 -48.82978 -62.81087 24.46426 -56.99645 -67.93764 28.47987 -48.82978 -61.53878 28.47987 -56.68199 -68.94012 25.33502 -48.84258 -68.83718 12 -48.48835 -68.94012 25.33502 -48.84258 -44.79069 129.5 -48.27375 -54.2379 28.47987 -63.70338 -55.2716 24.46426 -64.3339 -54.2379 28.47987 -63.70338 -48.27289 129.5 -44.7917 -37.09656 129.5 -54.40962 -46.14201 28.47987 -69.79101 -46.88196 24.46426 -70.68155 -46.14201 28.47987 -69.79101 -41.05839 129.5 -51.4856 -32.92695 129.5 -57.02968 -37.36978 28.47987 -74.85566 -37.36978 28.47987 -74.85566 -24.05798 129.5 -61.30075 -28.04979 28.47987 -78.82309 -37.77103 24.46426 -75.94175 -28.04979 28.47987 -78.82309 -28.5724 129.5 -59.33119 -14.65357 129.5 -64.20149 -18.31866 28.47987 -81.63515 -28.07899 24.46426 -80.03356 -18.31866 28.47987 -81.63515 -19.40983 129.5 -62.9271 -9.049017 37.77328 -81.52589 -8.31901 28.47987 -83.25061 -17.95494 24.46426 -82.89403 -8.31901 28.47987 -83.25061 -9.390129 45.94526 -80.03665 -9.495635 53.18627 -78.73831 -9.446903 59.64659 -77.59677 -9.815401 129.5 -65.11697 -8.08398 12 -82.62664 -8.31901 28.47987 -83.25061 -9.049017 37.77328 -81.52589 -7.828857 25.33501 -84.12519 -7.573555 12 -83.85892 -7.828857 25.33501 -84.12519 -8.395353 12 -81.3297 -9.390129 45.94526 -80.03665 -8.5 12 -80 -9.495635 53.18627 -78.73831 -8.395353 12 -78.67031 -9.446903 59.64659 -77.59677 -9.292576 65.42729 -76.58872 -8.08398 12 -77.37336 -9.292576 65.42729 -76.58872 -9.06434 70.6142 -75.69503 -9.06434 70.6142 -75.69503 -8.783785 75.27765 -74.90023 -7.573555 12 -76.14109 -8.783785 75.27765 -74.90023 -8.466131 79.47608 -74.19174 -8.466131 79.47608 -74.19174 -8.122282 83.25878 -73.55918 -6.876644 12 -75.00382 -8.122282 83.25878 -73.55918 -7.760439 86.66883 -72.99359 -7.760439 86.66883 -72.99359 -7.386609 89.74466 -72.48722 -6.010408 12 -73.9896 -7.386609 89.74466 -72.48722 -7.005258 92.5197 -72.03345 -7.005258 92.5197 -72.03345 -6.619599 95.02383 -71.62651 -6.619599 95.02383 -71.62651 -6.231984 97.28314 -71.26139 -4.996175 12 -73.12336 -6.231984 97.28314 -71.26139 -5.844246 99.31984 -70.93389 -5.844246 99.31984 -70.93389 -5.457476 101.1544 -70.64025 -5.457476 101.1544 -70.64025 -5.072514 102.8041 -70.37729 -3.858919 12 -72.42646 -4.689824 104.2849 -70.14215 -4.309144 105.6121 -69.9321 -3.930311 106.7978 -69.74501 -3.552864 107.8526 -69.57902 -2.626644 12 -71.91603 -3.17533 108.7874 -69.43228 -2.796289 109.6097 -69.30346 -2.413873 110.3256 -69.19152 -2.026049 110.9386 -69.09584 -1.629207 111.4509 -69.01597 -1.22397 111.857 -68.95272 -0.806836 112.1526 -68.90676 -9.621398 129.5 -60.74267 -9.815401 129.5 -65.11697 -14.65357 129.5 -64.20149 -19.00452 129.5 -58.48989 -19.40983 129.5 -62.9271 -24.05798 129.5 -61.30075 -27.91977 129.5 -54.79717 -28.5724 129.5 -59.33119 -32.92695 129.5 -57.02968 -36.14879 129.5 -49.75454 -37.09656 129.5 -54.40962 -41.05839 129.5 -51.4856 -43.48752 129.5 -43.48654 -44.79069 129.5 -48.27375 -48.27289 129.5 -44.7917 -49.75447 129.5 -36.14874 -51.48568 129.5 -41.05846 -54.4104 129.5 -37.0955 -54.79654 129.5 -27.92101 -57.0303 129.5 -32.92578 -58.48997 129.5 -19.00455 -59.3311 129.5 -28.57235 -60.74289 129.5 -9.620025 -61.30022 129.5 -24.0592 -61.4999 129.5 0 -62.92676 129.5 -19.4111 -62.92676 129.5 19.4111 -64.20159 129.5 -14.65359 -61.30022 129.5 24.0592 -64.20159 129.5 14.65359 -65.11721 129.5 -9.814099 -65.11721 129.5 9.814099 -65.66848 129.5 -4.920582 -65.66848 129.5 4.920582 -65.85256 129.5 0 -60.74289 129.5 9.620025 -59.3311 129.5 28.57235 -58.48997 129.5 19.00455 -57.0303 129.5 32.92578 -54.79654 129.5 27.92101 -54.4104 129.5 37.0955 -51.48568 129.5 41.05846 -49.75447 129.5 36.14874 -48.27289 129.5 44.7917 -44.79069 129.5 48.27375 -41.05839 129.5 51.4856 -43.48752 129.5 43.48654 -41.05839 129.5 51.4856 -42.55324 95 58 -37.09656 129.5 54.40962 -37.09656 129.5 54.40962 -34.50087 97.64976 62.58951 -32.92695 129.5 57.02968 -36.14879 129.5 49.75454 -32.92695 129.5 57.02968 -28.5724 129.5 59.33119 -28.5724 129.5 59.33119 -26.12594 99.69652 66.13462 -24.05798 129.5 61.30075 -27.91977 129.5 54.79717 -24.05798 129.5 61.30075 -17.52952 101.1482 68.64897 -19.40983 129.5 62.9271 -19.40983 129.5 62.9271 -14.65357 129.5 64.20149 -19.00452 129.5 58.48989 -14.65357 129.5 64.20149 -9.815401 129.5 65.11697 -9.815401 129.5 65.11697 -46.25 38 58 -37.5 85 58 -37.5 90.05471 58 -33.44577 90.05471 58 -32.74585 89.89495 58 -31.25827 90.05471 58 -30.13828 90.05471 58 -29.23825 90.05471 58 -28.17565 90.05471 58 -25.41853 90.05471 58 -46.56652 39.79531 58 -47.47806 41.37431 58 -48.87478 42.54642 58 -50.58826 43.17013 58 -52.41174 43.17013 58 -54.12522 42.54642 58 -55.52194 41.37431 58 -24.00547 15 89.58963 -24.00468 0 89.5898 -35.49389 15 85.68983 -35.49462 0 85.68946 -46.375 15 80.32386 -46.3744 0 80.32411 -56.46262 15 73.58352 -56.46306 0 73.58319 -65.58415 15 65.58415 -65.58409 0 65.58409 -23.33038 0 73.15058 -65.58409 0 65.58409 -21.09926 0 75.53565 -22.43872 0 74.55274 -73.58352 15 56.46262 -73.58319 0 56.46306 -34.91125 0 65.24723 -73.58319 0 56.46306 -23.65241 0 71.52102 -23.82219 0 70.73329 -24.28907 0 70.0765 -24.97726 0 69.65728 -30.02424 0 67.63539 -80.32386 15 46.375 -80.32411 0 46.3744 -48.34053 0 56.02841 -80.32411 0 46.3744 -39.60983 0 62.50645 -44.09431 0 59.42797 -85.68983 15 35.49389 -85.68946 0 35.49462 -70.73562 0 43.99369 -85.68946 0 35.49462 -69.28203 0 44.25 -56.02798 0 48.34104 -52.32561 0 52.32609 -89.58963 15 24.00547 -89.5898 0 24.00468 -65.24707 0 34.91158 -89.5898 0 24.00468 -73.46747 0 40.73801 -72.96264 0 42.125 -72.01388 0 43.25569 -73.46747 0 39.26199 -72.96264 0 37.875 -72.01388 0 36.74431 -70.73562 0 36.0063 -69.28203 0 35.75 -91.95652 15 12.1063 -91.95637 0 12.10664 -73.15052 0 23.33041 -91.95637 0 12.10664 -70.73329 0 23.82219 -67.6353 0 30.02444 -69.65728 0 24.97726 -70.0765 0 24.28907 -92.75 15 0 -92.75 0 0 -73.58609 0 7.81595 -92.75 0 0 -74.55265 0 22.43881 -75.53559 0 21.09942 -75.96543 0 19.49533 -75.78392 0 17.84387 -75.01544 0 16.37059 -73.76522 0 15.27692 -73.16793 0 14.73602 -72.83258 0 14.0033 -72.81361 0 13.1977 -91.95652 15 -12.1063 -91.95637 0 -12.10664 -73.93708 0 -3.049872 -91.95637 0 -12.10664 -73.96138 0 2.389604 -89.58963 15 -24.00547 -89.5898 0 -24.00468 -72.6923 0 -13.8499 -89.5898 0 -24.00468 -73.51329 0 -8.472777 -85.68983 15 -35.49389 -85.68946 0 -35.49462 -69.87857 0 -24.3511 -85.68946 0 -35.49462 -71.47854 0 -19.15223 -80.32386 15 -46.375 -80.32411 0 -46.3744 -72.01388 0 -36.74431 -80.32411 0 -46.3744 -70.73562 0 -36.0063 -69.28203 0 -35.75 -65.55659 0 -34.32678 -67.90103 0 -29.41839 -73.58352 15 -56.46262 -73.58319 0 -56.46306 -56.45958 0 -47.83634 -73.58319 0 -56.46306 -72.01388 0 -43.25569 -72.96264 0 -42.125 -73.46747 0 -40.73801 -70.73562 0 -43.99369 -69.28203 0 -44.25 -59.81959 0 -43.56166 -72.96264 0 -37.875 -73.46747 0 -39.26199 -65.58415 15 -65.58415 -65.58409 0 -65.58409 -53.3452 0 -56.70886 -65.58409 0 -65.58409 -56.0732 0 -48.54349 -55.99727 0 -49.34572 -56.24409 0 -50.11281 -56.77998 0 -51.685 -56.7089 0 -53.34508 -56.04042 0 -54.86601 -54.86616 0 -56.04032 -56.46262 15 -73.58352 -56.46306 0 -73.58319 -41.99308 0 -66.6058 -56.46306 0 -73.58319 -40.625 0 -66.36457 -34.32729 0 -65.55632 -51.68506 0 -56.77999 -43.56186 0 -59.81944 -39.05015 0 -62.85763 -46.375 15 -80.32386 -46.3744 0 -80.32411 -41.99308 0 -74.12334 -46.3744 0 -80.32411 -43.19615 0 -67.30039 -44.0891 0 -68.36457 -44.56423 0 -69.66997 -44.56423 0 -71.05916 -44.0891 0 -72.36457 -43.19615 0 -73.42874 -35.49389 15 -85.68983 -35.49462 0 -85.68946 -4.185433 0 -80.73801 -1.453586 0 -76.00631 0 0 -75.75 -40.625 0 -74.36457 -2.731847 0 -76.74431 -3.680608 0 -77.875 -4.185433 0 -79.262 -24.00547 15 -89.58963 -24.00468 0 -89.5898 -1.453586 0 -83.99369 -3.680608 0 -82.125 -2.731847 0 -83.25569 -22.24928 17.56821 -86.65523 -24.00547 15 -89.58963 0 17.56821 -89.46598 -11.21306 17.56821 -88.7605 -32.93462 17.56821 -83.18335 -35.49389 15 -85.68983 -43.10056 17.56821 -78.39963 -46.375 15 -80.32386 -52.58678 17.56821 -72.3795 -56.46262 15 -73.58352 -61.24367 17.56821 -65.21788 -65.58415 15 -65.58415 -68.93473 17.56821 -57.02775 -73.58352 15 -56.46262 -75.53861 17.56821 -47.93826 -80.32386 15 -46.375 -80.95124 17.56821 -38.09275 -85.68983 15 -35.49389 -85.08719 17.56821 -27.6465 -89.58963 15 -24.00547 -87.88128 17.56821 -16.76425 -91.95652 15 -12.1063 -89.28943 17.56821 -5.617614 -92.75 15 0 -89.28943 17.56821 5.617614 -91.95652 15 12.1063 -87.88128 17.56821 16.76425 -89.58963 15 24.00547 -85.08719 17.56821 27.6465 -85.68983 15 35.49389 -80.95124 17.56821 38.09275 -80.32386 15 46.375 -75.53861 17.56821 47.93826 -73.58352 15 56.46262 -68.93473 17.56821 57.02775 -65.58415 15 65.58415 -61.24367 17.56821 65.21788 -56.46262 15 73.58352 -52.58678 17.56821 72.3795 -46.375 15 80.32386 -43.10056 17.56821 78.39963 -35.49389 15 85.68983 -32.93462 17.56821 83.18335 -24.00547 15 89.58963 -22.24928 17.56821 86.65523 56.53218 26.88902 62.14625 -60.42392 28 58 56.53218 26.88902 62.14625 60.42392 28 58 -60.42392 28 58 -46.56652 36.20468 58 -50.58826 32.82986 58 -48.87478 33.45357 58 -47.47806 34.62569 58 -36.44685 85 58 -36.44685 86.8284 58 -31.25827 85 58 -30.13828 85 58 -29.23825 85 58 -25.98325 85 58 -25.47593 85 58 -20 85 58 69.38591 24.39945 48.82408 65.31641 20.77186 57.13412 70.31708 22.85943 48.72317 70.17053 12 48.45344 70.31708 22.85943 48.72317 54.74356 24.46426 64.78382 57.38381 20.77186 65.09716 52.49607 25.8636 65.97315 45.97255 24.43957 71.28771 48.48851 20.77186 71.96808 45.97255 24.43957 71.28771 52.49607 25.8636 65.97315 44.07157 24.07225 72.65855 44.07157 24.07225 72.65855 38.77975 20.77186 77.63164 35.34436 22.63173 78.03467 35.34436 22.63173 78.03467 71.82141 21.06345 48.36018 71.482 12 48.21037 71.82141 21.06345 48.36018 72.1659 20.73472 48.23857 72.1659 20.73472 48.23857 73.29663 19.81758 47.72366 72.73931 12 47.76514 73.29663 19.81758 47.72366 28.4204 20.77186 81.99282 26.49618 21.53731 82.11911 17.5829 20.77094 84.97924 17.5829 20.77094 84.97924 26.49618 21.53731 82.11911 8.800604 20.32513 86.64302 8.800604 20.32513 86.64302 0 20.17705 87.19565 0 20.17705 87.19565 74.6546 18.99996 46.82167 73.91146 12 47.1287 74.6546 18.99996 46.82167 75.83428 18.53583 45.67951 74.96965 12 46.31673 75.83428 18.53583 45.67951 76.78805 18.38519 44.3336 75.88777 12 45.34922 76.78805 18.38519 44.3336 77.47677 18.53584 42.83462 76.64325 12 44.25 76.78805 18.38519 44.3336 77.47677 18.53584 42.83462 76.64325 12 44.25 77.87606 18.99997 41.24192 77.59629 12 41.76725 77.87606 18.99997 41.24192 77.21747 12 43.04613 77.97822 19.81758 39.6149 77.7704 12 40.44485 77.97822 19.81758 39.6149 77.85877 20.73472 38.37821 77.73548 12 39.11151 77.85877 20.73472 38.37821 82.17361 20.77186 27.89335 77.79184 21.06346 38.01905 77.79184 21.06346 38.01905 85.11135 20.77186 16.92922 76.97584 24.39945 35.6779 77.35404 22.85944 36.53479 86.59291 20.77186 5.67544 86.59291 20.77186 -5.67544 85.11135 20.77186 -16.92922 82.17361 20.77186 -27.89335 77.85877 20.73472 -38.37821 77.79184 21.06346 -38.01905 76.97584 24.39945 -35.6779 77.35404 22.85944 -36.53479 77.97822 19.81758 -39.6149 77.73548 12 -39.11151 77.85877 20.73472 -38.37821 77.97822 19.81758 -39.6149 77.4924 12 -37.80004 77.79184 21.06346 -38.01905 77.87606 18.99997 -41.24192 77.7704 12 -40.44485 77.87606 18.99997 -41.24192 77.47677 18.53584 -42.83462 77.59629 12 -41.76725 77.47677 18.53584 -42.83462 76.78805 18.38519 -44.3336 77.21747 12 -43.04613 76.78805 18.38519 -44.3336 75.83428 18.53583 -45.67951 76.64325 12 -44.25 76.78805 18.38519 -44.3336 75.83428 18.53583 -45.67951 76.64325 12 -44.25 74.6546 18.99996 -46.82167 74.96965 12 -46.31673 74.6546 18.99996 -46.82167 75.88777 12 -45.34922 73.29663 19.81757 -47.72366 73.91146 12 -47.1287 73.29663 19.81757 -47.72366 72.1659 20.73472 -48.23857 72.73931 12 -47.76514 72.1659 20.73472 -48.23857 65.24315 20.77186 -57.21776 71.82141 21.06345 -48.36018 71.82141 21.06345 -48.36018 57.2168 20.77186 -65.24398 69.38591 24.39945 -48.82408 70.3171 22.85943 -48.72317 48.21152 20.77186 -72.15393 38.38137 20.77186 -77.82937 27.89454 20.77186 -82.17321 16.93045 20.77186 -85.11111 5.692887 20.73473 -86.61679 5.97046 21.06346 -86.37924 7.589947 24.39945 -84.50199 7.036967 22.85944 -85.25796 4.681576 19.81756 -87.3386 4.996175 12 -86.87664 5.692887 20.73473 -86.61679 4.681576 19.81756 -87.3386 6.010408 12 -86.01041 5.97046 21.06346 -86.37924 3.221466 18.99996 -88.06362 3.858919 12 -87.57357 3.221466 18.99996 -88.06362 0 17.56821 -89.46598 1.642664 18.53587 -88.51413 2.626644 12 -88.08398 1.642664 18.53587 -88.51413 0 18.38519 -88.66722 1.329693 12 -88.39535 0 18.38519 -88.66722 0 18.38519 -88.66722 -1.642655 18.53586 -88.51414 0 12 -88.5 0 18.38519 -88.66722 -1.642655 18.53586 -88.51414 0 12 -88.5 -8.800391 20.32512 86.64303 0 17.56821 89.46598 0 20.17705 87.19565 -8.800391 20.32512 86.64303 76.97584 24.39945 -35.6779 77.04718 12 -36.54274 77.35404 22.85944 -36.53479 77.04718 12 36.54274 76.97584 24.39945 35.6779 77.35404 22.85944 36.53479 77.4924 12 37.80004 7.589947 24.39945 -84.50199 6.876644 12 -84.99618 7.036967 22.85944 -85.25796 70.17053 12 -48.45344 69.38591 24.39945 -48.82408 70.3171 22.85943 -48.72317 71.482 12 -48.21037 -17.58298 20.77095 84.9792 -28.42046 20.77186 81.99279 -38.77979 20.77186 77.63162 -48.48854 20.77186 71.96807 -57.38383 20.77186 65.09713 -65.31642 20.77186 57.13411 -73.29663 19.81757 47.72366 -72.1659 20.73472 48.23857 -77.47677 18.53584 42.83462 -76.78805 18.38519 44.3336 -75.83428 18.53583 45.67951 -74.6546 18.99996 46.82167 -82.17361 20.77186 27.89335 -77.85877 20.73472 38.37821 -77.97822 19.81758 39.6149 -77.87606 18.99997 41.24192 -85.11135 20.77186 16.92922 -86.59291 20.77186 5.67544 -86.59291 20.77186 -5.67544 -85.11135 20.77186 -16.92922 -82.17361 20.77186 -27.89335 -75.83428 18.53583 -45.67951 -76.78805 18.38519 -44.3336 -77.47677 18.53584 -42.83462 -77.87606 18.99997 -41.24192 -77.97822 19.81758 -39.6149 -77.85877 20.73472 -38.37821 -72.1659 20.73472 -48.23857 -73.29663 19.81758 -47.72366 -74.6546 18.99996 -46.82167 -65.24315 20.77186 -57.21776 -57.2168 20.77186 -65.24398 -48.21152 20.77186 -72.15393 -38.38137 20.77186 -77.82937 -27.89454 20.77186 -82.17321 -16.93045 20.77186 -85.11111 -3.22146 18.99996 -88.06362 -4.681574 19.81756 -87.3386 -5.692884 20.73473 -86.61679 -2.626644 12 -88.08398 -3.22146 18.99996 -88.06362 -1.329693 12 -88.39535 -3.858919 12 -87.57357 -4.681574 19.81756 -87.3386 -4.996175 12 -86.87664 -5.692884 20.73473 -86.61679 -5.970464 21.06347 -86.37924 -5.970464 21.06347 -86.37924 -7.589947 24.39945 -84.50199 -7.036967 22.85944 -85.25796 -71.82141 21.06345 -48.36018 -69.38591 24.39945 -48.82408 -70.31708 22.85943 -48.72317 -72.73931 12 -47.76514 -72.1659 20.73472 -48.23857 -73.29663 19.81758 -47.72366 -71.482 12 -48.21037 -71.82141 21.06345 -48.36018 -73.91146 12 -47.1287 -74.6546 18.99996 -46.82167 -74.96965 12 -46.31673 -75.83428 18.53583 -45.67951 -75.88777 12 -45.34922 -76.78805 18.38519 -44.3336 -76.64325 12 -44.25 -76.78805 18.38519 -44.3336 -77.47677 18.53584 -42.83462 -76.64325 12 -44.25 -77.59629 12 -41.76725 -77.87606 18.99997 -41.24192 -77.21747 12 -43.04613 -77.7704 12 -40.44485 -77.97822 19.81758 -39.6149 -77.73548 12 -39.11151 -77.85877 20.73472 -38.37821 -77.79184 21.06346 -38.01905 -77.79184 21.06346 -38.01905 -76.97584 24.39945 -35.6779 -77.35404 22.85944 -36.53479 -77.79184 21.06346 38.01905 -76.97584 24.39945 35.6779 -77.35404 22.85944 36.53479 -77.73548 12 39.11151 -77.85877 20.73472 38.37821 -77.97822 19.81758 39.6149 -77.4924 12 37.80004 -77.79184 21.06346 38.01905 -77.7704 12 40.44485 -77.87606 18.99997 41.24192 -77.59629 12 41.76725 -77.47677 18.53584 42.83462 -77.21747 12 43.04613 -76.78805 18.38519 44.3336 -76.64325 12 44.25 -76.78805 18.38519 44.3336 -75.83428 18.53583 45.67951 -76.64325 12 44.25 -74.96965 12 46.31673 -74.6546 18.99996 46.82167 -75.88777 12 45.34922 -73.91146 12 47.1287 -73.29663 19.81757 47.72366 -72.73931 12 47.76514 -72.1659 20.73472 48.23857 -71.82141 21.06345 48.36018 -71.82141 21.06345 48.36018 -70.3171 22.85943 48.72317 -69.38591 24.39945 48.82408 -54.74356 24.46426 64.78382 -45.97254 24.43957 71.28771 -35.34425 22.63171 78.03473 -44.0715 24.07224 72.65859 -26.49603 21.53729 82.11917 -17.58298 20.77095 84.9792 -26.49603 21.53729 82.11917 -35.34425 22.63171 78.03473 -71.482 12 48.21037 -70.3171 22.85943 48.72317 -70.17053 12 48.45344 -69.38591 24.39945 48.82408 -52.49603 25.86359 65.97319 -56.53216 26.88901 62.14626 -45.97254 24.43957 71.28771 -44.0715 24.07224 72.65859 -52.49603 25.86359 65.97319 -56.53216 26.88901 62.14626 -69.38591 24.39945 -48.82408 -70.17053 12 -48.45344 -70.31708 22.85943 -48.72317 -6.876644 12 -84.99618 -7.589947 24.39945 -84.50199 -7.036967 22.85944 -85.25796 -6.010408 12 -86.01041 -76.97584 24.39945 35.6779 -77.04718 12 36.54274 -77.35404 22.85944 36.53479 -77.04718 12 -36.54274 -76.97584 24.39945 -35.6779 -77.35404 22.85944 -36.53479 -77.4924 12 -37.80004 0 10 -71.5 0 12 -71.5 1.329693 12 -71.60466 -2.626644 10 -71.91603 -1.329693 12 -71.60466 0 12 -71.5 0 10 -71.5 2.626644 12 -71.91603 2.626644 10 -71.91603 3.858919 12 -72.42646 4.996175 12 -73.12336 4.996175 10 -73.12336 6.010408 12 -73.9896 6.876644 12 -75.00382 6.876644 10 -75.00382 7.573555 12 -76.14109 8.08398 12 -77.37336 8.08398 10 -77.37336 8.395353 12 -78.67031 8.5 12 -80 8.5 10 -80 8.395353 12 -81.3297 8.08398 12 -82.62664 8.08398 10 -82.62664 7.573555 12 -83.85892 6.876644 12 -84.99618 6.876644 10 -84.99618 6.010408 12 -86.01041 4.996175 12 -86.87664 4.996175 10 -86.87664 3.858919 12 -87.57357 2.626644 12 -88.08398 2.626644 10 -88.08398 1.329693 12 -88.39535 0 12 -88.5 0 10 -88.5 0 12 -88.5 -1.329693 12 -88.39535 0 10 -88.5 -2.626644 12 -88.08398 -2.626644 10 -88.08398 -3.858919 12 -87.57357 -4.996175 12 -86.87664 -4.996175 10 -86.87664 -6.010408 12 -86.01041 -6.876644 12 -84.99618 -6.876644 10 -84.99618 -7.573555 12 -83.85892 -8.08398 12 -82.62664 -8.08398 10 -82.62664 -8.395353 12 -81.3297 -8.5 12 -80 -8.5 10 -80 -8.395353 12 -78.67031 -8.08398 12 -77.37336 -8.08398 10 -77.37336 -7.573555 12 -76.14109 -6.876644 12 -75.00382 -6.876644 10 -75.00382 -6.010408 12 -73.9896 -4.996175 12 -73.12336 -4.996175 10 -73.12336 -3.858919 12 -72.42646 -2.626644 12 -71.91603 -61.92081 10 -35.75 -61.92081 12 -35.75 -61.3466 12 -36.95387 -63.59442 10 -33.68327 -62.67629 12 -34.65077 -61.92081 12 -35.75 -61.92081 10 -35.75 -60.96778 12 -38.23275 -60.96778 10 -38.23275 -60.79368 12 -39.55514 -60.82859 12 -40.88849 -60.82859 10 -40.88849 -61.07166 12 -42.19996 -61.51689 12 -43.45726 -61.51689 10 -43.45726 -62.15333 12 -44.62943 -62.9653 12 -45.68761 -62.9653 10 -45.68761 -63.93281 12 -46.60574 -65.03203 12 -47.36122 -65.03203 10 -47.36122 -66.23591 12 -47.93543 -67.5148 12 -48.31425 -67.5148 10 -48.31425 -68.83718 12 -48.48835 -70.17053 12 -48.45344 -70.17053 10 -48.45344 -71.482 12 -48.21037 -72.73931 12 -47.76514 -72.73931 10 -47.76514 -73.91146 12 -47.1287 -74.96965 12 -46.31673 -74.96965 10 -46.31673 -75.88777 12 -45.34922 -76.64325 12 -44.25 -76.64325 10 -44.25 -76.64325 12 -44.25 -77.21747 12 -43.04613 -76.64325 10 -44.25 -77.59629 12 -41.76725 -77.59629 10 -41.76725 -77.7704 12 -40.44485 -77.73548 12 -39.11151 -77.73548 10 -39.11151 -77.4924 12 -37.80004 -77.04718 12 -36.54274 -77.04718 10 -36.54274 -76.41073 12 -35.37057 -75.59877 12 -34.31239 -75.59877 10 -34.31239 -74.63127 12 -33.39426 -73.53203 12 -32.63878 -73.53203 10 -32.63878 -72.32817 12 -32.06457 -71.04928 12 -31.68575 -71.04928 10 -31.68575 -69.72689 12 -31.51165 -68.39354 12 -31.54656 -68.39354 10 -31.54656 -67.08207 12 -31.78963 -65.82477 12 -32.23486 -65.82477 10 -32.23486 -64.65261 12 -32.8713 -63.59442 12 -33.68327 -61.92081 10 35.75 -61.92081 12 35.75 -62.67629 12 34.65077 -60.96778 10 38.23275 -61.3466 12 36.95387 -61.92081 12 35.75 -61.92081 10 35.75 -63.59442 12 33.68327 -63.59442 10 33.68327 -64.65261 12 32.8713 -65.82477 12 32.23486 -65.82477 10 32.23486 -67.08207 12 31.78963 -68.39354 12 31.54656 -68.39354 10 31.54656 -69.72689 12 31.51165 -71.04928 12 31.68575 -71.04928 10 31.68575 -72.32817 12 32.06457 -73.53203 12 32.63878 -73.53203 10 32.63878 -74.63127 12 33.39426 -75.59877 12 34.31239 -75.59877 10 34.31239 -76.41073 12 35.37057 -77.04718 12 36.54274 -77.04718 10 36.54274 -77.4924 12 37.80004 -77.73548 12 39.11151 -77.73548 10 39.11151 -77.7704 12 40.44485 -77.59629 12 41.76725 -77.59629 10 41.76725 -77.21747 12 43.04613 -76.64325 12 44.25 -76.64325 10 44.25 -76.64325 12 44.25 -75.88777 12 45.34922 -76.64325 10 44.25 -74.96965 12 46.31673 -74.96965 10 46.31673 -73.91146 12 47.1287 -72.73931 12 47.76514 -72.73931 10 47.76514 -71.482 12 48.21037 -70.17053 12 48.45344 -70.17053 10 48.45344 -68.83718 12 48.48835 -67.5148 12 48.31425 -67.5148 10 48.31425 -66.23591 12 47.93543 -65.03203 12 47.36122 -65.03203 10 47.36122 -63.93281 12 46.60574 -62.9653 12 45.68761 -62.9653 10 45.68761 -62.15333 12 44.62943 -61.51689 12 43.45726 -61.51689 10 43.45726 -61.07166 12 42.19996 -60.82859 12 40.88849 -60.82859 10 40.88849 -60.79368 12 39.55514 -60.96778 12 38.23275 61.92081 10 35.75 61.92081 12 35.75 61.3466 12 36.95387 63.59442 10 33.68327 62.67629 12 34.65077 61.92081 12 35.75 61.92081 10 35.75 60.96778 12 38.23275 60.96778 10 38.23275 60.79368 12 39.55514 60.82859 12 40.88849 60.82859 10 40.88849 61.07166 12 42.19996 61.51689 12 43.45726 61.51689 10 43.45726 62.15333 12 44.62943 62.9653 12 45.68761 62.9653 10 45.68761 63.93281 12 46.60574 65.03203 12 47.36122 65.03203 10 47.36122 66.23591 12 47.93543 67.5148 12 48.31425 67.5148 10 48.31425 68.83718 12 48.48835 70.17053 12 48.45344 70.17053 10 48.45344 71.482 12 48.21037 72.73931 12 47.76514 72.73931 10 47.76514 73.91146 12 47.1287 74.96965 12 46.31673 74.96965 10 46.31673 75.88777 12 45.34922 76.64325 12 44.25 76.64325 10 44.25 76.64325 12 44.25 77.21747 12 43.04613 76.64325 10 44.25 77.59629 12 41.76725 77.59629 10 41.76725 77.7704 12 40.44485 77.73548 12 39.11151 77.73548 10 39.11151 77.4924 12 37.80004 77.04718 12 36.54274 77.04718 10 36.54274 76.41073 12 35.37057 75.59877 12 34.31239 75.59877 10 34.31239 74.63127 12 33.39426 73.53203 12 32.63878 73.53203 10 32.63878 72.32817 12 32.06457 71.04928 12 31.68575 71.04928 10 31.68575 69.72689 12 31.51165 68.39354 12 31.54656 68.39354 10 31.54656 67.08207 12 31.78963 65.82477 12 32.23486 65.82477 10 32.23486 64.65261 12 32.8713 63.59442 12 33.68327 61.92081 10 -35.75 61.92081 12 -35.75 62.67629 12 -34.65077 60.96778 10 -38.23275 61.3466 12 -36.95387 61.92081 12 -35.75 61.92081 10 -35.75 63.59442 12 -33.68327 63.59442 10 -33.68327 64.65261 12 -32.8713 65.82477 12 -32.23486 65.82477 10 -32.23486 67.08207 12 -31.78963 68.39354 12 -31.54656 68.39354 10 -31.54656 69.72689 12 -31.51165 71.04928 12 -31.68575 71.04928 10 -31.68575 72.32817 12 -32.06457 73.53203 12 -32.63878 73.53203 10 -32.63878 74.63127 12 -33.39426 75.59877 12 -34.31239 75.59877 10 -34.31239 76.41073 12 -35.37057 77.04718 12 -36.54274 77.04718 10 -36.54274 77.4924 12 -37.80004 77.73548 12 -39.11151 77.73548 10 -39.11151 77.7704 12 -40.44485 77.59629 12 -41.76725 77.59629 10 -41.76725 77.21747 12 -43.04613 76.64325 12 -44.25 76.64325 10 -44.25 76.64325 12 -44.25 75.88777 12 -45.34922 76.64325 10 -44.25 74.96965 12 -46.31673 74.96965 10 -46.31673 73.91146 12 -47.1287 72.73931 12 -47.76514 72.73931 10 -47.76514 71.482 12 -48.21037 70.17053 12 -48.45344 70.17053 10 -48.45344 68.83718 12 -48.48835 67.5148 12 -48.31425 67.5148 10 -48.31425 66.23591 12 -47.93543 65.03203 12 -47.36122 65.03203 10 -47.36122 63.93281 12 -46.60574 62.9653 12 -45.68761 62.9653 10 -45.68761 62.15333 12 -44.62943 61.51689 12 -43.45726 61.51689 10 -43.45726 61.07166 12 -42.19996 60.82859 12 -40.88849 60.82859 10 -40.88849 60.79368 12 -39.55514 60.96778 12 -38.23275 0 10 -84.25 0 0 -84.25 1.453586 0 -83.99369 -1.453902 10 -83.99356 -1.453586 0 -83.99369 0 0 -84.25 0 10 -84.25 1.453902 10 -83.99356 2.731847 0 -83.25569 2.732141 10 -83.25537 3.680608 0 -82.125 3.680695 10 -82.12467 4.185433 0 -80.73801 4.185343 10 -80.73786 4.185433 0 -79.262 4.185343 10 -79.26214 3.680608 0 -77.875 2.731847 0 -76.74431 3.680695 10 -77.87535 2.731847 0 -76.74431 1.453586 0 -76.00631 2.732141 10 -76.74463 1.453586 0 -76.00631 17.84374 0 -75.78388 1.453902 10 -76.00644 0 0 -75.75 0 10 -75.75 0 0 -75.75 -1.453586 0 -76.00631 16.37053 0 -75.01541 0 10 -75.75 -1.453902 10 -76.00644 -2.731847 0 -76.74431 -2.732141 10 -76.74463 -3.680608 0 -77.875 -3.680695 10 -77.87535 -4.185433 0 -79.262 -4.185343 10 -79.26214 -4.185433 0 -80.73801 -4.185343 10 -80.73786 -3.680608 0 -82.125 -3.680695 10 -82.12467 -2.731847 0 -83.25569 -2.732141 10 -83.25537 -72.96264 10 -42.125 -72.96264 0 -42.125 -72.01388 0 -43.25569 -73.46751 10 -40.73766 -73.46747 0 -40.73801 -72.96264 0 -42.125 -72.96264 10 -42.125 -72.01361 10 -43.2559 -70.73562 0 -43.99369 -70.73519 10 -43.99379 -69.28203 0 -44.25 -67.82846 0 -43.99369 -69.2817 10 -44.24991 -67.82846 0 -43.99369 -66.5502 0 -43.25569 -67.82837 10 -43.99354 -66.5502 0 -43.25569 -62.85785 0 -39.0498 -65.60144 0 -42.125 -66.55036 10 -43.25568 -65.60144 0 -42.125 -65.09661 0 -40.73801 -65.60167 10 -42.12524 -65.09661 0 -40.73801 -65.09661 0 -39.26199 -65.09674 10 -40.73842 -65.09661 0 -39.26199 -65.60144 0 -37.875 -65.09656 10 -39.26234 -65.60144 0 -37.875 -66.5502 0 -36.74431 -65.60144 10 -37.875 -65.60144 0 -37.875 -66.5502 0 -36.74431 -65.60144 10 -37.875 -67.82846 0 -36.0063 -66.55046 10 -36.7441 -67.82846 0 -36.0063 -67.82888 10 -36.00621 -69.28203 0 -35.75 -69.28237 10 -35.75009 -70.73562 0 -36.0063 -70.73571 10 -36.00645 -72.01388 0 -36.74431 -72.01371 10 -36.74432 -72.96264 0 -37.875 -72.9624 10 -37.87476 -73.46747 0 -39.26199 -73.46734 10 -39.26158 -72.96264 10 42.125 -72.96264 0 42.125 -73.46747 0 40.73801 -72.01361 10 43.2559 -72.01388 0 43.25569 -72.96264 0 42.125 -72.96264 10 42.125 -73.46751 10 40.73766 -73.46747 0 39.26199 -73.46734 10 39.26158 -72.96264 0 37.875 -72.9624 10 37.87476 -72.01388 0 36.74431 -72.01371 10 36.74432 -70.73562 0 36.0063 -70.73571 10 36.00645 -69.28203 0 35.75 -67.82846 0 36.0063 -69.28237 10 35.75009 -67.82846 0 36.0063 -66.5502 0 36.74431 -67.82888 10 36.00621 -66.5502 0 36.74431 -62.50617 0 39.61026 -65.60144 0 37.875 -66.55046 10 36.7441 -65.60144 0 37.875 -65.09661 0 39.26199 -65.60144 10 37.875 -65.60144 0 37.875 -65.09661 0 39.26199 -65.60144 10 37.875 -65.09661 0 40.73801 -65.09656 10 39.26234 -65.09661 0 40.73801 -59.42761 0 44.09479 -65.60144 0 42.125 -65.09674 10 40.73842 -65.60144 0 42.125 -66.5502 0 43.25569 -65.60167 10 42.12524 -66.5502 0 43.25569 -67.82846 0 43.99369 -66.55036 10 43.25568 -67.82846 0 43.99369 -67.82837 10 43.99354 -69.28203 0 44.25 -69.2817 10 44.24991 -70.73562 0 43.99369 -70.73519 10 43.99379 72.96264 10 42.125 72.96264 0 42.125 72.01388 0 43.25569 73.46751 10 40.73766 73.46747 0 40.73801 72.96264 0 42.125 72.96264 10 42.125 72.01361 10 43.2559 70.73562 0 43.99369 70.73519 10 43.99379 69.28203 0 44.25 67.82846 0 43.99369 69.2817 10 44.24991 67.82846 0 43.99369 66.5502 0 43.25569 67.82837 10 43.99354 66.5502 0 43.25569 62.85779 0 39.04988 65.60144 0 42.125 66.55036 10 43.25568 65.60144 0 42.125 65.09661 0 40.73801 65.60167 10 42.12524 65.09661 0 40.73801 65.09661 0 39.26199 65.09674 10 40.73842 65.09661 0 39.26199 65.60144 0 37.875 65.09656 10 39.26234 65.60144 0 37.875 66.5502 0 36.74431 65.60144 10 37.875 65.60144 0 37.875 66.5502 0 36.74431 65.60144 10 37.875 67.82846 0 36.0063 66.55046 10 36.7441 67.82846 0 36.0063 67.82888 10 36.00621 69.28203 0 35.75 69.28237 10 35.75009 70.73562 0 36.0063 70.73571 10 36.00645 72.01388 0 36.74431 72.01371 10 36.74432 72.96264 0 37.875 72.9624 10 37.87476 73.46747 0 39.26199 73.46734 10 39.26158 72.96264 10 -42.125 72.96264 0 -42.125 73.46747 0 -40.73801 72.01361 10 -43.2559 72.01388 0 -43.25569 72.96264 0 -42.125 72.96264 10 -42.125 73.46751 10 -40.73766 73.46747 0 -39.26199 73.46734 10 -39.26158 72.96264 0 -37.875 72.9624 10 -37.87476 72.01388 0 -36.74431 72.01371 10 -36.74432 70.73562 0 -36.0063 70.73571 10 -36.00645 69.28203 0 -35.75 67.82846 0 -36.0063 69.28237 10 -35.75009 67.82846 0 -36.0063 66.5502 0 -36.74431 67.82888 10 -36.00621 66.5502 0 -36.74431 62.50635 0 -39.60998 65.60144 0 -37.875 66.55046 10 -36.7441 65.60144 0 -37.875 65.09661 0 -39.26199 65.60144 10 -37.875 65.60144 0 -37.875 65.09661 0 -39.26199 65.60144 10 -37.875 65.09661 0 -40.73801 65.09656 10 -39.26234 65.09661 0 -40.73801 59.42784 0 -44.09448 65.60144 0 -42.125 65.09674 10 -40.73842 65.60144 0 -42.125 66.5502 0 -43.25569 65.60167 10 -42.12524 66.5502 0 -43.25569 67.82846 0 -43.99369 66.55036 10 -43.25568 67.82846 0 -43.99369 67.82837 10 -43.99354 69.28203 0 -44.25 69.2817 10 -44.24991 70.73562 0 -43.99369 70.73519 10 -43.99379 -40.625 10 -66.36457 -40.625 0 -66.36457 -41.99308 0 -66.6058 -39.25692 0 -66.6058 -39.25692 10 -66.6058 -39.25692 0 -66.6058 -40.625 0 -66.36457 -40.625 10 -66.36457 -41.99308 10 -66.6058 -43.19615 0 -67.30039 -43.19615 10 -67.30039 -44.0891 0 -68.36457 -44.0891 10 -68.36457 -44.56423 0 -69.66997 -44.56423 10 -69.66997 -44.56423 0 -71.05916 -44.56423 10 -71.05916 -44.0891 0 -72.36457 -44.0891 10 -72.36457 -43.19615 0 -73.42874 -43.19615 10 -73.42874 -41.99308 0 -74.12334 -41.99308 10 -74.12334 -40.625 0 -74.36457 2.389175 0 -73.96141 -39.25692 0 -74.12334 -40.625 10 -74.36457 -40.625 0 -74.36457 -39.25692 0 -74.12334 -40.625 10 -74.36457 -8.473461 0 -73.51322 -38.05385 0 -73.42874 -39.25692 10 -74.12334 -38.05385 0 -73.42874 -3.050451 0 -73.93706 -13.85064 0 -72.69216 -37.1609 0 -72.36457 -38.05385 10 -73.42874 -37.1609 0 -72.36457 -19.15298 0 -71.47834 -36.68577 0 -71.05916 -37.1609 10 -72.36457 -36.68577 0 -71.05916 -24.35181 0 -69.87832 -36.68577 0 -69.66997 -36.68577 10 -71.05916 -36.68577 0 -69.66997 -29.41902 0 -67.90076 -37.1609 0 -68.36457 -36.68577 10 -69.66997 -37.1609 0 -68.36457 -38.05385 0 -67.30039 -37.1609 10 -68.36457 -38.05385 0 -67.30039 -38.05385 10 -67.30039 73.96138 0 -2.389636 78.67885 0 -3.064178 77.7859 0 -2 77.7859 10 -2 77.7859 0 -2 78.67885 0 -3.064178 77.31077 0 -0.694593 77.31077 10 -0.694593 77.31077 0 -0.694593 77.7859 0 -2 77.7859 10 -2 79.88192 0 -3.75877 78.67885 10 -3.064178 79.88192 0 -3.75877 81.25 0 -4 79.88192 10 -3.75877 81.25 0 -4 81.25 10 -4 82.61808 0 -3.75877 82.61808 10 -3.75877 83.82115 0 -3.064178 83.82115 10 -3.064178 84.71411 0 -2 84.71411 10 -2 85.18923 0 -0.694593 85.18923 10 -0.694593 85.18923 0 0.694593 85.18923 10 0.694593 84.71411 0 2 84.71411 10 2 84.71411 0 2 83.82115 0 3.064178 84.71411 10 2 83.82115 10 3.064178 82.61808 0 3.75877 82.61808 10 3.75877 81.25 0 4 73.93708 0 3.049869 79.88192 0 3.75877 81.25 10 4 79.88192 0 3.75877 78.67885 0 3.064178 79.88192 10 3.75877 78.67885 0 3.064178 77.7859 0 2 78.67885 10 3.064178 77.7859 0 2 77.31077 0 0.694593 77.7859 10 2 77.31077 0 0.694593 77.31077 10 0.694593 -71.52102 0 23.65241 -71.52102 7 23.65241 -71.52102 0 23.65241 -73.15052 0 23.33041 -70.73329 7 23.82219 -70.73329 0 23.82219 -71.52102 0 23.65241 -71.52102 7 23.65241 -73.15052 7 23.33041 -74.55265 0 22.43881 -74.55265 7 22.43881 -75.53559 0 21.09942 -75.53559 7 21.09942 -75.96543 0 19.49533 -75.96543 7 19.49533 -75.78392 0 17.84387 -75.78392 7 17.84387 -75.01544 0 16.37059 -75.01544 7 16.37059 -73.76522 0 15.27692 -73.76522 7 15.27692 -73.76522 0 15.27692 -73.16793 0 14.73602 -73.76522 7 15.27692 -73.16793 7 14.73602 -72.83258 0 14.0033 -72.83258 7 14.0033 -72.81361 0 13.1977 -72.81361 7 13.1977 -72.81361 0 13.1977 -73.58609 0 7.81595 -72.81361 7 13.1977 -73.58609 7 7.81595 -73.96138 0 2.389604 -73.96138 7 2.389604 -73.93708 0 -3.049872 -73.93708 7 -3.049872 -73.51329 0 -8.472777 -73.51329 7 -8.472778 -72.6923 0 -13.8499 -72.6923 7 -13.8499 -71.47854 0 -19.15223 -71.47854 7 -19.15223 -69.87857 0 -24.3511 -69.87857 7 -24.3511 -67.90103 0 -29.41839 -67.90103 7 -29.41839 -65.55659 0 -34.32678 -65.55659 7 -34.32678 -62.85785 0 -39.0498 -62.85785 7 -39.0498 -59.81959 0 -43.56166 -59.81959 7 -43.56166 -56.45958 0 -47.83634 -56.45958 7 -47.83634 -56.45958 0 -47.83634 -56.0732 0 -48.54349 -56.45958 7 -47.83634 -56.0732 7 -48.54349 -55.99727 0 -49.34572 -55.99727 7 -49.34572 -56.24409 0 -50.11281 -56.24409 7 -50.11281 -56.24409 0 -50.11281 -56.77998 0 -51.685 -56.24409 7 -50.11281 -56.77998 7 -51.685 -56.7089 0 -53.34508 -56.7089 7 -53.34508 -56.04042 0 -54.86601 -56.04042 7 -54.86601 -54.86616 0 -56.04032 -54.86616 7 -56.04032 -53.3452 0 -56.70886 -53.3452 7 -56.70886 -51.68506 0 -56.77999 -47.83634 0 -56.45958 -50.11281 0 -56.24409 -51.68506 7 -56.77999 -50.11281 0 -56.24409 -48.54349 0 -56.0732 -49.34572 0 -55.99727 -50.11281 7 -56.24409 -50.11281 0 -56.24409 -49.34572 0 -55.99727 -50.11281 7 -56.24409 -49.34572 7 -55.99727 -48.54349 0 -56.0732 -48.54349 7 -56.0732 -47.83634 0 -56.45958 -47.83634 7 -56.45958 -47.83634 0 -56.45958 -43.56186 0 -59.81944 -47.83634 7 -56.45958 -43.56186 7 -59.81944 -39.05015 0 -62.85763 -39.05015 7 -62.85763 -34.32729 0 -65.55632 -34.32729 7 -65.55632 -29.41902 0 -67.90076 -29.41902 7 -67.90076 -24.35181 0 -69.87832 -24.35181 7 -69.87832 -19.15298 0 -71.47834 -19.15298 7 -71.47834 -13.85064 0 -72.69216 -13.85064 7 -72.69216 -8.473461 0 -73.51322 -8.473461 7 -73.51322 -3.050451 0 -73.93706 -3.050451 7 -73.93706 2.389175 0 -73.96141 15.27692 0 -73.76522 7.8157 0 -73.58612 2.389175 7 -73.96141 7.8157 0 -73.58612 14.0033 0 -72.83258 13.1977 0 -72.81361 7.8157 7 -73.58612 13.1977 0 -72.81361 14.73602 0 -73.16793 13.1977 7 -72.81361 13.1977 0 -72.81361 14.0033 0 -72.83258 13.1977 7 -72.81361 14.0033 7 -72.83258 14.73602 0 -73.16793 14.73602 7 -73.16793 15.27692 0 -73.76522 15.27692 7 -73.76522 15.27692 0 -73.76522 16.37053 0 -75.01541 15.27692 7 -73.76522 16.37053 7 -75.01541 17.84374 0 -75.78388 17.84374 7 -75.78388 19.49515 0 -75.96544 19.49515 7 -75.96544 21.09926 0 -75.53565 21.09926 7 -75.53565 22.43872 0 -74.55274 22.43872 7 -74.55274 23.33038 0 -73.15058 23.33038 7 -73.15058 23.65241 0 -71.52102 23.65241 7 -71.52102 23.65241 0 -71.52102 23.82219 0 -70.73329 23.65241 7 -71.52102 23.82219 7 -70.73329 24.28907 0 -70.0765 24.28907 7 -70.0765 24.97726 0 -69.65728 24.97726 7 -69.65728 24.97726 0 -69.65728 30.02434 0 -67.63536 24.97726 7 -69.65728 30.02442 7 -67.63533 34.91143 0 -65.24713 34.91155 7 -65.24707 39.61006 0 -62.50629 39.61022 7 -62.50619 44.09458 0 -59.42776 44.09475 7 -59.42764 48.34083 0 -56.02815 48.341 7 -56.02801 52.3259 0 -52.3258 52.32606 7 -52.32564 56.02824 0 -48.34072 56.02838 7 -48.34056 59.42784 0 -44.09448 59.42795 7 -44.09433 62.50635 0 -39.60998 62.50643 7 -39.60985 65.24717 0 -34.91135 65.24723 7 -34.91126 67.63537 0 -30.0243 67.63539 7 -30.02425 69.65728 0 -24.97726 69.65728 7 -24.97726 69.65728 0 -24.97726 70.0765 0 -24.28907 69.65728 7 -24.97726 70.0765 7 -24.28907 70.73329 0 -23.82219 71.52102 0 -23.65241 70.73329 7 -23.82219 71.52102 0 -23.65241 71.52102 7 -23.65241 71.52102 0 -23.65241 73.15052 0 -23.33041 71.52102 7 -23.65241 73.15052 7 -23.33041 74.55265 0 -22.43881 74.55265 7 -22.43881 75.53559 0 -21.09942 75.53559 7 -21.09942 75.96543 0 -19.49533 75.96543 7 -19.49533 75.78392 0 -17.84387 75.78392 7 -17.84387 75.01544 0 -16.37059 75.01544 7 -16.37059 73.76522 0 -15.27692 73.76522 7 -15.27692 73.76522 0 -15.27692 73.16793 0 -14.73602 73.76522 7 -15.27692 73.16793 7 -14.73602 72.83258 0 -14.0033 72.83258 7 -14.0033 72.81361 0 -13.1977 72.81361 7 -13.1977 72.81361 0 -13.1977 73.58609 0 -7.815966 72.81361 7 -13.1977 73.5861 7 -7.815814 73.96138 0 -2.389636 73.96139 7 -2.389348 73.93708 0 3.049869 73.93708 7 3.050184 73.51329 0 8.472822 73.51325 7 8.473104 72.69229 0 13.84998 72.69224 7 13.85023 71.47851 0 19.15234 71.47846 7 19.15255 69.87854 0 24.35123 69.87847 7 24.35139 67.90097 0 29.41852 67.90092 7 29.41865 65.55654 0 34.32689 65.55648 7 34.32698 62.85779 0 39.04988 62.85776 7 39.04994 59.81955 0 43.56171 59.81953 7 43.56174 56.45958 0 47.83634 56.45958 7 47.83634 56.45958 0 47.83634 56.0732 0 48.54349 56.45958 7 47.83634 56.0732 7 48.54349 55.99727 0 49.34572 55.99727 7 49.34572 56.24409 0 50.11281 56.24409 7 50.11281 56.24409 0 50.11281 56.77998 0 51.685 56.24409 7 50.11281 56.77998 7 51.685 56.7089 0 53.34508 56.7089 7 53.34508 56.04042 0 54.86601 56.04042 7 54.86601 54.86616 0 56.04032 54.86616 7 56.04032 53.3452 0 56.70886 53.3452 7 56.70886 51.68506 0 56.77999 47.83634 0 56.45958 50.11281 0 56.24409 51.68506 7 56.77999 50.11281 0 56.24409 48.54349 0 56.0732 49.34572 0 55.99727 50.11281 7 56.24409 50.11281 0 56.24409 49.34572 0 55.99727 50.11281 7 56.24409 49.34572 7 55.99727 48.54349 0 56.0732 48.54349 7 56.0732 47.83634 0 56.45958 47.83634 7 56.45958 47.83634 0 56.45958 43.56184 0 59.81946 47.83634 7 56.45958 43.56184 7 59.81946 39.05011 0 62.85765 39.05011 7 62.85765 34.32722 0 65.55636 34.32722 7 65.55636 29.41893 0 67.90081 29.41893 7 67.90081 24.3517 0 69.87836 24.3517 7 69.87836 19.15286 0 71.47837 19.15286 7 71.47837 13.85052 0 72.69219 13.85052 7 72.69219 8.473347 0 73.51322 8.473347 7 73.51322 3.050353 0 73.93708 3.050352 7 73.93708 -2.389251 0 73.96141 -15.27692 0 73.76522 -7.815748 0 73.58612 -2.389251 7 73.96141 -7.815748 0 73.58612 -14.0033 0 72.83258 -13.1977 0 72.81361 -7.815748 7 73.58612 -13.1977 0 72.81361 -14.73602 0 73.16793 -13.1977 7 72.81361 -13.1977 0 72.81361 -14.0033 0 72.83258 -13.1977 7 72.81361 -14.0033 7 72.83258 -14.73602 0 73.16793 -14.73602 7 73.16793 -15.27692 0 73.76522 -15.27692 7 73.76522 -15.27692 0 73.76522 -16.37053 0 75.01541 -15.27692 7 73.76522 -16.37053 7 75.01541 -17.84374 0 75.78388 -17.84374 7 75.78388 -19.49515 0 75.96544 -19.49515 7 75.96544 -21.09926 0 75.53565 -21.09926 7 75.53565 -22.43872 0 74.55274 -22.43872 7 74.55274 -23.33038 0 73.15058 -23.33038 7 73.15058 -23.65241 0 71.52102 -23.65241 7 71.52102 -23.65241 0 71.52102 -23.82219 0 70.73329 -23.65241 7 71.52102 -23.82219 7 70.73329 -24.28907 0 70.0765 -24.28907 7 70.0765 -24.97726 0 69.65728 -24.97726 7 69.65728 -24.97726 0 69.65728 -30.02424 0 67.63539 -24.97726 7 69.65728 -30.02424 7 67.63539 -34.91125 0 65.24723 -34.91125 7 65.24723 -39.60983 0 62.50645 -39.60983 7 62.50645 -44.09431 0 59.42797 -44.09431 7 59.42797 -48.34053 0 56.02841 -48.34053 7 56.02841 -52.32561 0 52.32609 -52.32561 7 52.32609 -56.02798 0 48.34104 -56.02798 7 48.34104 -59.42761 0 44.09479 -59.42761 7 44.09479 -62.50617 0 39.61026 -62.50617 7 39.61026 -65.24707 0 34.91158 -65.24707 7 34.91157 -67.6353 0 30.02444 -67.6353 7 30.02444 -69.65728 0 24.97726 -69.65728 7 24.97726 -69.65728 0 24.97726 -70.0765 0 24.28907 -69.65728 7 24.97726 -70.0765 7 24.28907 0 122.7 61.5 0 129.5 61.5 9.621398 129.5 60.74267 -9.621379 122.7 60.74265 -9.621398 129.5 60.74267 0 129.5 61.5 0 122.7 61.5 9.621379 122.7 60.74265 19.00452 129.5 58.48989 19.00415 122.7 58.49 27.91977 129.5 54.79717 27.91989 122.7 54.79715 36.14879 129.5 49.75454 36.14939 122.7 49.75405 43.48752 129.5 43.48654 43.48699 122.7 43.48699 49.75447 129.5 36.14874 49.75405 122.7 36.14939 54.79654 129.5 27.92101 54.79715 122.7 27.91989 58.48997 129.5 19.00455 58.49 122.7 19.00415 60.74289 129.5 9.620025 60.74265 122.7 9.621379 61.4999 129.5 0 61.5 122.7 0 60.74289 129.5 -9.620025 60.74265 122.7 -9.621379 58.48997 129.5 -19.00455 58.49 122.7 -19.00415 54.79654 129.5 -27.92101 54.79715 122.7 -27.91989 49.75447 129.5 -36.14874 49.75405 122.7 -36.14939 43.48752 129.5 -43.48654 43.48699 122.7 -43.48699 36.14879 129.5 -49.75454 36.14939 122.7 -49.75405 27.91977 129.5 -54.79717 27.91989 122.7 -54.79715 19.00452 129.5 -58.48989 19.00415 122.7 -58.49 9.621398 129.5 -60.74267 9.621379 122.7 -60.74265 0 129.5 -61.5 0 122.7 -61.5 0 129.5 -61.5 -9.621398 129.5 -60.74267 0 122.7 -61.5 -9.621379 122.7 -60.74265 -19.00452 129.5 -58.48989 -19.00415 122.7 -58.49 -27.91977 129.5 -54.79717 -27.91989 122.7 -54.79715 -36.14879 129.5 -49.75454 -36.14939 122.7 -49.75405 -43.48752 129.5 -43.48654 -43.48699 122.7 -43.48699 -49.75447 129.5 -36.14874 -49.75405 122.7 -36.14939 -54.79654 129.5 -27.92101 -54.79715 122.7 -27.91989 -58.48997 129.5 -19.00455 -58.49 122.7 -19.00415 -60.74289 129.5 -9.620025 -60.74265 122.7 -9.621379 -61.4999 129.5 0 -61.5 122.7 0 -60.74289 129.5 9.620025 -60.74265 122.7 9.621379 -58.48997 129.5 19.00455 -58.49 122.7 19.00415 -54.79654 129.5 27.92101 -54.79715 122.7 27.91989 -49.75447 129.5 36.14874 -49.75405 122.7 36.14939 -43.48752 129.5 43.48654 -43.48699 122.7 43.48699 -36.14879 129.5 49.75454 -36.14939 122.7 49.75405 -27.91977 129.5 54.79717 -27.91989 122.7 54.79715 -19.00452 129.5 58.48989 -19.00415 122.7 58.49 8.379154 129.5 -47.51683 4.576298 129.5 -52.30016 0 129.5 -52.5 0 122.7 -52.5 0 129.5 -52.5 4.576298 129.5 -52.30016 0 129.5 -48.25 -4.576298 129.5 -52.30016 -4.576581 122.7 -52.30014 -4.576298 129.5 -52.30016 0 129.5 -52.5 0 122.7 -52.5 9.117215 129.5 -51.70225 4.576581 122.7 -52.30014 9.117215 129.5 -51.70225 16.50293 129.5 -45.33992 13.58867 129.5 -50.71087 9.117303 122.7 -51.70221 13.58867 129.5 -50.71087 17.95656 129.5 -49.33359 13.58857 122.7 -50.71086 17.95656 129.5 -49.33359 24.12495 129.5 -41.78564 22.1877 129.5 -47.58094 17.95623 122.7 -49.33368 22.1877 129.5 -47.58094 26.24995 129.5 -45.46625 22.18721 122.7 -47.58115 26.24995 129.5 -45.46625 31.01406 129.5 -36.96192 30.11246 129.5 -43.00558 26.24942 122.7 -45.46656 30.11246 129.5 -43.00558 33.74587 129.5 -40.21763 30.11208 122.7 -43.00589 33.74587 129.5 -40.21763 36.96121 129.5 -31.01498 37.12257 129.5 -37.12356 33.74585 122.7 -40.21773 37.12257 129.5 -37.12356 41.78572 129.5 -24.125 40.21686 129.5 -33.74686 37.1231 122.7 -37.1231 40.21686 129.5 -33.74686 43.0052 129.5 -30.11315 40.21773 122.7 -33.74585 43.0052 129.5 -30.11315 45.34036 129.5 -16.50186 45.46633 129.5 -26.25 43.00589 122.7 -30.11208 45.46633 129.5 -26.25 47.51699 129.5 -8.378005 47.58135 129.5 -22.18702 45.46656 122.7 -26.24942 47.58135 129.5 -22.18702 49.33407 129.5 17.95539 49.33407 129.5 -17.95539 47.58115 122.7 -22.18721 49.33407 129.5 -17.95539 48.24991 129.5 0 50.71123 129.5 13.5873 50.71123 129.5 -13.5873 49.33368 122.7 -17.95623 50.71123 129.5 -13.5873 51.70243 129.5 9.115964 51.70243 129.5 -9.115964 50.71086 122.7 -13.58857 51.70243 129.5 -9.115964 52.30015 129.5 4.575363 52.30015 129.5 -4.575363 51.70221 122.7 -9.117303 52.30015 129.5 -4.575363 52.4999 129.5 0 52.30015 122.7 -4.576309 52.4999 129.5 0 52.5 122.7 0 52.30015 129.5 4.575363 52.30015 122.7 4.576309 51.70243 129.5 9.115964 51.70221 122.7 9.117303 50.71123 129.5 13.5873 50.71086 122.7 13.58857 49.33407 129.5 17.95539 47.58135 129.5 22.18702 49.33368 122.7 17.95623 47.58135 129.5 22.18702 47.51699 129.5 8.378005 45.46633 129.5 26.25 47.58115 122.7 22.18721 45.46633 129.5 26.25 45.34036 129.5 16.50186 43.0052 129.5 30.11315 45.46656 122.7 26.24942 43.0052 129.5 30.11315 41.78572 129.5 24.125 40.21686 129.5 33.74686 43.00589 122.7 30.11208 40.21686 129.5 33.74686 36.96121 129.5 31.01498 37.12257 129.5 37.12356 40.21773 122.7 33.74585 37.12257 129.5 37.12356 33.74587 129.5 40.21763 37.1231 122.7 37.1231 33.74587 129.5 40.21763 31.01406 129.5 36.96192 30.11246 129.5 43.00558 33.74585 122.7 40.21773 30.11246 129.5 43.00558 24.12495 129.5 41.78564 26.24995 129.5 45.46625 30.11208 122.7 43.00589 26.24995 129.5 45.46625 22.1877 129.5 47.58094 26.24942 122.7 45.46656 22.1877 129.5 47.58094 16.50293 129.5 45.33992 17.95656 129.5 49.33359 22.18721 122.7 47.58115 17.95656 129.5 49.33359 13.58867 129.5 50.71087 17.95623 122.7 49.33368 13.58867 129.5 50.71087 8.379154 129.5 47.51683 9.117215 129.5 51.70225 13.58857 122.7 50.71086 9.117215 129.5 51.70225 4.576298 129.5 52.30016 9.117303 122.7 51.70221 4.576298 129.5 52.30016 0 129.5 48.25 0 129.5 52.5 4.576581 122.7 52.30014 0 129.5 52.5 -8.379154 129.5 47.51683 -4.576298 129.5 52.30016 0 122.7 52.5 0 129.5 52.5 -4.576298 129.5 52.30016 0 122.7 52.5 -9.117215 129.5 51.70225 -4.576581 122.7 52.30014 -9.117215 129.5 51.70225 -16.50293 129.5 45.33992 -13.58867 129.5 50.71087 -9.117303 122.7 51.70221 -13.58867 129.5 50.71087 -17.95656 129.5 49.33359 -13.58857 122.7 50.71086 -17.95656 129.5 49.33359 -24.12495 129.5 41.78564 -22.1877 129.5 47.58094 -17.95623 122.7 49.33368 -22.1877 129.5 47.58094 -26.24995 129.5 45.46625 -22.18721 122.7 47.58115 -26.24995 129.5 45.46625 -31.01406 129.5 36.96192 -30.11246 129.5 43.00558 -26.24942 122.7 45.46656 -30.11246 129.5 43.00558 -33.74587 129.5 40.21763 -30.11208 122.7 43.00589 -33.74587 129.5 40.21763 -36.96121 129.5 31.01498 -37.12257 129.5 37.12356 -33.74585 122.7 40.21773 -37.12257 129.5 37.12356 -41.78572 129.5 24.125 -40.21686 129.5 33.74686 -37.1231 122.7 37.1231 -40.21686 129.5 33.74686 -43.0052 129.5 30.11315 -40.21773 122.7 33.74585 -43.0052 129.5 30.11315 -45.34036 129.5 16.50186 -45.46633 129.5 26.25 -43.00589 122.7 30.11208 -45.46633 129.5 26.25 -47.51699 129.5 8.378005 -47.58135 129.5 22.18702 -45.46656 122.7 26.24942 -47.58135 129.5 22.18702 -49.33407 129.5 -17.95539 -49.33407 129.5 17.95539 -47.58115 122.7 22.18721 -49.33407 129.5 17.95539 -48.24991 129.5 0 -50.71123 129.5 -13.5873 -50.71123 129.5 13.5873 -49.33368 122.7 17.95623 -50.71123 129.5 13.5873 -51.70243 129.5 -9.115964 -51.70243 129.5 9.115964 -50.71086 122.7 13.58857 -51.70243 129.5 9.115964 -52.30015 129.5 -4.575363 -52.30015 129.5 4.575363 -51.70221 122.7 9.117303 -52.30015 129.5 4.575363 -52.4999 129.5 0 -52.30015 122.7 4.576309 -52.4999 129.5 0 -52.5 122.7 0 -52.30015 129.5 -4.575363 -52.30015 122.7 -4.576309 -51.70243 129.5 -9.115964 -51.70221 122.7 -9.117303 -50.71123 129.5 -13.5873 -50.71086 122.7 -13.58857 -49.33407 129.5 -17.95539 -47.58135 129.5 -22.18702 -49.33368 122.7 -17.95623 -47.58135 129.5 -22.18702 -47.51699 129.5 -8.378005 -45.46633 129.5 -26.25 -47.58115 122.7 -22.18721 -45.46633 129.5 -26.25 -45.34036 129.5 -16.50186 -43.0052 129.5 -30.11315 -45.46656 122.7 -26.24942 -43.0052 129.5 -30.11315 -41.78572 129.5 -24.125 -40.21686 129.5 -33.74686 -43.00589 122.7 -30.11208 -40.21686 129.5 -33.74686 -36.96121 129.5 -31.01498 -37.12257 129.5 -37.12356 -40.21773 122.7 -33.74585 -37.12257 129.5 -37.12356 -33.74587 129.5 -40.21763 -37.1231 122.7 -37.1231 -33.74587 129.5 -40.21763 -31.01406 129.5 -36.96192 -30.11246 129.5 -43.00558 -33.74585 122.7 -40.21773 -30.11246 129.5 -43.00558 -24.12495 129.5 -41.78564 -26.24995 129.5 -45.46625 -30.11208 122.7 -43.00589 -26.24995 129.5 -45.46625 -22.1877 129.5 -47.58094 -26.24942 122.7 -45.46656 -22.1877 129.5 -47.58094 -16.50293 129.5 -45.33992 -17.95656 129.5 -49.33359 -22.18721 122.7 -47.58115 -17.95656 129.5 -49.33359 -13.58867 129.5 -50.71087 -17.95623 122.7 -49.33368 -13.58867 129.5 -50.71087 -8.379154 129.5 -47.51683 -9.117215 129.5 -51.70225 -13.58857 122.7 -50.71086 -9.117215 129.5 -51.70225 -9.117303 122.7 -51.70221 0 110.4 48.25 0 129.5 48.25 8.379154 129.5 47.51683 -8.379238 110.4 47.51679 -8.379154 129.5 47.51683 0 129.5 48.25 0 110.4 48.25 8.379238 110.4 47.51679 16.50293 129.5 45.33992 16.50263 110.4 45.34 24.12495 129.5 41.78564 24.12447 110.4 41.78593 31.01406 129.5 36.96192 31.01404 110.4 36.96201 36.96121 129.5 31.01498 36.96201 110.4 31.01404 41.78572 129.5 24.125 41.78593 110.4 24.12447 45.34036 129.5 16.50186 45.34 110.4 16.50263 47.51699 129.5 8.378005 47.51679 110.4 8.379238 48.24991 129.5 0 48.25 110.4 0 47.51699 129.5 -8.378005 47.51679 110.4 -8.379238 45.34036 129.5 -16.50186 45.34 110.4 -16.50263 41.78572 129.5 -24.125 41.78593 110.4 -24.12447 36.96121 129.5 -31.01498 36.96201 110.4 -31.01404 31.01406 129.5 -36.96192 31.01404 110.4 -36.96201 24.12495 129.5 -41.78564 24.12447 110.4 -41.78593 16.50293 129.5 -45.33992 16.50263 110.4 -45.34 8.379154 129.5 -47.51683 8.379238 110.4 -47.51679 0 129.5 -48.25 0 110.4 -48.25 0 129.5 -48.25 -8.379154 129.5 -47.51683 0 110.4 -48.25 -8.379238 110.4 -47.51679 -16.50293 129.5 -45.33992 -16.50263 110.4 -45.34 -24.12495 129.5 -41.78564 -24.12447 110.4 -41.78593 -31.01406 129.5 -36.96192 -31.01404 110.4 -36.96201 -36.96121 129.5 -31.01498 -36.96201 110.4 -31.01404 -41.78572 129.5 -24.125 -41.78593 110.4 -24.12447 -45.34036 129.5 -16.50186 -45.34 110.4 -16.50263 -47.51699 129.5 -8.378005 -47.51679 110.4 -8.379238 -48.24991 129.5 0 -48.25 110.4 0 -47.51699 129.5 8.378005 -47.51679 110.4 8.379238 -45.34036 129.5 16.50186 -45.34 110.4 16.50263 -41.78572 129.5 24.125 -41.78593 110.4 24.12447 -36.96121 129.5 31.01498 -36.96201 110.4 31.01404 -31.01406 129.5 36.96192 -31.01404 110.4 36.96201 -24.12495 129.5 41.78564 -24.12447 110.4 41.78593 -16.50293 129.5 45.33992 -16.50263 110.4 45.34 -46.25 38 57.9 -46.25 38 58 -46.56652 39.79531 58 -46.56661 36.20439 57.9 -46.56652 36.20468 58 -46.25 38 58 -46.25 38 57.9 -46.56661 39.7956 57.9 -47.47806 41.37431 58 -47.47827 41.37463 57.9 -48.87478 42.54642 58 -48.875 42.54663 57.9 -50.58826 43.17013 58 -50.58835 43.17024 57.9 -52.41174 43.17013 58 -52.41165 43.17024 57.9 -54.12522 42.54642 58 -54.125 42.54663 57.9 -55.52194 41.37431 58 -55.52173 41.37463 57.9 -56.43347 39.79531 58 -56.43339 39.7956 57.9 -56.75 38 58 -56.75 38 57.9 -56.75 38 58 -56.43347 36.20468 58 -56.75 38 57.9 -56.43339 36.20439 57.9 -55.52194 34.62569 58 -55.52173 34.62537 57.9 -54.12522 33.45357 58 -54.125 33.45336 57.9 -52.41174 32.82986 58 -52.41165 32.82976 57.9 -50.58826 32.82986 58 -50.58835 32.82976 57.9 -48.87478 33.45357 58 -48.875 33.45336 57.9 -47.47806 34.62569 58 -47.47827 34.62537 57.9 -36.44685 89.08293 58.5 -36.44685 89.08293 58 -33.44577 89.08293 58 -36.44685 89.08293 58.5 -36.44685 87.80018 58.5 -36.44685 89.08293 58 -32.8903 88.12107 58 -32.8903 88.76204 58 -33.1249 88.99686 58 -20 85 58.5 -20 85.97177 58 -20 85.97177 58.5 -23.94784 85.97177 58.5 -23.94784 85.97177 58 -20.17238 89.08293 58 -20 85.97177 58.5 -23.94784 85.97177 58 -23.94784 85.97177 58.5 -20.17238 89.08293 58.5 -20.17238 89.08293 58 -20.17238 90.05471 58 -20.17238 89.08293 58.5 -20.17238 90.05471 58.5 -36.44685 89.08293 58.5 -33.44577 89.08293 58 -33.44577 89.08293 58.5 -32.18442 89.44702 58.5 -32.18456 89.44734 58 -32.74585 89.89495 58 -31.87316 88.80036 58.5 -32.74557 89.89479 58.5 -33.44577 90.05471 58 -33.44577 90.05471 58.5 -33.44577 90.05471 58 -37.5 90.05471 58 -33.44577 90.05471 58.5 -37.5 90.05471 58.5 15.68508 44.53391 58 15.50007 46.4 58 15.68508 48.26609 58 15.68508 48.26609 62.5 15.68508 48.26609 58 15.50007 46.4 58 18.72646 53.53391 58 18.72646 53.53391 62.5 18.72646 53.53391 58 15.68508 48.26609 58 17.20601 50.90041 63 15.68508 48.26609 62.5 15.5 46.4 62.5 15.68508 44.53391 58 15.54638 47.3376 62.5 18.72646 39.26609 58 15.68508 44.53391 62.5 15.68508 44.53391 58 18.72646 39.26609 58 15.54638 45.46239 62.5 15.68508 44.53391 62.5 20.25304 54.629 58 20.25304 38.171 58 18.72646 39.26609 62.5 18.72646 39.26609 58 20.25304 38.171 58 17.20553 41.90041 63 18.72646 39.26609 62.5 21.95862 55.4 58 21.95862 37.4 58 20.25001 38.17276 62.5 21.95862 37.4 58 28.04138 55.4 58 28.04138 37.4 58 21.95862 37.4 62.5 21.95862 37.4 58 28.04138 37.4 58 21.95862 37.4 62.5 29.74696 54.629 58 29.74696 38.171 58 28.04138 37.4 62.5 28.04138 37.4 58 29.74696 38.171 58 24.99953 37.4 63 28.04138 37.4 62.5 31.27354 53.53391 58 31.27354 39.26609 58 29.75 38.17276 62.5 31.27354 39.26609 58 34.31492 48.26609 58 34.31492 44.53391 58 31.27354 39.26609 62.5 31.27354 39.26609 58 34.31492 44.53391 58 31.27354 39.26609 62.5 34.49993 46.4 58 34.31492 44.53391 62.5 34.31492 44.53391 58 34.49993 46.4 58 32.79399 41.89959 63 34.31492 44.53391 62.5 34.5 46.4 62.5 34.31492 48.26609 58 34.45362 45.46239 62.5 34.31492 48.26609 62.5 34.31492 48.26609 58 31.27354 53.53391 58 34.45362 47.3376 62.5 34.31492 48.26609 62.5 31.27354 53.53391 62.5 31.27354 53.53391 58 29.74696 54.629 58 32.79446 50.89959 63 31.27354 53.53391 62.5 29.75 54.62724 62.5 28.04138 55.4 58 28.04138 55.4 62.5 28.04138 55.4 58 21.95862 55.4 58 28.04138 55.4 62.5 21.95862 55.4 62.5 21.95862 55.4 58 20.25304 54.629 58 25.00048 55.4 63 21.95862 55.4 62.5 20.25001 54.62724 62.5 18.72646 53.53391 58 18.72646 53.53391 62.5 32.31127 48.07153 64.5 30.40465 49.00365 64.5 31 46.4 64.5 31 46.4 76.5 31 46.4 64.5 30.40465 49.00365 64.5 32.5 46.4 64.5 30.40465 43.79634 64.5 30.40511 43.79825 76.5 30.40465 43.79634 64.5 31 46.4 64.5 31 46.4 76.5 30.86299 51.07585 64.5 28.7424 51.08954 64.5 30.40511 49.00175 76.5 28.7424 51.08954 64.5 31.75617 49.65515 64.5 29.67668 52.26232 64.5 26.33299 52.24942 64.5 28.73861 51.09243 76.5 26.33299 52.24942 64.5 23.66701 52.24942 64.5 26.33759 52.24808 76.5 23.66701 52.24942 64.5 19.13702 51.07585 64.5 21.25761 51.08954 64.5 23.66241 52.24808 76.5 21.25761 51.08954 64.5 20.32333 52.26232 64.5 18.24383 49.65515 64.5 19.59535 49.00365 64.5 21.26139 51.09243 76.5 19.59535 49.00365 64.5 17.5 46.4 64.5 19 46.4 64.5 19.59489 49.00175 76.5 19 46.4 64.5 17.68872 48.07153 64.5 17.68872 44.72847 64.5 19.59535 43.79634 64.5 19 46.4 76.5 19 46.4 64.5 19.59535 43.79634 64.5 19 46.4 76.5 19.13702 41.72415 64.5 21.25761 41.71046 64.5 19.59489 43.79825 76.5 21.25761 41.71046 64.5 18.24383 43.14485 64.5 20.32332 40.53768 64.5 23.66701 40.55058 64.5 21.26139 41.70757 76.5 23.66701 40.55058 64.5 26.33299 40.55058 64.5 23.66241 40.55192 76.5 26.33299 40.55058 64.5 30.86298 41.72415 64.5 28.7424 41.71046 64.5 26.33759 40.55192 76.5 28.7424 41.71046 64.5 29.67667 40.53767 64.5 31.75617 43.14485 64.5 28.73861 41.70757 76.5 32.31127 44.72847 64.5 15.5 46.4 62.5 17.5 46.4 64.5 17.68872 48.07153 64.5 15.68508 44.53391 62.5 17.68872 44.72847 64.5 17.5 46.4 64.5 15.54638 45.46239 62.5 15.5 46.4 62.5 15.68508 48.26609 62.5 18.24383 49.65515 64.5 15.54638 47.3376 62.5 17.20601 50.90041 63 19.13702 51.07585 64.5 18.72646 53.53391 62.5 20.32333 52.26232 64.5 28.25598 53.15576 64.5 21.74402 53.15577 64.5 20.25001 54.62724 62.5 21.74402 53.15577 64.5 26.67096 53.71129 64.5 23.32905 53.71129 64.5 21.95862 55.4 62.5 23.32905 53.71129 64.5 25 53.9 64.5 25 53.9 64.5 25.00048 55.4 63 26.67096 53.71129 64.5 28.04138 55.4 62.5 28.25598 53.15576 64.5 29.75 54.62724 62.5 29.67668 52.26232 64.5 31.27354 53.53391 62.5 30.86299 51.07585 64.5 32.79446 50.89959 63 31.75617 49.65515 64.5 32.31127 48.07153 64.5 34.31492 48.26609 62.5 32.5 46.4 64.5 34.5 46.4 62.5 32.5 46.4 64.5 32.31127 44.72847 64.5 34.45362 47.3376 62.5 34.5 46.4 62.5 34.31492 44.53391 62.5 31.75617 43.14485 64.5 34.45362 45.46239 62.5 32.79399 41.89959 63 30.86298 41.72415 64.5 31.27354 39.26609 62.5 29.67667 40.53767 64.5 21.74402 39.64423 64.5 28.25598 39.64423 64.5 29.75 38.17276 62.5 28.25598 39.64423 64.5 23.32904 39.08871 64.5 26.67095 39.08871 64.5 28.04138 37.4 62.5 26.67095 39.08871 64.5 25 38.9 64.5 25 38.9 64.5 24.99953 37.4 63 23.32904 39.08871 64.5 21.95862 37.4 62.5 21.74402 39.64423 64.5 20.25001 38.17276 62.5 20.32332 40.53768 64.5 18.72646 39.26609 62.5 19.13702 41.72415 64.5 17.20553 41.90041 63 18.24383 43.14485 64.5 19.59489 43.79825 76.5 30.40511 43.79825 76.5 31 46.4 76.5 19 46.4 76.5 30.40511 49.00175 76.5 21.26139 41.70757 76.5 28.73861 41.70757 76.5 23.66241 40.55192 76.5 26.33759 40.55192 76.5 19.59489 49.00175 76.5 28.73861 51.09243 76.5 21.26139 51.09243 76.5 26.33759 52.24808 76.5 23.66241 52.24808 76.5 -20.17238 90.05471 58 -20.17238 89.08293 58 -20 85.97177 58 -31.25827 85 58 -31.87307 88.08259 58 -32.18456 87.43577 58 -33.44577 87.80018 58 -33.1249 87.88626 58 -33.44577 89.08293 58 -33.44577 86.8284 58.5 -33.44577 86.8284 58 -32.74585 86.98815 58 -36.44685 86.8284 58.5 -33.44577 86.8284 58 -33.44577 86.8284 58.5 -33.1249 87.88626 58 -33.1249 88.99686 58 -33.44577 89.08293 58 -33.44577 89.08293 58.5 -33.1249 88.99686 58 -33.12493 88.99678 58.5 -33.44577 89.08293 58.5 -33.44577 89.08293 58 -33.1249 88.99686 58 -31.87316 88.08275 58.5 -31.87307 88.08259 58 -31.87307 88.80051 58 -32.18442 87.43608 58.5 -9.117303 122.7 51.70221 -9.621379 122.7 60.74265 0 122.7 61.5 0 122.7 52.5 9.621379 122.7 60.74265 -4.576581 122.7 52.30014 -17.95623 122.7 49.33368 -19.00415 122.7 58.49 -13.58857 122.7 50.71086 -26.24942 122.7 45.46656 -27.91989 122.7 54.79715 -22.18721 122.7 47.58115 -33.74585 122.7 40.21773 -36.14939 122.7 49.75405 -30.11208 122.7 43.00589 -43.00589 122.7 30.11208 -43.48699 122.7 43.48699 -40.21773 122.7 33.74585 -37.1231 122.7 37.1231 -49.33368 122.7 17.95623 -49.75405 122.7 36.14939 -47.58115 122.7 22.18721 -45.46656 122.7 26.24942 -52.30015 122.7 4.576309 -54.79715 122.7 27.91989 -51.70221 122.7 9.117303 -50.71086 122.7 13.58857 -58.49 122.7 -19.00415 -58.49 122.7 19.00415 -54.79715 122.7 -27.91989 -60.74265 122.7 -9.621379 -60.74265 122.7 9.621379 -61.5 122.7 0 -50.71086 122.7 -13.58857 -49.75405 122.7 -36.14939 -51.70221 122.7 -9.117303 -52.30015 122.7 -4.576309 -52.5 122.7 0 -45.46656 122.7 -26.24942 -43.48699 122.7 -43.48699 -47.58115 122.7 -22.18721 -49.33368 122.7 -17.95623 -37.1231 122.7 -37.1231 -36.14939 122.7 -49.75405 -40.21773 122.7 -33.74585 -43.00589 122.7 -30.11208 -30.11208 122.7 -43.00589 -27.91989 122.7 -54.79715 -33.74585 122.7 -40.21773 -22.18721 122.7 -47.58115 -19.00415 122.7 -58.49 -26.24942 122.7 -45.46656 -13.58857 122.7 -50.71086 -9.621379 122.7 -60.74265 -17.95623 122.7 -49.33368 0 122.7 -52.5 0 122.7 -61.5 -4.576581 122.7 -52.30014 -9.117303 122.7 -51.70221 9.117303 122.7 -51.70221 9.621379 122.7 -60.74265 4.576581 122.7 -52.30014 17.95623 122.7 -49.33368 19.00415 122.7 -58.49 13.58857 122.7 -50.71086 26.24942 122.7 -45.46656 27.91989 122.7 -54.79715 22.18721 122.7 -47.58115 33.74585 122.7 -40.21773 36.14939 122.7 -49.75405 30.11208 122.7 -43.00589 43.00589 122.7 -30.11208 43.48699 122.7 -43.48699 40.21773 122.7 -33.74585 37.1231 122.7 -37.1231 49.33368 122.7 -17.95623 49.75405 122.7 -36.14939 47.58115 122.7 -22.18721 45.46656 122.7 -26.24942 52.30015 122.7 -4.576309 54.79715 122.7 -27.91989 51.70221 122.7 -9.117303 50.71086 122.7 -13.58857 58.49 122.7 19.00415 58.49 122.7 -19.00415 54.79715 122.7 27.91989 60.74265 122.7 9.621379 60.74265 122.7 -9.621379 61.5 122.7 0 50.71086 122.7 13.58857 49.75405 122.7 36.14939 51.70221 122.7 9.117303 52.30015 122.7 4.576309 52.5 122.7 0 45.46656 122.7 26.24942 43.48699 122.7 43.48699 47.58115 122.7 22.18721 49.33368 122.7 17.95623 37.1231 122.7 37.1231 36.14939 122.7 49.75405 40.21773 122.7 33.74585 43.00589 122.7 30.11208 30.11208 122.7 43.00589 27.91989 122.7 54.79715 33.74585 122.7 40.21773 22.18721 122.7 47.58115 19.00415 122.7 58.49 26.24942 122.7 45.46656 13.58857 122.7 50.71086 17.95623 122.7 49.33368 4.576581 122.7 52.30014 9.117303 122.7 51.70221 -8.379238 110.4 -47.51679 -8.379238 110.4 47.51679 0 110.4 48.25 0 110.4 -48.25 8.379238 110.4 47.51679 -16.50263 110.4 -45.34 -16.50263 110.4 45.34 -24.12447 110.4 -41.78593 -24.12447 110.4 41.78593 -31.01404 110.4 -36.96201 -31.01404 110.4 36.96201 -36.96201 110.4 -31.01404 -36.96201 110.4 31.01404 -41.78593 110.4 -24.12447 -41.78593 110.4 24.12447 -45.34 110.4 -16.50263 -45.34 110.4 16.50263 -47.51679 110.4 -8.379238 -47.51679 110.4 8.379238 -48.25 110.4 0 8.379238 110.4 -47.51679 16.50263 110.4 45.34 16.50263 110.4 -45.34 24.12447 110.4 41.78593 24.12447 110.4 -41.78593 31.01404 110.4 36.96201 31.01404 110.4 -36.96201 36.96201 110.4 31.01404 36.96201 110.4 -31.01404 41.78593 110.4 24.12447 41.78593 110.4 -24.12447 45.34 110.4 16.50263 45.34 110.4 -16.50263 47.51679 110.4 8.379238 47.51679 110.4 -8.379238 48.25 110.4 0 0 10 -71.5 0 10 -75.75 -1.453902 10 -76.00644 2.626644 10 -71.91603 1.453902 10 -76.00644 -2.626644 10 -71.91603 -2.732141 10 -76.74463 -3.680695 10 -77.87535 -4.185343 10 -79.26214 -4.996175 10 -86.87664 -4.185343 10 -80.73786 -4.996175 10 -73.12336 -3.680695 10 -82.12467 -2.732141 10 -83.25537 -2.626644 10 -88.08398 -1.453902 10 -83.99356 0 10 -84.25 0 10 -88.5 1.453902 10 -83.99356 2.626644 10 -88.08398 2.732141 10 -83.25537 3.680695 10 -82.12467 4.185343 10 -80.73786 4.996175 10 -73.12336 4.185343 10 -79.26214 4.996175 10 -86.87664 3.680695 10 -77.87535 2.732141 10 -76.74463 -61.92081 10 -35.75 -65.60144 10 -37.875 -66.55046 10 -36.7441 -60.96778 10 -38.23275 -65.09656 10 -39.26234 -63.59442 10 -33.68327 -67.82888 10 -36.00621 -69.28237 10 -35.75009 -70.73571 10 -36.00645 -77.73548 10 -39.11151 -72.01371 10 -36.74432 -65.82477 10 -32.23486 -72.9624 10 -37.87476 -73.46734 10 -39.26158 -77.59629 10 -41.76725 -73.46751 10 -40.73766 -72.96264 10 -42.125 -76.64325 10 -44.25 -72.01361 10 -43.2559 -74.96965 10 -46.31673 -70.73519 10 -43.99379 -69.2817 10 -44.24991 -67.82837 10 -43.99354 -60.82859 10 -40.88849 -66.55036 10 -43.25568 -72.73931 10 -47.76514 -65.60167 10 -42.12524 -65.09674 10 -40.73842 -61.92081 10 35.75 -65.60144 10 37.875 -65.09656 10 39.26234 -63.59442 10 33.68327 -66.55046 10 36.7441 -60.96778 10 38.23275 -65.09674 10 40.73842 -65.60167 10 42.12524 -66.55036 10 43.25568 -72.73931 10 47.76514 -67.82837 10 43.99354 -60.82859 10 40.88849 -69.2817 10 44.24991 -70.73519 10 43.99379 -74.96965 10 46.31673 -72.01361 10 43.2559 -72.96264 10 42.125 -76.64325 10 44.25 -73.46751 10 40.73766 -77.59629 10 41.76725 -73.46734 10 39.26158 -72.9624 10 37.87476 -72.01371 10 36.74432 -65.82477 10 32.23486 -70.73571 10 36.00645 -77.73548 10 39.11151 -69.28237 10 35.75009 -67.82888 10 36.00621 61.92081 10 35.75 65.60144 10 37.875 66.55046 10 36.7441 60.96778 10 38.23275 65.09656 10 39.26234 63.59442 10 33.68327 67.82888 10 36.00621 69.28237 10 35.75009 70.73571 10 36.00645 77.73548 10 39.11151 72.01371 10 36.74432 65.82477 10 32.23486 72.9624 10 37.87476 73.46734 10 39.26158 77.59629 10 41.76725 73.46751 10 40.73766 72.96264 10 42.125 76.64325 10 44.25 72.01361 10 43.2559 74.96965 10 46.31673 70.73519 10 43.99379 69.2817 10 44.24991 67.82837 10 43.99354 60.82859 10 40.88849 66.55036 10 43.25568 72.73931 10 47.76514 65.60167 10 42.12524 65.09674 10 40.73842 61.92081 10 -35.75 65.60144 10 -37.875 65.09656 10 -39.26234 63.59442 10 -33.68327 66.55046 10 -36.7441 60.96778 10 -38.23275 65.09674 10 -40.73842 65.60167 10 -42.12524 66.55036 10 -43.25568 72.73931 10 -47.76514 67.82837 10 -43.99354 60.82859 10 -40.88849 69.2817 10 -44.24991 70.73519 10 -43.99379 74.96965 10 -46.31673 72.01361 10 -43.2559 72.96264 10 -42.125 76.64325 10 -44.25 73.46751 10 -40.73766 77.59629 10 -41.76725 73.46734 10 -39.26158 72.9624 10 -37.87476 72.01371 10 -36.74432 65.82477 10 -32.23486 70.73571 10 -36.00645 77.73548 10 -39.11151 69.28237 10 -35.75009 67.82888 10 -36.00621 6.876644 10 -75.00382 6.876644 10 -84.99618 8.08398 10 -77.37336 8.08398 10 -82.62664 8.5 10 -80 -6.876644 10 -84.99618 -6.876644 10 -75.00382 -8.08398 10 -82.62664 -8.08398 10 -77.37336 -8.5 10 -80 -61.51689 10 -43.45726 -70.17053 10 -48.45344 -62.9653 10 -45.68761 -67.5148 10 -48.31425 -65.03203 10 -47.36122 -77.04718 10 -36.54274 -68.39354 10 -31.54656 -75.59877 10 -34.31239 -71.04928 10 -31.68575 -73.53203 10 -32.63878 -68.39354 10 31.54656 -77.04718 10 36.54274 -71.04928 10 31.68575 -75.59877 10 34.31239 -73.53203 10 32.63878 -70.17053 10 48.45344 -61.51689 10 43.45726 -67.5148 10 48.31425 -62.9653 10 45.68761 -65.03203 10 47.36122 61.51689 10 43.45726 70.17053 10 48.45344 62.9653 10 45.68761 67.5148 10 48.31425 65.03203 10 47.36122 77.04718 10 36.54274 68.39354 10 31.54656 75.59877 10 34.31239 71.04928 10 31.68575 73.53203 10 32.63878 68.39354 10 -31.54656 77.04718 10 -36.54274 71.04928 10 -31.68575 75.59877 10 -34.31239 73.53203 10 -32.63878 70.17053 10 -48.45344 61.51689 10 -43.45726 67.5148 10 -48.31425 62.9653 10 -45.68761 65.03203 10 -47.36122 -41.99308 10 -74.12334 -40.625 10 -74.36457 -40.625 12.40344 -70.36457 -39.25692 10 -74.12334 -40.625 12.40344 -70.36457 -40.625 10 -74.36457 -43.19615 10 -73.42874 -44.0891 10 -72.36457 -44.56423 10 -71.05916 -44.56423 10 -69.66997 -44.0891 10 -68.36457 -43.19615 10 -67.30039 -41.99308 10 -66.6058 -40.625 10 -66.36457 -39.25692 10 -66.6058 -40.625 10 -66.36457 -38.05385 10 -67.30039 -37.1609 10 -68.36457 -36.68577 10 -69.66997 -36.68577 10 -71.05916 -37.1609 10 -72.36457 -38.05385 10 -73.42874 85.18923 10 0.694593 84.71411 10 2 81.25 12.40344 0 83.82115 10 3.064178 81.25 12.40344 0 84.71411 10 2 85.18923 10 -0.694593 84.71411 10 -2 83.82115 10 -3.064178 82.61808 10 -3.75877 81.25 10 -4 79.88192 10 -3.75877 78.67885 10 -3.064178 77.7859 10 -2 77.31077 10 -0.694593 77.7859 10 -2 77.31077 10 0.694593 77.7859 10 2 78.67885 10 3.064178 79.88192 10 3.75877 81.25 10 4 82.61808 10 3.75877 24.3517 7 69.87836 -24.28907 7 70.0765 -24.97726 7 69.65728 29.41893 7 67.90081 -30.02424 7 67.63539 19.15286 7 71.47837 -23.82219 7 70.73329 -23.65241 7 71.52102 -14.0033 7 72.83258 -23.33038 7 73.15058 -13.1977 7 72.81361 13.85052 7 72.69219 -15.27692 7 73.76522 -22.43872 7 74.55274 -14.73602 7 73.16793 -16.37053 7 75.01541 -21.09926 7 75.53565 -17.84374 7 75.78388 -19.49515 7 75.96544 8.473347 7 73.51322 -7.815748 7 73.58612 3.050352 7 73.93708 -2.389251 7 73.96141 34.32722 7 65.55636 -34.91125 7 65.24723 39.05011 7 62.85765 -39.60983 7 62.50645 43.56184 7 59.81946 -44.09431 7 59.42797 47.83634 7 56.45958 -48.34053 7 56.02841 48.54349 7 56.0732 49.34572 7 55.99727 54.86616 7 56.04032 50.11281 7 56.24409 56.04042 7 54.86601 -52.32561 7 52.32609 53.3452 7 56.70886 51.68506 7 56.77999 56.7089 7 53.34508 56.77998 7 51.685 -56.02798 7 48.34104 56.24409 7 50.11281 55.99727 7 49.34572 56.0732 7 48.54349 56.45958 7 47.83634 -59.42761 7 44.09479 59.81953 7 43.56174 -62.50617 7 39.61026 62.85776 7 39.04994 -65.24707 7 34.91157 65.55648 7 34.32698 -67.6353 7 30.02444 67.90092 7 29.41865 -69.65728 7 24.97726 69.87847 7 24.35139 -75.96543 7 19.49533 71.47846 7 19.15255 -75.53559 7 21.09942 -74.55265 7 22.43881 -73.15052 7 23.33041 -71.52102 7 23.65241 -70.73329 7 23.82219 -70.0765 7 24.28907 -72.83258 7 14.0033 72.69224 7 13.85023 -73.16793 7 14.73602 -73.76522 7 15.27692 -75.01544 7 16.37059 -75.78392 7 17.84387 -72.81361 7 13.1977 73.51325 7 8.473104 -73.58609 7 7.81595 73.93708 7 3.050184 -73.96138 7 2.389604 73.96139 7 -2.389348 -73.93708 7 -3.049872 73.5861 7 -7.815814 -73.51329 7 -8.472778 72.81361 7 -13.1977 -72.6923 7 -13.8499 72.83258 7 -14.0033 -71.47854 7 -19.15223 73.16793 7 -14.73602 73.76522 7 -15.27692 75.01544 7 -16.37059 75.78392 7 -17.84387 75.96543 7 -19.49533 -69.87857 7 -24.3511 75.53559 7 -21.09942 74.55265 7 -22.43881 73.15052 7 -23.33041 71.52102 7 -23.65241 70.73329 7 -23.82219 70.0765 7 -24.28907 69.65728 7 -24.97726 -67.90103 7 -29.41839 67.63539 7 -30.02425 -65.55659 7 -34.32678 65.24723 7 -34.91126 -62.85785 7 -39.0498 62.50643 7 -39.60985 -59.81959 7 -43.56166 59.42795 7 -44.09433 -56.45958 7 -47.83634 56.02838 7 -48.34056 -56.77998 7 -51.685 52.32606 7 -52.32564 -56.24409 7 -50.11281 -55.99727 7 -49.34572 -56.0732 7 -48.54349 -49.34572 7 -55.99727 48.341 7 -56.02801 -56.04042 7 -54.86601 -56.7089 7 -53.34508 -47.83634 7 -56.45958 44.09475 7 -59.42764 -48.54349 7 -56.0732 -43.56186 7 -59.81944 39.61022 7 -62.50619 -39.05015 7 -62.85763 34.91155 7 -65.24707 -34.32729 7 -65.55632 30.02442 7 -67.63533 -29.41902 7 -67.90076 24.97726 7 -69.65728 -24.35181 7 -69.87832 24.28907 7 -70.0765 -19.15298 7 -71.47834 23.82219 7 -70.73329 23.65241 7 -71.52102 14.0033 7 -72.83258 23.33038 7 -73.15058 13.1977 7 -72.81361 -13.85064 7 -72.69216 15.27692 7 -73.76522 22.43872 7 -74.55274 14.73602 7 -73.16793 16.37053 7 -75.01541 21.09926 7 -75.53565 17.84374 7 -75.78388 19.49515 7 -75.96544 -8.473461 7 -73.51322 7.8157 7 -73.58612 -3.050451 7 -73.93706 2.389175 7 -73.96141 -54.86616 7 -56.04032 -50.11281 7 -56.24409 -53.3452 7 -56.70886 -51.68506 7 -56.77999 -52.21591 39.4866 49 -51.5 38 48.00858 -51.5 39.65 49 -50.78409 39.4866 49 -51.5 39.65 49 -51.5 38 48.00858 -52.21591 39.4866 57.9 -52.21591 39.4866 49 -51.5 39.65 49 -51.5 39.65 57.9 -50.78409 39.4866 49 -51.5 39.65 57.9 -51.5 39.65 49 -52.21591 36.5134 49 -51.5 36.35 49 -50.78409 36.5134 49 -51.5 36.35 49 -52.79002 36.97124 49 -53.10863 37.63284 49 -53.10863 38.36716 49 -52.79002 39.02876 49 -50.20998 39.02876 49 -49.89137 38.36716 49 -49.89137 37.63284 49 -50.20998 36.97124 49 -51.5 36.35 57.9 -51.5 36.35 49 -52.21591 36.5134 49 -50.78409 36.5134 57.9 -51.5 36.35 49 -51.5 36.35 57.9 -50.78409 36.5134 49 -52.21591 36.5134 57.9 -52.79002 36.97124 49 -52.79002 36.97124 57.9 -53.10863 37.63284 49 -53.10863 37.63284 57.9 -53.10863 38.36716 49 -53.10863 38.36716 57.9 -52.79002 39.02876 49 -52.79002 39.02876 57.9 -56.43339 39.7956 57.9 -52.21591 39.4866 57.9 -51.5 39.65 57.9 -50.78409 39.4866 57.9 -46.56661 39.7956 57.9 -50.78409 39.4866 57.9 -56.43339 36.20439 57.9 -51.5 36.35 57.9 -52.21591 36.5134 57.9 -46.56661 36.20439 57.9 -50.78409 36.5134 57.9 -52.79002 36.97124 57.9 -53.10863 37.63284 57.9 -56.75 38 57.9 -53.10863 38.36716 57.9 -52.79002 39.02876 57.9 -50.20998 39.02876 49 -50.20998 39.02876 57.9 -49.89137 38.36716 49 -49.89137 38.36716 57.9 -49.89137 37.63284 49 -49.89137 37.63284 57.9 -50.20998 36.97124 49 -50.20998 36.97124 57.9 -50.20998 39.02876 57.9 -49.89137 38.36716 57.9 -46.25 38 57.9 -49.89137 37.63284 57.9 -50.20998 36.97124 57.9 -55.52173 34.62537 57.9 -47.47827 34.62537 57.9 -54.125 33.45336 57.9 -48.875 33.45336 57.9 -52.41165 32.82976 57.9 -50.58835 32.82976 57.9 -47.47827 41.37463 57.9 -55.52173 41.37463 57.9 -48.875 42.54663 57.9 -54.125 42.54663 57.9 -50.58835 43.17024 57.9 -52.41165 43.17024 57.9 -20 85.97177 58.5 -20 85.97177 58 -23.94784 85.97177 58 -31.25827 85 58 -33.44577 86.8284 58 -36.44685 86.8284 58 -31.87316 88.08275 58.5 -31.87307 88.80051 58 -31.87316 88.80036 58.5 -36.44685 85 58.5 -37.5 90.05471 58.5 -37.5 85 58.5 -33.44577 89.08293 58.5 -33.44577 90.05471 58.5 -36.44685 86.8284 58.5 -36.44685 87.80018 58.5 -36.44685 89.08293 58.5 -32.89055 88.7624 58.5 -32.74557 89.89479 58.5 -33.12493 88.99678 58.5 -32.18442 87.43608 58.5 -32.18442 89.44702 58.5 -32.74557 86.98833 58.5 -32.8044 88.44155 58.5 -31.87316 88.08275 58.5 -31.87316 88.80036 58.5 -33.44577 87.80018 58.5 -33.44577 86.8284 58.5 -33.12493 87.88633 58.5 -32.89055 88.12071 58.5 -30.13828 85 58.5 -30.13828 90.05471 58.5 -31.25827 90.05471 58.5 -31.25827 85 58.5 -28.17565 85.97177 58.5 -28.17565 90.05471 58.5 -29.23825 90.05471 58.5 -29.23825 85 58.5 -25.98325 85 58.5 -25.98325 85.97177 58.5 -20.17238 89.08293 58.5 -20.17238 90.05471 58.5 -25.41853 90.05471 58.5 -21.70046 89.08293 58.5 -25.41853 89.08293 58.5 -23.94784 85.97177 58.5 -20 85 58.5 -20 85.97177 58.5 -25.47593 85.97177 58.5 -25.47593 85 58.5 -32.8903 88.12107 58 -32.8045 88.44155 58 -32.8903 88.76204 58 -25.47593 85 58 -25.98325 85.97177 58 -25.98325 85 58 -31.25827 90.05471 58 -32.18456 89.44734 58 -31.87307 88.80051 58 -33.12493 88.99678 58.5 -33.1249 88.99686 58 -32.8903 88.76204 58 -20.17238 89.08293 58 -23.94784 85.97177 58 -20 85.97177 58 -25.47593 85.97177 58 -21.70046 89.08293 58 -25.41853 89.08293 58 -31.25827 85 58 -31.25827 90.05471 58 -31.87307 88.80051 58 -36.44685 86.8284 58.5 -36.44685 86.8284 58 -33.44577 86.8284 58 -36.44685 85 58.5 -36.44685 86.8284 58 -36.44685 86.8284 58.5 -37.5 85 58.5 -37.5 85 58 -36.44685 85 58 -37.5 90.05471 58.5 -37.5 90.05471 58 -37.5 85 58 -37.5 85 58.5 -36.44685 85 58.5 -36.44685 85 58 -36.44685 86.8284 58 -36.44685 85 58.5 -31.25827 85 58 -32.18456 87.43577 58 -32.74585 86.98815 58 -31.25827 85 58 -32.74585 86.98815 58 -33.44577 86.8284 58 -25.41853 89.08293 58 -25.41853 90.05471 58 -28.17565 90.05471 58 -25.47593 85.97177 58 -33.44577 87.80018 58 -36.44685 89.08293 58 -36.44685 87.80018 58 -36.44685 87.80018 58.5 -36.44685 87.80018 58 -36.44685 89.08293 58 -33.44577 87.80018 58.5 -33.44577 87.80018 58 -36.44685 87.80018 58 -36.44685 87.80018 58.5 -31.87316 88.80036 58.5 -31.87307 88.80051 58 -32.18456 89.44734 58 -34.31492 44.53391 58 -34.49993 46.4 58 -34.31492 48.26609 58 -34.31492 48.26609 62.5 -34.31492 48.26609 58 -34.49993 46.4 58 -31.27354 53.53391 58 -31.27354 53.53391 62.5 -31.27354 53.53391 58 -34.31492 48.26609 58 -32.79399 50.90041 63 -34.31492 48.26609 62.5 -34.5 46.4 62.5 -34.31492 44.53391 58 -34.45362 47.3376 62.5 -31.27354 39.26609 58 -34.31492 44.53391 62.5 -34.31492 44.53391 58 -31.27354 39.26609 58 -34.45362 45.46239 62.5 -34.31492 44.53391 62.5 -29.74696 54.629 58 -29.74696 38.171 58 -31.27354 39.26609 62.5 -31.27354 39.26609 58 -29.74696 38.171 58 -32.79446 41.90041 63 -31.27354 39.26609 62.5 -28.04138 55.4 58 -28.04138 37.4 58 -29.75 38.17276 62.5 -28.04138 37.4 58 -21.95862 55.4 58 -21.95862 37.4 58 -28.04138 37.4 62.5 -28.04138 37.4 58 -21.95862 37.4 58 -28.04138 37.4 62.5 -20.25304 54.629 58 -20.25304 38.171 58 -21.95862 37.4 62.5 -21.95862 37.4 58 -20.25304 38.171 58 -25.00048 37.4 63 -21.95862 37.4 62.5 -18.72646 53.53391 58 -18.72646 39.26609 58 -20.25001 38.17276 62.5 -18.72646 39.26609 58 -15.68508 48.26609 58 -15.68508 44.53391 58 -18.72646 39.26609 62.5 -18.72646 39.26609 58 -15.68508 44.53391 58 -18.72646 39.26609 62.5 -15.50007 46.4 58 -15.68508 44.53391 62.5 -15.68508 44.53391 58 -15.50007 46.4 58 -17.20601 41.89959 63 -15.68508 44.53391 62.5 -15.5 46.4 62.5 -15.68508 48.26609 58 -15.54638 45.46239 62.5 -15.68508 48.26609 62.5 -15.68508 48.26609 58 -18.72646 53.53391 58 -15.54638 47.3376 62.5 -15.68508 48.26609 62.5 -18.72646 53.53391 62.5 -18.72646 53.53391 58 -20.25304 54.629 58 -17.20553 50.89959 63 -18.72646 53.53391 62.5 -20.25001 54.62724 62.5 -21.95862 55.4 58 -21.95862 55.4 62.5 -21.95862 55.4 58 -28.04138 55.4 58 -21.95862 55.4 62.5 -28.04138 55.4 62.5 -28.04138 55.4 58 -29.74696 54.629 58 -24.99953 55.4 63 -28.04138 55.4 62.5 -29.75 54.62724 62.5 -31.27354 53.53391 58 -31.27354 53.53391 62.5 -17.68872 48.07153 64.5 -19.59535 49.00365 64.5 -19 46.4 64.5 -19 46.4 76.5 -19 46.4 64.5 -19.59535 49.00365 64.5 -17.5 46.4 64.5 -19.59535 43.79634 64.5 -19.59489 43.79825 76.5 -19.59535 43.79634 64.5 -19 46.4 64.5 -19 46.4 76.5 -19.13702 51.07585 64.5 -21.25761 51.08954 64.5 -19.59489 49.00175 76.5 -21.25761 51.08954 64.5 -18.24383 49.65515 64.5 -20.32332 52.26232 64.5 -23.66701 52.24942 64.5 -21.26139 51.09243 76.5 -23.66701 52.24942 64.5 -26.33299 52.24942 64.5 -23.66241 52.24808 76.5 -26.33299 52.24942 64.5 -30.86298 51.07585 64.5 -28.7424 51.08954 64.5 -26.33759 52.24808 76.5 -28.7424 51.08954 64.5 -29.67667 52.26232 64.5 -31.75617 49.65515 64.5 -30.40465 49.00365 64.5 -28.73861 51.09243 76.5 -30.40465 49.00365 64.5 -32.5 46.4 64.5 -31 46.4 64.5 -30.40511 49.00175 76.5 -31 46.4 64.5 -32.31127 48.07153 64.5 -32.31127 44.72847 64.5 -30.40465 43.79634 64.5 -31 46.4 76.5 -31 46.4 64.5 -30.40465 43.79634 64.5 -31 46.4 76.5 -30.86299 41.72415 64.5 -28.7424 41.71046 64.5 -30.40511 43.79825 76.5 -28.7424 41.71046 64.5 -31.75617 43.14485 64.5 -29.67668 40.53768 64.5 -26.33299 40.55058 64.5 -28.73861 41.70757 76.5 -26.33299 40.55058 64.5 -23.66701 40.55058 64.5 -26.33759 40.55192 76.5 -23.66701 40.55058 64.5 -19.13702 41.72415 64.5 -21.25761 41.71046 64.5 -23.66241 40.55192 76.5 -21.25761 41.71046 64.5 -20.32333 40.53767 64.5 -18.24383 43.14485 64.5 -21.26139 41.70757 76.5 -17.68872 44.72847 64.5 -34.5 46.4 62.5 -32.5 46.4 64.5 -32.31127 48.07153 64.5 -34.31492 44.53391 62.5 -32.31127 44.72847 64.5 -32.5 46.4 64.5 -34.45362 45.46239 62.5 -34.5 46.4 62.5 -34.31492 48.26609 62.5 -31.75617 49.65515 64.5 -34.45362 47.3376 62.5 -32.79399 50.90041 63 -30.86298 51.07585 64.5 -31.27354 53.53391 62.5 -29.67667 52.26232 64.5 -21.74402 53.15576 64.5 -28.25598 53.15577 64.5 -29.75 54.62724 62.5 -28.25598 53.15577 64.5 -23.32904 53.71129 64.5 -26.67095 53.71129 64.5 -28.04138 55.4 62.5 -26.67095 53.71129 64.5 -25 53.9 64.5 -25 53.9 64.5 -24.99953 55.4 63 -23.32904 53.71129 64.5 -21.95862 55.4 62.5 -21.74402 53.15576 64.5 -20.25001 54.62724 62.5 -20.32332 52.26232 64.5 -18.72646 53.53391 62.5 -19.13702 51.07585 64.5 -17.20553 50.89959 63 -18.24383 49.65515 64.5 -17.68872 48.07153 64.5 -15.68508 48.26609 62.5 -17.5 46.4 64.5 -15.5 46.4 62.5 -17.5 46.4 64.5 -17.68872 44.72847 64.5 -15.54638 47.3376 62.5 -15.5 46.4 62.5 -15.68508 44.53391 62.5 -18.24383 43.14485 64.5 -15.54638 45.46239 62.5 -17.20601 41.89959 63 -19.13702 41.72415 64.5 -18.72646 39.26609 62.5 -20.32333 40.53767 64.5 -28.25598 39.64423 64.5 -21.74402 39.64423 64.5 -20.25001 38.17276 62.5 -21.74402 39.64423 64.5 -26.67096 39.08871 64.5 -23.32905 39.08871 64.5 -21.95862 37.4 62.5 -23.32905 39.08871 64.5 -25 38.9 64.5 -25 38.9 64.5 -25.00048 37.4 63 -26.67096 39.08871 64.5 -28.04138 37.4 62.5 -28.25598 39.64423 64.5 -29.75 38.17276 62.5 -29.67668 40.53768 64.5 -31.27354 39.26609 62.5 -30.86299 41.72415 64.5 -32.79446 41.90041 63 -31.75617 43.14485 64.5 -30.40511 43.79825 76.5 -19.59489 43.79825 76.5 -19 46.4 76.5 -31 46.4 76.5 -19.59489 49.00175 76.5 -28.73861 41.70757 76.5 -21.26139 41.70757 76.5 -26.33759 40.55192 76.5 -23.66241 40.55192 76.5 -30.40511 49.00175 76.5 -21.26139 51.09243 76.5 -28.73861 51.09243 76.5 -23.66241 52.24808 76.5 -26.33759 52.24808 76.5 -32.18442 87.43608 58.5 -32.18456 87.43577 58 -31.87307 88.08259 58 -32.74557 86.98833 58.5 -32.89055 88.7624 58.5 -32.8903 88.76204 58 -32.8045 88.44155 58 -33.12493 88.99678 58.5 -32.8044 88.44155 58.5 -32.8903 88.12107 58 -32.89055 88.12071 58.5 -33.1249 87.88626 58 -33.12493 87.88633 58.5 -33.44577 87.80018 58 -33.44577 87.80018 58.5 -31.25827 90.05471 58.5 -31.25827 90.05471 58 -31.25827 85 58 -30.13828 90.05471 58.5 -30.13828 90.05471 58 -31.25827 90.05471 58 -31.25827 90.05471 58.5 -31.25827 85 58.5 -31.25827 85 58 -30.13828 85 58 -31.25827 85 58.5 -30.13828 85 58.5 -30.13828 85 58 -30.13828 90.05471 58 -31.25827 85 58.5 -30.13828 85 58 -30.13828 85 58.5 -28.17565 90.05471 58 -28.17565 85.97177 58 -25.98325 85.97177 58 -25.41853 89.08293 58.5 -25.41853 89.08293 58 -21.70046 89.08293 58 -25.41853 89.08293 58.5 -25.41853 90.05471 58.5 -25.41853 89.08293 58 -21.70046 89.08293 58.5 -21.70046 89.08293 58 -25.47593 85.97177 58 -21.70046 89.08293 58.5 -25.47593 85.97177 58.5 -25.47593 85.97177 58 -25.47593 85 58 -25.47593 85.97177 58.5 -25.47593 85 58.5 -25.47593 85 58 -20 85 58 -25.47593 85 58.5 -20 85 58.5 -20 85 58 -20 85.97177 58 -20 85 58.5 -29.23825 85 58 -30.13828 90.05471 58 -30.13828 85 58 -25.47593 85.97177 58 -28.17565 90.05471 58 -25.98325 85.97177 58 -25.47593 85 58 -31.25827 90.05471 58 -32.74585 89.89495 58 -32.18456 89.44734 58 -29.23825 85 58 -29.23825 90.05471 58 -30.13828 90.05471 58 -25.98325 85.97177 58.5 -25.98325 85.97177 58 -28.17565 85.97177 58 -25.98325 85 58.5 -25.98325 85 58 -25.98325 85.97177 58 -29.23825 85 58.5 -25.98325 85 58 -25.98325 85 58.5 -33.1249 87.88626 58 -32.8903 88.12107 58 -33.1249 88.99686 58 -30.13828 85 58.5 -30.13828 90.05471 58 -30.13828 90.05471 58.5 -29.23825 90.05471 58.5 -29.23825 90.05471 58 -29.23825 85 58 -28.17565 90.05471 58.5 -28.17565 90.05471 58 -29.23825 90.05471 58 -29.23825 90.05471 58.5 -29.23825 85 58.5 -29.23825 85 58 -25.98325 85 58 -29.23825 85 58.5 -31.25827 85 58 -31.87307 88.80051 58 -31.87307 88.08259 58 -28.17565 85.97177 58.5 -28.17565 90.05471 58 -28.17565 90.05471 58.5 -25.41853 90.05471 58.5 -25.41853 90.05471 58 -25.41853 89.08293 58 -20.17238 90.05471 58.5 -20.17238 90.05471 58 -25.41853 90.05471 58 -25.41853 90.05471 58.5 -25.98325 85 58.5 -25.98325 85.97177 58 -25.98325 85.97177 58.5 -28.17565 85.97177 58.5 -28.17565 85.97177 58 -28.17565 90.05471 58 -25.98325 85.97177 58.5 -28.17565 85.97177 58 -28.17565 85.97177 58.5 15.68508 75.53392 58 15.50007 77.4 58 15.68508 79.26609 58 15.68508 79.26609 62.5 15.68508 79.26609 58 15.50007 77.4 58 18.72646 84.53392 58 18.72646 84.53392 62.5 18.72646 84.53392 58 15.68508 79.26609 58 17.20601 81.90042 63 15.68508 79.26609 62.5 15.5 77.4 62.5 15.68508 75.53392 58 15.54638 78.33761 62.5 18.72646 70.26609 58 15.68508 75.53392 62.5 15.68508 75.53392 58 18.72646 70.26609 58 15.54638 76.4624 62.5 15.68508 75.53392 62.5 20.25304 85.629 58 20.25304 69.17102 58 18.72646 70.26609 62.5 18.72646 70.26609 58 20.25304 69.17102 58 17.20553 72.90042 63 18.72646 70.26609 62.5 21.95862 86.4 58 21.95862 68.4 58 20.25001 69.17276 62.5 21.95862 68.4 58 28.04138 86.4 58 28.04138 68.4 58 21.95862 68.4 62.5 21.95862 68.4 58 28.04138 68.4 58 21.95862 68.4 62.5 29.74696 85.629 58 29.74696 69.17102 58 28.04138 68.4 62.5 28.04138 68.4 58 29.74696 69.17102 58 24.99953 68.4 63 28.04138 68.4 62.5 31.27354 84.53392 58 31.27354 70.26609 58 29.75 69.17276 62.5 31.27354 70.26609 58 34.31492 79.26609 58 34.31492 75.53392 58 31.27354 70.26609 62.5 31.27354 70.26609 58 34.31492 75.53392 58 31.27354 70.26609 62.5 34.49993 77.4 58 34.31492 75.53392 62.5 34.31492 75.53392 58 34.49993 77.4 58 32.79399 72.89959 63 34.31492 75.53392 62.5 34.5 77.4 62.5 34.31492 79.26609 58 34.45362 76.4624 62.5 34.31492 79.26609 62.5 34.31492 79.26609 58 31.27354 84.53392 58 34.45362 78.33761 62.5 34.31492 79.26609 62.5 31.27354 84.53392 62.5 31.27354 84.53392 58 29.74696 85.629 58 32.79446 81.89959 63 31.27354 84.53392 62.5 29.75 85.62725 62.5 28.04138 86.4 58 28.04138 86.4 62.5 28.04138 86.4 58 21.95862 86.4 58 28.04138 86.4 62.5 21.95862 86.4 62.5 21.95862 86.4 58 20.25304 85.629 58 25.00048 86.4 63 21.95862 86.4 62.5 20.25001 85.62725 62.5 18.72646 84.53392 58 18.72646 84.53392 62.5 32.31127 79.07154 64.5 30.40465 80.00366 64.5 31 77.4 64.5 31 77.4 76.5 31 77.4 64.5 30.40465 80.00366 64.5 32.5 77.4 64.5 30.40465 74.79634 64.5 30.40511 74.79825 76.5 30.40465 74.79634 64.5 31 77.4 64.5 31 77.4 76.5 30.86299 82.07585 64.5 28.7424 82.08954 64.5 30.40511 80.00175 76.5 28.7424 82.08954 64.5 31.75617 80.65515 64.5 29.67668 83.26232 64.5 26.33299 83.24942 64.5 28.73861 82.09243 76.5 26.33299 83.24942 64.5 23.66701 83.24942 64.5 26.33759 83.24808 76.5 23.66701 83.24942 64.5 19.13702 82.07585 64.5 21.25761 82.08954 64.5 23.66241 83.24808 76.5 21.25761 82.08954 64.5 20.32333 83.26233 64.5 18.24383 80.65515 64.5 19.59535 80.00366 64.5 21.26139 82.09243 76.5 19.59535 80.00366 64.5 17.5 77.4 64.5 19 77.4 64.5 19.59489 80.00175 76.5 19 77.4 64.5 17.68872 79.07154 64.5 17.68872 75.72847 64.5 19.59535 74.79634 64.5 19 77.4 76.5 19 77.4 64.5 19.59535 74.79634 64.5 19 77.4 76.5 19.13702 72.72415 64.5 21.25761 72.71046 64.5 19.59489 74.79825 76.5 21.25761 72.71046 64.5 18.24383 74.14485 64.5 20.32332 71.53768 64.5 23.66701 71.55059 64.5 21.26139 72.70758 76.5 23.66701 71.55059 64.5 26.33299 71.55059 64.5 23.66241 71.55194 76.5 26.33299 71.55059 64.5 30.86298 72.72415 64.5 28.7424 72.71046 64.5 26.33759 71.55194 76.5 28.7424 72.71046 64.5 29.67667 71.53768 64.5 31.75617 74.14485 64.5 28.73861 72.70758 76.5 32.31127 75.72847 64.5 15.5 77.4 62.5 17.5 77.4 64.5 17.68872 79.07154 64.5 15.68508 75.53392 62.5 17.68872 75.72847 64.5 17.5 77.4 64.5 15.54638 76.4624 62.5 15.5 77.4 62.5 15.68508 79.26609 62.5 18.24383 80.65515 64.5 15.54638 78.33761 62.5 17.20601 81.90042 63 19.13702 82.07585 64.5 18.72646 84.53392 62.5 20.32333 83.26233 64.5 28.25598 84.15577 64.5 21.74402 84.15577 64.5 20.25001 85.62725 62.5 21.74402 84.15577 64.5 26.67096 84.71129 64.5 23.32905 84.71129 64.5 21.95862 86.4 62.5 23.32905 84.71129 64.5 25 84.9 64.5 25 84.9 64.5 25.00048 86.4 63 26.67096 84.71129 64.5 28.04138 86.4 62.5 28.25598 84.15577 64.5 29.75 85.62725 62.5 29.67668 83.26232 64.5 31.27354 84.53392 62.5 30.86299 82.07585 64.5 32.79446 81.89959 63 31.75617 80.65515 64.5 32.31127 79.07154 64.5 34.31492 79.26609 62.5 32.5 77.4 64.5 34.5 77.4 62.5 32.5 77.4 64.5 32.31127 75.72847 64.5 34.45362 78.33761 62.5 34.5 77.4 62.5 34.31492 75.53392 62.5 31.75617 74.14485 64.5 34.45362 76.4624 62.5 32.79399 72.89959 63 30.86298 72.72415 64.5 31.27354 70.26609 62.5 29.67667 71.53768 64.5 21.74402 70.64424 64.5 28.25598 70.64424 64.5 29.75 69.17276 62.5 28.25598 70.64424 64.5 23.32904 70.08872 64.5 26.67095 70.08871 64.5 28.04138 68.4 62.5 26.67095 70.08871 64.5 25 69.9 64.5 25 69.9 64.5 24.99953 68.4 63 23.32904 70.08872 64.5 21.95862 68.4 62.5 21.74402 70.64424 64.5 20.25001 69.17276 62.5 20.32332 71.53768 64.5 18.72646 70.26609 62.5 19.13702 72.72415 64.5 17.20553 72.90042 63 18.24383 74.14485 64.5 19.59489 74.79825 76.5 30.40511 74.79825 76.5 31 77.4 76.5 19 77.4 76.5 30.40511 80.00175 76.5 21.26139 72.70758 76.5 28.73861 72.70758 76.5 23.66241 71.55194 76.5 26.33759 71.55194 76.5 19.59489 80.00175 76.5 28.73861 82.09243 76.5 21.26139 82.09243 76.5 26.33759 83.24808 76.5 23.66241 83.24808 76.5 -33.44577 87.80018 58 -33.44577 89.08293 58 -36.44685 89.08293 58 -32.74557 86.98833 58.5 -32.74585 86.98815 58 -32.18456 87.43577 58 -33.44577 86.8284 58.5 + + + + + + + + + + 0 -0.8660238 0.5000029 0.4938971 0.1724047 0.8522572 0.4846759 0.1709077 0.8578345 0.5879557 0.1721597 0.7903602 -5.5399e-6 -0.8660327 0.4999873 2.86058e-6 -0.8660214 0.500007 2.93474e-6 -0.8660196 0.50001 -1.99472e-6 -0.8660287 0.4999946 0.553528 0.1723423 0.8148036 0.6140754 0.1745999 0.7696924 0.6738069 0.1728923 0.7183958 0 0 1 0 -0.8660258 0.4999995 4.35738e-7 -0.8660227 0.5000047 -1.69633e-7 -0.8660241 0.5000024 0 -0.866027 0.4999973 0.4269962 0.1738687 0.8873805 0.3687059 0.169963 0.9138756 0.2907833 0.1738352 0.9408647 0.2480635 0.1703605 0.9536467 0.3596646 0.1736217 0.9167862 0.1482912 0.1727674 0.9737357 0.1242424 0.171913 0.977246 0.2177251 0.1727701 0.9605969 0.0416277 0.1673043 0.9850262 0.06137341 0.1733167 0.982952 0.0706824 0.1702055 0.9828704 -0.07309389 0.1738688 0.9820525 -0.05856639 0.1695039 0.9837878 -0.03683614 0.1735298 0.9841396 -0.1254957 0.1703897 0.9773527 0 1 0 0 1 5.22092e-6 0 1 2.78484e-6 0.6698419 0.1741747 0.7217861 0 1 2.80769e-6 0.7285062 0.1732605 0.6627666 0.7218454 0.1740522 0.6698098 0 1 -2.87797e-6 0.7563231 0.1724021 0.6310729 0.7699418 0.1740212 0.613927 0 1 2.74477e-6 0 1 2.8196e-6 0.8021505 0.1761904 0.5705361 0.8136528 0.1740227 0.5546939 0.7999897 0.176063 0.5736011 0.7979041 0.1756097 0.5766372 0.7958396 0.1751781 0.5796137 0.7938042 0.174875 0.5824893 0.7918056 0.174597 0.5852862 0.7898617 0.1743549 0.5879787 0.7880064 0.1741732 0.5905165 0.7862008 0.17405 0.5929543 0.7845349 0.1739307 0.5951918 0.7827257 0.1738373 0.5975962 0.7801617 0.1736846 0.6009837 0.7692586 0.1731945 0.6150162 0.7734584 0.1733208 0.6096901 0.8506338 0.1774696 0.4949008 0.8527851 0.1739262 0.4924504 0 1 2.7216e-6 0.84765 0.1817744 0.4984453 0.8439691 0.1798782 0.5053316 0.8406013 0.1783565 0.5114474 0.8375985 0.1771942 0.5167505 0.8348184 0.1762781 0.5215403 0.832179 0.1755794 0.5259754 0.8296312 0.1749965 0.5301778 0.8271318 0.1745699 0.5342084 0.8246688 0.1742056 0.5381208 0.8221471 0.1739574 0.5420452 0.8195453 0.1737791 0.5460278 0.8168981 0.1736828 0.5500108 0.8140976 0.1736233 0.5541662 0.8868893 0.1740512 0.4279409 0.8870807 0.1742665 0.4274566 0.9149008 0.192911 0.3546011 0.9018666 0.1871119 0.3893917 0.8929532 0.1834797 0.4110594 0.886304 0.1809475 0.4262902 0.8809827 0.1790593 0.4379582 0.8764619 0.1776241 0.4475089 0.8725364 0.176491 0.4555561 0.8689829 0.1755789 0.4626457 0.8655861 0.1748751 0.469233 0.8623455 0.1743246 0.4753643 0.8591163 0.173929 0.4813188 0.855926 0.1737121 0.4870471 0.9066131 0.1740528 0.3843935 0.916759 0.1741411 0.3594828 0.9185135 0.176494 0.353812 0.9087631 0.1753619 0.3786793 0.9035781 0.1747522 0.3911629 0.8998599 0.1743869 0.399802 0.89682 0.1740841 0.4067049 0.8941106 0.1738963 0.4127063 0.8915941 0.173747 0.418177 0.8892645 0.1736535 0.4231469 0 1 -5.18145e-7 0.9407093 0.1718509 0.2924609 0.9414033 0.1727401 0.2896907 0 1 -7.98783e-7 0.9231631 0.1726448 0.3434585 0.9105904 0.1736826 0.375046 0.9089162 0.1738361 0.3790152 0.9077498 0.1739264 0.3817591 0 1 -9.36554e-7 0.9686481 0.1731047 0.1782014 0.960068 0.1728903 0.2199507 0 1 1.00213e-6 0.9738693 0.173624 0.1464008 0.9831733 0.1726467 0.05969536 0.9820494 0.1735631 0.07385665 0.9847584 0.1739281 0 0.9831287 0.1728578 -0.05981659 0.9821044 0.1731348 -0.07413083 0.9687598 0.1728892 -0.1778028 0.9739775 0.1732248 -0.1461546 0.9600419 0.1738067 -0.2193413 0.9406956 0.1713962 -0.2927714 0.9410827 0.1736223 -0.2902048 0.9167074 0.1738377 -0.3597612 0.8951727 0.1762146 -0.4094075 0.8872203 0.1740198 -0.4272672 0.8967523 0.1760665 -0.4059999 0.8983404 0.1756089 -0.4026738 0.8998835 0.1751791 -0.3994023 0.9013611 0.1748458 -0.3962034 0.9027858 0.1745998 -0.3930556 0.9041398 0.1743578 -0.390039 0.9054206 0.1741745 -0.3871392 0.9066131 0.1740528 -0.3843935 0.9077339 0.1739292 -0.3817957 0.9089052 0.1738093 -0.3790538 0.9105852 0.1736875 -0.3750563 0.9172185 0.1731649 -0.3587815 0.9232351 0.1725553 -0.34331 0 1 7.02416e-7 0.8539162 0.1774668 -0.4892165 0.852887 0.1739283 -0.4922732 0.8554918 0.181774 -0.4848631 0.8596103 0.1798815 -0.4782395 0.8632314 0.1783533 -0.4722518 0.8663312 0.1771971 -0.4669814 0.8691016 0.1762802 -0.4621556 0.8716118 0.1755797 -0.4576733 0.8739592 0.1749994 -0.4533991 0.8762047 0.1745695 -0.4492113 0.8783762 0.1742042 -0.4450936 0.8805029 0.1739581 -0.4409686 0.8826599 0.1737791 -0.4367062 0.8847945 0.1736872 -0.4324021 0.8869748 0.1736228 -0.4279379 0.8140681 0.1740508 -0.5540754 0.8137455 0.1742672 -0.554481 0 1 -2.7216e-6 0.76442 0.1929132 -0.6151801 0.7881519 0.1871727 -0.5863301 0.802472 0.1834814 -0.5677793 0.812332 0.1809489 -0.5544134 0.8197336 0.179084 -0.5440273 0.8257898 0.177622 -0.5352771 0.8308054 0.176495 -0.527837 0.8351516 0.1756061 -0.5212334 0.8391557 0.1748749 -0.5150114 0.8428539 0.1743267 -0.5091243 0.8463932 0.1739298 -0.5033558 0.8497512 0.1737163 -0.4977406 0.7861892 0.1740542 -0.5929686 0.7696962 0.174143 -0.6142004 0.7656748 0.1764946 -0.6185401 0.7823912 0.175333 -0.5975972 0.7905665 0.1747522 -0.5869126 0.7961604 0.174388 -0.5794114 0.8006381 0.1740809 -0.5733014 0.804503 0.1738954 -0.5679221 0.8079714 0.1737471 -0.5630224 0.8111044 0.1736533 -0.5585289 0.7236443 0.1718544 -0.6684348 0.721568 0.1727393 -0.6704482 0 1 -2.74477e-6 0.7590215 0.1726492 -0.6277568 0.7801093 0.1736865 -0.6010513 0.7827298 0.1738077 -0.5975994 0.7845089 0.1739317 -0.5952257 0 1 -1.56504e-6 0.6386691 0.1731032 -0.749758 0.6705085 0.1728916 -0.7214756 0.6137398 0.1736233 -0.7701809 0.5432964 0.172645 -0.8215978 0.5549906 0.1735624 -0.8135488 0.4923912 0.173927 -0.852819 0.4397488 0.1728598 -0.8813288 0.4268197 0.1731389 -0.887608 0.3303723 0.1728923 -0.9278807 0.3603708 0.173227 -0.9165835 0.2900558 0.1738076 -0.9410943 0 1 5.09709e-6 0.2167794 0.171397 -0.9610566 0.2191902 0.1736248 -0.9601094 0 1 -5.94659e-6 0.1468273 0.1738062 -0.9737727 0.09302294 0.1762187 -0.9799458 0.07358199 0.174021 -0.981989 0.09677678 0.1760661 -0.9796097 0.1004379 0.1756062 -0.9793236 0.10407 0.1751794 -0.9790208 0.1075173 0.1748719 -0.9787032 0.1109993 0.1746019 -0.9783627 0.1142652 0.1743583 -0.97803 0.1174083 0.1741744 -0.9776905 0.1203985 0.1740513 -0.9773488 0.1232672 0.1739292 -0.9770128 0.1261343 0.1738352 -0.9766635 0.1305589 0.1736817 -0.9761092 0.1478974 0.1731676 -0.9737246 0.1642536 0.1725548 -0.9712083 0.009338796 0.1812835 -0.9833866 0.03683614 0.1735298 -0.9841396 0 1 -5.22092e-6 0.007812917 0.1818039 -0.9833039 0.01562565 0.1798787 -0.9835647 0.02264547 0.1783561 -0.9837055 0.02874904 0.1771944 -0.983756 0.03424215 0.1762769 -0.9837449 0.03943002 0.1755737 -0.9836764 0.04428333 0.174997 -0.9835726 0.04904443 0.1745702 -0.9834225 0.05365324 0.1742053 -0.9832467 0.05838304 0.1739589 -0.9830207 0.06305176 0.1737738 -0.9827651 0.06787371 0.1736823 -0.9824601 0.07288008 0.1736243 -0.9821116 -0.006164729 0.1737124 -0.9847771 -0.0366224 0.1741092 -0.9840452 -0.002807676 0.173621 -0.9848086 -0.1504919 0.1929141 -0.9696063 -0.07281833 0.1740499 -0.9820409 -0.0733686 0.1742658 -0.9819616 -0.1136549 0.1871154 -0.975741 -0.0904268 0.1834782 -0.9788559 -0.07385504 0.1809449 -0.9807163 -0.06122195 0.1790574 -0.9819319 -0.05066108 0.1776189 -0.9827945 -0.04175007 0.1764918 -0.9834163 -0.03375452 0.1755785 -0.9838866 -0.02642941 0.1748735 -0.9842361 -0.01950186 0.1743268 -0.9844947 -0.01272654 0.1739296 -0.9846758 -0.07837384 0.02615511 -0.9965808 -0.01748752 0.02615493 -0.9995049 -0.03222823 0.02621597 -0.9991367 0.1563193 0.026277 -0.987357 0.03201431 0.02682608 -0.9991274 0.01800632 0.02694845 -0.9994747 0.0784043 0.02609407 -0.9965801 -0.06582945 0.02633786 -0.9974833 -0.100804 0.026582 -0.9945512 -0.1356561 0.02667343 -0.9903969 -0.1563491 0.02627688 -0.9873523 -0.1713019 0.02615457 -0.9848714 -0.2057932 0.0262773 -0.9782427 -0.2398503 0.02646011 -0.9704493 -0.2735754 0.02664333 -0.9614815 -0.3088847 0.02636855 -0.9507339 -0.3091253 0.02615463 -0.9506617 -0.3437713 0.0262162 -0.9386875 -0.3783749 0.02639895 -0.925276 -0.4131435 0.02661305 -0.910277 -0.4538455 0.02630722 -0.8906921 -0.4508654 0.02615523 -0.8922086 -0.4876667 0.02621597 -0.8726363 -0.5245609 0.02645999 -0.8509618 -0.5614259 0.02679556 -0.8270931 -0.5875898 0.02624666 -0.8087332 -0.60293 0.02615463 -0.7973654 -0.641938 0.02636843 -0.7663031 -0.6806094 0.02679586 -0.7321563 -0.7067993 0.02639925 -0.7069214 -0.7240318 0.02615469 -0.6892707 -0.7641137 0.02646028 -0.6445388 -0.8087267 0.0265516 -0.587585 -0.8066502 0.02609378 -0.5904529 -0.8466798 0.0263071 -0.5314523 -0.8906979 0.02658206 -0.453818 -0.8867861 0.02606308 -0.4614449 -0.9229345 0.02633816 -0.384055 -0.9507054 0.02667379 -0.3089464 -0.9567142 0.02594125 -0.2898709 -0.9873521 0.02664309 -0.156288 -0.9828739 0.02594137 -0.1824443 0.1617811 0.1716387 -0.9717855 -0.9996516 0.02639895 6.10381e-5 -0.9980518 0.02609342 -0.0566731 0.1588803 0.1698976 -0.9725698 -0.9873594 0.02636861 0.1562891 -0.9949853 0.02584969 0.09662359 0.1572033 0.1682512 -0.9731284 -0.9508332 0.02704018 0.308521 -0.9566618 0.02438497 0.2901787 0.1978272 0.3747181 -0.9057874 0.1413325 0.2542214 -0.9567638 0.2135387 0.2763156 -0.9370437 0.1403268 0.2964321 -0.9446886 -0.8907449 0.02795594 0.4536432 -0.9040143 0.02581936 0.4267219 0.3086124 0.3752363 -0.8740459 0.3243299 0.2760176 -0.9047787 0.4138982 0.3753833 -0.8293225 0.4303833 0.2754977 -0.8595762 0.5291994 0.275495 -0.8025276 0.5112572 0.3753858 -0.7731117 0.6214057 0.2760176 -0.7332594 0.6026345 0.375235 -0.7042943 0.704728 0.2763244 -0.653455 0.7628313 0.1699012 -0.6238766 0.7641472 0.1682235 -0.6227199 0.6854968 0.3747175 -0.6242444 0.7579042 0.2542217 -0.6007934 0.7606914 0.17164 -0.6260101 0.758585 0.172708 -0.6282681 0.2082017 0.02703994 0.9777121 0.2268205 0.02438503 0.9736313 0.4132277 0.02584958 0.9102608 0.7479479 0.2964385 -0.5938841 0.05200433 0.02722293 0.9982758 0.0823397 0.0263682 0.9962555 0.3582915 0.02639877 0.9332365 0.5474272 0.02609407 0.8364464 0.4997505 0.02642953 0.8657662 0.6488597 0.02591043 0.7604668 0.6290288 0.02667367 0.7769243 0.7289595 0.02594161 0.6840652 0.742949 0.02661234 0.6688188 0.7942627 0.02649068 0.6069968 0.8427007 0.0260635 0.5377512 0.8383892 0.02645999 0.5444296 0.8841629 0.02661246 0.4664202 0.9144361 0.02612411 0.4038864 0.9132088 0.02649015 0.4066301 0.9399843 0.02639889 0.340195 0.9588081 0.02615457 0.282848 0.9655918 0.0264905 0.2587099 0.9735786 0.02618503 0.2268459 0.9846912 0.02652084 0.172279 0.9919531 0.02615457 0.1238759 0.9941853 0.02636831 0.1044053 0.9967762 0.02618515 0.07583934 0.9992257 0.02642953 0.02914571 0.9995122 0.02682656 -0.01599216 0.9981272 0.02621591 -0.05527007 0.9982852 0.02627706 -0.05230998 0.9950664 0.02624619 -0.09567654 0.9905024 0.02646017 -0.1349256 0.98456 0.0267961 -0.1729847 0.9779227 0.02621585 -0.2073161 0.9778172 0.02630704 -0.2078014 0.9697804 0.02621603 -0.2425672 0.9604399 0.02636855 -0.2772366 0.9499006 0.02664297 -0.3114148 0.9386203 0.02624654 -0.3439522 0.9332395 0.02627682 -0.3582927 0.9258657 0.02618557 -0.3769446 0.9117801 0.02627664 -0.4098372 0.8966796 0.02652102 -0.441885 0.881268 0.0268262 -0.471855 0.8745716 0.02694791 -0.4841471 0.8238749 0.02615523 -0.5661679 0.8568359 0.02615523 -0.5149255 0.8491355 0.02621597 -0.5275242 0.9022816 0.02609425 -0.4303569 0.8309249 0.02633833 -0.5557609 0.8109059 0.02658253 -0.5845725 0.7898645 0.02667367 -0.6127012 0.7768905 0.02627676 -0.6290872 0.7672801 0.02615481 -0.6407786 0.74427 0.02627694 -0.6673618 0.7204892 0.02645981 -0.6929612 0.6959074 0.02664357 -0.7176373 0.6688873 0.02636849 -0.7428961 0.668682 0.02615517 -0.7430885 0.6410594 0.02621608 -0.7670434 0.612054 0.02639871 -0.7903752 0.5817856 0.02661263 -0.8129067 0.5444103 0.02630794 -0.8384065 0.5472423 0.02615505 -0.8365656 0.5118933 0.02621567 -0.858649 0.4746617 0.02645993 -0.8797706 0.435541 0.02679592 -0.8997701 0.4065818 0.02624678 -0.9132373 0.3890905 0.02615499 -0.9208282 0.3426361 0.02636831 -0.9390982 0.2937422 0.02679538 -0.9555091 0.2588036 0.02639913 -0.9655692 0.2349053 0.02615481 -0.9716663 0.1760935 0.02645975 -0.9840178 0.1044985 0.0265519 -0.9941706 0.1080053 0.02609336 -0.9938079 0.03689724 0.02630722 -0.9989728 -0.05230957 0.02658206 -0.9982771 -0.04373365 0.0260632 -0.9987033 -0.1288807 0.02633768 -0.9913103 -0.2077764 0.02667397 -0.9778127 -0.2272728 0.02594089 -0.9734857 -0.3582994 0.02664351 -0.9332265 -0.3334184 0.02594101 -0.9424221 0.9224858 0.1716366 -0.3457758 -0.4999049 0.02639913 -0.8656778 -0.44994 0.0260936 -0.8926776 0.9217126 0.1699008 -0.3486827 -0.6290339 0.02636867 -0.7769306 -0.5811768 0.02584969 -0.8133667 0.9213584 0.1682494 -0.3504153 -0.7426232 0.02703994 -0.6691635 -0.729622 0.02438479 -0.6834159 0.8833571 0.3747187 -0.2815426 0.8992596 0.2542281 -0.3559499 0.9182767 0.2763162 -0.2835796 0.8883057 0.2964071 -0.3507931 -0.83824 0.02795553 -0.5445845 -0.8215499 0.0258193 -0.5695518 0.9112628 0.3752294 -0.1697154 0.945731 0.2760162 -0.1714877 0.9251617 0.3753872 -0.05621647 0.9596168 0.2754667 -0.05704045 0.9596168 0.2754667 0.05704045 0.9251617 0.3753872 0.05621647 0.945731 0.2760162 0.1714877 0.9112628 0.3752294 0.1697154 0.9182767 0.2763162 0.2835796 0.9217126 0.1699008 0.3486827 0.9213584 0.1682494 0.3504153 0.8833571 0.3747187 0.2815426 0.8992596 0.2542281 0.3559499 0.9224812 0.1716414 0.3457855 0.9233977 0.1727098 0.3427949 -0.7426232 0.02703994 0.6691635 -0.7297694 0.02438461 0.6832584 -0.5816934 0.02584964 0.8129974 0.8883057 0.2964071 0.3507931 -0.8385196 0.02722322 0.5441909 -0.8216007 0.02636837 0.5694532 -0.6290519 0.02639865 0.7769151 -0.4506468 0.0260939 0.8923209 -0.4999046 0.02642959 0.8656772 -0.3341559 0.02591085 0.9421616 -0.3582991 0.02667403 0.9332258 -0.2279432 0.02594077 0.9733289 -0.2077413 0.02661234 0.9778218 -0.1285461 0.0264905 0.9913497 -0.04434424 0.02606326 0.9986764 -0.05230975 0.02646005 0.9982803 0.03811824 0.02661257 0.9989188 0.1074557 0.02612382 0.9938666 0.1044352 0.02649027 0.9941789 0.1753628 0.02639901 0.98415 0.2344161 0.02615469 0.9717845 0.2587383 0.02649027 0.9655842 0.2902662 0.02618527 0.9565877 0.3431245 0.02652096 0.9389155 0.3886882 0.02615463 0.9209982 0.4066427 0.02636891 0.9132066 0.4326958 0.02618509 0.9011597 0.4743255 0.02642935 0.8799528 0.5136373 0.02682632 0.857588 0.5469083 0.02621614 0.8367819 0.5444537 0.02627658 0.8383793 0.5803854 0.02624654 0.813919 0.6120869 0.02645987 0.7903478 0.6421284 0.02679604 0.7661287 0.6684887 0.02621579 0.7432603 0.6688883 0.02630746 0.7428973 0.6949542 0.02621603 0.718576 0.7203414 0.02636843 0.6931183 0.7446382 0.02664327 0.6669363 0.7671806 0.02624613 0.6408939 0.7769175 0.02627664 0.6290538 0.7893806 0.02618551 0.6133456 0.8108338 0.026277 0.5846865 0.8310292 0.0265209 0.5555962 0.8492651 0.02682656 0.5272848 0.8565778 0.02694827 0.5153139 0.9022564 0.02615451 0.430406 0.8743588 0.02615445 0.4845748 0.8814179 0.02621573 0.4716094 0.823862 0.02609378 0.5661896 0.8967745 0.02633798 0.4417035 0.9117118 0.02658253 0.4099696 0.9255436 0.02667337 0.3777006 0.9332497 0.02627706 0.3582661 0.9385795 0.02615469 0.3440705 0.9500901 0.02627694 0.3108675 0.9603677 0.02645981 0.2774775 0.969447 0.02664333 0.2438495 0.9778082 0.02636867 0.2078365 0.9778721 0.02615511 0.2075624 0.9848164 0.02621579 0.1716081 0.9905081 0.02639925 0.1348959 0.9948937 0.02661269 0.09735608 0.9982859 0.02630758 0.05227953 0.9981104 0.02615439 0.05560481 0.9995586 0.02621579 0.0139777 0.9992347 0.02646028 -0.02881026 0.9969964 0.02679568 -0.07266587 0.9941821 0.02624619 -0.104466 0.9920102 0.02615451 -0.1234176 0.9846042 0.02636837 -0.1727986 0.9743731 0.02679544 -0.2233364 0.9656115 0.02639865 -0.258646 0.9589504 0.02615511 -0.2823656 0.9402355 0.02646011 -0.3394956 0.9132413 0.02655214 -0.406553 0.9146633 0.02609395 -0.4033735 0.8836023 0.02630782 -0.4674986 0.8383634 0.02658224 -0.5444632 0.8430191 0.02606296 -0.5372519 0.7940546 0.02633821 -0.6072756 0.742919 0.02667337 -0.6688498 0.7294173 0.02594161 -0.683577 0.6290293 0.02664315 -0.7769249 0.6494507 0.02594137 -0.7599611 0.7755948 0.1727715 0.6071266 0.4997509 0.02639901 -0.8657668 0.548093 0.02609384 -0.8360104 0.7775636 0.1718831 0.6048564 0.3582918 0.02636831 -0.9332372 0.4138118 0.02584987 -0.9099954 0.7790641 0.170755 0.6032429 0.2082017 0.02703994 -0.9777121 0.2270299 0.02438455 -0.9735826 0.7718538 0.3263082 0.5456781 0.7662438 0.2466556 0.5933225 0.7476075 0.2569138 0.6124364 0.05249339 0.02795577 -0.99823 0.08243179 0.02581906 -0.9962623 0.6817993 0.3701981 0.6309543 0.6744493 0.254929 0.6929137 0.7426903 0.3812487 0.5505095 0.5804173 0.1863512 0.79271 0.1305003 0 -0.9914484 0.1305303 0 -0.9914444 0.06540286 0 -0.997859 0 -1 0 -0.1305003 0 -0.9914484 -0.06540286 0 -0.997859 0.2588022 0 -0.9659304 0.3826816 0 -0.9238803 0.4999893 0 -0.8660317 0.6087679 0 -0.7933484 0.7071068 0 -0.7071068 0.7933484 0 -0.6087679 0.8660317 0 -0.4999893 0.9238803 0 -0.3826816 0.9659304 0 -0.2588022 0.9914484 0 -0.1305003 1 0 0 0.9914484 0 0.1305003 0.9914444 0 0.1305303 0.9659304 0 0.2588022 0.9238803 0 0.3826816 0.8660317 0 0.4999893 0.7933484 0 0.6087679 0.7071068 0 0.7071068 0.6087679 0 0.7933484 0.4999893 0 0.8660317 0.3826816 0 0.9238803 0.2588022 0 0.9659304 0.1305003 0 0.9914484 0.06540286 0 0.997859 -0.1305003 0 0.9914484 -0.06540286 0 0.997859 -0.1305303 0 0.9914444 0.02383524 0.7544878 0.6558813 0.03985822 0.7925565 0.6084945 0.08044922 0.7872487 0.6113652 -0.08484214 0.722898 0.6857261 -0.0813328 0.7869294 0.6116594 -0.03622668 0.7908234 0.6109715 -0.03894275 0.7614592 0.647042 0.1716687 0.7229924 0.6691876 0.1616282 0.7867778 0.5956988 0.08343875 0.7231156 0.6856689 0.03222811 0.6992228 0.7141771 0.2541956 0.7225762 0.6428596 0.2387837 0.7868816 0.5690342 0.3329637 0.722052 0.6064455 0.3112981 0.7871876 0.5323809 0.4067925 0.7214165 0.5604269 0.3780112 0.7876099 0.4865987 0.4744238 0.7207151 0.505462 0.43786 0.7880992 0.4326412 0.5347046 0.7201421 0.4421384 0.4899293 0.788593 0.3716052 0.582585 0.7258737 0.365653 0.5335311 0.7890353 0.3045784 0.627996 0.7197982 0.2958238 0.5680521 0.7894072 0.2327082 0.6617485 0.7184532 0.2142755 0.5930258 0.7896938 0.1571757 0.6835972 0.7182363 0.1297366 0.6081511 0.7898609 0.07919663 0.6943979 0.7182943 0.04318428 0.6131945 0.789932 0 0.6943979 0.7182943 -0.04318428 0.6081318 0.7898755 -0.07919812 0.6835972 0.7182363 -0.1297366 0.5930258 0.7896938 -0.1571757 0.6617485 0.7184532 -0.2142755 0.5680521 0.7894072 -0.2327082 0.6280638 0.7197753 -0.2957354 0.5335311 0.7890353 -0.3045784 0.5774522 0.7285523 -0.3684573 0.4899293 0.788593 -0.3716052 0.5349081 0.7204641 -0.441367 0.43786 0.7880992 -0.4326412 0.4742434 0.7210245 -0.5051902 0.3780112 0.7876099 -0.4865987 0.4064928 0.7217926 -0.5601599 0.3112981 0.7871876 -0.5323809 0.3325426 0.7224928 -0.6061517 0.2387837 0.7868816 -0.5690342 0.2536134 0.7230575 -0.6425483 0.1616282 0.7867778 -0.5956988 0.1709656 0.7234453 -0.6688779 0.0813328 0.7869294 -0.6116594 0.08438587 0.7240095 -0.6846089 0.02682685 0.8045313 -0.5933041 -0.02868813 0.7750388 -0.6312621 -0.03833186 0.8099144 -0.5852943 -0.07983696 0.7873221 -0.6113511 0.03125166 0.7822381 -0.6221954 -0.7218454 0.1740522 0.6698098 -0.7563231 0.1724021 0.6310729 -0.7285062 0.1732605 0.6627666 -0.731114 0.1910186 0.654969 -0.7320635 0.185404 0.6555215 -0.7554335 0.2390238 0.6100721 -0.6698419 0.1741747 0.7217861 -0.6738069 0.1728923 0.7183958 0 0 1 -0.7775636 0.1718831 0.6048564 -0.7790681 0.1707254 0.603246 -0.6821351 0.3729448 0.6289706 -0.7630749 0.240065 0.6000711 -0.7755948 0.1727715 0.6071266 -0.7737474 0.1732562 0.6093418 -0.7733332 0.1733506 0.6098403 -0.7697542 0.1743254 0.614076 -0.7005703 0.2470842 0.6694406 -0.2082017 0.02703994 -0.9777121 -0.2268205 0.02438503 -0.9736313 -0.4132277 0.02584958 -0.9102608 -0.746737 0.2960336 0.5956073 -0.05200433 0.02722293 -0.9982758 -0.0823397 0.0263682 -0.9962555 -0.3582915 0.02639877 -0.9332365 -0.5474272 0.02609407 -0.8364464 -0.4997505 0.02642953 -0.8657662 -0.6488597 0.02591043 -0.7604668 -0.6290288 0.02667367 -0.7769243 -0.7289595 0.02594161 -0.6840652 -0.7801093 0.1736865 0.6010513 -0.742949 0.02661234 -0.6688188 -0.7942627 0.02649068 -0.6069968 -0.7827298 0.1738077 0.5975994 -0.8427007 0.0260635 -0.5377512 -0.7845089 0.1739317 0.5952257 -0.8383892 0.02645999 -0.5444296 -0.8841629 0.02661246 -0.4664202 -0.7862008 0.17405 0.5929543 -0.9144361 0.02612411 -0.4038864 -0.8137455 0.1742672 0.554481 -0.7656748 0.1764946 0.6185401 -0.9132088 0.02649015 -0.4066301 -0.9399843 0.02639889 -0.340195 -0.7823912 0.175333 0.5975972 -0.9588081 0.02615457 -0.282848 -0.7905551 0.1747565 0.5869268 -0.9655918 0.0264905 -0.2587099 -0.9735786 0.02618503 -0.2268459 -0.7961604 0.174388 0.5794114 -0.9846912 0.02652084 -0.172279 -0.8006381 0.1740809 0.5733014 -0.9919531 0.02615457 -0.1238759 -0.804503 0.1738954 0.5679221 -0.9941853 0.02636831 -0.1044053 -0.9967762 0.02618515 -0.07583934 -0.8079714 0.1737471 0.5630224 -0.9992257 0.02642953 -0.02914571 -0.8111044 0.1736533 0.5585289 -0.9995122 0.02682656 0.01599216 -0.8138731 0.1736413 0.55449 -0.9981272 0.02621591 0.05527007 -0.852887 0.1739283 0.4922732 -0.76442 0.1929132 0.6151801 -0.8140681 0.1740508 0.5540754 -0.9982852 0.02627706 0.05230998 -0.9950664 0.02624619 0.09567654 -0.7881564 0.1871432 0.5863334 -0.9905024 0.02646017 0.1349256 -0.802472 0.1834814 0.5677793 -0.98456 0.0267961 0.1729847 -0.8123561 0.1809474 0.5543786 -0.9779227 0.02621585 0.2073161 -0.8197236 0.1790885 0.5440409 -0.9778172 0.02630704 0.2078014 -0.9697804 0.02621603 0.2425672 -0.8257898 0.177622 0.5352771 -0.9604399 0.02636855 0.2772366 -0.8308149 0.1764906 0.5278236 -0.9499006 0.02664297 0.3114148 -0.8351516 0.1756061 0.5212334 -0.9386203 0.02624654 0.3439522 -0.8391557 0.1748749 0.5150114 -0.9332395 0.02627682 0.3582927 -0.9258657 0.02618557 0.3769446 -0.8428539 0.1743267 0.5091243 -0.9117801 0.02627664 0.4098372 -0.8463932 0.1739298 0.5033558 -0.8966796 0.02652102 0.441885 -0.8497512 0.1737163 0.4977406 -0.881268 0.0268262 0.471855 -0.8539162 0.1774668 0.4892165 -0.8745716 0.02694791 0.4841471 -0.8872203 0.1740198 0.4272672 -0.855487 0.1818035 0.4848604 -0.8238749 0.02615523 0.5661679 -0.8568359 0.02615523 0.5149255 -0.8491355 0.02621597 0.5275242 -0.9022816 0.02609425 0.4303569 -0.8596103 0.1798815 0.4782395 -0.8309249 0.02633833 0.5557609 -0.8632314 0.1783533 0.4722518 -0.8109059 0.02658253 0.5845725 -0.8663312 0.1771971 0.4669814 -0.7898645 0.02667367 0.6127012 -0.8691016 0.1762802 0.4621556 -0.7768905 0.02627676 0.6290872 -0.7672801 0.02615481 0.6407786 -0.8716118 0.1755797 0.4576733 -0.74427 0.02627694 0.6673618 -0.8739592 0.1749994 0.4533991 -0.7204892 0.02645981 0.6929612 -0.8762047 0.1745695 0.4492113 -0.6959074 0.02664357 0.7176373 -0.8783762 0.1742042 0.4450936 -0.6688873 0.02636849 0.7428961 -0.668682 0.02615517 0.7430885 -0.8805029 0.1739581 0.4409686 -0.6410594 0.02621608 0.7670434 -0.8826599 0.1737791 0.4367062 -0.612054 0.02639871 0.7903752 -0.8847945 0.1736872 0.4324021 -0.5817856 0.02661263 0.8129067 -0.8869748 0.1736228 0.4279379 -0.5444103 0.02630794 0.8384065 -0.5472423 0.02615505 0.8365656 -0.8871297 0.1736432 0.4276086 -0.5118933 0.02621567 0.858649 -0.9167074 0.1738377 0.3597612 -0.8967523 0.1760665 0.4059999 -0.8951727 0.1762146 0.4094075 -0.4746617 0.02645993 0.8797706 -0.8983404 0.1756089 0.4026738 -0.435541 0.02679592 0.8997701 -0.8998835 0.1751791 0.3994023 -0.4065818 0.02624678 0.9132373 -0.3890905 0.02615499 0.9208282 -0.9013611 0.1748458 0.3962034 -0.3426361 0.02636831 0.9390982 -0.9027858 0.1745998 0.3930556 -0.2937422 0.02679538 0.9555091 -0.9041398 0.1743578 0.390039 -0.2588036 0.02639913 0.9655692 -0.2349053 0.02615481 0.9716663 -0.9054206 0.1741745 0.3871392 -0.1760935 0.02645975 0.9840178 -0.9066185 0.174048 0.3843829 -0.1044985 0.0265519 0.9941706 -0.1080053 0.02609336 0.9938079 -0.9077339 0.1739292 0.3817957 -0.03689724 0.02630722 0.9989728 -0.9089052 0.1738093 0.3790538 0.05230957 0.02658206 0.9982771 0.04373365 0.0260632 0.9987033 -0.9105748 0.1736855 0.3750826 0.1288807 0.02633768 0.9913103 -0.9172185 0.1731649 0.3587815 0.2077764 0.02667397 0.9778127 0.2272728 0.02594089 0.9734857 -0.9232351 0.1725553 0.34331 0.3582994 0.02664351 0.9332265 0.3334184 0.02594101 0.9424221 -0.9406956 0.1713962 0.2927714 -0.9224858 0.1716366 0.3457758 0.4999049 0.02639913 0.8656778 0.44994 0.0260936 0.8926776 -0.9217126 0.1699008 0.3486827 0.6290339 0.02636867 0.7769306 0.5811768 0.02584969 0.8133667 -0.9213584 0.1682494 0.3504153 0.7426232 0.02703994 0.6691635 0.729622 0.02438479 0.6834159 -0.8833571 0.3747187 0.2815426 -0.8992596 0.2542281 0.3559499 -0.9182767 0.2763162 0.2835796 -0.8883057 0.2964071 0.3507931 0.83824 0.02795553 0.5445845 0.8215499 0.0258193 0.5695518 -0.9600419 0.1738067 0.2193413 -0.9687598 0.1728892 0.1778028 -0.9112628 0.3752294 0.1697154 -0.945731 0.2760162 0.1714877 -0.9410827 0.1736223 0.2902048 -0.9821044 0.1731348 0.07413083 -0.9831287 0.1728578 0.05981659 -0.9251617 0.3753872 0.05621647 -0.9596168 0.2754667 0.05704045 -0.9739775 0.1732248 0.1461546 -0.9847584 0.1739281 0 -0.9831733 0.1726467 -0.05969536 -0.9596168 0.2754667 -0.05704045 -0.9738693 0.173624 -0.1464008 -0.9686481 0.1731047 -0.1782014 -0.9251617 0.3753872 -0.05621647 -0.945731 0.2760162 -0.1714877 -0.9820494 0.1735631 -0.07385665 -0.9414033 0.1727401 -0.2896907 -0.9407093 0.1718509 -0.2924609 -0.9112628 0.3752294 -0.1697154 -0.9182767 0.2763162 -0.2835796 -0.960068 0.1728903 -0.2199507 -0.9217126 0.1699008 -0.3486827 -0.9213584 0.1682494 -0.3504153 -0.8833571 0.3747187 -0.2815426 -0.8992596 0.2542281 -0.3559499 -0.9224812 0.1716414 -0.3457855 -0.9233977 0.1727098 -0.3427949 -0.9231631 0.1726448 -0.3434585 -0.916759 0.1741411 -0.3594828 0.7426232 0.02703994 -0.6691635 0.7297694 0.02438461 -0.6832584 0.5816934 0.02584964 -0.8129974 -0.8883057 0.2964071 -0.3507931 0.8385196 0.02722322 -0.5441909 0.8216007 0.02636837 -0.5694532 0.6290519 0.02639865 -0.7769151 0.4506468 0.0260939 -0.8923209 0.4999046 0.02642959 -0.8656772 0.3341559 0.02591085 -0.9421616 0.3582991 0.02667403 -0.9332258 0.2279432 0.02594077 -0.9733289 -0.9105904 0.1736826 -0.375046 0.2077413 0.02661234 -0.9778218 0.1285461 0.0264905 -0.9913497 -0.9089162 0.1738361 -0.3790152 0.04434424 0.02606326 -0.9986764 -0.9077605 0.1739284 -0.381733 0.05230975 0.02646005 -0.9982803 -0.03811824 0.02661257 -0.9989188 -0.9066131 0.1740528 -0.3843935 -0.1074557 0.02612382 -0.9938666 -0.8870807 0.1742665 -0.4274566 -0.9185281 0.1764909 -0.3537754 -0.1044352 0.02649027 -0.9941789 -0.1753628 0.02639901 -0.98415 -0.9087631 0.1753619 -0.3786793 -0.2344161 0.02615469 -0.9717845 -0.9035781 0.1747522 -0.3911629 -0.2587383 0.02649027 -0.9655842 -0.2902662 0.02618527 -0.9565877 -0.8998599 0.1743869 -0.399802 -0.3431245 0.02652096 -0.9389155 -0.89682 0.1740841 -0.4067049 -0.3886882 0.02615463 -0.9209982 -0.8941106 0.1738963 -0.4127063 -0.4066427 0.02636891 -0.9132066 -0.4326958 0.02618509 -0.9011597 -0.8915941 0.173747 -0.418177 -0.4743255 0.02642935 -0.8799528 -0.8892645 0.1736535 -0.4231469 -0.5136373 0.02682632 -0.857588 -0.8871486 0.1736443 -0.4275687 -0.5469083 0.02621614 -0.8367819 -0.8527851 0.1739262 -0.4924504 -0.9149008 0.192911 -0.3546011 -0.8868893 0.1740512 -0.4279409 -0.5444537 0.02627658 -0.8383793 -0.5803854 0.02624654 -0.813919 -0.9018666 0.1871119 -0.3893917 -0.6120869 0.02645987 -0.7903478 -0.8929532 0.1834797 -0.4110594 -0.6421284 0.02679604 -0.7661287 -0.886304 0.1809475 -0.4262902 -0.6684887 0.02621579 -0.7432603 -0.8809827 0.1790593 -0.4379582 -0.6688883 0.02630746 -0.7428973 -0.6949542 0.02621603 -0.718576 -0.8764619 0.1776241 -0.4475089 -0.7203414 0.02636843 -0.6931183 -0.8725364 0.176491 -0.4555561 -0.7446382 0.02664327 -0.6669363 -0.8689829 0.1755789 -0.4626457 -0.7671806 0.02624613 -0.6408939 -0.8655984 0.1748776 -0.4692091 -0.7769175 0.02627664 -0.6290538 -0.7893806 0.02618551 -0.6133456 -0.8623455 0.1743246 -0.4753643 -0.8108338 0.026277 -0.5846865 -0.8591163 0.173929 -0.4813188 -0.8310292 0.0265209 -0.5555962 -0.855926 0.1737121 -0.4870471 -0.8492651 0.02682656 -0.5272848 -0.8506338 0.1774696 -0.4949008 -0.8565778 0.02694827 -0.5153139 -0.8136528 0.1740227 -0.5546939 -0.8476586 0.1817697 -0.4984324 -0.9022564 0.02615451 -0.430406 -0.8743588 0.02615445 -0.4845748 -0.8814179 0.02621573 -0.4716094 -0.823862 0.02609378 -0.5661896 -0.8439691 0.1798782 -0.5053316 -0.8967745 0.02633798 -0.4417035 -0.8406013 0.1783565 -0.5114474 -0.9117118 0.02658253 -0.4099696 -0.8375985 0.1771942 -0.5167505 -0.9255436 0.02667337 -0.3777006 -0.8348184 0.1762781 -0.5215403 -0.9332497 0.02627706 -0.3582661 -0.9385795 0.02615469 -0.3440705 -0.832179 0.1755794 -0.5259754 -0.9500901 0.02627694 -0.3108675 -0.8296312 0.1749965 -0.5301778 -0.9603677 0.02645981 -0.2774775 -0.8271318 0.1745699 -0.5342084 -0.969447 0.02664333 -0.2438495 -0.8246785 0.1742012 -0.5381072 -0.9778082 0.02636867 -0.2078365 -0.9778721 0.02615511 -0.2075624 -0.8221471 0.1739574 -0.5420452 -0.9848164 0.02621579 -0.1716081 -0.8195453 0.1737791 -0.5460278 -0.9905081 0.02639925 -0.1348959 -0.8168981 0.1736828 -0.5500108 -0.9948937 0.02661269 -0.09735608 -0.8140976 0.1736233 -0.5541662 -0.9982859 0.02630758 -0.05227953 -0.9981104 0.02615439 -0.05560481 -0.8138757 0.1736436 -0.5544857 -0.9995586 0.02621579 -0.0139777 -0.7699106 0.173838 -0.614018 -0.7999897 0.176063 -0.5736011 -0.8021505 0.1761904 -0.5705361 -0.9992347 0.02646028 0.02881026 -0.7979084 0.1755801 -0.5766402 -0.9969964 0.02679568 0.07266587 -0.7958396 0.1751781 -0.5796137 -0.9941821 0.02624619 0.104466 -0.9920102 0.02615451 0.1234176 -0.7938042 0.174875 -0.5824893 -0.9846042 0.02636837 0.1727986 -0.7918056 0.174597 -0.5852862 -0.9743731 0.02679544 0.2233364 -0.7898617 0.1743549 -0.5879787 -0.9656115 0.02639865 0.258646 -0.9589504 0.02615511 0.2823656 -0.7880064 0.1741732 -0.5905165 -0.9402355 0.02646011 0.3394956 -0.7862008 0.17405 -0.5929543 -0.9132413 0.02655214 0.406553 -0.9146633 0.02609395 0.4033735 -0.7845349 0.1739307 -0.5951918 -0.8836023 0.02630782 0.4674986 -0.7827257 0.1738373 -0.5975962 -0.8383634 0.02658224 0.5444632 -0.8430191 0.02606296 0.5372519 -0.7801617 0.1736846 -0.6009837 -0.7940546 0.02633821 0.6072756 -0.7692586 0.1731945 -0.6150162 -0.742919 0.02667337 0.6688498 -0.7294173 0.02594161 0.683577 -0.7589495 0.1725551 -0.6278699 -0.6290293 0.02664315 0.7769249 -0.6494507 0.02594137 0.7599611 -0.7238913 0.1713973 -0.6682848 -0.7606914 0.17164 -0.6260101 -0.4997509 0.02639901 0.8657668 -0.548093 0.02609384 0.8360104 -0.7628313 0.1699012 -0.6238766 -0.3582918 0.02636831 0.9332372 -0.4138118 0.02584987 0.9099954 -0.7641433 0.1682531 -0.6227167 -0.2082017 0.02703994 0.9777121 -0.2270299 0.02438455 0.9735826 -0.6854968 0.3747175 -0.6242444 -0.7579042 0.2542217 -0.6007934 -0.704728 0.2763244 -0.653455 -0.7479479 0.2964385 -0.5938841 -0.05249339 0.02795577 0.99823 -0.08243179 0.02581906 0.9962623 -0.6699666 0.1738092 -0.7217584 -0.6383659 0.1728901 -0.7500654 -0.6026345 0.375235 -0.7042943 -0.6214057 0.2760176 -0.7332594 -0.7218693 0.1736234 -0.6698952 -0.5552769 0.1731387 -0.8134437 -0.5433954 0.172861 -0.8214868 -0.5112572 0.3753858 -0.7731117 -0.5291994 0.275495 -0.8025276 -0.6135859 0.1732262 -0.7703928 -0.4923912 0.173927 -0.852819 -0.4398754 0.172648 -0.8813073 -0.4303833 0.2754977 -0.8595762 -0.3600969 0.1736242 -0.916616 -0.3299692 0.1731026 -0.9279848 -0.4138982 0.3753833 -0.8293225 -0.3243299 0.2760176 -0.9047787 -0.4270571 0.1735634 -0.8874108 -0.2198274 0.1727368 -0.9601239 -0.2170495 0.1718512 -0.9609145 -0.3086124 0.3752363 -0.8740459 -0.2135387 0.2763156 -0.9370437 -0.289507 0.1728923 -0.9414318 -0.1588803 0.1698976 -0.9725698 -0.1572033 0.1682512 -0.9731284 -0.1978272 0.3747181 -0.9057874 -0.1413325 0.2542214 -0.9567638 -0.1617811 0.1716387 -0.9717855 -0.1648033 0.1727077 -0.971088 -0.1641322 0.1726471 -0.9712125 -0.1470707 0.174141 -0.9736761 0.9508332 0.02704018 0.308521 0.9566084 0.02438443 0.2903548 0.9949228 0.02584964 0.09726434 -0.1403268 0.2964321 -0.9446886 0.8905523 0.02722316 0.4540657 0.9039723 0.02636837 0.4267774 0.9873585 0.02639913 0.156289 0.9980981 0.02609384 -0.05585002 0.9996507 0.02642947 6.1038e-5 0.9830164 0.02591061 -0.1816795 0.9873513 0.02667361 -0.1562879 0.9568988 0.02594131 -0.2892609 -0.1303489 0.1736866 -0.9761364 0.950689 0.02661228 -0.3090021 0.9228153 0.0264908 -0.3843309 -0.1262288 0.1738088 -0.976656 0.8870693 0.02606332 -0.4609 -0.1232672 0.1739292 -0.9770128 0.8907008 0.02646005 -0.4538195 0.8460376 0.02661222 -0.5324587 -0.1204285 0.1740506 -0.9773451 0.8069847 0.02612429 -0.5899943 -0.1526852 0.1764898 -0.9723881 0.8087531 0.02649044 -0.5875515 0.7646162 0.02639865 -0.6439452 -0.1262591 0.1753344 -0.9763793 0.7243742 0.02615493 -0.6889109 -0.1129518 0.1747533 -0.9781121 0.7068434 0.02649021 -0.706874 0.6832578 0.02618521 -0.7297076 -0.1036436 0.1743569 -0.9792129 0.6415364 0.02655136 -0.766633 -0.09613496 0.1740806 -0.9800276 0.6032755 0.02615505 -0.7971038 -0.08957499 0.1738702 -0.9806863 0.5875189 0.02636826 -0.8087807 0.5640657 0.02618592 -0.8253147 -0.08359068 0.1737429 -0.9812371 0.5248641 0.02642935 -0.8507755 -0.07809817 0.1736532 -0.9817053 0.4858931 0.0268262 -0.8736065 -0.07328784 0.1736401 -0.9820784 0.4511935 0.02621585 -0.892041 0.4538217 0.02627706 -0.8907051 0.414665 0.02624654 -0.9095956 0.3783743 0.02645993 -0.9252746 0.3424608 0.02679622 -0.93915 0.3094642 0.02621591 -0.9505497 0.3089128 0.02630728 -0.9507265 0.2748242 0.02621585 -0.9611371 0.2400952 0.02636861 -0.9703912 0.2052113 0.02664327 -0.9783551 0.1713955 0.02624642 -0.9848527 0.1365131 0.02618557 -0.9902922 0.1009257 0.02627664 -0.9945469 0.06561642 0.02652126 -0.9974924 0 1 -2.78484e-6 0 1 -2.80769e-6 0 1 2.87797e-6 0 1 -2.8196e-6 0 1 5.18145e-7 0 1 7.98783e-7 0 1 9.36554e-7 0 1 -1.00213e-6 0 1 -7.02416e-7 0 1 1.56504e-6 -0.6140754 0.1745999 0.7696924 -0.5880744 0.1719146 0.7903252 -0.5538989 0.1731373 0.814383 -0.4843426 0.1704508 0.8581136 -0.4933395 0.1731647 0.852426 -0.4269962 0.1738687 0.8873805 -0.3677549 0.1714257 0.9139856 -0.3577447 0.1707543 0.9180751 -0.2494636 0.1719754 0.9529913 -0.2931383 0.17042 0.9407588 0 1 -5.09709e-6 -0.2177251 0.1727701 0.9605969 0 1 5.94659e-6 -0.1482606 0.1727978 0.973735 -6.46178e-6 0 1 6.59248e-6 0 1 -0.2588022 0 0.9659304 -0.3826816 0 0.9238803 -0.4999893 0 0.8660317 -0.6087679 0 0.7933484 -0.7071068 0 0.7071068 -0.7933484 0 0.6087679 -0.8660317 0 0.4999893 -0.9238803 0 0.3826816 -0.9659304 0 0.2588022 -0.9914484 0 0.1305003 -1 0 0 -0.9914484 0 -0.1305003 -0.9914444 0 -0.1305303 -0.9659304 0 -0.2588022 -0.9238803 0 -0.3826816 -0.8660317 0 -0.4999893 -0.7933484 0 -0.6087679 -0.7071068 0 -0.7071068 -0.6087679 0 -0.7933484 -0.4999893 0 -0.8660317 -0.3826816 0 -0.9238803 -0.2588022 0 -0.9659304 -0.1709656 0.7234453 -0.6688779 -0.1616282 0.7867778 -0.5956988 -0.03448724 0.7272236 -0.6855337 -0.08429366 0.7238516 -0.6847872 -0.2536134 0.7230575 -0.6425483 -0.2387837 0.7868816 -0.5690342 -0.3325426 0.7224928 -0.6061517 -0.3112981 0.7871876 -0.5323809 -0.4064928 0.7217926 -0.5601599 -0.3780112 0.7876099 -0.4865987 -0.4742434 0.7210245 -0.5051902 -0.43786 0.7880992 -0.4326412 -0.5346075 0.7203482 -0.4419202 -0.4899293 0.788593 -0.3716052 -0.582585 0.7258737 -0.365653 -0.5335311 0.7890353 -0.3045784 -0.627996 0.7197982 -0.2958238 -0.5680521 0.7894072 -0.2327082 -0.6617485 0.7184532 -0.2142755 -0.5930258 0.7896938 -0.1571757 -0.6835972 0.7182363 -0.1297366 -0.6081511 0.7898609 -0.07919663 -0.6943979 0.7182943 -0.04318428 -0.6131945 0.789932 0 -0.6943979 0.7182943 0.04318428 -0.6081318 0.7898755 0.07919812 -0.6835972 0.7182363 0.1297366 -0.5930258 0.7896938 0.1571757 -0.6617485 0.7184532 0.2142755 -0.5680521 0.7894072 0.2327082 -0.6280638 0.7197753 0.2957354 -0.5335311 0.7890353 0.3045784 -0.5774522 0.7285523 0.3684573 -0.4899293 0.788593 0.3716052 -0.5350053 0.7202581 0.4415854 -0.43786 0.7880992 0.4326412 -0.4744238 0.7207151 0.505462 -0.3780112 0.7876099 0.4865987 -0.4067925 0.7214165 0.5604269 -0.3112981 0.7871876 0.5323809 -0.3329637 0.722052 0.6064455 -0.2387837 0.7868816 0.5690342 -0.2541956 0.7225762 0.6428596 -0.1616282 0.7867778 0.5956988 -0.1716687 0.7229924 0.6691876 2.20938e-5 0 1 0.6578044 0.276135 0.7007445 0 0.9659263 0.2588176 7.87392e-7 0 1 8.54534e-4 0.02636843 -0.999652 0.6237149 0.5607849 0.5445184 0.7152436 0.4479581 0.5364328 -0.1048944 0.0275588 -0.9941015 -0.095739 0.02542257 -0.9950819 0.5895965 0.3942749 0.7049278 0.5477608 0.5600907 0.6214955 0.5801628 0.2824822 0.7639471 0.4899893 0.4587984 0.7412251 0.4639568 0.5594216 0.6868709 0 0.9659258 0.2588194 0.4465568 0.4569638 0.7692667 -7.10621e-7 0.9659256 0.2588202 -1.26973e-7 0.9659255 0.2588203 0.3622952 0.5770599 0.7319456 0.3500568 0.4829074 0.8026585 1.92327e-7 0.9659261 0.2588184 0.6851633 0.5051592 0.5247527 -0.2580069 0.02789425 -0.9657403 -0.2347839 0.02484256 -0.9717301 0.6457004 0.6108471 0.4581887 -0.3343431 0.02639949 -0.9420816 0.6702863 0.6933281 0.2645987 -0.4065106 0.02905386 -0.913184 -0.4478018 0.02313321 -0.8938336 0.2644449 0.5986862 0.7560713 0.2455865 0.4782635 0.8431794 0.1566555 0.6333363 0.7578551 -1.27173e-7 0.9659261 0.2588181 0.0618931 0.6414542 0.7646605 -2.81333e-7 0.9659258 0.2588196 1.55574e-7 0.9659259 0.2588192 0.04559636 0.6507101 0.7579562 0 0.9659258 0.2588197 0.6382579 0.6781777 0.3642828 -0.544283 0.02905446 -0.8383985 -0.6039251 0.02157747 -0.796749 0.6597001 0.65323 0.3716001 -0.6690979 0.02874886 -0.742618 -0.7496407 0.02224838 -0.6614711 0.4454559 -0.8000566 0.4018442 -0.7774193 0.02722322 -0.6283934 -0.8156729 0.0230416 -0.5780544 0.6856533 0.6238511 0.3750858 -0.9034844 0.02252298 -0.4280289 -0.9093627 0.02603322 -0.4151889 -0.9473754 0.02349972 -0.3192608 -0.823838 0.02609395 -0.5662246 0.6706067 0.6486326 0.3599479 -0.9776766 0.02874886 -0.2081396 -0.9919674 0.02157711 -0.1246406 -0.9324881 0.02533102 -0.3603114 0.6739518 0.6330257 0.3808775 -0.9982162 0.0290541 -0.05215698 -0.9979849 0.02313369 0.05908554 0.7176609 0.6087986 0.3381231 -0.9940761 0.02856606 0.1048644 -0.9822278 0.02942043 0.1853732 0.7824793 0.5610632 0.2700635 0.7974274 0.5048431 0.3305193 -0.9590057 0.02578872 0.2822113 0.8116623 0.5607627 0.1635532 0.8503603 0.3918073 0.3512471 0.8225766 0.4477126 0.3506014 0.8261312 0.5608561 0.0542941 0.8261312 0.5608561 -0.0542941 0.8116623 0.5607627 -0.1635532 0.7824793 0.5610632 -0.2700635 0.7176609 0.6087986 -0.3381231 0.7974274 0.5048431 -0.3305193 0.8503603 0.3918073 -0.3512471 0.8225766 0.4477126 -0.3506014 0.6739518 0.6330257 -0.3808775 -0.9940975 0.0290541 -0.1045278 -0.9830431 0.02639877 -0.1814652 -0.9979849 0.02313369 -0.05908554 -0.9653629 0.02789479 -0.2594159 -0.9589411 0.02484256 -0.2825154 0.6706067 0.6486326 -0.3599479 -0.9982162 0.0290541 0.05215698 -0.9919674 0.02157711 0.1246406 0.6857993 0.623601 -0.3752349 -0.9776766 0.02874886 0.2081396 -0.9476828 0.0222485 0.3184375 0.6831843 0.6245864 -0.3783531 -0.9329171 0.02722328 0.3590608 -0.9084556 0.02304172 0.4173457 0.6326637 0.6784425 -0.3734333 -0.8224306 0.0225231 0.5684195 -0.814253 0.02603286 0.5799263 -0.7501641 0.02349984 0.6608341 0.6382447 0.6781941 -0.3642753 -0.6690979 0.02874886 0.742618 -0.6039251 0.02157747 0.796749 -0.7782995 0.0253309 0.6273822 0.6402654 0.6343752 -0.4331611 -0.544283 0.02905446 0.8383985 -0.4478018 0.02313321 0.8938336 0.6672426 0.5735484 -0.4752154 -0.4062049 0.02856552 0.9133354 -0.3305839 0.02942049 0.943318 0.6228965 0.560027 -0.5462324 0.684947 0.5048519 -0.5253305 -0.2350873 0.025819 0.9716313 0.5455363 0.5592702 -0.6241852 0.729382 0.3918074 -0.5607931 0.7149235 0.4477237 -0.5370548 0.4588041 0.5591531 -0.6905409 0.365072 0.5587781 -0.7446407 0.2643621 0.5581147 -0.7865245 0.1584857 0.5581946 -0.814433 0.06720381 0.5920162 -0.8031193 0.1124331 0.5048505 -0.8558532 0.1209774 0.3918031 -0.9120608 0.1076404 0.4477133 -0.8876748 0.03827089 0.6110222 -0.7906879 -0.5875877 0.02905434 0.8086388 -0.6486852 0.02639907 0.760599 -0.5501705 0.02313357 0.8347319 -0.7073503 0.02789479 0.7063126 -0.72413 0.02484261 0.689216 0.04416179 0.6394457 -0.7675669 -0.4539088 0.02905404 0.8905745 -0.3880185 0.02157688 0.9213991 0.02993929 0.7143936 -0.6991034 -0.004059016 0.7047472 -0.709447 -0.3085519 0.02874934 0.9507731 -0.1980685 0.02224832 0.9799357 0.00250256 0.6990787 -0.7150404 -0.1554926 0.02722263 0.9874619 -0.09277892 0.02304208 0.9954201 -0.04348927 0.6804474 -0.7315054 -0.03274691 0.5383558 -0.8420812 0.08105921 0.02252322 0.9964548 0.0950967 0.02603256 0.9951277 0.1972121 0.02349942 0.9800791 -0.07843464 0.02609401 0.9965777 -0.06729525 0.647225 0.7593228 -0.04138404 0.6897035 0.7229084 -0.03628724 0.6560397 0.7538536 -3.54392e-7 0.9659255 0.2588201 -0.8653092 0.02636849 -0.5005444 -0.9133777 0.0275588 -0.4061796 -0.9096317 0.02542269 -0.414637 -0.9132053 0.02688765 0.4066116 -0.8600273 0.03054958 0.5093327 -0.9096317 0.02542269 0.414637 -0.965469 0.02737551 0.2590759 -0.8661572 0.02636831 0.4990757 -0.8084645 0.02755916 0.5878993 -0.8138971 0.02542281 0.5804526 -0.1044372 0.02688753 0.9941681 0.01110893 0.03054964 0.9994716 -0.09570878 0.02542263 0.9950847 -0.2583467 0.02737587 0.9656643 -0.1566555 0.6333363 0.7578551 -0.2644449 0.5986862 0.7560713 -0.3625102 0.5771535 0.7317652 -0.4629156 0.5600278 0.6870794 -0.5477608 0.5600907 0.6214955 -0.6237149 0.5607849 0.5445184 -0.6402654 0.6343752 0.4331611 -0.6673969 0.5735195 0.4750335 -0.6857993 0.623601 0.3752349 -0.6831713 0.624605 0.3783459 -0.6326637 0.6784425 0.3734333 -0.6382447 0.6781941 0.3642753 -0.7824793 0.5610632 0.2700635 -0.7176609 0.6087986 0.3381231 -0.6739518 0.6330257 0.3808775 -0.6706067 0.6486326 0.3599479 -0.8116623 0.5607627 0.1635532 -0.8261312 0.5608561 0.0542941 -0.8261312 0.5608561 -0.0542941 -0.8116623 0.5607627 -0.1635532 -0.7824793 0.5610632 -0.2700635 -0.6597001 0.65323 -0.3716001 -0.4454667 -0.8000455 -0.4018539 -0.6856533 0.6238511 -0.3750858 -0.6706067 0.6486326 -0.3599479 -0.6739518 0.6330257 -0.3808775 -0.7176609 0.6087986 -0.3381231 -0.6455421 0.6109029 -0.4583373 -0.6702863 0.6933281 -0.2645987 -0.6382579 0.6781777 -0.3642828 -0.6228965 0.560027 -0.5462324 -0.5455363 0.5592702 -0.6241852 -0.4588041 0.5591531 -0.6905409 -0.365072 0.5587781 -0.7446407 -0.2643621 0.5581147 -0.7865245 -0.1584857 0.5581946 -0.814433 -0.04233002 0.6183792 -0.7847391 -0.03827089 0.6110222 -0.7906879 -0.06720215 0.5920017 -0.8031301 0.3085516 0.0287798 0.9507722 0.3880185 0.02157688 0.9213991 0.1541821 0.02533078 0.9877178 0.4539088 0.02905404 0.8905745 0.5501705 0.02313357 0.8347319 0.5878627 0.02856606 0.8084563 0.65165 0.02942067 0.7579491 -0.112465 0.5048261 -0.8558635 0.7239191 0.02581936 0.6894017 -0.1209774 0.3918031 -0.9120608 -0.1076404 0.4477133 -0.8876748 -0.684947 0.5048519 -0.5253305 -0.729382 0.3918074 -0.5607931 -0.7149235 0.4477237 -0.5370548 0.4065106 0.02905386 0.913184 0.3343431 0.02639949 0.9420816 0.4478018 0.02313321 0.8938336 0.2580069 0.02789425 0.9657403 0.2347839 0.02484256 0.9717301 0.544283 0.02905446 0.8383985 0.6039251 0.02157747 0.796749 0.6690979 0.02874886 0.742618 0.7496407 0.02224838 0.6614711 0.7774193 0.02722322 0.6283934 0.8156729 0.0230416 0.5780544 0.9034844 0.02252298 0.4280289 0.9093627 0.02603322 0.4151889 0.9473754 0.02349972 0.3192608 0.823838 0.02609395 0.5662246 0.9776766 0.02874886 0.2081396 0.9919674 0.02157711 0.1246406 0.9324881 0.02533102 0.3603114 0.9982162 0.0290541 0.05215698 0.9979849 0.02313369 -0.05908554 0.9940761 0.02856606 -0.1048644 0.9822278 0.02942043 -0.1853732 -0.7974274 0.5048431 -0.3305193 0.9590057 0.02578872 -0.2822113 -0.8503603 0.3918073 -0.3512471 -0.8225766 0.4477126 -0.3506014 -0.7974274 0.5048431 0.3305193 -0.8503603 0.3918073 0.3512471 -0.8225766 0.4477126 0.3506014 0.9940975 0.0290541 0.1045278 0.9830431 0.02639877 0.1814652 0.9979849 0.02313369 0.05908554 0.9653629 0.02789479 0.2594159 0.9589411 0.02484256 0.2825154 0.9982162 0.0290541 -0.05215698 0.9919674 0.02157711 -0.1246406 0.9776766 0.02874886 -0.2081396 0.9476828 0.0222485 -0.3184375 0.9329171 0.02722328 -0.3590608 0.9084556 0.02304172 -0.4173457 0.8224306 0.0225231 -0.5684195 0.814253 0.02603286 -0.5799263 0.7501641 0.02349984 -0.6608341 0.6690979 0.02874886 -0.742618 0.6039251 0.02157747 -0.796749 0.7782995 0.0253309 -0.6273822 0.544283 0.02905446 -0.8383985 0.4478018 0.02313321 -0.8938336 0.4062049 0.02856552 -0.9133354 0.3305839 0.02942049 -0.943318 -0.6851366 0.5051925 0.5247556 0.2350873 0.025819 -0.9716313 -0.7152436 0.4479581 0.5364328 -0.7287313 0.3925041 0.5611518 -0.589513 0.3942192 0.705029 -0.48663 0.451777 0.7477225 -0.3500568 0.4829074 0.8026585 -0.4745821 0.4114978 0.7781011 -0.24559 0.4782399 0.8431916 1.11208e-6 0.965927 0.2588151 -4.99875e-7 0.9659252 0.2588216 -1.1817e-6 0.9659257 0.2588199 0.2583467 0.02737587 -0.9656643 0.09570878 0.02542263 -0.9950847 0.1044372 0.02688753 -0.9941681 -0.01110893 0.03054964 -0.9994716 -0.5801425 0.2824872 0.7639607 -0.6557418 0.2792839 0.7014295 8.79029e-6 0.9659267 0.2588158 -2.98354e-6 0.9659267 0.258816 3.68322e-7 0.9659256 0.25882 -3.20171e-5 0.965924 0.2588263 -8.54534e-4 0.02636843 0.999652 0.1048944 0.0275588 0.9941015 0.095739 0.02542257 0.9950819 0.808759 0.02688741 0.5875253 0.8711223 0.03055012 0.4901151 0.8138971 0.02542281 0.5804526 0.7071164 0.02737516 0.7065671 0.8653092 0.02636849 0.5005444 0.9133777 0.0275588 0.4061796 0.9096317 0.02542269 0.414637 0.9132053 0.02688765 -0.4066116 0.8600273 0.03054958 -0.5093327 0.9096317 0.02542269 -0.414637 0.965469 0.02737551 -0.2590759 -0.1441406 0.02258396 -0.9892995 -0.0784654 0 -0.9969169 -0.1846684 0.07147467 -0.9801984 0.3148976 0.01141417 -0.9490571 0.1272324 0.07147479 -0.9892944 0.1243641 0.04281789 -0.9913125 0.1564405 0 -0.9876874 -0.286881 0.02151602 -0.9577246 -0.3030567 0.01141417 -0.9529042 -0.4785338 0.07147485 -0.8751553 -0.5687798 0.02151578 -0.8222084 -0.5827034 0.01141417 -0.8126047 -0.7255532 0.0714749 -0.6844444 -0.7950213 0.0215159 -0.6061999 -0.8052957 0.01141393 -0.5927637 -0.9015519 0.07147711 -0.4267264 -0.9434451 0.02151614 -0.3308299 -0.9490571 0.01141417 -0.3148976 -0.9892944 0.07147479 -0.1272324 -0.9995016 0.02151596 -0.02310293 -0.9999157 0.01141399 -0.006195247 -0.9801984 0.07147467 0.1846684 -0.9577246 0.02151602 0.286881 -0.9529042 0.01141417 0.3030567 -0.8751553 0.07147485 0.4785338 -0.8222084 0.02151578 0.5687798 -0.8126047 0.01141417 0.5827034 -0.6844444 0.0714749 0.7255532 -0.6061999 0.0215159 0.7950213 -0.5927637 0.01141393 0.8052957 -0.4267264 0.07147711 0.9015519 -0.3308299 0.02151614 0.9434451 -0.3148976 0.01141417 0.9490571 -0.1272324 0.07147479 0.9892944 -0.1243641 0.04281789 0.9913125 0.1441406 0.02258396 0.9892995 0.07843506 0 0.9969193 0.1846684 0.07147467 0.9801984 -0.1564108 0 0.9876922 0.286881 0.02151602 0.9577246 0.3030567 0.01141417 0.9529042 0.4785338 0.07147485 0.8751553 0.5687798 0.02151578 0.8222084 0.5827034 0.01141417 0.8126047 0.7255532 0.0714749 0.6844444 0.7950213 0.0215159 0.6061999 0.8052849 0.01141422 0.5927783 0.9015519 0.07147711 0.4267264 0.9434451 0.02151614 0.3308299 0.9490571 0.01141417 0.3148976 0.9892944 0.07147479 0.1272324 0.9995016 0.02151596 0.02310293 0.9999157 0.01141399 0.006195247 0.9801984 0.07147467 -0.1846684 0.9577246 0.02151602 -0.286881 0.9529042 0.01141417 -0.3030567 0.8751553 0.07147485 -0.4785338 0.8222084 0.02151578 -0.5687798 0.8126047 0.01141417 -0.5827034 0.6844444 0.0714749 -0.7255532 0.6061999 0.0215159 -0.7950213 0.5927637 0.01141393 -0.8052957 0.4267146 0.07147514 -0.9015575 0.3308299 0.02151614 -0.9434451 -0.9288343 0.02258449 -0.3698063 -0.9025918 0 -0.4304974 -0.9412156 0.07147622 -0.3301579 -0.6644645 0.01141417 -0.7472327 -0.7931234 0.07147508 -0.6048527 -0.7963122 0.04281866 -0.6033685 -0.7771361 0 -0.6293326 -0.9728538 0.02151584 -0.2304183 -0.9767733 0.01141422 -0.2139714 -0.9971742 0.0714752 -0.02313327 -0.9964423 0.02151578 0.08148545 -0.9950884 0.01141393 0.09833079 -0.9555251 0.07147592 0.2861173 -0.9225008 0.02151596 0.3853952 -0.9159982 0.01141411 0.4010201 -0.8203397 0.07147717 0.5673922 -0.7582466 0.0215159 0.6516129 -0.7472327 0.01141417 0.6644645 -0.6048527 0.07147508 0.7931234 -0.5197656 0.02151572 0.854038 -0.5053403 0.01141422 0.8628447 -0.3301579 0.07147622 0.9412158 -0.2304183 0.02151584 0.9728538 -0.2139714 0.01141422 0.9767733 -0.02313327 0.0714752 0.9971742 0.08148545 0.02151578 0.9964423 0.09833079 0.01141393 0.9950884 0.2861173 0.07147592 0.9555251 0.3853952 0.02151596 0.9225008 0.4010201 0.01141411 0.9159982 0.5673922 0.07147717 0.8203397 0.6516129 0.0215159 0.7582466 0.6644645 0.01141417 0.7472327 0.7931234 0.07147508 0.6048527 0.7963122 0.04281866 0.6033685 0.9288343 0.02258449 0.3698063 0.9025918 0 0.4304974 0.9412156 0.07147622 0.3301579 0.7771511 0 0.6293141 0.9728538 0.02151584 0.2304183 0.9767733 0.01141422 0.2139714 0.9971742 0.0714752 0.02313327 0.9964423 0.02151578 -0.08148545 0.9950884 0.01141393 -0.09833079 0.9555251 0.07147592 -0.2861173 0.92249 0.02151566 -0.3854212 0.9159982 0.01141411 -0.4010201 0.8203496 0.07147538 -0.567378 0.7582466 0.0215159 -0.6516129 0.7472327 0.01141417 -0.6644645 0.6048527 0.07147508 -0.7931234 0.5197656 0.02151572 -0.854038 0.5053403 0.01141422 -0.8628447 0.3301579 0.07147622 -0.9412158 0.2304183 0.02151584 -0.9728538 0.2139714 0.01141422 -0.9767733 0.02313327 0.0714752 -0.9971742 -0.08148545 0.02151578 -0.9964423 -0.09833079 0.01141393 -0.9950884 -0.2861173 0.07147592 -0.9555251 -0.3853952 0.02151596 -0.9225008 -0.4010201 0.01141411 -0.9159982 -0.5673922 0.07147717 -0.8203397 -0.6516129 0.0215159 -0.7582466 -0.784685 0.02258437 0.6194833 -0.824131 0 0.5663993 -0.7565407 0.07147598 0.6500287 -0.9793617 0.01141417 0.201793 -0.9203888 0.0714752 0.384416 -0.9206953 0.04281806 0.3879262 -0.9335846 0 0.3583573 -0.6859797 0.02151602 0.7273026 -0.6736993 0.01141393 0.7389176 -0.5186403 0.07147556 0.8519997 -0.4276317 0.02151584 0.903697 -0.4123775 0.01141422 0.9109417 -0.2299621 0.07147592 0.9705713 -0.1274459 0.0215156 0.9916121 -0.1106923 0.01141405 0.9937893 0.08121144 0.0714758 0.9941308 0.1851892 0.02151584 0.9824673 0.201793 0.01141417 0.9793617 0.384416 0.0714752 0.9203888 0.479731 0.02151602 0.8771519 0.4945644 0.01141417 0.8690661 0.6500287 0.07147598 0.7565407 0.7273026 0.02151602 0.6859797 0.7389176 0.01141393 0.6736993 0.8519997 0.07147556 0.5186403 0.903697 0.02151584 0.4276317 0.9109417 0.01141422 0.4123775 0.9705713 0.07147592 0.2299621 0.9916121 0.0215156 0.1274459 0.9937893 0.01141405 0.1106923 0.9941308 0.0714758 -0.08121144 0.9824674 0.02151584 -0.1851892 0.9793617 0.01141417 -0.201793 0.9203888 0.0714752 -0.384416 0.9206953 0.04281806 -0.3879262 0.784685 0.02258437 -0.6194833 0.824131 0 -0.5663993 0.7565407 0.07147598 -0.6500287 0.9335846 0 -0.3583573 0.6859797 0.02151602 -0.7273026 0.6736993 0.01141393 -0.7389176 0.5186403 0.07147556 -0.8519997 0.4276317 0.02151584 -0.903697 0.4123775 0.01141422 -0.9109417 0.2299621 0.07147592 -0.9705713 0.1274459 0.0215156 -0.9916121 0.1106923 0.01141405 -0.9937893 -0.08121144 0.0714758 -0.9941308 -0.1851892 0.02151584 -0.9824673 -0.201793 0.01141417 -0.9793617 -0.384416 0.0714752 -0.9203888 -0.479731 0.02151602 -0.8771519 -0.4945644 0.01141417 -0.8690661 -0.6500287 0.07147598 -0.7565407 -0.7273026 0.02151602 -0.6859797 -0.7389176 0.01141393 -0.6736993 -0.8519997 0.07147556 -0.5186403 -0.903697 0.02151584 -0.4276317 -0.9109417 0.01141422 -0.4123775 -0.9705713 0.07147592 -0.2299621 -0.9916121 0.0215156 -0.1274459 -0.9937893 0.01141405 -0.1106923 -0.9941308 0.0714758 0.08121144 -0.9824674 0.02151584 0.1851892 0.7771361 0 0.6293326 0.9225008 0.02151596 -0.3853952 0.8203397 0.07147717 -0.5673922 -0.7771511 0 -0.6293141 -0.92249 0.02151566 0.3854212 -0.8203496 0.07147538 0.567378 -0.1736861 0 0.9848011 -0.1736513 0 0.9848073 -0.3420028 0 0.9396989 0.3420935 0 0.939666 0.3420028 0 0.9396989 0.1736513 0 0.9848073 0.1736861 0 0.9848011 -0.3420935 0 0.939666 -0.6427834 0 0.7660481 -0.6428821 0 0.7659652 -0.8660789 0 0.4999074 -0.9848124 0 0.1736217 -0.9848178 0 0.1735921 -0.9848124 0 -0.1736217 -0.9848178 0 -0.1735921 -0.8660789 0 -0.4999074 -0.6427834 0 -0.7660481 -0.6428821 0 -0.7659652 -0.3420028 0 -0.9396989 -0.3420935 0 -0.939666 -0.1736513 0 -0.9848073 0.1736861 0 -0.9848011 0.1736513 0 -0.9848073 0.3420028 0 -0.9396989 -0.1736861 0 -0.9848011 0.3420935 0 -0.939666 0.6427834 0 -0.7660481 0.6428821 0 -0.7659652 0.8660789 0 -0.4999074 0.9848124 0 -0.1736217 0.9848178 0 -0.1735921 0.9848124 0 0.1736217 0.9848178 0 0.1735921 0.8660657 0 0.4999303 0.6427984 0 0.7660355 0.6428821 0 0.7659652 0.7660204 0 0.6428163 0.7660355 0 0.6427984 0.6427834 0 0.7660481 0.9848229 0 0.1735625 0.9396989 0 0.3420028 0.9397124 0 0.341966 0.6427325 0 0.7660908 0.3419024 0 0.9397356 -6.1037e-5 0 1 -0.3420298 0 0.9396891 -0.3420567 0 0.9396793 -0.6427984 0 0.7660355 -0.6427654 0 0.7660631 -0.8659768 0 0.5000844 -0.9847906 0 0.1737453 -0.9848229 0 -0.1735625 -0.9396989 0 -0.3420028 -0.7660204 0 -0.6428163 -0.7660355 0 -0.6427984 -0.6427984 0 -0.7660355 -0.9397124 0 -0.341966 -0.6427325 0 -0.7660908 -0.3419024 0 -0.9397356 0 0 -1 6.1037e-5 0 -1 0.3420298 0 -0.9396891 0.3420567 0 -0.9396793 0.6427984 0 -0.7660355 0.6427654 0 -0.7660631 0.8659768 0 -0.5000844 0.9847906 0 -0.1737453 0.9397124 0 -0.341966 0.9396891 0 -0.3420298 0.9848073 0 -0.1736513 0.6427325 0 -0.7660908 0.7660355 0 -0.6427984 0.7660204 0 -0.6428163 0.9848229 0 -0.1735625 0.9848073 0 0.1736513 0.9847906 0 0.1737453 0.866024 0 0.5000025 0.8659768 0 0.5000844 0.6427654 0 0.7660631 0.3420567 0 0.9396793 6.1037e-5 0 1 -0.3419024 0 0.9397356 -0.6427325 0 0.7660908 -0.7660355 0 0.6427984 -0.9397124 0 0.341966 -0.9396891 0 0.3420298 -0.9848073 0 0.1736513 -0.7660204 0 0.6428163 -0.9848229 0 0.1735625 -0.9848073 0 -0.1736513 -0.9847906 0 -0.1737453 -0.866024 0 -0.5000025 -0.8659768 0 -0.5000844 -0.6427654 0 -0.7660631 -0.3420298 0 -0.9396891 -6.1037e-5 0 -1 0.3419024 0 -0.9397356 -0.3420567 0 -0.9396793 0.3420298 0 0.9396891 0.1736217 0 -0.9848124 -0.1736217 0 -0.9848124 -0.1736217 0 0.9848124 0.1736217 0 0.9848124 0.193856 0 -0.98103 0.3716012 0 -0.9283925 0.4033133 0 -0.915062 0.2106732 0 -0.9775565 0.6831377 0 -0.7302896 0.9015551 0 -0.4326646 0.9971013 0 -0.07608503 0.95677 0 0.2908459 0.7860229 0 0.6181976 0.6584138 0 0.7526561 0.6712498 0 0.7412313 0.8068037 0 0.5908198 0.9744879 0 0.2244404 0.9997232 0 0.02353042 0.9898572 0 -0.1420665 0.9944092 0 -0.1055966 0.9994797 0 -0.03225898 0.999151 0 0.04120022 0.9934259 0 0.114477 0.9823322 0 0.1871457 0.9443114 0 0.3290533 0.9175846 0 0.3975406 0.8859087 0 0.4638599 0.849444 0 0.5276789 0.8083876 0 0.5886507 0.7861965 0 0.6179765 0.877549 0 0.4794871 0.9561558 0 0.2928589 0.9941237 0 -0.1082506 0.9519397 0 -0.3062858 0.9465285 0 -0.3226205 0.9898136 0 -0.1423698 0.9740222 0 0.2264529 0.8254854 0 0.5644235 0.5644586 0 0.8254615 0.2264818 0 0.9740154 -0.1423399 0 0.9898179 -0.3226205 0 0.9465285 -0.3062858 0 0.9519397 -0.1082506 0 0.9941237 0.2928589 0 0.9561558 0.4794871 0 0.877549 0.6179765 0 0.7861965 0.5886507 0 0.8083876 0.5277009 0 0.8494303 0.4638599 0 0.8859087 0.3975406 0 0.9175846 0.3290627 0 0.9443081 0.1871752 0 0.9823266 0.1145071 0 0.9934225 0.04120022 0 0.999151 -0.03225898 0 0.9994797 -0.1055966 0 0.9944092 -0.1420665 0 0.9898572 0.02353042 0 0.9997232 0.2244404 0 0.9744879 0.5908198 0 0.8068037 0.7412313 0 0.6712498 0.7526713 0 0.6583966 0.6181976 0 0.7860229 0.2908738 0 0.9567614 -0.07605236 0 0.9971039 -0.4326398 0 0.9015669 -0.7302754 0 0.683153 -0.9283925 0 0.3716012 -0.928382 0 0.3716275 -0.98103 0 0.193856 -0.9775565 0 0.2106732 -0.9150782 0 0.4032765 -0.915062 0 0.4033133 -0.681622 0 0.7317045 -0.5202335 0 0.8540241 -0.37188 0 0.9282808 -0.4057505 0 0.9139839 -0.4717632 0 0.8817254 -0.535275 0 0.8446779 -0.5958806 0 0.8030731 -0.6532535 0 0.7571393 -0.7571393 0 0.6532535 -0.8030731 0 0.5958806 -0.8030877 0 0.5958609 -0.8446779 0 0.535275 -0.8817254 0 0.4717632 -0.9139953 0 0.405725 -0.9282808 0 0.37188 -0.8540241 0 0.5202335 -0.7317045 0 0.681622 -0.4033133 0 0.915062 -0.2106732 0 0.9775565 -0.193856 0 0.98103 -0.3716012 0 0.9283925 -0.6831377 0 0.7302896 -0.9015551 0 0.4326646 -0.9971013 0 0.07608503 -0.95677 0 -0.2908459 -0.7860229 0 -0.6181976 -0.6584138 0 -0.7526561 -0.6712498 0 -0.7412313 -0.8068037 0 -0.5908198 -0.9744879 0 -0.2244404 -0.9997232 0 -0.02353042 -0.9898572 0 0.1420665 -0.9944092 0 0.1055966 -0.9994797 0 0.03225898 -0.999151 0 -0.04120022 -0.9934259 0 -0.114477 -0.9823322 0 -0.1871457 -0.9443114 0 -0.3290533 -0.9175846 0 -0.3975406 -0.8859087 0 -0.4638599 -0.8494303 0 -0.5277009 -0.8083876 0 -0.5886507 -0.7861965 0 -0.6179765 -0.877549 0 -0.4794871 -0.9561558 0 -0.2928589 -0.9941237 0 0.1082506 -0.9519397 0 0.3062858 -0.9465285 0 0.3226205 -0.9898136 0 0.1423698 -0.9740222 0 -0.2264529 -0.8254854 0 -0.5644235 -0.5644586 0 -0.8254615 -0.2264818 0 -0.9740154 0.1423399 0 -0.9898179 0.3226205 0 -0.9465285 0.3062858 0 -0.9519397 0.1082506 0 -0.9941237 -0.2928589 0 -0.9561558 -0.4794871 0 -0.877549 -0.6179765 0 -0.7861965 -0.5886507 0 -0.8083876 -0.5277009 0 -0.8494303 -0.4638599 0 -0.8859087 -0.3975406 0 -0.9175846 -0.3290533 0 -0.9443114 -0.3290627 0 -0.9443081 -0.1871752 0 -0.9823266 -0.1871457 0 -0.9823322 -0.1145071 0 -0.9934225 -0.04120022 0 -0.999151 0.03225898 0 -0.9994797 0.1055966 0 -0.9944092 0.1420665 0 -0.9898572 -0.02353042 0 -0.9997232 -0.2244404 0 -0.9744879 -0.5908198 0 -0.8068037 -0.7412313 0 -0.6712498 -0.7526713 0 -0.6583966 -0.6181976 0 -0.7860229 -0.2908738 0 -0.9567614 0.07605236 0 -0.9971039 0.4326398 0 -0.9015669 0.7302754 0 -0.683153 0.9283925 0 -0.3716012 0.928382 0 -0.3716275 0.98103 0 -0.193856 0.9775565 0 -0.2106732 0.9150782 0 -0.4032765 0.915062 0 -0.4033133 0.681622 0 -0.7317045 0.5202335 0 -0.8540241 0.37188 0 -0.9282808 0.405725 0 -0.9139953 0.4717632 0 -0.8817254 0.535275 0 -0.8446779 0.5958609 0 -0.8030877 0.6532535 0 -0.7571393 0.7571393 0 -0.6532535 0.8030731 0 -0.5958806 0.8446779 0 -0.535275 0.8817254 0 -0.4717632 0.9139839 0 -0.4057505 0.9282808 0 -0.37188 0.8540241 0 -0.5202335 0.7317045 0 -0.681622 -0.1564405 0 -0.9876874 0.0784654 0 -0.9969169 -0.309004 0 -0.9510608 -0.4539761 0 -0.8910139 -0.587767 0 -0.8090303 -0.5878015 0 -0.8090053 -0.707122 0 -0.7070915 -0.8090158 0 -0.587787 -0.8090053 0 -0.5878015 -0.8910016 0 -0.4540003 -0.8910139 0 -0.4539761 -0.9510608 0 -0.309004 -0.9876922 0 -0.1564108 -0.9876874 0 -0.1564405 -0.9876922 0 0.1564108 -0.9876874 0 0.1564405 -0.9510608 0 0.309004 -0.8910016 0 0.4540003 -0.8910139 0 0.4539761 -0.8090303 0 0.587767 -0.8090053 0 0.5878015 -0.587767 0 0.8090303 -0.5878015 0 0.8090053 -0.4539761 0 0.8910139 -0.309004 0 0.9510608 -0.1564405 0 0.9876874 -0.0784654 0 0.9969169 0.0784654 0 0.9969169 0.1564405 0 0.9876874 0.309004 0 0.9510608 0.4539761 0 0.8910139 0.587767 0 0.8090303 0.5878015 0 0.8090053 0.707122 0 0.7070915 0.8090158 0 0.587787 0.8090053 0 0.5878015 0.8910016 0 0.4540003 0.8910139 0 0.4539761 0.9510608 0 0.309004 0.9876922 0 0.1564108 0.9876874 0 0.1564405 0.9876922 0 -0.1564108 0.9876874 0 -0.1564405 0.9510608 0 -0.309004 0.8910016 0 -0.4540003 0.8910139 0 -0.4539761 0.8090303 0 -0.587767 0.8090053 0 -0.5878015 0.587767 0 -0.8090303 0.5878015 0 -0.8090053 0.4539761 0 -0.8910139 0.309004 0 -0.9510608 0.043612 0 -0.9990487 0.08716166 0 -0.9961942 -0.08716166 0 -0.9961942 -0.043612 0 -0.9990487 0.2588307 0 -0.9659227 0 1 -6.27741e-6 0.4226315 0 -0.9063016 0.4225947 0 -0.9063188 0.573571 0 -0.819156 0 1 -3.13879e-6 0.5735505 0 -0.8191702 0 1 2.88909e-6 0.7070915 0 -0.707122 0 1 -2.49375e-6 0 1 3.99148e-6 0.7660631 0 -0.6427654 0.8191459 0 -0.5735853 0.8191702 0 -0.5735505 0.8660449 0 -0.4999665 0.9063188 0 -0.4225947 0.9397026 0 -0.341993 0 1 -1.43139e-6 0.9659227 0 -0.2588307 0.9961968 0 -0.08713132 0.9961942 0 -0.08716166 0.9961968 0 0.08713132 0.9961942 0 0.08716166 0.9659227 0 0.2588307 0.9397026 0 0.341993 0.9396891 0 0.3420298 0.9063188 0 0.4225947 0 1 1.07355e-6 0.8191459 0 0.5735853 0 1 5.14539e-7 0.8191702 0 0.5735505 0.7660631 0 0.6427654 0.7070915 0 0.707122 0 1 -2.88909e-6 0 1 3.13879e-6 0.573571 0 0.819156 0.5735505 0 0.8191702 0.4226315 0 0.9063016 0.4225947 0 0.9063188 0 1 6.27741e-6 0.2588307 0 0.9659227 0.08716166 0 0.9961942 0.043612 0 0.9990487 -0.043612 0 0.9990487 -0.08716166 0 0.9961942 -0.2588307 0 0.9659227 -0.4226315 0 0.9063016 -0.4225947 0 0.9063188 -0.573571 0 0.819156 -0.5735505 0 0.8191702 -0.7070915 0 0.707122 0 1 2.49375e-6 0 1 -3.99148e-6 -0.7660631 0 0.6427654 -0.8191459 0 0.5735853 -0.8191702 0 0.5735505 -0.8660449 0 0.4999665 -0.9063188 0 0.4225947 -0.9397026 0 0.341993 0 1 1.43139e-6 -0.9659227 0 0.2588307 -0.9961968 0 0.08713132 -0.9961942 0 0.08716166 -0.9961968 0 -0.08713132 -0.9961942 0 -0.08716166 -0.9659227 0 -0.2588307 -0.9397026 0 -0.341993 -0.9396891 0 -0.3420298 -0.9063188 0 -0.4225947 0 1 -1.07355e-6 -0.8191459 0 -0.5735853 0 1 -5.14539e-7 -0.8191702 0 -0.5735505 -0.7660631 0 -0.6427654 -0.7070915 0 -0.707122 -0.573571 0 -0.819156 -0.5735505 0 -0.8191702 -0.4226315 0 -0.9063016 -0.4225947 0 -0.9063188 -0.2588307 0 -0.9659227 -0.9848124 -0.1736217 0 -0.9848178 -0.1735921 0 -0.9398113 -0.3416941 -1.52596e-4 -0.9395803 0.3423287 -1.52594e-4 -0.9398113 0.3416941 -1.22077e-4 -0.9848124 0.1736217 0 -0.9848073 0.1736513 0 -0.9395902 -0.3423017 -1.22076e-4 -0.7663141 -0.642466 -4.88312e-4 -0.7657842 -0.6430975 -4.57786e-4 -0.5002973 -0.8658534 -7.62974e-4 -0.4997171 -0.8661885 -7.32455e-4 -0.1737452 -0.9847903 -8.54535e-4 -0.1735328 -0.9848278 -8.54541e-4 0.1737748 -0.9847851 -8.85049e-4 0.1735328 -0.9848277 -9.15579e-4 0.5003334 -0.8658326 -7.01944e-4 0.4997532 -0.8661676 -7.32463e-4 0.7663267 -0.642451 -3.96744e-4 0.7657842 -0.6430976 -4.27267e-4 0.9398113 -0.3416941 -2.13635e-4 0.9395803 -0.3423287 -2.4415e-4 0.9848124 -0.1736217 0 0.9848124 0.1736217 0 0.9398113 0.3416941 -2.13635e-4 0.9395902 0.3423017 -2.13633e-4 0.7663141 0.642466 -4.27273e-4 0.7657842 0.6430976 -3.96748e-4 0.5003334 0.8658326 -7.32463e-4 0.4997532 0.8661676 -7.01943e-4 0.1737452 0.9847904 -7.93497e-4 0.1735328 0.9848278 -7.93502e-4 -0.1737748 0.9847851 -8.24011e-4 -0.1735328 0.9848278 -8.24022e-4 -0.5003334 0.8658326 -6.40905e-4 -0.4997532 0.8661676 -6.71424e-4 -0.7663418 0.6424331 -3.96752e-4 -0.7657992 0.6430796 -4.27275e-4 -2.20985e-5 0 -1 -0.9906696 0.1354117 -0.01541197 -0.9951235 0.09863644 0 -0.9999993 -2.44155e-4 -0.00125128 -0.8660247 0.5000014 0 -0.8660263 0.4999986 1.82462e-6 -0.866025 0.5000009 0 -0.999951 -0.006195306 -0.007721245 -0.9950689 -0.0991559 -0.002471983 -0.9943926 0.1051065 -0.01165813 -1.40654e-6 0 -1 -0.8660248 -0.500001 0 -0.9956673 -0.09225749 -0.01162755 -0.989026 -0.147742 0 3.03664e-6 0 -1 -0.5829806 -0.8124861 -3.05193e-5 -0.5828913 -0.8125503 0 -0.4998123 -0.8661338 3.05192e-5 -0.8660259 -0.4999992 0 -0.8660251 -0.5000006 -9.12308e-7 1.49107e-6 0 -1 -0.5000254 -0.8660107 0 -0.4119465 -0.9112081 3.05191e-5 -4.34871e-6 0 -1 -0.4120708 -0.9111519 0 2.71795e-6 0 -1 0.412034 -0.9111685 3.05188e-5 0.4119097 -0.9112247 0 0.4998123 -0.8661338 0 -3.50278e-6 0 -1 0.5000254 -0.8660107 0 0.5829114 -0.8125358 -3.05189e-5 0.8660251 -0.5000005 0 0.5830353 -0.8124468 0 2.20982e-5 0 -1 0.9906696 -0.1354117 -0.01541197 0.9951235 -0.09863644 0 0.9999993 2.44155e-4 -0.00125128 0.8660247 -0.5000013 0 0.8660264 -0.4999983 0 0.999951 0.006195306 -0.007721245 0.9950689 0.0991559 -0.002471983 0.9943926 -0.1051065 -0.01165813 0.8660247 0.5000014 0 0.9956673 0.09225749 -0.01162755 0.989026 0.147742 0 0.5830008 0.8124717 -3.05188e-5 0.5828913 0.8125503 0 0.4998123 0.8661338 3.05192e-5 0.8660264 0.4999983 0 0.8660256 0.5 3.64924e-6 0.5000254 0.8660107 0 0.4119465 0.9112081 3.05191e-5 0.4120708 0.9111519 0 -0.412034 0.9111685 3.05188e-5 -0.4119097 0.9112247 0 -0.4998123 0.8661338 0 -0.5000254 0.8660107 3.05191e-5 -0.5829114 0.8125358 -3.05189e-5 -0.5830353 0.8124468 0 0.9748455 0.222882 0 0.9748389 0.222911 0 0.9009518 0.4339193 3.0519e-5 0.9009518 -0.4339193 3.0519e-5 0.9748455 -0.222882 0 0.6235965 0.7817465 0 3.04939e-6 0 1 0.6234438 0.7818683 0 0.2223914 0.9749575 0 6.10406e-6 0 1 0.222456 0.9749428 0 -0.2223914 0.9749575 0 -0.222456 0.9749428 0 -0.6235965 0.7817465 0 -3.83148e-6 0 1 -0.6234438 0.7818683 0 -0.9009518 0.4339193 3.0519e-5 -0.9748455 0.222882 0 -3.04939e-6 0 1 -0.9748455 -0.222882 0 -0.9009518 -0.4339193 3.0519e-5 6.93496e-6 0 1 -0.6235965 -0.7817465 0 -0.6234438 -0.7818683 0 -0.2223914 -0.9749575 0 -0.222456 -0.9749428 0 0.2223914 -0.9749575 0 0.222456 -0.9749428 0 0.6235965 -0.7817465 0 0.6234438 -0.7818683 0 -0.6940107 0.04931926 0.7182736 -0.7048652 0.07956284 0.7048652 -0.6893147 0.16154 0.7062225 -0.6850357 -0.1622405 0.7102141 -0.6917296 -0.1698728 0.7018927 -0.6995212 -0.07446581 0.7107216 -0.6957151 -0.07440572 0.7144539 -0.7066749 -0.03494459 0.7066749 -0.6908279 0.1659927 0.7037069 -0.6434693 0.3000048 0.7042333 -0.6923493 0.0619226 0.7189007 -0.6239387 0.3579927 0.6946523 -0.5536231 0.4439362 0.7045724 -0.479549 0.5293564 0.6998675 -0.438069 0.5480899 0.7125259 -0.3556978 0.6145896 0.7041015 -0.3044918 0.6310187 0.7135125 -0.2138463 0.6785583 0.7027294 -0.1426165 0.7059409 0.6937637 -0.01046806 0.7136597 0.7004144 -0.007660269 0.7125279 0.7016021 0.1518958 0.6936789 0.7040861 0.2176029 0.6799404 0.7002358 0.3044576 0.6310108 0.7135342 0.3557044 0.6145706 0.7041147 0.438069 0.5480899 0.7125259 0.479549 0.5293564 0.6998675 0.5536231 0.4439362 0.7045724 0.6240552 0.3535031 0.6968433 0.6528195 0.2958593 0.6973479 0.6917296 0.1698728 0.7018927 0.6850357 0.1622405 0.7102141 0.6995212 0.07446581 0.7107216 0.6940107 -0.04931926 0.7182736 0.7048652 -0.07956284 0.7048652 0.6893147 -0.16154 0.7062225 0.6957151 0.07440572 0.7144539 0.7066749 0.03494459 0.7066749 0.6908279 -0.1659927 0.7037069 0.6434693 -0.3000048 0.7042333 0.6923493 -0.0619226 0.7189007 0.6239387 -0.3579927 0.6946523 0.5536231 -0.4439362 0.7045724 0.479549 -0.5293564 0.6998675 0.438069 -0.5480899 0.7125259 0.3556978 -0.6145896 0.7041015 0.3044642 -0.6310245 0.7135192 -9.12969e-7 0 1 0.2138463 -0.6785583 0.7027294 0.1426165 -0.7059409 0.6937637 0.01046806 -0.7136597 0.7004144 0.007660269 -0.7125279 0.7016021 -0.1518958 -0.6936789 0.7040861 -0.2176029 -0.6799404 0.7002358 -0.3044918 -0.6310187 0.7135125 -0.3556978 -0.6145896 0.7041015 -0.438069 -0.5480899 0.7125259 -0.479549 -0.5293564 0.6998675 -0.5536156 -0.4439607 0.7045629 -0.6240552 -0.3535031 0.6968433 -0.6528136 -0.2958872 0.6973416 0 1 -2.79455e-6 0 1 -1.4915e-6 0 1 1.50419e-6 0 1 -1.20677e-6 0 1 1.70491e-6 0 1 -7.69778e-7 0 1 6.10165e-6 0 1 -8.7771e-7 0 1 8.34195e-6 0 1 -1.68723e-6 0 1 -1.30552e-6 0 1 3.18297e-6 0 1 4.38855e-7 0 1 -1.41974e-6 0 1 2.95182e-6 0 1 -2.94605e-6 0 1 -2.86586e-6 0 1 2.94608e-6 0 1 -1.50419e-6 0 1 2.95202e-6 0 1 1.30506e-6 0 1 2.79455e-6 0 1 1.4915e-6 0 1 1.20677e-6 0 1 -1.70491e-6 0 1 7.69778e-7 0 1 -6.10165e-6 0 1 8.7771e-7 0 1 -8.34195e-6 0 1 1.68723e-6 0 1 1.30552e-6 0 1 -3.18297e-6 0 1 -4.38855e-7 0 1 1.41974e-6 0 1 -2.95182e-6 0 1 2.94605e-6 0 1 2.86586e-6 0 1 -2.94608e-6 0 1 -2.95202e-6 0 1 -1.30506e-6 0 1 1.23405e-6 0 1 3.18161e-7 0 1 -3.37161e-7 0 1 -1.23406e-6 0 1 -3.18159e-7 0 1 3.37162e-7 0.1761578 -0.8571672 0.4839763 0.09042823 -0.8536511 0.5129354 0.3636639 -0.9315302 0 -0.1761578 -0.8571672 0.4839763 -0.3636639 -0.9315302 0 -0.09042823 -0.8536511 0.5129354 0.3310479 -0.8571781 0.394529 0.4460394 -0.8571648 0.2575218 0.5072053 -0.8571736 0.0894224 0.5072053 -0.8571736 -0.0894224 0.4460394 -0.8571648 -0.2575218 0.3310479 -0.8571781 -0.394529 0.1761282 -0.8571718 -0.4839789 0.09042823 -0.8536511 -0.5129354 -0.1761282 -0.8571718 -0.4839789 -0.09042823 -0.8536511 -0.5129354 -0.3310479 -0.8571781 -0.394529 -0.4460394 -0.8571648 -0.2575218 -0.5072053 -0.8571736 -0.0894224 -0.5072053 -0.8571736 0.0894224 -0.4460394 -0.8571648 0.2575218 -0.3310479 -0.8571781 0.394529 -0.4894379 -0.8536552 -0.1781106 -0.1818329 -0.9315353 0.3149268 0.1818329 -0.9315353 -0.3149268 -0.3989788 -0.8536552 -0.3347967 -0.1761282 -0.8571718 0.4839789 0 -0.8571642 0.5150432 0.3989788 -0.8536552 0.3347967 0.4894353 -0.8536506 0.1781402 0.1761578 -0.8571672 -0.4839763 0 -0.8571642 -0.5150432 0 -1 -1.85833e-6 0 -1 5.13557e-7 0 -1 5.47346e-7 0 -1 7.94772e-7 0 -1 -1.47041e-6 0 -1 -2.49303e-7 0 -1 4.21147e-7 0 -1 7.13726e-7 0 -1 -1.33034e-6 0 -1 3.51026e-6 0 -1 -2.34431e-6 0 -1 -3.79669e-7 0 -1 -2.02571e-7 0 -1 6.65995e-7 0 -1 4.37897e-7 0 -1 -4.5533e-7 0 -1 1.83273e-6 0 -1 -3.75453e-7 0 -1 -3.09614e-6 0 -1 -2.74909e-7 0 -1 0 0 -1 -8.01356e-7 0 -1 5.93754e-7 0 -1 -1.44222e-6 0 -1 0 0 -1 1.35293e-7 0 -1 0 0 -1 -2.29858e-7 0 -1 1.90541e-7 0 -1 0 0 -1 1.78127e-7 0 -1 0 0 -1 -6.37211e-7 0 -1 -5.20422e-6 0 -1 1.86934e-6 0 -1 0 0 -1 -7.45722e-7 0 -1 0 0 -1 1.04127e-6 0 -1 2.6553e-7 0 -1 -3.04301e-7 0 -1 0 0 -1 0 0 -1 -3.05947e-7 0 -1 2.60318e-7 0 -1 1.55913e-7 0 -1 5.67946e-7 0 -1 -1.58238e-7 0 -1 -4.66077e-7 0 -1 7.00059e-7 0 -1 -4.38767e-7 0 -1 -1.97431e-7 0 -1 1.59362e-7 0 -1 2.38954e-7 0 -1 -4.84047e-7 0 -1 -3.43727e-6 0 -1 5.85468e-6 0 -1 -2.103e-6 0 -1 6.3387e-7 0 -1 0 0 -1 0 0 -1 -1.83884e-7 0 -1 -3.61723e-7 0 -1 1.98098e-7 0 -1 -1.56456e-7 0 -1 2.16466e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.46617e-6 0 -1 6.74127e-7 0 -1 -3.5198e-7 0 -1 1.6512e-5 0 -1 -2.2766e-7 0 -1 -8.20184e-7 0 -1 5.07419e-7 0 -1 3.7251e-7 0 -1 3.24113e-7 0 -1 -1.28384e-7 0 -1 -1.11499e-6 0 -1 -5.47344e-7 0 -1 1.4704e-6 0 -1 2.49303e-7 0 -1 4.21141e-7 0 -1 -1.17984e-6 0 -1 -7.13726e-7 0 -1 1.33034e-6 0 -1 1.17593e-6 0 -1 -2.3444e-6 0.2234616 -0.4640445 0.8571625 0.3679099 0 0.9298614 0.1167373 -0.5115076 0.8513122 -0.2234616 -0.4640445 0.8571625 -0.1167373 -0.5115076 0.8513122 -0.3679099 0 0.9298614 0.4338826 -0.9009695 0 0.222514 -0.9749296 0 -0.4338826 -0.9009695 0 -0.222514 -0.9749296 0 0.2234616 0.4640445 0.8571625 0.1167373 0.5115076 0.8513122 -0.2234616 0.4640445 0.8571625 -0.1167373 0.5115076 0.8513122 0.4026722 0.3211246 0.8571664 0.5021331 0.1145997 0.8571635 0.5021331 -0.1145997 0.8571635 0.4026722 -0.3211246 0.8571664 -0.4026722 -0.3211246 0.8571664 -0.5021331 -0.1145997 0.8571635 -0.5021331 0.1145997 0.8571635 -0.4026722 0.3211246 0.8571664 0.222514 0.9749296 0 0.4338826 0.9009695 0 -0.4338826 0.9009695 0 -0.222514 0.9749296 0 0.7818415 0.6234773 0 0.9749296 0.222514 0 0.9749296 -0.222514 0 0.7818415 -0.6234773 0 2.09509e-6 0 1 -2.09509e-6 0 1 1.80932e-6 0 1 -2.87382e-6 0 1 -0.7818415 -0.6234773 0 -0.9749296 -0.222514 0 -0.9749296 0.222514 0 -0.7818415 0.6234773 0 2.87385e-6 0 1 -1.18797e-6 0 1 -9.82017e-6 0 1 -2.20982e-5 0 -1 -0.8660251 0.5000005 0 -0.8660247 0.5000013 1.82462e-6 -0.8660264 0.4999983 0 -1.40654e-6 0 -1 -0.8660247 -0.5000014 0 -0.5830008 -0.8124717 -3.05188e-5 -0.4998123 -0.8661338 0 -0.8660264 -0.4999983 0 -0.8660256 -0.5 1.82462e-6 0.5000254 -0.8660107 3.05191e-5 0.8660247 -0.5000014 0 2.20985e-5 0 -1 0.8660263 -0.4999986 9.1231e-7 0.866025 -0.5000009 0 0.8660248 0.500001 0 0.5829806 0.8124861 -3.05193e-5 0.8660259 0.4999992 0 0.8660251 0.5000006 0 0 1 -3.64924e-6 6.93498e-6 0 1 0.3556978 0.6145896 0.7041015 0.5536156 0.4439607 0.7045629 0.6528136 0.2958872 0.6973416 -0.5536231 -0.4439362 0.7045724 -0.6528195 -0.2958593 0.6973479 2.68854e-6 0 -1 -0.8660258 0.4999995 0 -0.8660263 0.4999986 3.64924e-6 -0.8660255 0.5 0 -0.8660259 -0.499999 0 -2.42931e-6 0 -1 -0.5828768 -0.8125606 0 5.60443e-6 0 -1 -0.8660265 -0.4999983 0 -0.8660251 -0.5000006 -1.82462e-6 -1.98809e-6 0 -1 4.34872e-6 0 -1 -2.17436e-6 0 -1 0.4119212 -0.9112195 0 -2.80222e-6 0 -1 4.85862e-6 0 -1 0.8660262 -0.4999986 0 0.8660247 -0.5000013 -3.64923e-6 0.8660269 -0.4999974 0 0.8660258 0.4999995 0 0.5828768 0.8125606 0 0.4998123 0.8661338 0 0.8660269 0.4999974 0 0.8660256 0.5 5.47385e-6 -0.5000254 0.8660107 0 -3.04941e-6 0 1 6.10407e-6 0 1 3.04938e-6 0 1 6.93491e-6 0 1 -6.10411e-6 0 1 6.28828e-6 0 1 -0.6957135 -0.07443606 0.7144523 -0.3044642 0.6310245 0.7135192 -0.2138507 0.6785418 0.702744 -0.1426134 0.705926 0.6937796 0.3044642 0.6310245 0.7135192 0.4795567 0.5293345 0.6998788 0.6923334 -0.06192392 0.7189159 0.3557044 -0.6145706 0.7041147 0.3044918 -0.6310187 0.7135125 0.2138507 -0.6785418 0.702744 -0.3044576 -0.6310108 0.7135342 -0.3557044 -0.6145706 0.7041147 -0.4795567 -0.5293345 0.6998788 0.635944 -0.7717353 0 0.7819901 0.623291 9.15572e-5 0.7465028 0.6653824 1.83116e-4 0.4338579 0.9009814 1.22076e-4 0.9010525 0.4337101 3.05193e-5 0.4341037 0.9008629 0 0.2226077 0.9749081 6.10386e-5 0.2226657 0.9748949 0 -0.2593244 -0.9657903 -1.52598e-4 -0.2590737 -0.9658576 0 0.961336 -0.2753781 2.44157e-4 0.9856551 -0.1687723 2.13636e-4 1 0 1.52593e-4 0.9010525 -0.4337101 2.74674e-4 2.98191e-5 0 1 6.76105e-6 0 1 -0.7074272 -0.7067863 -1.22075e-4 0.9009814 0.4338579 2.74671e-4 0.7467185 -0.6651402 1.83116e-4 0.8148003 -0.5797418 1.22077e-4 0.9009814 -0.4338579 3.0519e-5 0.6236971 -0.7816662 2.74676e-4 -0.8659009 -0.5002156 6.10391e-5 -0.9204894 -0.3907678 -1.52596e-4 -1 -1.22078e-4 3.05194e-5 -0.707122 -0.7070915 1.52594e-4 -1 -1.22074e-4 3.05185e-5 -0.8662019 0.4996944 6.10388e-5 -0.8658668 0.5002745 -1.52597e-4 -0.5002385 0.8658878 -3.05191e-5 -0.5001795 0.8659218 -9.15577e-5 -0.2591667 0.9658326 -6.10379e-5 -0.2593244 0.9657903 0 -0.6359428 0.7717363 0 -0.6359432 0.771736 0 0.3840844 -0.9232981 9.15577e-5 0.482481 -0.8759065 3.05194e-5 0.6234773 -0.7818415 -6.10384e-5 0.2226657 -0.9748949 1.83113e-4 + + + + + + + + + + 0.41842 0.6816 0.36595 0.66181 0.391895 0.673037 0.420745 0.628405 0.391895 0.673037 0.36595 0.66181 0.445377 0.687621 0.36595 0.66181 0.41842 0.6816 0.472617 0.691195 0.36595 0.66181 0.445377 0.687621 0.5 0.692379 0.36595 0.66181 0.472617 0.691195 0.527383 0.691195 0.36595 0.66181 0.5 0.692379 0.411195 0.622189 0.420745 0.628405 0.36595 0.66181 0.40227 0.61531 0.411195 0.622189 0.36595 0.66181 0.289328 0.694466 0.40227 0.61531 0.36595 0.66181 0.139297 0.727973 0.289328 0.694466 0.36595 0.66181 0.554622 0.687621 0.36595 0.66181 0.527383 0.691195 0.58158 0.6816 0.36595 0.66181 0.554622 0.687621 0.608105 0.673037 0.36595 0.66181 0.58158 0.6816 0.63405 0.66181 0.36595 0.66181 0.608105 0.673037 0.570144 0.678603 0.36595 0.66181 0.63405 0.66181 0.572756 0.685048 0.139297 0.727973 0.36595 0.66181 0.570144 0.678603 0.572756 0.685048 0.36595 0.66181 0.430877 0.633909 0.41842 0.6816 0.391895 0.673037 0.420745 0.628405 0.430877 0.633909 0.391895 0.673037 0.452643 0.642594 0.445377 0.687621 0.41842 0.6816 0.441532 0.638652 0.452643 0.642594 0.41842 0.6816 0.430877 0.633909 0.441532 0.638652 0.41842 0.6816 0.47592 0.647939 0.472617 0.691195 0.445377 0.687621 0.464134 0.645699 0.47592 0.647939 0.445377 0.687621 0.452643 0.642594 0.464134 0.645699 0.445377 0.687621 0.5 0.649744 0.5 0.692379 0.472617 0.691195 0.487906 0.649292 0.5 0.649744 0.472617 0.691195 0.47592 0.647939 0.487906 0.649292 0.472617 0.691195 0.512094 0.649292 0.5 0.692379 0.5 0.649744 0.527383 0.691195 0.5 0.692379 0.512094 0.649292 0.5 0.641129 0.5 0.649744 0.487906 0.649292 0.523606 0.63927 0.512094 0.649292 0.5 0.649744 0.523606 0.63927 0.5 0.649744 0.5 0.641129 0.476394 0.63927 0.487906 0.649292 0.47592 0.647939 0.476394 0.63927 0.5 0.641129 0.487906 0.649292 0.476394 0.63927 0.47592 0.647939 0.464134 0.645699 0.453618 0.63377 0.464134 0.645699 0.452643 0.642594 0.453618 0.63377 0.476394 0.63927 0.464134 0.645699 0.453618 0.63377 0.452643 0.642594 0.441532 0.638652 0.432408 0.624844 0.441532 0.638652 0.430877 0.633909 0.432408 0.624844 0.453618 0.63377 0.441532 0.638652 0.432408 0.624844 0.430877 0.633909 0.420745 0.628405 0.413352 0.612819 0.420745 0.628405 0.411195 0.622189 0.413352 0.612819 0.432408 0.624844 0.420745 0.628405 0.413352 0.612819 0.411195 0.622189 0.40227 0.61531 0.289328 0.694466 0.394005 0.607817 0.40227 0.61531 0.396874 0.5981 0.40227 0.61531 0.394005 0.607817 0.396874 0.5981 0.413352 0.612819 0.40227 0.61531 0.140457 0.727862 0.386424 0.599763 0.394005 0.607817 0.396874 0.5981 0.394005 0.607817 0.386424 0.599763 0.289328 0.694466 0.140457 0.727862 0.394005 0.607817 0.132754 0.707196 0.379548 0.591201 0.386424 0.599763 0.383239 0.581138 0.386424 0.599763 0.379548 0.591201 0.140457 0.727862 0.132754 0.707196 0.386424 0.599763 0.383239 0.581138 0.396874 0.5981 0.386424 0.599763 0.333248 0.605095 0.373388 0.582186 0.379548 0.591201 0.383239 0.581138 0.379548 0.591201 0.373388 0.582186 0.330571 0.607593 0.333248 0.605095 0.379548 0.591201 0.327461 0.610323 0.330571 0.607593 0.379548 0.591201 0.323845 0.613315 0.327461 0.610323 0.379548 0.591201 0.319635 0.616601 0.323845 0.613315 0.379548 0.591201 0.314721 0.620221 0.319635 0.616601 0.379548 0.591201 0.308965 0.624217 0.314721 0.620221 0.379548 0.591201 0.302193 0.628634 0.308965 0.624217 0.379548 0.591201 0.294182 0.633523 0.302193 0.628634 0.379548 0.591201 0.284653 0.638929 0.294182 0.633523 0.379548 0.591201 0.273243 0.644892 0.284653 0.638929 0.379548 0.591201 0.259479 0.65143 0.273243 0.644892 0.379548 0.591201 0.242742 0.658515 0.259479 0.65143 0.379548 0.591201 0.222219 0.666031 0.242742 0.658515 0.379548 0.591201 0.132754 0.707196 0.222219 0.666031 0.379548 0.591201 0.344685 0.584139 0.367955 0.572772 0.373388 0.582186 0.372583 0.562393 0.373388 0.582186 0.367955 0.572772 0.345035 0.585014 0.344685 0.584139 0.373388 0.582186 0.345244 0.586047 0.345035 0.585014 0.373388 0.582186 0.345272 0.587164 0.345244 0.586047 0.373388 0.582186 0.345124 0.588337 0.345272 0.587164 0.373388 0.582186 0.344807 0.589577 0.345124 0.588337 0.373388 0.582186 0.344327 0.590879 0.344807 0.589577 0.373388 0.582186 0.34368 0.592256 0.344327 0.590879 0.373388 0.582186 0.34286 0.593718 0.34368 0.592256 0.373388 0.582186 0.341854 0.595279 0.34286 0.593718 0.373388 0.582186 0.340645 0.596951 0.341854 0.595279 0.373388 0.582186 0.33921 0.598752 0.340645 0.596951 0.373388 0.582186 0.337522 0.600697 0.33921 0.598752 0.373388 0.582186 0.335548 0.602804 0.337522 0.600697 0.373388 0.582186 0.333248 0.605095 0.335548 0.602804 0.373388 0.582186 0.372583 0.562393 0.383239 0.581138 0.373388 0.582186 0.323908 0.579438 0.363249 0.563012 0.367955 0.572772 0.364962 0.542321 0.367955 0.572772 0.363249 0.563012 0.326817 0.579302 0.323908 0.579438 0.367955 0.572772 0.329423 0.579262 0.326817 0.579302 0.367955 0.572772 0.331759 0.579311 0.329423 0.579262 0.367955 0.572772 0.333854 0.57944 0.331759 0.579311 0.367955 0.572772 0.335737 0.579648 0.333854 0.57944 0.367955 0.572772 0.337429 0.579929 0.335737 0.579648 0.367955 0.572772 0.338946 0.580286 0.337429 0.579929 0.367955 0.572772 0.340303 0.58072 0.338946 0.580286 0.367955 0.572772 0.34151 0.581239 0.340303 0.58072 0.367955 0.572772 0.342562 0.581844 0.34151 0.581239 0.367955 0.572772 0.34346 0.582547 0.342562 0.581844 0.367955 0.572772 0.34418 0.583337 0.34346 0.582547 0.367955 0.572772 0.344685 0.584139 0.34418 0.583337 0.367955 0.572772 0.364962 0.542321 0.372583 0.562393 0.367955 0.572772 0.273602 0.587993 0.359272 0.552957 0.363249 0.563012 0.360393 0.521376 0.363249 0.563012 0.359272 0.552957 0.282542 0.586041 0.273602 0.587993 0.363249 0.563012 0.290305 0.584437 0.282542 0.586041 0.363249 0.563012 0.297081 0.583127 0.290305 0.584437 0.363249 0.563012 0.303025 0.582066 0.297081 0.583127 0.363249 0.563012 0.30826 0.581219 0.303025 0.582066 0.363249 0.563012 0.31289 0.580555 0.30826 0.581219 0.363249 0.563012 0.316997 0.58005 0.31289 0.580555 0.363249 0.563012 0.32065 0.579683 0.316997 0.58005 0.363249 0.563012 0.323908 0.579438 0.32065 0.579683 0.363249 0.563012 0.360393 0.521376 0.364962 0.542321 0.363249 0.563012 0.109044 0.591111 0.356022 0.542657 0.359272 0.552957 0.358871 0.5 0.359272 0.552957 0.356022 0.542657 0.220382 0.600791 0.109044 0.591111 0.359272 0.552957 0.237063 0.596655 0.220382 0.600791 0.359272 0.552957 0.251195 0.593215 0.237063 0.596655 0.359272 0.552957 0.263251 0.590359 0.251195 0.593215 0.359272 0.552957 0.273602 0.587993 0.263251 0.590359 0.359272 0.552957 0.358871 0.5 0.360393 0.521376 0.359272 0.552957 0.356022 0.457343 0.356022 0.542657 0.353497 0.53216 0.10606 0.554725 0.353497 0.53216 0.356022 0.542657 0.359272 0.447043 0.356022 0.542657 0.356022 0.457343 0.358871 0.5 0.356022 0.542657 0.359272 0.447043 0.109044 0.591111 0.10606 0.554725 0.356022 0.542657 0.353497 0.46784 0.353497 0.53216 0.351695 0.521519 0.10606 0.554725 0.351695 0.521519 0.353497 0.53216 0.356022 0.457343 0.353497 0.53216 0.353497 0.46784 0.351695 0.478481 0.351695 0.521519 0.350615 0.510783 0.104616 0.518251 0.350615 0.510783 0.351695 0.521519 0.353497 0.46784 0.351695 0.521519 0.351695 0.478481 0.10606 0.554725 0.104616 0.518251 0.351695 0.521519 0.350615 0.489217 0.350615 0.510783 0.350256 0.5 0.104616 0.518251 0.350256 0.5 0.350615 0.510783 0.351695 0.478481 0.350615 0.510783 0.350615 0.489217 0.104616 0.481749 0.350615 0.489217 0.350256 0.5 0.104616 0.518251 0.104616 0.481749 0.350256 0.5 0.10606 0.445275 0.351695 0.478481 0.350615 0.489217 0.104616 0.481749 0.10606 0.445275 0.350615 0.489217 0.10606 0.445275 0.353497 0.46784 0.351695 0.478481 0.109044 0.408889 0.356022 0.457343 0.353497 0.46784 0.10606 0.445275 0.109044 0.408889 0.353497 0.46784 0.109044 0.408889 0.359272 0.447043 0.356022 0.457343 0.320682 0.42032 0.363249 0.436988 0.359272 0.447043 0.360393 0.478624 0.359272 0.447043 0.363249 0.436988 0.317033 0.419954 0.320682 0.42032 0.359272 0.447043 0.31293 0.41945 0.317033 0.419954 0.359272 0.447043 0.308305 0.418788 0.31293 0.41945 0.359272 0.447043 0.303074 0.417942 0.308305 0.418788 0.359272 0.447043 0.297136 0.416884 0.303074 0.417942 0.359272 0.447043 0.290366 0.415575 0.297136 0.416884 0.359272 0.447043 0.282609 0.413973 0.290366 0.415575 0.359272 0.447043 0.273677 0.412023 0.282609 0.413973 0.359272 0.447043 0.263334 0.409661 0.273677 0.412023 0.359272 0.447043 0.251287 0.406807 0.263334 0.409661 0.359272 0.447043 0.237166 0.40337 0.251287 0.406807 0.359272 0.447043 0.220499 0.399238 0.237166 0.40337 0.359272 0.447043 0.200685 0.394277 0.220499 0.399238 0.359272 0.447043 0.109044 0.408889 0.200685 0.394277 0.359272 0.447043 0.360393 0.478624 0.358871 0.5 0.359272 0.447043 0.344685 0.415861 0.367955 0.427228 0.363249 0.436988 0.364962 0.457679 0.363249 0.436988 0.367955 0.427228 0.34418 0.416663 0.344685 0.415861 0.363249 0.436988 0.343461 0.417452 0.34418 0.416663 0.363249 0.436988 0.342563 0.418156 0.343461 0.417452 0.363249 0.436988 0.341513 0.41876 0.342563 0.418156 0.363249 0.436988 0.340308 0.419278 0.341513 0.41876 0.363249 0.436988 0.338953 0.419712 0.340308 0.419278 0.363249 0.436988 0.337438 0.420069 0.338953 0.419712 0.363249 0.436988 0.335749 0.420351 0.337438 0.420069 0.363249 0.436988 0.333869 0.420558 0.335749 0.420351 0.363249 0.436988 0.331777 0.420689 0.333869 0.420558 0.363249 0.436988 0.329444 0.420738 0.331777 0.420689 0.363249 0.436988 0.326842 0.420699 0.329444 0.420738 0.363249 0.436988 0.323936 0.420564 0.326842 0.420699 0.363249 0.436988 0.320682 0.42032 0.323936 0.420564 0.363249 0.436988 0.364962 0.457679 0.360393 0.478624 0.363249 0.436988 0.335529 0.397176 0.373388 0.417814 0.367955 0.427228 0.372583 0.437607 0.367955 0.427228 0.373388 0.417814 0.337506 0.399285 0.335529 0.397176 0.367955 0.427228 0.339197 0.401232 0.337506 0.399285 0.367955 0.427228 0.340634 0.403035 0.339197 0.401232 0.367955 0.427228 0.341846 0.404709 0.340634 0.403035 0.367955 0.427228 0.342854 0.406272 0.341846 0.404709 0.367955 0.427228 0.343676 0.407736 0.342854 0.406272 0.367955 0.427228 0.344324 0.409115 0.343676 0.407736 0.367955 0.427228 0.344806 0.410418 0.344324 0.409115 0.367955 0.427228 0.345123 0.411659 0.344806 0.410418 0.367955 0.427228 0.345272 0.412835 0.345123 0.411659 0.367955 0.427228 0.345244 0.413952 0.345272 0.412835 0.367955 0.427228 0.345036 0.414985 0.345244 0.413952 0.367955 0.427228 0.344685 0.415861 0.345036 0.414985 0.367955 0.427228 0.372583 0.437607 0.364962 0.457679 0.367955 0.427228 0.294114 0.366437 0.379548 0.408799 0.373388 0.417814 0.372583 0.437607 0.373388 0.417814 0.379548 0.408799 0.302132 0.371328 0.294114 0.366437 0.373388 0.417814 0.308912 0.375748 0.302132 0.371328 0.373388 0.417814 0.314675 0.379746 0.308912 0.375748 0.373388 0.417814 0.319595 0.383368 0.314675 0.379746 0.373388 0.417814 0.32381 0.386657 0.319595 0.383368 0.373388 0.417814 0.32743 0.389651 0.32381 0.386657 0.373388 0.417814 0.330545 0.392383 0.32743 0.389651 0.373388 0.417814 0.333225 0.394883 0.330545 0.392383 0.373388 0.417814 0.335529 0.397176 0.333225 0.394883 0.373388 0.417814 0.137969 0.278376 0.386424 0.400237 0.379548 0.408799 0.383239 0.418862 0.379548 0.408799 0.386424 0.400237 0.242623 0.341438 0.137969 0.278376 0.379548 0.408799 0.259378 0.348525 0.242623 0.341438 0.379548 0.408799 0.273155 0.355064 0.259378 0.348525 0.379548 0.408799 0.284576 0.361028 0.273155 0.355064 0.379548 0.408799 0.294114 0.366437 0.284576 0.361028 0.379548 0.408799 0.383239 0.418862 0.372583 0.437607 0.379548 0.408799 0.153909 0.243778 0.394005 0.392183 0.386424 0.400237 0.383239 0.418862 0.386424 0.400237 0.394005 0.392183 0.137969 0.278376 0.153909 0.243778 0.386424 0.400237 0.153909 0.243778 0.40227 0.38469 0.394005 0.392183 0.396874 0.4019 0.394005 0.392183 0.40227 0.38469 0.396874 0.4019 0.383239 0.418862 0.394005 0.392183 0.176021 0.210251 0.411195 0.377811 0.40227 0.38469 0.396874 0.4019 0.40227 0.38469 0.411195 0.377811 0.153909 0.243778 0.176021 0.210251 0.40227 0.38469 0.176021 0.210251 0.420745 0.371595 0.411195 0.377811 0.413352 0.387181 0.411195 0.377811 0.420745 0.371595 0.413352 0.387181 0.396874 0.4019 0.411195 0.377811 0.207285 0.17842 0.430877 0.366091 0.420745 0.371595 0.413352 0.387181 0.420745 0.371595 0.430877 0.366091 0.176021 0.210251 0.207285 0.17842 0.420745 0.371595 0.252422 0.149394 0.441532 0.361348 0.430877 0.366091 0.432408 0.375156 0.430877 0.366091 0.441532 0.361348 0.207285 0.17842 0.252422 0.149394 0.430877 0.366091 0.432408 0.375156 0.413352 0.387181 0.430877 0.366091 0.252422 0.149394 0.452643 0.357406 0.441532 0.361348 0.432408 0.375156 0.441532 0.361348 0.452643 0.357406 0.318057 0.12516 0.464134 0.354301 0.452643 0.357406 0.453618 0.36623 0.452643 0.357406 0.464134 0.354301 0.252422 0.149394 0.318057 0.12516 0.452643 0.357406 0.453618 0.36623 0.432408 0.375156 0.452643 0.357406 0.318057 0.12516 0.47592 0.352061 0.464134 0.354301 0.453618 0.36623 0.464134 0.354301 0.47592 0.352061 0.482857 0.3062 0.487906 0.350708 0.47592 0.352061 0.476394 0.36073 0.47592 0.352061 0.487906 0.350708 0.481306 0.30288 0.482857 0.3062 0.47592 0.352061 0.479653 0.299107 0.481306 0.30288 0.47592 0.352061 0.477878 0.294812 0.479653 0.299107 0.47592 0.352061 0.475962 0.289913 0.477878 0.294812 0.47592 0.352061 0.473879 0.28431 0.475962 0.289913 0.47592 0.352061 0.471594 0.277881 0.473879 0.28431 0.47592 0.352061 0.469067 0.270476 0.471594 0.277881 0.47592 0.352061 0.466243 0.261909 0.469067 0.270476 0.47592 0.352061 0.46305 0.251956 0.466243 0.261909 0.47592 0.352061 0.45939 0.240337 0.46305 0.251956 0.47592 0.352061 0.455122 0.226705 0.45939 0.240337 0.47592 0.352061 0.450037 0.210623 0.455122 0.226705 0.47592 0.352061 0.443805 0.19155 0.450037 0.210623 0.47592 0.352061 0.318057 0.12516 0.443805 0.19155 0.47592 0.352061 0.476394 0.36073 0.453618 0.36623 0.47592 0.352061 0.5 0.324989 0.5 0.350256 0.487906 0.350708 0.476394 0.36073 0.487906 0.350708 0.5 0.350256 0.498904 0.324907 0.5 0.324989 0.487906 0.350708 0.497711 0.324634 0.498904 0.324907 0.487906 0.350708 0.496518 0.324169 0.497711 0.324634 0.487906 0.350708 0.495351 0.323529 0.496518 0.324169 0.487906 0.350708 0.494192 0.322717 0.495351 0.323529 0.487906 0.350708 0.493042 0.321738 0.494192 0.322717 0.487906 0.350708 0.491888 0.320587 0.493042 0.321738 0.487906 0.350708 0.49072 0.319251 0.491888 0.320587 0.487906 0.350708 0.489527 0.317717 0.49072 0.319251 0.487906 0.350708 0.488301 0.315965 0.489527 0.317717 0.487906 0.350708 0.487031 0.313968 0.488301 0.315965 0.487906 0.350708 0.485707 0.311699 0.487031 0.313968 0.487906 0.350708 0.48432 0.309124 0.485707 0.311699 0.487906 0.350708 0.482857 0.3062 0.48432 0.309124 0.487906 0.350708 0.501097 0.324907 0.5 0.350256 0.5 0.324989 0.514305 0.311678 0.515693 0.309099 0.5 0.350256 0.512094 0.350708 0.5 0.350256 0.515693 0.309099 0.51298 0.31395 0.514305 0.311678 0.5 0.350256 0.511709 0.31595 0.51298 0.31395 0.5 0.350256 0.510482 0.317705 0.511709 0.31595 0.5 0.350256 0.509288 0.319242 0.510482 0.317705 0.5 0.350256 0.508119 0.320579 0.509288 0.319242 0.5 0.350256 0.506963 0.321733 0.508119 0.320579 0.5 0.350256 0.505813 0.322713 0.506963 0.321733 0.5 0.350256 0.504653 0.323527 0.505813 0.322713 0.5 0.350256 0.503483 0.324169 0.504653 0.323527 0.5 0.350256 0.50229 0.324633 0.503483 0.324169 0.5 0.350256 0.501097 0.324907 0.50229 0.324633 0.5 0.350256 0.5 0.358871 0.5 0.350256 0.512094 0.350708 0.5 0.358871 0.476394 0.36073 0.5 0.350256 0.5 0.05292898 0.5 0.324989 0.498904 0.324907 0.535128 0.05317091 0.501097 0.324907 0.5 0.324989 0.535128 0.05317091 0.5 0.324989 0.5 0.05292898 0.5 0.05292898 0.498904 0.324907 0.497711 0.324634 0.5 0.05292898 0.497711 0.324634 0.496518 0.324169 0.5 0.05292898 0.496518 0.324169 0.495351 0.323529 0.464872 0.05317091 0.495351 0.323529 0.494192 0.322717 0.464872 0.05317091 0.5 0.05292898 0.495351 0.323529 0.464872 0.05317091 0.494192 0.322717 0.493042 0.321738 0.464872 0.05317091 0.493042 0.321738 0.491888 0.320587 0.464872 0.05317091 0.491888 0.320587 0.49072 0.319251 0.431408 0.05385088 0.49072 0.319251 0.489527 0.317717 0.431408 0.05385088 0.464872 0.05317091 0.49072 0.319251 0.431408 0.05385088 0.489527 0.317717 0.488301 0.315965 0.431408 0.05385088 0.488301 0.315965 0.487031 0.313968 0.431408 0.05385088 0.487031 0.313968 0.485707 0.311699 0.400963 0.05484998 0.485707 0.311699 0.48432 0.309124 0.400963 0.05484998 0.431408 0.05385088 0.485707 0.311699 0.400963 0.05484998 0.48432 0.309124 0.482857 0.3062 0.400963 0.05484998 0.482857 0.3062 0.481306 0.30288 0.400963 0.05484998 0.481306 0.30288 0.479653 0.299107 0.374421 0.0559979 0.479653 0.299107 0.477878 0.294812 0.374421 0.0559979 0.400963 0.05484998 0.479653 0.299107 0.374421 0.0559979 0.477878 0.294812 0.475962 0.289913 0.374421 0.0559979 0.475962 0.289913 0.473879 0.28431 0.352196 0.05711793 0.473879 0.28431 0.471594 0.277881 0.352196 0.05711793 0.374421 0.0559979 0.473879 0.28431 0.352196 0.05711793 0.471594 0.277881 0.469067 0.270476 0.334361 0.05804389 0.469067 0.270476 0.466243 0.261909 0.334361 0.05804389 0.352196 0.05711793 0.469067 0.270476 0.334361 0.05804389 0.466243 0.261909 0.46305 0.251956 0.320793 0.058649 0.46305 0.251956 0.45939 0.240337 0.320793 0.058649 0.334361 0.05804389 0.46305 0.251956 0.320793 0.058649 0.45939 0.240337 0.455122 0.226705 0.311296 0.05884498 0.455122 0.226705 0.450037 0.210623 0.311296 0.05884498 0.320793 0.058649 0.455122 0.226705 0.305683 0.058586 0.450037 0.210623 0.443805 0.19155 0.305683 0.058586 0.311296 0.05884498 0.450037 0.210623 0.318057 0.12516 0.435874 0.168828 0.443805 0.19155 0.303827 0.05786496 0.443805 0.19155 0.435874 0.168828 0.303827 0.05786496 0.305683 0.058586 0.443805 0.19155 0.318057 0.12516 0.42519 0.1416079 0.435874 0.168828 0.305683 0.05671089 0.435874 0.168828 0.42519 0.1416079 0.305683 0.05671089 0.303827 0.05786496 0.435874 0.168828 0.318057 0.12516 0.409538 0.108976 0.42519 0.1416079 0.311296 0.0551809 0.42519 0.1416079 0.409538 0.108976 0.311296 0.0551809 0.305683 0.05671089 0.42519 0.1416079 0.298467 0.111704 0.409538 0.108976 0.318057 0.12516 0.298467 0.111704 0.404601 0.09719598 0.409538 0.108976 0.320793 0.053357 0.409538 0.108976 0.404601 0.09719598 0.320793 0.053357 0.311296 0.0551809 0.409538 0.108976 0.228136 0.138631 0.318057 0.12516 0.252422 0.149394 0.228136 0.138631 0.298467 0.111704 0.318057 0.12516 0.18295 0.170279 0.252422 0.149394 0.207285 0.17842 0.18295 0.170279 0.228136 0.138631 0.252422 0.149394 0.18295 0.170279 0.207285 0.17842 0.176021 0.210251 0.153093 0.2044579 0.176021 0.210251 0.153909 0.243778 0.153093 0.2044579 0.18295 0.170279 0.176021 0.210251 0.132639 0.240079 0.153909 0.243778 0.137969 0.278376 0.132639 0.240079 0.153093 0.2044579 0.153909 0.243778 0.1653 0.319117 0.126354 0.313674 0.137969 0.278376 0.118225 0.276575 0.137969 0.278376 0.126354 0.313674 0.1967419 0.326279 0.1653 0.319117 0.137969 0.278376 0.222082 0.333923 0.1967419 0.326279 0.137969 0.278376 0.242623 0.341438 0.222082 0.333923 0.137969 0.278376 0.118225 0.276575 0.132639 0.240079 0.137969 0.278376 0.05599099 0.304626 0.126354 0.313674 0.1653 0.319117 0.1121 0.313201 0.118225 0.276575 0.126354 0.313674 0.054937 0.306901 0.1121 0.313201 0.126354 0.313674 0.05599099 0.304626 0.054937 0.306901 0.126354 0.313674 0.05704993 0.303026 0.1653 0.319117 0.1967419 0.326279 0.05704993 0.303026 0.05599099 0.304626 0.1653 0.319117 0.05808293 0.302169 0.1967419 0.326279 0.222082 0.333923 0.05808293 0.302169 0.05704993 0.303026 0.1967419 0.326279 0.05905896 0.302109 0.222082 0.333923 0.242623 0.341438 0.05905896 0.302109 0.05808293 0.302169 0.222082 0.333923 0.05994492 0.302888 0.242623 0.341438 0.259378 0.348525 0.05994492 0.302888 0.05905896 0.302109 0.242623 0.341438 0.05994492 0.302888 0.259378 0.348525 0.273155 0.355064 0.06070894 0.304527 0.273155 0.355064 0.284576 0.361028 0.06070894 0.304527 0.05994492 0.302888 0.273155 0.355064 0.06070894 0.304527 0.284576 0.361028 0.294114 0.366437 0.06132197 0.307023 0.294114 0.366437 0.302132 0.371328 0.06132197 0.307023 0.06070894 0.304527 0.294114 0.366437 0.06132197 0.307023 0.302132 0.371328 0.308912 0.375748 0.06175798 0.310343 0.308912 0.375748 0.314675 0.379746 0.06175798 0.310343 0.06132197 0.307023 0.308912 0.375748 0.06175798 0.310343 0.314675 0.379746 0.319595 0.383368 0.06175798 0.310343 0.319595 0.383368 0.32381 0.386657 0.06199896 0.314422 0.32381 0.386657 0.32743 0.389651 0.06199896 0.314422 0.06175798 0.310343 0.32381 0.386657 0.06199896 0.314422 0.32743 0.389651 0.330545 0.392383 0.06199896 0.314422 0.330545 0.392383 0.333225 0.394883 0.06199896 0.314422 0.333225 0.394883 0.335529 0.397176 0.06203293 0.31916 0.335529 0.397176 0.337506 0.399285 0.06203293 0.31916 0.06199896 0.314422 0.335529 0.397176 0.06203293 0.31916 0.337506 0.399285 0.339197 0.401232 0.06203293 0.31916 0.339197 0.401232 0.340634 0.403035 0.06203293 0.31916 0.340634 0.403035 0.341846 0.404709 0.06186091 0.324424 0.341846 0.404709 0.342854 0.406272 0.06186091 0.324424 0.06203293 0.31916 0.341846 0.404709 0.06186091 0.324424 0.342854 0.406272 0.343676 0.407736 0.06186091 0.324424 0.343676 0.407736 0.344324 0.409115 0.06186091 0.324424 0.344324 0.409115 0.344806 0.410418 0.06148797 0.330053 0.344806 0.410418 0.345123 0.411659 0.06148797 0.330053 0.06186091 0.324424 0.344806 0.410418 0.06148797 0.330053 0.345123 0.411659 0.345272 0.412835 0.06148797 0.330053 0.345272 0.412835 0.345244 0.413952 0.06148797 0.330053 0.345244 0.413952 0.345036 0.414985 0.06148797 0.330053 0.345036 0.414985 0.344685 0.415861 0.06093198 0.335862 0.344685 0.415861 0.34418 0.416663 0.06148797 0.330053 0.344685 0.415861 0.06093198 0.335862 0.06093198 0.335862 0.34418 0.416663 0.343461 0.417452 0.06093198 0.335862 0.343461 0.417452 0.342563 0.418156 0.06093198 0.335862 0.342563 0.418156 0.341513 0.41876 0.06021493 0.341658 0.341513 0.41876 0.340308 0.419278 0.06021493 0.341658 0.06093198 0.335862 0.341513 0.41876 0.06021493 0.341658 0.340308 0.419278 0.338953 0.419712 0.06021493 0.341658 0.338953 0.419712 0.337438 0.420069 0.06021493 0.341658 0.337438 0.420069 0.335749 0.420351 0.05936592 0.347246 0.335749 0.420351 0.333869 0.420558 0.05936592 0.347246 0.06021493 0.341658 0.335749 0.420351 0.05936592 0.347246 0.333869 0.420558 0.331777 0.420689 0.05936592 0.347246 0.331777 0.420689 0.329444 0.420738 0.05936592 0.347246 0.329444 0.420738 0.326842 0.420699 0.05841588 0.352444 0.326842 0.420699 0.323936 0.420564 0.05841588 0.352444 0.05936592 0.347246 0.326842 0.420699 0.05841588 0.352444 0.323936 0.420564 0.320682 0.42032 0.05841588 0.352444 0.320682 0.42032 0.317033 0.419954 0.05841588 0.352444 0.317033 0.419954 0.31293 0.41945 0.05739796 0.357093 0.31293 0.41945 0.308305 0.418788 0.05739796 0.357093 0.05841588 0.352444 0.31293 0.41945 0.05739796 0.357093 0.308305 0.418788 0.303074 0.417942 0.05739796 0.357093 0.303074 0.417942 0.297136 0.416884 0.05634492 0.361064 0.297136 0.416884 0.290366 0.415575 0.05634492 0.361064 0.05739796 0.357093 0.297136 0.416884 0.05634492 0.361064 0.290366 0.415575 0.282609 0.413973 0.05528599 0.364262 0.282609 0.413973 0.273677 0.412023 0.05528599 0.364262 0.05634492 0.361064 0.282609 0.413973 0.05528599 0.364262 0.273677 0.412023 0.263334 0.409661 0.05425 0.366626 0.263334 0.409661 0.251287 0.406807 0.05425 0.366626 0.05528599 0.364262 0.263334 0.409661 0.05425 0.366626 0.251287 0.406807 0.237166 0.40337 0.05325895 0.368128 0.237166 0.40337 0.220499 0.399238 0.05325895 0.368128 0.05425 0.366626 0.237166 0.40337 0.05233395 0.368768 0.220499 0.399238 0.200685 0.394277 0.05233395 0.368768 0.05325895 0.368128 0.220499 0.399238 0.109044 0.408889 0.176975 0.388339 0.200685 0.394277 0.05149191 0.368572 0.200685 0.394277 0.176975 0.388339 0.05149191 0.368572 0.05233395 0.368768 0.200685 0.394277 0.109044 0.408889 0.148377 0.381224 0.176975 0.388339 0.05074691 0.367583 0.176975 0.388339 0.148377 0.381224 0.05074691 0.367583 0.05149191 0.368572 0.176975 0.388339 0.109044 0.408889 0.113774 0.37266 0.148377 0.381224 0.05010789 0.365862 0.148377 0.381224 0.113774 0.37266 0.05010789 0.365862 0.05074691 0.367583 0.148377 0.381224 0.09362095 0.405221 0.113774 0.37266 0.109044 0.408889 0.09362095 0.405221 0.101465 0.369008 0.113774 0.37266 0.04958397 0.363475 0.113774 0.37266 0.101465 0.369008 0.04958397 0.363475 0.05010789 0.365862 0.113774 0.37266 0.09087496 0.443085 0.109044 0.408889 0.10606 0.445275 0.09087496 0.443085 0.09362095 0.405221 0.109044 0.408889 0.08954995 0.481021 0.10606 0.445275 0.104616 0.481749 0.08954995 0.481021 0.09087496 0.443085 0.10606 0.445275 0.08954995 0.481021 0.104616 0.481749 0.104616 0.518251 0.08954995 0.518979 0.104616 0.518251 0.10606 0.554725 0.08954995 0.518979 0.08954995 0.481021 0.104616 0.518251 0.09087496 0.556915 0.10606 0.554725 0.109044 0.591111 0.09087496 0.556915 0.08954995 0.518979 0.10606 0.554725 0.148292 0.618797 0.113774 0.62734 0.109044 0.591111 0.09362095 0.594779 0.109044 0.591111 0.113774 0.62734 0.176846 0.611693 0.148292 0.618797 0.109044 0.591111 0.200554 0.605755 0.176846 0.611693 0.109044 0.591111 0.220382 0.600791 0.200554 0.605755 0.109044 0.591111 0.09362095 0.594779 0.09087496 0.556915 0.109044 0.591111 0.05010789 0.634138 0.113774 0.62734 0.148292 0.618797 0.101465 0.630992 0.09362095 0.594779 0.113774 0.62734 0.04958397 0.636525 0.101465 0.630992 0.113774 0.62734 0.05010789 0.634138 0.04958397 0.636525 0.113774 0.62734 0.05074691 0.632417 0.148292 0.618797 0.176846 0.611693 0.05074691 0.632417 0.05010789 0.634138 0.148292 0.618797 0.05149191 0.631428 0.176846 0.611693 0.200554 0.605755 0.05149191 0.631428 0.05074691 0.632417 0.176846 0.611693 0.05233395 0.631232 0.200554 0.605755 0.220382 0.600791 0.05233395 0.631232 0.05149191 0.631428 0.200554 0.605755 0.05325895 0.631872 0.220382 0.600791 0.237063 0.596655 0.05325895 0.631872 0.05233395 0.631232 0.220382 0.600791 0.05325895 0.631872 0.237063 0.596655 0.251195 0.593215 0.05425 0.633374 0.251195 0.593215 0.263251 0.590359 0.05425 0.633374 0.05325895 0.631872 0.251195 0.593215 0.05425 0.633374 0.263251 0.590359 0.273602 0.587993 0.05528599 0.635738 0.273602 0.587993 0.282542 0.586041 0.05528599 0.635738 0.05425 0.633374 0.273602 0.587993 0.05528599 0.635738 0.282542 0.586041 0.290305 0.584437 0.05634492 0.638936 0.290305 0.584437 0.297081 0.583127 0.05634492 0.638936 0.05528599 0.635738 0.290305 0.584437 0.05634492 0.638936 0.297081 0.583127 0.303025 0.582066 0.05634492 0.638936 0.303025 0.582066 0.30826 0.581219 0.05739796 0.642907 0.30826 0.581219 0.31289 0.580555 0.05739796 0.642907 0.05634492 0.638936 0.30826 0.581219 0.05739796 0.642907 0.31289 0.580555 0.316997 0.58005 0.05739796 0.642907 0.316997 0.58005 0.32065 0.579683 0.05739796 0.642907 0.32065 0.579683 0.323908 0.579438 0.05841588 0.647556 0.323908 0.579438 0.326817 0.579302 0.05841588 0.647556 0.05739796 0.642907 0.323908 0.579438 0.05841588 0.647556 0.326817 0.579302 0.329423 0.579262 0.05841588 0.647556 0.329423 0.579262 0.331759 0.579311 0.05841588 0.647556 0.331759 0.579311 0.333854 0.57944 0.05936592 0.652754 0.333854 0.57944 0.335737 0.579648 0.05936592 0.652754 0.05841588 0.647556 0.333854 0.57944 0.05936592 0.652754 0.335737 0.579648 0.337429 0.579929 0.05936592 0.652754 0.337429 0.579929 0.338946 0.580286 0.05936592 0.652754 0.338946 0.580286 0.340303 0.58072 0.06021493 0.658342 0.340303 0.58072 0.34151 0.581239 0.06021493 0.658342 0.05936592 0.652754 0.340303 0.58072 0.06021493 0.658342 0.34151 0.581239 0.342562 0.581844 0.06021493 0.658342 0.342562 0.581844 0.34346 0.582547 0.06021493 0.658342 0.34346 0.582547 0.34418 0.583337 0.06021493 0.658342 0.34418 0.583337 0.344685 0.584139 0.06093198 0.664138 0.344685 0.584139 0.345035 0.585014 0.06021493 0.658342 0.344685 0.584139 0.06093198 0.664138 0.06093198 0.664138 0.345035 0.585014 0.345244 0.586047 0.06093198 0.664138 0.345244 0.586047 0.345272 0.587164 0.06093198 0.664138 0.345272 0.587164 0.345124 0.588337 0.06148797 0.669947 0.345124 0.588337 0.344807 0.589577 0.06148797 0.669947 0.06093198 0.664138 0.345124 0.588337 0.06148797 0.669947 0.344807 0.589577 0.344327 0.590879 0.06148797 0.669947 0.344327 0.590879 0.34368 0.592256 0.06148797 0.669947 0.34368 0.592256 0.34286 0.593718 0.06186091 0.675576 0.34286 0.593718 0.341854 0.595279 0.06186091 0.675576 0.06148797 0.669947 0.34286 0.593718 0.06186091 0.675576 0.341854 0.595279 0.340645 0.596951 0.06186091 0.675576 0.340645 0.596951 0.33921 0.598752 0.06186091 0.675576 0.33921 0.598752 0.337522 0.600697 0.06203293 0.68084 0.337522 0.600697 0.335548 0.602804 0.06203293 0.68084 0.06186091 0.675576 0.337522 0.600697 0.06203293 0.68084 0.335548 0.602804 0.333248 0.605095 0.06203293 0.68084 0.333248 0.605095 0.330571 0.607593 0.06203293 0.68084 0.330571 0.607593 0.327461 0.610323 0.06199896 0.685578 0.327461 0.610323 0.323845 0.613315 0.06199896 0.685578 0.06203293 0.68084 0.327461 0.610323 0.06199896 0.685578 0.323845 0.613315 0.319635 0.616601 0.06199896 0.685578 0.319635 0.616601 0.314721 0.620221 0.06175798 0.689657 0.314721 0.620221 0.308965 0.624217 0.06175798 0.689657 0.06199896 0.685578 0.314721 0.620221 0.06175798 0.689657 0.308965 0.624217 0.302193 0.628634 0.06132197 0.692977 0.302193 0.628634 0.294182 0.633523 0.06132197 0.692977 0.06175798 0.689657 0.302193 0.628634 0.06132197 0.692977 0.294182 0.633523 0.284653 0.638929 0.06070894 0.695473 0.284653 0.638929 0.273243 0.644892 0.06070894 0.695473 0.06132197 0.692977 0.284653 0.638929 0.06070894 0.695473 0.273243 0.644892 0.259479 0.65143 0.05994492 0.697112 0.259479 0.65143 0.242742 0.658515 0.05994492 0.697112 0.06070894 0.695473 0.259479 0.65143 0.05905896 0.697891 0.242742 0.658515 0.222219 0.666031 0.05905896 0.697891 0.05994492 0.697112 0.242742 0.658515 0.132754 0.707196 0.196882 0.673684 0.222219 0.666031 0.05808293 0.697831 0.222219 0.666031 0.196882 0.673684 0.05808293 0.697831 0.05905896 0.697891 0.222219 0.666031 0.132754 0.707196 0.165394 0.680865 0.196882 0.673684 0.05704993 0.696974 0.196882 0.673684 0.165394 0.680865 0.05704993 0.696974 0.05808293 0.697831 0.196882 0.673684 0.132754 0.707196 0.126354 0.686326 0.165394 0.680865 0.05599099 0.695374 0.165394 0.680865 0.126354 0.686326 0.05599099 0.695374 0.05704993 0.696974 0.165394 0.680865 0.1121 0.686799 0.126354 0.686326 0.132754 0.707196 0.054937 0.693099 0.126354 0.686326 0.1121 0.686799 0.054937 0.693099 0.05599099 0.695374 0.126354 0.686326 0.1186259 0.724637 0.132754 0.707196 0.140457 0.727862 0.107634 0.686537 0.1121 0.686799 0.132754 0.707196 0.1186259 0.724637 0.107634 0.686537 0.132754 0.707196 0.139297 0.727973 0.140457 0.727862 0.289328 0.694466 0.139297 0.727973 0.138126 0.728074 0.140457 0.727862 0.1186259 0.724637 0.140457 0.727862 0.138126 0.728074 0.283853 0.06577199 0 0.04166793 1 0 1 0.04166793 1 0 0 0.04166793 0.5 0.05103695 0.283853 0.06577199 1 0 1 0.04166793 0.5 0.05103695 1 0 0.177775 0.097413 0 0.08333098 0 0.04166793 1 0.04166793 0 0.04166793 0 0.08333098 0.283853 0.06577199 0.177775 0.097413 0 0.04166793 0.127274 0.134515 0 0.125003 0 0.08333098 1 0.08333098 0 0.08333098 0 0.125003 0.177775 0.097413 0.127274 0.134515 0 0.08333098 1 0.04166793 0 0.08333098 1 0.08333098 0.099577 0.173608 0 0.166664 0 0.125003 0.176712 0 0 0.125003 0 0.166664 0.127274 0.134515 0.099577 0.173608 0 0.125003 1 0.08333098 0 0.125003 1 0.125003 0.176712 0 1 0.125003 0 0.125003 0.08265399 0.213598 0 0.208335 0 0.166664 0 0.01679295 0 0.166664 0 0.208335 0.099577 0.173608 0.08265399 0.213598 0 0.166664 0 0.005507946 0.176712 0 0 0.166664 0 0.01044088 0 0.005507946 0 0.166664 0 0.014256 0 0.01044088 0 0.166664 0 0.01648592 0 0.014256 0 0.166664 0 0.01679295 0 0.01648592 0 0.166664 0.07157099 0.254057 0 0.25 0 0.208335 0 0.09827399 0 0.208335 0 0.25 0.08265399 0.213598 0.07157099 0.254057 0 0.208335 0 0.01503288 0 0.01679295 0 0.208335 0 0.07996296 0 0.01503288 0 0.208335 0 0.086703 0 0.07996296 0 0.208335 0 0.093059 0 0.086703 0 0.208335 0 0.09827399 0 0.093059 0 0.208335 0.06400996 0.294788 0 0.291665 0 0.25 0 0.156387 0 0.25 0 0.291665 0.07157099 0.254057 0.06400996 0.294788 0 0.25 0 0.101663 0 0.09827399 0 0.25 0 0.1034049 0 0.101663 0 0.25 0 0.106204 0 0.1034049 0 0.25 0 0.109592 0 0.106204 0 0.25 0 0.132984 0 0.109592 0 0.25 0 0.156387 0 0.132984 0 0.25 0.05876588 0.335686 0 0.333336 0 0.291665 0 0.226597 0 0.291665 0 0.333336 0.06400996 0.294788 0.05876588 0.335686 0 0.291665 0 0.179791 0 0.156387 0 0.291665 0 0.203194 0 0.179791 0 0.291665 0 0.226597 0 0.203194 0 0.291665 0.05516093 0.376689 0 0.374997 0 0.333336 0 0.322892 0 0.333336 0 0.374997 0.05876588 0.335686 0.05516093 0.376689 0 0.333336 0 0.322892 0 0.319077 0 0.333336 0 0.273404 0 0.333336 0 0.319077 0 0.25 0 0.226597 0 0.333336 0 0.273404 0 0.25 0 0.333336 0.05280488 0.41776 0 0.416669 0 0.374997 0 0.343613 0 0.374997 0 0.416669 0.05516093 0.376689 0.05280488 0.41776 0 0.374997 0 0.338841 0 0.333333 0 0.374997 0 0.327825 0 0.374997 0 0.333333 0 0.343774 0 0.338841 0 0.374997 0 0.34759 0 0.343774 0 0.374997 0 0.34982 0 0.34759 0 0.374997 0 0.350126 0 0.34982 0 0.374997 0 0.348366 0 0.350126 0 0.374997 0 0.343613 0 0.348366 0 0.374997 0 0.327825 0 0.322892 0 0.374997 0.05146998 0.458871 0 0.458332 0 0.416669 0 0.401726 0 0.416669 0 0.458332 0.05280488 0.41776 0.05146998 0.458871 0 0.416669 0 0.367016 0 0.343613 0 0.416669 0 0.390408 0 0.367016 0 0.416669 0 0.393796 0 0.390408 0 0.416669 0 0.396595 0 0.393796 0 0.416669 0 0.401726 0 0.396595 0 0.416669 0.05103695 0.5 0 0.5 0 0.458332 0 0.466317 0 0.458332 0 0.5 0.05146998 0.458871 0.05103695 0.5 0 0.458332 0 0.40694 0 0.401726 0 0.458332 0 0.413296 0 0.40694 0 0.458332 0 0.420036 0 0.413296 0 0.458332 0 0.426392 0 0.420036 0 0.458332 0 0.431608 0 0.426392 0 0.458332 0 0.434996 0 0.431608 0 0.458332 0 0.436739 0 0.434996 0 0.458332 0 0.439537 0 0.436739 0 0.458332 0 0.442925 0 0.439537 0 0.458332 0 0.466317 0 0.442925 0 0.458332 0.05146998 0.541129 0 0.541668 0 0.5 0 0.502595 0 0.5 0 0.541668 0.05103695 0.5 0.05146998 0.541129 0 0.5 0 0.488369 0 0.485528 0 0.5 0 0.466317 0 0.5 0 0.485528 0 0.492486 0 0.488369 0 0.5 0 0.497405 0 0.492486 0 0.5 0 0.502595 0 0.497405 0 0.5 0.05280488 0.58224 0 0.583331 0 0.541668 0 0.559929 0 0.541668 0 0.583331 0.05146998 0.541129 0.05280488 0.58224 0 0.541668 0 0.507514 0 0.502595 0 0.541668 0 0.511631 0 0.507514 0 0.541668 0 0.514472 0 0.511631 0 0.541668 0 0.515658 0 0.514472 0 0.541668 0 0.536526 0 0.515658 0 0.541668 0 0.559929 0 0.536526 0 0.541668 0.05516093 0.623311 0 0.625003 0 0.583331 0 0.606736 0 0.583331 0 0.625003 0.05280488 0.58224 0.05516093 0.623311 0 0.583331 0 0.583332 0 0.559929 0 0.583331 0 0.606736 0 0.583332 0 0.583331 0.05876588 0.664314 0 0.666664 0 0.625003 0 0.65018 0 0.625003 0 0.666664 0.05516093 0.623311 0.05876588 0.664314 0 0.625003 0 0.649874 0 0.651634 0 0.625003 0 0.653542 0 0.625003 0 0.651634 0 0.65018 0 0.649874 0 0.625003 0 0.630139 0 0.606736 0 0.625003 0 0.653542 0 0.630139 0 0.625003 0.06400996 0.705212 0 0.708335 0 0.666664 0 0.723742 0 0.666664 0 0.708335 0.05876588 0.664314 0.06400996 0.705212 0 0.666664 0 0.672175 0 0.666667 0 0.666664 0 0.661159 0 0.666664 0 0.666667 0 0.677108 0 0.672175 0 0.666664 0 0.680923 0 0.677108 0 0.666664 0 0.700349 0 0.680923 0 0.666664 0 0.65241 0 0.65018 0 0.666664 0 0.656226 0 0.65241 0 0.666664 0 0.661159 0 0.656226 0 0.666664 0 0.723742 0 0.700349 0 0.666664 0.07157099 0.745943 0 0.75 0 0.708335 0 0.759726 0 0.708335 0 0.75 0.06400996 0.705212 0.07157099 0.745943 0 0.708335 0 0.727129 0 0.723742 0 0.708335 0 0.729928 0 0.727129 0 0.708335 0 0.73167 0 0.729928 0 0.708335 0 0.735059 0 0.73167 0 0.708335 0 0.740274 0 0.735059 0 0.708335 0 0.746629 0 0.740274 0 0.708335 0 0.75337 0 0.746629 0 0.708335 0 0.759726 0 0.75337 0 0.708335 0.08265399 0.786402 0 0.791665 0 0.75 0 0.869859 0 0.75 0 0.791665 0.07157099 0.745943 0.08265399 0.786402 0 0.75 0 0.764941 0 0.759726 0 0.75 0 0.79965 0 0.764941 0 0.75 0 0.823053 0 0.79965 0 0.75 0 0.846456 0 0.823053 0 0.75 0 0.869859 0 0.846456 0 0.75 0.099577 0.826392 0 0.833336 0 0.791665 0 0.986875 0 0.791665 0 0.833336 0.08265399 0.786402 0.099577 0.826392 0 0.791665 0 0.893262 0 0.869859 0 0.791665 0 0.916665 0 0.893262 0 0.791665 0 0.940069 0 0.916665 0 0.791665 0 0.963472 0 0.940069 0 0.791665 0 0.986875 0 0.963472 0 0.791665 0.127274 0.865485 0 0.874997 0 0.833336 1 0.833336 0 0.833336 0 0.874997 0.099577 0.826392 0.127274 0.865485 0 0.833336 1 0.791665 0 0.833336 1 0.833336 1 0.920037 0 0.833336 1 0.791665 1 0.989721 0 0.986875 0 0.833336 1 0.931608 1 0.989721 0 0.833336 1 0.926393 1 0.931608 0 0.833336 1 0.920037 1 0.926393 0 0.833336 0.177775 0.902587 0 0.916669 0 0.874997 1 0.874997 0 0.874997 0 0.916669 0.127274 0.865485 0.177775 0.902587 0 0.874997 1 0.833336 0 0.874997 1 0.874997 0.283853 0.934228 0 0.958332 0 0.916669 1 0.916669 0 0.916669 0 0.958332 0.177775 0.902587 0.283853 0.934228 0 0.916669 1 0.874997 0 0.916669 1 0.916669 0.5 0.948963 0 1 0 0.958332 1 0.958332 0 0.958332 0 1 0.283853 0.934228 0.5 0.948963 0 0.958332 1 0.916669 0 0.958332 1 0.958332 0.716147 0.934228 0 1 0.5 0.948963 0.716147 0.934228 1 0.958332 0 1 0.5 0.939293 0.5 0.948963 0.283853 0.934228 0.680824 0.926588 0.716147 0.934228 0.5 0.948963 0.680824 0.926588 0.5 0.948963 0.5 0.939293 0.212749 0.899359 0.283853 0.934228 0.177775 0.902587 0.319176 0.926588 0.283853 0.934228 0.212749 0.899359 0.5 0.93828 0.283853 0.934228 0.319176 0.926588 0.5 0.939293 0.283853 0.934228 0.5 0.93828 0.155981 0.865736 0.177775 0.902587 0.127274 0.865485 0.212749 0.899359 0.177775 0.902587 0.155981 0.865736 0.123202 0.829465 0.127274 0.865485 0.099577 0.826392 0.155981 0.865736 0.127274 0.865485 0.123202 0.829465 0.10263 0.79193 0.099577 0.826392 0.08265399 0.786402 0.123202 0.829465 0.099577 0.826392 0.10263 0.79193 0.08892196 0.753714 0.08265399 0.786402 0.07157099 0.745943 0.10263 0.79193 0.08265399 0.786402 0.08892196 0.753714 0.07943099 0.715096 0.07157099 0.745943 0.06400996 0.705212 0.08892196 0.753714 0.07157099 0.745943 0.07943099 0.715096 0.07273697 0.676229 0.06400996 0.705212 0.05876588 0.664314 0.07943099 0.715096 0.06400996 0.705212 0.07273697 0.676229 0.06802499 0.637199 0.05876588 0.664314 0.05516093 0.623311 0.07273697 0.676229 0.05876588 0.664314 0.06802499 0.637199 0.064812 0.598064 0.05516093 0.623311 0.05280488 0.58224 0.06802499 0.637199 0.05516093 0.623311 0.064812 0.598064 0.06280499 0.558862 0.05280488 0.58224 0.05146998 0.541129 0.064812 0.598064 0.05280488 0.58224 0.06280499 0.558862 0.06183898 0.519625 0.05146998 0.541129 0.05103695 0.5 0.06280499 0.558862 0.05146998 0.541129 0.06183898 0.519625 0.06183898 0.480375 0.05103695 0.5 0.05146998 0.458871 0.06183898 0.519625 0.05103695 0.5 0.06183898 0.480375 0.06280499 0.441138 0.05146998 0.458871 0.05280488 0.41776 0.06183898 0.480375 0.05146998 0.458871 0.06280499 0.441138 0.064812 0.401936 0.05280488 0.41776 0.05516093 0.376689 0.06280499 0.441138 0.05280488 0.41776 0.064812 0.401936 0.06802499 0.362801 0.05516093 0.376689 0.05876588 0.335686 0.064812 0.401936 0.05516093 0.376689 0.06802499 0.362801 0.07273697 0.323771 0.05876588 0.335686 0.06400996 0.294788 0.06802499 0.362801 0.05876588 0.335686 0.07273697 0.323771 0.07943099 0.284904 0.06400996 0.294788 0.07157099 0.254057 0.07273697 0.323771 0.06400996 0.294788 0.07943099 0.284904 0.08892196 0.246286 0.07157099 0.254057 0.08265399 0.213598 0.07943099 0.284904 0.07157099 0.254057 0.08892196 0.246286 0.10263 0.20807 0.08265399 0.213598 0.099577 0.173608 0.08892196 0.246286 0.08265399 0.213598 0.10263 0.20807 0.123202 0.170535 0.099577 0.173608 0.127274 0.134515 0.10263 0.20807 0.099577 0.173608 0.123202 0.170535 0.155981 0.134264 0.127274 0.134515 0.177775 0.097413 0.123202 0.170535 0.127274 0.134515 0.155981 0.134264 0.212749 0.100641 0.177775 0.097413 0.283853 0.06577199 0.155981 0.134264 0.177775 0.097413 0.212749 0.100641 0.319176 0.073412 0.283853 0.06577199 0.5 0.05103695 0.212749 0.100641 0.283853 0.06577199 0.319176 0.073412 0.716147 0.06577199 0.5 0.05103695 1 0.04166793 0.5 0.0575369 0.5 0.05103695 0.716147 0.06577199 0.5 0.0575369 0.319176 0.073412 0.5 0.05103695 0.613576 0.599763 0.867246 0.707196 0.859543 0.727862 0.860703 0.727973 0.859543 0.727862 0.867246 0.707196 0.605995 0.607817 0.613576 0.599763 0.859543 0.727862 0.710673 0.694466 0.605995 0.607817 0.859543 0.727862 0.804498 0.722377 0.710673 0.694466 0.859543 0.727862 0.860703 0.727973 0.138126 0.728074 0.859543 0.727862 0.821876 0.739791 0.859543 0.727862 0.138126 0.728074 0.812187 0.724104 0.804498 0.722377 0.859543 0.727862 0.818433 0.727007 0.812187 0.724104 0.859543 0.727862 0.822504 0.730852 0.818433 0.727007 0.859543 0.727862 0.823782 0.735278 0.822504 0.730852 0.859543 0.727862 0.821876 0.739791 0.823782 0.735278 0.859543 0.727862 0.8347 0.680883 0.873646 0.686326 0.867246 0.707196 0.881374 0.724637 0.867246 0.707196 0.873646 0.686326 0.803258 0.673721 0.8347 0.680883 0.867246 0.707196 0.777918 0.666077 0.803258 0.673721 0.867246 0.707196 0.757377 0.658562 0.777918 0.666077 0.867246 0.707196 0.620452 0.591201 0.757377 0.658562 0.867246 0.707196 0.613576 0.599763 0.620452 0.591201 0.867246 0.707196 0.861874 0.728074 0.867246 0.707196 0.881374 0.724637 0.861874 0.728074 0.860703 0.727973 0.867246 0.707196 0.944009 0.695374 0.873646 0.686326 0.8347 0.680883 0.8879 0.686799 0.881374 0.724637 0.873646 0.686326 0.945063 0.693099 0.8879 0.686799 0.873646 0.686326 0.944009 0.695374 0.945063 0.693099 0.873646 0.686326 0.94295 0.696974 0.8347 0.680883 0.803258 0.673721 0.94295 0.696974 0.944009 0.695374 0.8347 0.680883 0.941917 0.697831 0.803258 0.673721 0.777918 0.666077 0.941917 0.697831 0.94295 0.696974 0.803258 0.673721 0.940941 0.697891 0.777918 0.666077 0.757377 0.658562 0.940941 0.697891 0.941917 0.697831 0.777918 0.666077 0.620452 0.591201 0.740622 0.651475 0.757377 0.658562 0.940055 0.697112 0.757377 0.658562 0.740622 0.651475 0.940055 0.697112 0.940941 0.697891 0.757377 0.658562 0.620452 0.591201 0.726845 0.644936 0.740622 0.651475 0.940055 0.697112 0.740622 0.651475 0.726845 0.644936 0.620452 0.591201 0.715424 0.638972 0.726845 0.644936 0.939291 0.695473 0.726845 0.644936 0.715424 0.638972 0.939291 0.695473 0.940055 0.697112 0.726845 0.644936 0.620452 0.591201 0.705886 0.633563 0.715424 0.638972 0.939291 0.695473 0.715424 0.638972 0.705886 0.633563 0.626612 0.582186 0.697868 0.628672 0.705886 0.633563 0.938678 0.692977 0.705886 0.633563 0.697868 0.628672 0.620452 0.591201 0.626612 0.582186 0.705886 0.633563 0.938678 0.692977 0.939291 0.695473 0.705886 0.633563 0.626612 0.582186 0.691088 0.624252 0.697868 0.628672 0.938678 0.692977 0.697868 0.628672 0.691088 0.624252 0.626612 0.582186 0.685325 0.620254 0.691088 0.624252 0.938242 0.689657 0.691088 0.624252 0.685325 0.620254 0.938242 0.689657 0.938678 0.692977 0.691088 0.624252 0.626612 0.582186 0.680405 0.616632 0.685325 0.620254 0.938242 0.689657 0.685325 0.620254 0.680405 0.616632 0.626612 0.582186 0.67619 0.613343 0.680405 0.616632 0.938242 0.689657 0.680405 0.616632 0.67619 0.613343 0.626612 0.582186 0.67257 0.610349 0.67619 0.613343 0.938001 0.685578 0.67619 0.613343 0.67257 0.610349 0.938001 0.685578 0.938242 0.689657 0.67619 0.613343 0.626612 0.582186 0.669455 0.607617 0.67257 0.610349 0.938001 0.685578 0.67257 0.610349 0.669455 0.607617 0.626612 0.582186 0.666775 0.605117 0.669455 0.607617 0.938001 0.685578 0.669455 0.607617 0.666775 0.605117 0.626612 0.582186 0.664471 0.602824 0.666775 0.605117 0.938001 0.685578 0.666775 0.605117 0.664471 0.602824 0.632045 0.572772 0.662494 0.600715 0.664471 0.602824 0.937967 0.68084 0.664471 0.602824 0.662494 0.600715 0.626612 0.582186 0.632045 0.572772 0.664471 0.602824 0.937967 0.68084 0.938001 0.685578 0.664471 0.602824 0.632045 0.572772 0.660803 0.598768 0.662494 0.600715 0.937967 0.68084 0.662494 0.600715 0.660803 0.598768 0.632045 0.572772 0.659366 0.596965 0.660803 0.598768 0.937967 0.68084 0.660803 0.598768 0.659366 0.596965 0.632045 0.572772 0.658154 0.595291 0.659366 0.596965 0.937967 0.68084 0.659366 0.596965 0.658154 0.595291 0.632045 0.572772 0.657146 0.593728 0.658154 0.595291 0.938139 0.675576 0.658154 0.595291 0.657146 0.593728 0.938139 0.675576 0.937967 0.68084 0.658154 0.595291 0.632045 0.572772 0.656324 0.592264 0.657146 0.593728 0.938139 0.675576 0.657146 0.593728 0.656324 0.592264 0.632045 0.572772 0.655676 0.590885 0.656324 0.592264 0.938139 0.675576 0.656324 0.592264 0.655676 0.590885 0.632045 0.572772 0.655194 0.589582 0.655676 0.590885 0.938139 0.675576 0.655676 0.590885 0.655194 0.589582 0.632045 0.572772 0.654877 0.588341 0.655194 0.589582 0.938512 0.669947 0.655194 0.589582 0.654877 0.588341 0.938512 0.669947 0.938139 0.675576 0.655194 0.589582 0.632045 0.572772 0.654728 0.587165 0.654877 0.588341 0.938512 0.669947 0.654877 0.588341 0.654728 0.587165 0.632045 0.572772 0.654756 0.586048 0.654728 0.587165 0.938512 0.669947 0.654728 0.587165 0.654756 0.586048 0.632045 0.572772 0.654964 0.585015 0.654756 0.586048 0.938512 0.669947 0.654756 0.586048 0.654964 0.585015 0.632045 0.572772 0.655315 0.584139 0.654964 0.585015 0.938512 0.669947 0.654964 0.585015 0.655315 0.584139 0.636751 0.563012 0.65582 0.583337 0.655315 0.584139 0.939068 0.664138 0.655315 0.584139 0.65582 0.583337 0.632045 0.572772 0.636751 0.563012 0.655315 0.584139 0.938512 0.669947 0.655315 0.584139 0.939068 0.664138 0.636751 0.563012 0.656539 0.582548 0.65582 0.583337 0.939068 0.664138 0.65582 0.583337 0.656539 0.582548 0.636751 0.563012 0.657437 0.581844 0.656539 0.582548 0.939068 0.664138 0.656539 0.582548 0.657437 0.581844 0.636751 0.563012 0.658487 0.58124 0.657437 0.581844 0.939068 0.664138 0.657437 0.581844 0.658487 0.58124 0.636751 0.563012 0.659692 0.580722 0.658487 0.58124 0.939785 0.658342 0.658487 0.58124 0.659692 0.580722 0.939785 0.658342 0.939068 0.664138 0.658487 0.58124 0.636751 0.563012 0.661047 0.580288 0.659692 0.580722 0.939785 0.658342 0.659692 0.580722 0.661047 0.580288 0.636751 0.563012 0.662562 0.579931 0.661047 0.580288 0.939785 0.658342 0.661047 0.580288 0.662562 0.579931 0.636751 0.563012 0.664251 0.579649 0.662562 0.579931 0.939785 0.658342 0.662562 0.579931 0.664251 0.579649 0.636751 0.563012 0.666131 0.579442 0.664251 0.579649 0.940634 0.652754 0.664251 0.579649 0.666131 0.579442 0.940634 0.652754 0.939785 0.658342 0.664251 0.579649 0.636751 0.563012 0.668223 0.579311 0.666131 0.579442 0.940634 0.652754 0.666131 0.579442 0.668223 0.579311 0.636751 0.563012 0.670556 0.579262 0.668223 0.579311 0.940634 0.652754 0.668223 0.579311 0.670556 0.579262 0.636751 0.563012 0.673158 0.579301 0.670556 0.579262 0.940634 0.652754 0.670556 0.579262 0.673158 0.579301 0.636751 0.563012 0.676064 0.579436 0.673158 0.579301 0.941584 0.647556 0.673158 0.579301 0.676064 0.579436 0.941584 0.647556 0.940634 0.652754 0.673158 0.579301 0.636751 0.563012 0.679318 0.57968 0.676064 0.579436 0.941584 0.647556 0.676064 0.579436 0.679318 0.57968 0.640728 0.552957 0.682967 0.580046 0.679318 0.57968 0.941584 0.647556 0.679318 0.57968 0.682967 0.580046 0.636751 0.563012 0.640728 0.552957 0.679318 0.57968 0.640728 0.552957 0.68707 0.58055 0.682967 0.580046 0.941584 0.647556 0.682967 0.580046 0.68707 0.58055 0.640728 0.552957 0.691695 0.581212 0.68707 0.58055 0.942602 0.642907 0.68707 0.58055 0.691695 0.581212 0.942602 0.642907 0.941584 0.647556 0.68707 0.58055 0.640728 0.552957 0.696926 0.582058 0.691695 0.581212 0.942602 0.642907 0.691695 0.581212 0.696926 0.582058 0.640728 0.552957 0.702864 0.583116 0.696926 0.582058 0.942602 0.642907 0.696926 0.582058 0.702864 0.583116 0.640728 0.552957 0.709634 0.584425 0.702864 0.583116 0.943655 0.638936 0.702864 0.583116 0.709634 0.584425 0.943655 0.638936 0.942602 0.642907 0.702864 0.583116 0.640728 0.552957 0.717391 0.586027 0.709634 0.584425 0.943655 0.638936 0.709634 0.584425 0.717391 0.586027 0.640728 0.552957 0.726323 0.587977 0.717391 0.586027 0.944714 0.635738 0.717391 0.586027 0.726323 0.587977 0.944714 0.635738 0.943655 0.638936 0.717391 0.586027 0.640728 0.552957 0.736666 0.590339 0.726323 0.587977 0.944714 0.635738 0.726323 0.587977 0.736666 0.590339 0.640728 0.552957 0.748713 0.593193 0.736666 0.590339 0.94575 0.633374 0.736666 0.590339 0.748713 0.593193 0.94575 0.633374 0.944714 0.635738 0.736666 0.590339 0.640728 0.552957 0.762834 0.59663 0.748713 0.593193 0.94575 0.633374 0.748713 0.593193 0.762834 0.59663 0.640728 0.552957 0.779501 0.600762 0.762834 0.59663 0.946741 0.631872 0.762834 0.59663 0.779501 0.600762 0.946741 0.631872 0.94575 0.633374 0.762834 0.59663 0.640728 0.552957 0.799315 0.605723 0.779501 0.600762 0.947666 0.631232 0.779501 0.600762 0.799315 0.605723 0.947666 0.631232 0.946741 0.631872 0.779501 0.600762 0.890956 0.591111 0.823025 0.611661 0.799315 0.605723 0.948508 0.631428 0.799315 0.605723 0.823025 0.611661 0.640728 0.552957 0.890956 0.591111 0.799315 0.605723 0.948508 0.631428 0.947666 0.631232 0.799315 0.605723 0.890956 0.591111 0.851623 0.618776 0.823025 0.611661 0.949253 0.632417 0.823025 0.611661 0.851623 0.618776 0.949253 0.632417 0.948508 0.631428 0.823025 0.611661 0.890956 0.591111 0.886226 0.62734 0.851623 0.618776 0.949892 0.634138 0.851623 0.618776 0.886226 0.62734 0.949892 0.634138 0.949253 0.632417 0.851623 0.618776 0.906379 0.594779 0.886226 0.62734 0.890956 0.591111 0.906379 0.594779 0.898535 0.630992 0.886226 0.62734 0.950416 0.636525 0.886226 0.62734 0.898535 0.630992 0.950416 0.636525 0.949892 0.634138 0.886226 0.62734 0.646503 0.53216 0.89394 0.554725 0.890956 0.591111 0.909125 0.556915 0.890956 0.591111 0.89394 0.554725 0.643978 0.542657 0.646503 0.53216 0.890956 0.591111 0.640728 0.552957 0.643978 0.542657 0.890956 0.591111 0.909125 0.556915 0.906379 0.594779 0.890956 0.591111 0.649385 0.510783 0.895384 0.518251 0.89394 0.554725 0.91045 0.518979 0.89394 0.554725 0.895384 0.518251 0.648305 0.521519 0.649385 0.510783 0.89394 0.554725 0.646503 0.53216 0.648305 0.521519 0.89394 0.554725 0.91045 0.518979 0.909125 0.556915 0.89394 0.554725 0.649744 0.5 0.895384 0.481749 0.895384 0.518251 0.91045 0.518979 0.895384 0.518251 0.895384 0.481749 0.649385 0.510783 0.649744 0.5 0.895384 0.518251 0.648305 0.478481 0.89394 0.445275 0.895384 0.481749 0.91045 0.481021 0.895384 0.481749 0.89394 0.445275 0.649385 0.489217 0.648305 0.478481 0.895384 0.481749 0.649744 0.5 0.649385 0.489217 0.895384 0.481749 0.91045 0.481021 0.91045 0.518979 0.895384 0.481749 0.643978 0.457343 0.890956 0.408889 0.89394 0.445275 0.909125 0.443085 0.89394 0.445275 0.890956 0.408889 0.646503 0.46784 0.643978 0.457343 0.89394 0.445275 0.648305 0.478481 0.646503 0.46784 0.89394 0.445275 0.909125 0.443085 0.91045 0.481021 0.89394 0.445275 0.851708 0.381203 0.886226 0.37266 0.890956 0.408889 0.906379 0.405221 0.890956 0.408889 0.886226 0.37266 0.823154 0.388307 0.851708 0.381203 0.890956 0.408889 0.799446 0.394245 0.823154 0.388307 0.890956 0.408889 0.779618 0.399209 0.799446 0.394245 0.890956 0.408889 0.640728 0.447043 0.779618 0.399209 0.890956 0.408889 0.643978 0.457343 0.640728 0.447043 0.890956 0.408889 0.906379 0.405221 0.909125 0.443085 0.890956 0.408889 0.949892 0.365862 0.886226 0.37266 0.851708 0.381203 0.898535 0.369008 0.906379 0.405221 0.886226 0.37266 0.950416 0.363475 0.898535 0.369008 0.886226 0.37266 0.949892 0.365862 0.950416 0.363475 0.886226 0.37266 0.949253 0.367583 0.851708 0.381203 0.823154 0.388307 0.949253 0.367583 0.949892 0.365862 0.851708 0.381203 0.948508 0.368572 0.823154 0.388307 0.799446 0.394245 0.948508 0.368572 0.949253 0.367583 0.823154 0.388307 0.947666 0.368768 0.799446 0.394245 0.779618 0.399209 0.947666 0.368768 0.948508 0.368572 0.799446 0.394245 0.640728 0.447043 0.762937 0.403345 0.779618 0.399209 0.946741 0.368128 0.779618 0.399209 0.762937 0.403345 0.946741 0.368128 0.947666 0.368768 0.779618 0.399209 0.640728 0.447043 0.748805 0.406785 0.762937 0.403345 0.946741 0.368128 0.762937 0.403345 0.748805 0.406785 0.640728 0.447043 0.736749 0.409641 0.748805 0.406785 0.94575 0.366626 0.748805 0.406785 0.736749 0.409641 0.94575 0.366626 0.946741 0.368128 0.748805 0.406785 0.640728 0.447043 0.726398 0.412007 0.736749 0.409641 0.94575 0.366626 0.736749 0.409641 0.726398 0.412007 0.636751 0.436988 0.717458 0.413959 0.726398 0.412007 0.944714 0.364262 0.726398 0.412007 0.717458 0.413959 0.640728 0.447043 0.636751 0.436988 0.726398 0.412007 0.944714 0.364262 0.94575 0.366626 0.726398 0.412007 0.636751 0.436988 0.709695 0.415563 0.717458 0.413959 0.944714 0.364262 0.717458 0.413959 0.709695 0.415563 0.636751 0.436988 0.702919 0.416873 0.709695 0.415563 0.943655 0.361064 0.709695 0.415563 0.702919 0.416873 0.943655 0.361064 0.944714 0.364262 0.709695 0.415563 0.636751 0.436988 0.696975 0.417934 0.702919 0.416873 0.943655 0.361064 0.702919 0.416873 0.696975 0.417934 0.636751 0.436988 0.69174 0.418781 0.696975 0.417934 0.943655 0.361064 0.696975 0.417934 0.69174 0.418781 0.636751 0.436988 0.68711 0.419445 0.69174 0.418781 0.942602 0.357093 0.69174 0.418781 0.68711 0.419445 0.942602 0.357093 0.943655 0.361064 0.69174 0.418781 0.636751 0.436988 0.683003 0.41995 0.68711 0.419445 0.942602 0.357093 0.68711 0.419445 0.683003 0.41995 0.636751 0.436988 0.67935 0.420317 0.683003 0.41995 0.942602 0.357093 0.683003 0.41995 0.67935 0.420317 0.636751 0.436988 0.676092 0.420562 0.67935 0.420317 0.942602 0.357093 0.67935 0.420317 0.676092 0.420562 0.632045 0.427228 0.673183 0.420698 0.676092 0.420562 0.941584 0.352444 0.676092 0.420562 0.673183 0.420698 0.636751 0.436988 0.632045 0.427228 0.676092 0.420562 0.941584 0.352444 0.942602 0.357093 0.676092 0.420562 0.632045 0.427228 0.670577 0.420738 0.673183 0.420698 0.941584 0.352444 0.673183 0.420698 0.670577 0.420738 0.632045 0.427228 0.668241 0.420689 0.670577 0.420738 0.941584 0.352444 0.670577 0.420738 0.668241 0.420689 0.632045 0.427228 0.666146 0.42056 0.668241 0.420689 0.941584 0.352444 0.668241 0.420689 0.666146 0.42056 0.632045 0.427228 0.664263 0.420352 0.666146 0.42056 0.940634 0.347246 0.666146 0.42056 0.664263 0.420352 0.940634 0.347246 0.941584 0.352444 0.666146 0.42056 0.632045 0.427228 0.662571 0.420071 0.664263 0.420352 0.940634 0.347246 0.664263 0.420352 0.662571 0.420071 0.632045 0.427228 0.661054 0.419714 0.662571 0.420071 0.940634 0.347246 0.662571 0.420071 0.661054 0.419714 0.632045 0.427228 0.659697 0.41928 0.661054 0.419714 0.940634 0.347246 0.661054 0.419714 0.659697 0.41928 0.632045 0.427228 0.65849 0.418761 0.659697 0.41928 0.939785 0.341658 0.659697 0.41928 0.65849 0.418761 0.939785 0.341658 0.940634 0.347246 0.659697 0.41928 0.632045 0.427228 0.657438 0.418156 0.65849 0.418761 0.939785 0.341658 0.65849 0.418761 0.657438 0.418156 0.632045 0.427228 0.65654 0.417453 0.657438 0.418156 0.939785 0.341658 0.657438 0.418156 0.65654 0.417453 0.632045 0.427228 0.65582 0.416663 0.65654 0.417453 0.939785 0.341658 0.65654 0.417453 0.65582 0.416663 0.632045 0.427228 0.655315 0.415861 0.65582 0.416663 0.939785 0.341658 0.65582 0.416663 0.655315 0.415861 0.626612 0.417814 0.654965 0.414986 0.655315 0.415861 0.939068 0.335862 0.655315 0.415861 0.654965 0.414986 0.632045 0.427228 0.626612 0.417814 0.655315 0.415861 0.939785 0.341658 0.655315 0.415861 0.939068 0.335862 0.626612 0.417814 0.654756 0.413953 0.654965 0.414986 0.939068 0.335862 0.654965 0.414986 0.654756 0.413953 0.626612 0.417814 0.654728 0.412836 0.654756 0.413953 0.939068 0.335862 0.654756 0.413953 0.654728 0.412836 0.626612 0.417814 0.654876 0.411663 0.654728 0.412836 0.939068 0.335862 0.654728 0.412836 0.654876 0.411663 0.626612 0.417814 0.655193 0.410423 0.654876 0.411663 0.938512 0.330053 0.654876 0.411663 0.655193 0.410423 0.938512 0.330053 0.939068 0.335862 0.654876 0.411663 0.626612 0.417814 0.655673 0.409121 0.655193 0.410423 0.938512 0.330053 0.655193 0.410423 0.655673 0.409121 0.626612 0.417814 0.65632 0.407744 0.655673 0.409121 0.938512 0.330053 0.655673 0.409121 0.65632 0.407744 0.626612 0.417814 0.65714 0.406282 0.65632 0.407744 0.938512 0.330053 0.65632 0.407744 0.65714 0.406282 0.626612 0.417814 0.658146 0.404721 0.65714 0.406282 0.938139 0.324424 0.65714 0.406282 0.658146 0.404721 0.938139 0.324424 0.938512 0.330053 0.65714 0.406282 0.626612 0.417814 0.659355 0.403049 0.658146 0.404721 0.938139 0.324424 0.658146 0.404721 0.659355 0.403049 0.626612 0.417814 0.66079 0.401248 0.659355 0.403049 0.938139 0.324424 0.659355 0.403049 0.66079 0.401248 0.626612 0.417814 0.662478 0.399303 0.66079 0.401248 0.938139 0.324424 0.66079 0.401248 0.662478 0.399303 0.626612 0.417814 0.664452 0.397196 0.662478 0.399303 0.937967 0.31916 0.662478 0.399303 0.664452 0.397196 0.937967 0.31916 0.938139 0.324424 0.662478 0.399303 0.626612 0.417814 0.666752 0.394905 0.664452 0.397196 0.937967 0.31916 0.664452 0.397196 0.666752 0.394905 0.620452 0.408799 0.669429 0.392407 0.666752 0.394905 0.937967 0.31916 0.666752 0.394905 0.669429 0.392407 0.626612 0.417814 0.620452 0.408799 0.666752 0.394905 0.620452 0.408799 0.672539 0.389677 0.669429 0.392407 0.937967 0.31916 0.669429 0.392407 0.672539 0.389677 0.620452 0.408799 0.676155 0.386685 0.672539 0.389677 0.938001 0.314422 0.672539 0.389677 0.676155 0.386685 0.938001 0.314422 0.937967 0.31916 0.672539 0.389677 0.620452 0.408799 0.680365 0.383399 0.676155 0.386685 0.938001 0.314422 0.676155 0.386685 0.680365 0.383399 0.620452 0.408799 0.685279 0.379779 0.680365 0.383399 0.938001 0.314422 0.680365 0.383399 0.685279 0.379779 0.620452 0.408799 0.691035 0.375783 0.685279 0.379779 0.938242 0.310343 0.685279 0.379779 0.691035 0.375783 0.938242 0.310343 0.938001 0.314422 0.685279 0.379779 0.620452 0.408799 0.697807 0.371366 0.691035 0.375783 0.938242 0.310343 0.691035 0.375783 0.697807 0.371366 0.620452 0.408799 0.705818 0.366477 0.697807 0.371366 0.938678 0.307023 0.697807 0.371366 0.705818 0.366477 0.938678 0.307023 0.938242 0.310343 0.697807 0.371366 0.620452 0.408799 0.715347 0.361071 0.705818 0.366477 0.938678 0.307023 0.705818 0.366477 0.715347 0.361071 0.620452 0.408799 0.726757 0.355108 0.715347 0.361071 0.939291 0.304527 0.715347 0.361071 0.726757 0.355108 0.939291 0.304527 0.938678 0.307023 0.715347 0.361071 0.620452 0.408799 0.740521 0.34857 0.726757 0.355108 0.939291 0.304527 0.726757 0.355108 0.740521 0.34857 0.620452 0.408799 0.757258 0.341485 0.740521 0.34857 0.940055 0.302888 0.740521 0.34857 0.757258 0.341485 0.940055 0.302888 0.939291 0.304527 0.740521 0.34857 0.620452 0.408799 0.777781 0.333969 0.757258 0.341485 0.940941 0.302109 0.757258 0.341485 0.777781 0.333969 0.940941 0.302109 0.940055 0.302888 0.757258 0.341485 0.862031 0.278376 0.803118 0.326316 0.777781 0.333969 0.941917 0.302169 0.777781 0.333969 0.803118 0.326316 0.620452 0.408799 0.862031 0.278376 0.777781 0.333969 0.941917 0.302169 0.940941 0.302109 0.777781 0.333969 0.862031 0.278376 0.834606 0.319135 0.803118 0.326316 0.94295 0.303026 0.803118 0.326316 0.834606 0.319135 0.94295 0.303026 0.941917 0.302169 0.803118 0.326316 0.862031 0.278376 0.873646 0.313674 0.834606 0.319135 0.944009 0.304626 0.834606 0.319135 0.873646 0.313674 0.944009 0.304626 0.94295 0.303026 0.834606 0.319135 0.881775 0.276575 0.873646 0.313674 0.862031 0.278376 0.881775 0.276575 0.8879 0.313201 0.873646 0.313674 0.945063 0.306901 0.873646 0.313674 0.8879 0.313201 0.945063 0.306901 0.944009 0.304626 0.873646 0.313674 0.605995 0.392183 0.846091 0.243778 0.862031 0.278376 0.867361 0.240079 0.862031 0.278376 0.846091 0.243778 0.613576 0.400237 0.605995 0.392183 0.862031 0.278376 0.620452 0.408799 0.613576 0.400237 0.862031 0.278376 0.867361 0.240079 0.881775 0.276575 0.862031 0.278376 0.588805 0.377811 0.823979 0.210251 0.846091 0.243778 0.846907 0.2044579 0.846091 0.243778 0.823979 0.210251 0.59773 0.38469 0.588805 0.377811 0.846091 0.243778 0.605995 0.392183 0.59773 0.38469 0.846091 0.243778 0.846907 0.2044579 0.867361 0.240079 0.846091 0.243778 0.579255 0.371595 0.792715 0.17842 0.823979 0.210251 0.846907 0.2044579 0.823979 0.210251 0.792715 0.17842 0.588805 0.377811 0.579255 0.371595 0.823979 0.210251 0.558468 0.361348 0.747578 0.149394 0.792715 0.17842 0.81705 0.170279 0.792715 0.17842 0.747578 0.149394 0.569123 0.366091 0.558468 0.361348 0.792715 0.17842 0.579255 0.371595 0.569123 0.366091 0.792715 0.17842 0.81705 0.170279 0.846907 0.2044579 0.792715 0.17842 0.535866 0.354301 0.681943 0.12516 0.747578 0.149394 0.771864 0.138631 0.747578 0.149394 0.681943 0.12516 0.547357 0.357406 0.535866 0.354301 0.747578 0.149394 0.558468 0.361348 0.547357 0.357406 0.747578 0.149394 0.771864 0.138631 0.81705 0.170279 0.747578 0.149394 0.574844 0.1415269 0.590462 0.108976 0.681943 0.12516 0.701533 0.111704 0.681943 0.12516 0.590462 0.108976 0.564171 0.168705 0.574844 0.1415269 0.681943 0.12516 0.556237 0.191425 0.564171 0.168705 0.681943 0.12516 0.549999 0.210511 0.556237 0.191425 0.681943 0.12516 0.52408 0.352061 0.549999 0.210511 0.681943 0.12516 0.535866 0.354301 0.52408 0.352061 0.681943 0.12516 0.701533 0.111704 0.771864 0.138631 0.681943 0.12516 0.688704 0.0551809 0.590462 0.108976 0.574844 0.1415269 0.595399 0.09719598 0.701533 0.111704 0.590462 0.108976 0.679207 0.053357 0.595399 0.09719598 0.590462 0.108976 0.688704 0.0551809 0.679207 0.053357 0.590462 0.108976 0.694317 0.05671089 0.574844 0.1415269 0.564171 0.168705 0.694317 0.05671089 0.688704 0.0551809 0.574844 0.1415269 0.696173 0.05786496 0.564171 0.168705 0.556237 0.191425 0.696173 0.05786496 0.694317 0.05671089 0.564171 0.168705 0.694317 0.058586 0.556237 0.191425 0.549999 0.210511 0.694317 0.058586 0.696173 0.05786496 0.556237 0.191425 0.52408 0.352061 0.544909 0.2266049 0.549999 0.210511 0.688704 0.05884498 0.549999 0.210511 0.544909 0.2266049 0.688704 0.05884498 0.694317 0.058586 0.549999 0.210511 0.52408 0.352061 0.540637 0.240248 0.544909 0.2266049 0.688704 0.05884498 0.544909 0.2266049 0.540637 0.240248 0.52408 0.352061 0.536975 0.251876 0.540637 0.240248 0.679207 0.058649 0.540637 0.240248 0.536975 0.251876 0.679207 0.058649 0.688704 0.05884498 0.540637 0.240248 0.52408 0.352061 0.53378 0.261837 0.536975 0.251876 0.679207 0.058649 0.536975 0.251876 0.53378 0.261837 0.512094 0.350708 0.530955 0.270411 0.53378 0.261837 0.665639 0.05804389 0.53378 0.261837 0.530955 0.270411 0.52408 0.352061 0.512094 0.350708 0.53378 0.261837 0.665639 0.05804389 0.679207 0.058649 0.53378 0.261837 0.512094 0.350708 0.528426 0.277823 0.530955 0.270411 0.665639 0.05804389 0.530955 0.270411 0.528426 0.277823 0.512094 0.350708 0.52614 0.284258 0.528426 0.277823 0.647804 0.05711793 0.528426 0.277823 0.52614 0.284258 0.647804 0.05711793 0.665639 0.05804389 0.528426 0.277823 0.512094 0.350708 0.524055 0.289866 0.52614 0.284258 0.647804 0.05711793 0.52614 0.284258 0.524055 0.289866 0.512094 0.350708 0.522139 0.29477 0.524055 0.289866 0.647804 0.05711793 0.524055 0.289866 0.522139 0.29477 0.512094 0.350708 0.520363 0.29907 0.522139 0.29477 0.625579 0.0559979 0.522139 0.29477 0.520363 0.29907 0.625579 0.0559979 0.647804 0.05711793 0.522139 0.29477 0.512094 0.350708 0.518709 0.302847 0.520363 0.29907 0.625579 0.0559979 0.520363 0.29907 0.518709 0.302847 0.512094 0.350708 0.517157 0.306172 0.518709 0.302847 0.625579 0.0559979 0.518709 0.302847 0.517157 0.306172 0.512094 0.350708 0.515693 0.309099 0.517157 0.306172 0.625579 0.0559979 0.517157 0.306172 0.515693 0.309099 0.599037 0.05484998 0.515693 0.309099 0.514305 0.311678 0.599037 0.05484998 0.625579 0.0559979 0.515693 0.309099 0.599037 0.05484998 0.514305 0.311678 0.51298 0.31395 0.599037 0.05484998 0.51298 0.31395 0.511709 0.31595 0.599037 0.05484998 0.511709 0.31595 0.510482 0.317705 0.568592 0.05385088 0.510482 0.317705 0.509288 0.319242 0.568592 0.05385088 0.599037 0.05484998 0.510482 0.317705 0.568592 0.05385088 0.509288 0.319242 0.508119 0.320579 0.568592 0.05385088 0.508119 0.320579 0.506963 0.321733 0.568592 0.05385088 0.506963 0.321733 0.505813 0.322713 0.535128 0.05317091 0.505813 0.322713 0.504653 0.323527 0.535128 0.05317091 0.568592 0.05385088 0.505813 0.322713 0.535128 0.05317091 0.504653 0.323527 0.503483 0.324169 0.535128 0.05317091 0.503483 0.324169 0.50229 0.324633 0.535128 0.05317091 0.50229 0.324633 0.501097 0.324907 0.523606 0.36073 0.512094 0.350708 0.52408 0.352061 0.523606 0.36073 0.5 0.358871 0.512094 0.350708 0.523606 0.36073 0.52408 0.352061 0.535866 0.354301 0.546382 0.36623 0.535866 0.354301 0.547357 0.357406 0.546382 0.36623 0.523606 0.36073 0.535866 0.354301 0.546382 0.36623 0.547357 0.357406 0.558468 0.361348 0.567592 0.375156 0.558468 0.361348 0.569123 0.366091 0.567592 0.375156 0.546382 0.36623 0.558468 0.361348 0.567592 0.375156 0.569123 0.366091 0.579255 0.371595 0.586648 0.387181 0.579255 0.371595 0.588805 0.377811 0.586648 0.387181 0.567592 0.375156 0.579255 0.371595 0.586648 0.387181 0.588805 0.377811 0.59773 0.38469 0.603126 0.4019 0.59773 0.38469 0.605995 0.392183 0.603126 0.4019 0.586648 0.387181 0.59773 0.38469 0.603126 0.4019 0.605995 0.392183 0.613576 0.400237 0.616761 0.418862 0.613576 0.400237 0.620452 0.408799 0.616761 0.418862 0.603126 0.4019 0.613576 0.400237 0.616761 0.418862 0.620452 0.408799 0.626612 0.417814 0.627417 0.437607 0.626612 0.417814 0.632045 0.427228 0.627417 0.437607 0.616761 0.418862 0.626612 0.417814 0.635038 0.457679 0.632045 0.427228 0.636751 0.436988 0.635038 0.457679 0.627417 0.437607 0.632045 0.427228 0.639607 0.478624 0.636751 0.436988 0.640728 0.447043 0.639607 0.478624 0.635038 0.457679 0.636751 0.436988 0.641129 0.5 0.640728 0.447043 0.643978 0.457343 0.641129 0.5 0.639607 0.478624 0.640728 0.447043 0.643978 0.542657 0.643978 0.457343 0.646503 0.46784 0.640728 0.552957 0.643978 0.457343 0.643978 0.542657 0.641129 0.5 0.643978 0.457343 0.640728 0.552957 0.646503 0.53216 0.646503 0.46784 0.648305 0.478481 0.643978 0.542657 0.646503 0.46784 0.646503 0.53216 0.648305 0.521519 0.648305 0.478481 0.649385 0.489217 0.646503 0.53216 0.648305 0.478481 0.648305 0.521519 0.649385 0.510783 0.649385 0.489217 0.649744 0.5 0.648305 0.521519 0.649385 0.489217 0.649385 0.510783 0.639607 0.521376 0.640728 0.552957 0.636751 0.563012 0.639607 0.521376 0.641129 0.5 0.640728 0.552957 0.635038 0.542321 0.636751 0.563012 0.632045 0.572772 0.635038 0.542321 0.639607 0.521376 0.636751 0.563012 0.627417 0.562393 0.632045 0.572772 0.626612 0.582186 0.627417 0.562393 0.635038 0.542321 0.632045 0.572772 0.627417 0.562393 0.626612 0.582186 0.620452 0.591201 0.616761 0.581138 0.620452 0.591201 0.613576 0.599763 0.616761 0.581138 0.627417 0.562393 0.620452 0.591201 0.616761 0.581138 0.613576 0.599763 0.605995 0.607817 0.710673 0.694466 0.59773 0.61531 0.605995 0.607817 0.603126 0.5981 0.605995 0.607817 0.59773 0.61531 0.603126 0.5981 0.616761 0.581138 0.605995 0.607817 0.63405 0.66181 0.588805 0.622189 0.59773 0.61531 0.603126 0.5981 0.59773 0.61531 0.588805 0.622189 0.710673 0.694466 0.63405 0.66181 0.59773 0.61531 0.608105 0.673037 0.579255 0.628405 0.588805 0.622189 0.586648 0.612819 0.588805 0.622189 0.579255 0.628405 0.63405 0.66181 0.608105 0.673037 0.588805 0.622189 0.586648 0.612819 0.603126 0.5981 0.588805 0.622189 0.608105 0.673037 0.569123 0.633909 0.579255 0.628405 0.586648 0.612819 0.579255 0.628405 0.569123 0.633909 0.58158 0.6816 0.558468 0.638652 0.569123 0.633909 0.567592 0.624844 0.569123 0.633909 0.558468 0.638652 0.608105 0.673037 0.58158 0.6816 0.569123 0.633909 0.567592 0.624844 0.586648 0.612819 0.569123 0.633909 0.554622 0.687621 0.547357 0.642594 0.558468 0.638652 0.567592 0.624844 0.558468 0.638652 0.547357 0.642594 0.58158 0.6816 0.554622 0.687621 0.558468 0.638652 0.554622 0.687621 0.535866 0.645699 0.547357 0.642594 0.546382 0.63377 0.547357 0.642594 0.535866 0.645699 0.546382 0.63377 0.567592 0.624844 0.547357 0.642594 0.527383 0.691195 0.52408 0.647939 0.535866 0.645699 0.546382 0.63377 0.535866 0.645699 0.52408 0.647939 0.554622 0.687621 0.527383 0.691195 0.535866 0.645699 0.527383 0.691195 0.512094 0.649292 0.52408 0.647939 0.523606 0.63927 0.52408 0.647939 0.512094 0.649292 0.523606 0.63927 0.546382 0.63377 0.52408 0.647939 0.781071 0.744981 0.63405 0.66181 0.710673 0.694466 0.632255 0.677647 0.63405 0.66181 0.781071 0.744981 0.625597 0.670745 0.63405 0.66181 0.632255 0.677647 0.613193 0.672899 0.611195 0.673475 0.63405 0.66181 0.606345 0.673989 0.63405 0.66181 0.611195 0.673475 0.625597 0.670745 0.613193 0.672899 0.63405 0.66181 0.602798 0.674527 0.63405 0.66181 0.606345 0.673989 0.599929 0.674948 0.63405 0.66181 0.602798 0.674527 0.596519 0.675432 0.63405 0.66181 0.599929 0.674948 0.587567 0.676623 0.63405 0.66181 0.596519 0.675432 0.570144 0.678603 0.63405 0.66181 0.587567 0.676623 0.774906 0.741315 0.781071 0.744981 0.710673 0.694466 0.771832 0.736914 0.774906 0.741315 0.710673 0.694466 0.771999 0.732394 0.771832 0.736914 0.710673 0.694466 0.775132 0.728291 0.771999 0.732394 0.710673 0.694466 0.780681 0.725017 0.775132 0.728291 0.710673 0.694466 0.787945 0.722849 0.780681 0.725017 0.710673 0.694466 0.79615 0.721949 0.787945 0.722849 0.710673 0.694466 0.804498 0.722377 0.79615 0.721949 0.710673 0.694466 0.822225 0.902587 1 0.916669 1 0.958332 0.716147 0.934228 0.822225 0.902587 1 0.958332 0.872726 0.865485 1 0.874997 1 0.916669 0.822225 0.902587 0.872726 0.865485 1 0.916669 0.900423 0.826392 1 0.833336 1 0.874997 0.872726 0.865485 0.900423 0.826392 1 0.874997 0.917346 0.786402 1 0.791665 1 0.833336 0.900423 0.826392 0.917346 0.786402 1 0.833336 0.928429 0.745943 1 0.75 1 0.791665 1 0.901726 1 0.791665 1 0.75 0.917346 0.786402 0.928429 0.745943 1 0.791665 1 0.913297 1 0.920037 1 0.791665 1 0.906941 1 0.913297 1 0.791665 1 0.901726 1 0.906941 1 0.791665 0.93599 0.705212 1 0.708335 1 0.75 1 0.843614 1 0.75 1 0.708335 0.928429 0.745943 0.93599 0.705212 1 0.75 1 0.898337 1 0.901726 1 0.75 1 0.896595 1 0.898337 1 0.75 1 0.893796 1 0.896595 1 0.75 1 0.890408 1 0.893796 1 0.75 1 0.867016 1 0.890408 1 0.75 1 0.843614 1 0.867016 1 0.75 0.941234 0.664314 1 0.666664 1 0.708335 1 0.773405 1 0.708335 1 0.666664 0.93599 0.705212 0.941234 0.664314 1 0.708335 1 0.820211 1 0.843614 1 0.708335 1 0.796808 1 0.820211 1 0.708335 1 0.773405 1 0.796808 1 0.708335 0.944839 0.623311 1 0.625003 1 0.666664 1 0.677108 1 0.666664 1 0.625003 0.941234 0.664314 0.944839 0.623311 1 0.666664 1 0.677108 1 0.680923 1 0.666664 1 0.726598 1 0.666664 1 0.680923 1 0.750001 1 0.773405 1 0.666664 1 0.726598 1 0.750001 1 0.666664 0.947195 0.58224 1 0.583331 1 0.625003 1 0.656388 1 0.625003 1 0.583331 0.944839 0.623311 0.947195 0.58224 1 0.625003 1 0.661159 1 0.666667 1 0.625003 1 0.672175 1 0.625003 1 0.666667 1 0.656226 1 0.661159 1 0.625003 1 0.65241 1 0.656226 1 0.625003 1 0.65018 1 0.65241 1 0.625003 1 0.649874 1 0.65018 1 0.625003 1 0.651634 1 0.649874 1 0.625003 1 0.656388 1 0.651634 1 0.625003 1 0.672175 1 0.677108 1 0.625003 0.94853 0.541129 1 0.541668 1 0.583331 1 0.598274 1 0.583331 1 0.541668 0.947195 0.58224 0.94853 0.541129 1 0.583331 1 0.603405 1 0.583331 1 0.598274 1 0.632985 1 0.656388 1 0.583331 1 0.609592 1 0.632985 1 0.583331 1 0.606204 1 0.609592 1 0.583331 1 0.603405 1 0.606204 1 0.583331 0.948963 0.5 1 0.5 1 0.541668 1 0.533683 1 0.541668 1 0.5 0.94853 0.541129 0.948963 0.5 1 0.541668 1 0.59306 1 0.598274 1 0.541668 1 0.586704 1 0.59306 1 0.541668 1 0.579964 1 0.586704 1 0.541668 1 0.573608 1 0.579964 1 0.541668 1 0.568392 1 0.573608 1 0.541668 1 0.565004 1 0.568392 1 0.541668 1 0.563261 1 0.565004 1 0.541668 1 0.560463 1 0.563261 1 0.541668 1 0.557075 1 0.560463 1 0.541668 1 0.533683 1 0.557075 1 0.541668 0.94853 0.458871 1 0.458332 1 0.5 1 0.486877 1 0.5 1 0.458332 0.948963 0.5 0.94853 0.458871 1 0.5 1 0.510281 1 0.533683 1 0.5 1 0.486877 1 0.510281 1 0.5 0.947195 0.41776 1 0.416669 1 0.458332 1 0.440071 1 0.458332 1 0.416669 0.94853 0.458871 0.947195 0.41776 1 0.458332 1 0.463474 1 0.486877 1 0.458332 1 0.440071 1 0.463474 1 0.458332 0.944839 0.376689 1 0.374997 1 0.416669 1 0.393265 1 0.416669 1 0.374997 0.947195 0.41776 0.944839 0.376689 1 0.416669 1 0.416668 1 0.440071 1 0.416669 1 0.393265 1 0.416668 1 0.416669 0.941234 0.335686 1 0.333336 1 0.374997 1 0.34982 1 0.374997 1 0.333336 0.944839 0.376689 0.941234 0.335686 1 0.374997 1 0.350126 1 0.348366 1 0.374997 1 0.346458 1 0.374997 1 0.348366 1 0.34982 1 0.350126 1 0.374997 1 0.369862 1 0.393265 1 0.374997 1 0.346458 1 0.369862 1 0.374997 0.93599 0.294788 1 0.291665 1 0.333336 1 0.276258 1 0.333336 1 0.291665 0.941234 0.335686 0.93599 0.294788 1 0.333336 1 0.327825 1 0.333333 1 0.333336 1 0.338841 1 0.333336 1 0.333333 1 0.322892 1 0.327825 1 0.333336 1 0.319077 1 0.322892 1 0.333336 1 0.299651 1 0.319077 1 0.333336 1 0.34759 1 0.34982 1 0.333336 1 0.343774 1 0.34759 1 0.333336 1 0.338841 1 0.343774 1 0.333336 1 0.276258 1 0.299651 1 0.333336 0.928429 0.254057 1 0.25 1 0.291665 1 0.240274 1 0.291665 1 0.25 0.93599 0.294788 0.928429 0.254057 1 0.291665 1 0.272871 1 0.276258 1 0.291665 1 0.270072 1 0.272871 1 0.291665 1 0.26833 1 0.270072 1 0.291665 1 0.264941 1 0.26833 1 0.291665 1 0.259726 1 0.264941 1 0.291665 1 0.253371 1 0.259726 1 0.291665 1 0.24663 1 0.253371 1 0.291665 1 0.240274 1 0.24663 1 0.291665 0.917346 0.213598 1 0.208335 1 0.25 1 0.179057 1 0.25 1 0.208335 0.928429 0.254057 0.917346 0.213598 1 0.25 1 0.179057 1 0.174849 1 0.25 1 0.153544 1 0.25 1 0.174849 1 0.235059 1 0.240274 1 0.25 1 0.20035 1 0.235059 1 0.25 1 0.1769469 1 0.20035 1 0.25 1 0.153544 1 0.1769469 1 0.25 0.900423 0.173608 1 0.166664 1 0.208335 1 0.164071 1 0.208335 1 0.166664 0.917346 0.213598 0.900423 0.173608 1 0.208335 1 0.1816329 1 0.179057 1 0.208335 1 0.182325 1 0.1816329 1 0.208335 1 0.181138 1 0.182325 1 0.208335 1 0.1782979 1 0.181138 1 0.208335 1 0.17418 1 0.1782979 1 0.208335 1 0.169262 1 0.17418 1 0.208335 1 0.164071 1 0.169262 1 0.208335 0.872726 0.134515 1 0.125003 1 0.166664 1 0.01648592 1 0.166664 1 0.125003 0.900423 0.173608 0.872726 0.134515 1 0.166664 1 0.006086945 0.176712 0 1 0.166664 1 0.159153 1 0.166664 0.176712 0 1 0.01132589 1 0.006086945 1 0.166664 1 0.01503288 1 0.01132589 1 0.166664 1 0.01679295 1 0.01503288 1 0.166664 1 0.01648592 1 0.01679295 1 0.166664 1 0.159153 1 0.164071 1 0.166664 0.822225 0.097413 1 0.08333098 1 0.125003 0.872726 0.134515 0.822225 0.097413 1 0.125003 1 0.005507946 1 0.125003 0.176712 0 1 0.014256 1 0.01648592 1 0.125003 1 0.01044088 1 0.014256 1 0.125003 1 0.005507946 1 0.01044088 1 0.125003 0.716147 0.06577199 1 0.04166793 1 0.08333098 0.822225 0.097413 0.716147 0.06577199 1 0.08333098 0.787251 0.100641 0.716147 0.06577199 0.822225 0.097413 0.5 0.0575369 0.716147 0.06577199 0.5 0.06171995 0.680824 0.073412 0.5 0.06171995 0.716147 0.06577199 0.680824 0.073412 0.716147 0.06577199 0.787251 0.100641 0.844019 0.134264 0.822225 0.097413 0.872726 0.134515 0.787251 0.100641 0.822225 0.097413 0.844019 0.134264 0.876798 0.170535 0.872726 0.134515 0.900423 0.173608 0.844019 0.134264 0.872726 0.134515 0.876798 0.170535 0.89737 0.20807 0.900423 0.173608 0.917346 0.213598 0.876798 0.170535 0.900423 0.173608 0.89737 0.20807 0.911078 0.246286 0.917346 0.213598 0.928429 0.254057 0.89737 0.20807 0.917346 0.213598 0.911078 0.246286 0.920569 0.284904 0.928429 0.254057 0.93599 0.294788 0.911078 0.246286 0.928429 0.254057 0.920569 0.284904 0.927263 0.323771 0.93599 0.294788 0.941234 0.335686 0.920569 0.284904 0.93599 0.294788 0.927263 0.323771 0.931975 0.362801 0.941234 0.335686 0.944839 0.376689 0.927263 0.323771 0.941234 0.335686 0.931975 0.362801 0.935188 0.401936 0.944839 0.376689 0.947195 0.41776 0.931975 0.362801 0.944839 0.376689 0.935188 0.401936 0.937195 0.441138 0.947195 0.41776 0.94853 0.458871 0.935188 0.401936 0.947195 0.41776 0.937195 0.441138 0.938161 0.480375 0.94853 0.458871 0.948963 0.5 0.937195 0.441138 0.94853 0.458871 0.938161 0.480375 0.938161 0.519625 0.948963 0.5 0.94853 0.541129 0.938161 0.480375 0.948963 0.5 0.938161 0.519625 0.937195 0.558862 0.94853 0.541129 0.947195 0.58224 0.938161 0.519625 0.94853 0.541129 0.937195 0.558862 0.935188 0.598064 0.947195 0.58224 0.944839 0.623311 0.937195 0.558862 0.947195 0.58224 0.935188 0.598064 0.931975 0.637199 0.944839 0.623311 0.941234 0.664314 0.935188 0.598064 0.944839 0.623311 0.931975 0.637199 0.927263 0.676229 0.941234 0.664314 0.93599 0.705212 0.931975 0.637199 0.941234 0.664314 0.927263 0.676229 0.920569 0.715096 0.93599 0.705212 0.928429 0.745943 0.927263 0.676229 0.93599 0.705212 0.920569 0.715096 0.911078 0.753714 0.928429 0.745943 0.917346 0.786402 0.920569 0.715096 0.928429 0.745943 0.911078 0.753714 0.89737 0.79193 0.917346 0.786402 0.900423 0.826392 0.911078 0.753714 0.917346 0.786402 0.89737 0.79193 0.876798 0.829465 0.900423 0.826392 0.872726 0.865485 0.89737 0.79193 0.900423 0.826392 0.876798 0.829465 0.844019 0.865736 0.872726 0.865485 0.822225 0.902587 0.876798 0.829465 0.872726 0.865485 0.844019 0.865736 0.787251 0.899359 0.822225 0.902587 0.716147 0.934228 0.844019 0.865736 0.822225 0.902587 0.787251 0.899359 0.787251 0.899359 0.716147 0.934228 0.680824 0.926588 0.572756 0.685048 0.138126 0.728074 0.139297 0.727973 0.14132 0.748839 0.1186259 0.724637 0.138126 0.728074 0.861874 0.728074 0.14132 0.748839 0.138126 0.728074 0.861874 0.728074 0.138126 0.728074 0.860703 0.727973 0.789642 0.74732 0.138126 0.728074 0.781071 0.744981 0.632255 0.677647 0.781071 0.744981 0.138126 0.728074 0.816766 0.743793 0.821876 0.739791 0.138126 0.728074 0.808941 0.746667 0.816766 0.743793 0.138126 0.728074 0.799427 0.74792 0.808941 0.746667 0.138126 0.728074 0.789642 0.74732 0.799427 0.74792 0.138126 0.728074 0.628939 0.678295 0.632255 0.677647 0.138126 0.728074 0.626503 0.675721 0.628939 0.678295 0.138126 0.728074 0.612171 0.681313 0.626503 0.675721 0.138126 0.728074 0.60846 0.681922 0.612171 0.681313 0.138126 0.728074 0.605456 0.6824 0.60846 0.681922 0.138126 0.728074 0.594431 0.684035 0.605456 0.6824 0.138126 0.728074 0.592691 0.684276 0.594431 0.684035 0.138126 0.728074 0.573558 0.686626 0.592691 0.684276 0.138126 0.728074 0.572756 0.685048 0.573558 0.686626 0.138126 0.728074 0.054937 0.693099 0.1121 0.686799 0.107634 0.686537 0.09800899 0.72119 0.107634 0.686537 0.1186259 0.724637 0.09800899 0.72119 0.100049 0.685463 0.107634 0.686537 0.05391293 0.690224 0.107634 0.686537 0.100049 0.685463 0.05391293 0.690224 0.054937 0.693099 0.107634 0.686537 0.14132 0.748839 0.133774 0.762299 0.1186259 0.724637 0.110552 0.760267 0.1186259 0.724637 0.133774 0.762299 0.110552 0.760267 0.09800899 0.72119 0.1186259 0.724637 0.145713 0.76903 0.155531 0.799208 0.133774 0.762299 0.128832 0.798665 0.133774 0.762299 0.155531 0.799208 0.14132 0.748839 0.145713 0.76903 0.133774 0.762299 0.128832 0.798665 0.110552 0.760267 0.133774 0.762299 0.861874 0.728074 0.155531 0.799208 0.145713 0.76903 0.128832 0.798665 0.155531 0.799208 0.159132 0.8075 0.861874 0.728074 0.159132 0.8075 0.155531 0.799208 0.861874 0.728074 0.145713 0.76903 0.14132 0.748839 0.156529 0.835892 0.128832 0.798665 0.159132 0.8075 0.18129 0.84293 0.156529 0.835892 0.159132 0.8075 0.861874 0.728074 0.18129 0.84293 0.159132 0.8075 0.09800899 0.72119 0.090806 0.682597 0.100049 0.685463 0.05294191 0.686829 0.100049 0.685463 0.090806 0.682597 0.05294191 0.686829 0.05391293 0.690224 0.100049 0.685463 0.09800899 0.72119 0.08905798 0.68177 0.090806 0.682597 0.05294191 0.686829 0.090806 0.682597 0.08905798 0.68177 0.07943099 0.715096 0.08905798 0.68177 0.09800899 0.72119 0.07273697 0.676229 0.08405297 0.678615 0.08905798 0.68177 0.05204397 0.682997 0.08905798 0.68177 0.08405297 0.678615 0.07943099 0.715096 0.07273697 0.676229 0.08905798 0.68177 0.05204397 0.682997 0.05294191 0.686829 0.08905798 0.68177 0.08892196 0.753714 0.09800899 0.72119 0.110552 0.760267 0.08892196 0.753714 0.07943099 0.715096 0.09800899 0.72119 0.10263 0.79193 0.110552 0.760267 0.128832 0.798665 0.10263 0.79193 0.08892196 0.753714 0.110552 0.760267 0.123202 0.829465 0.128832 0.798665 0.156529 0.835892 0.123202 0.829465 0.10263 0.79193 0.128832 0.798665 0.18129 0.84293 0.200902 0.870915 0.156529 0.835892 0.155981 0.865736 0.156529 0.835892 0.200902 0.870915 0.155981 0.865736 0.123202 0.829465 0.156529 0.835892 0.217254 0.874569 0.276398 0.901349 0.200902 0.870915 0.212749 0.899359 0.200902 0.870915 0.276398 0.901349 0.18129 0.84293 0.217254 0.874569 0.200902 0.870915 0.212749 0.899359 0.155981 0.865736 0.200902 0.870915 0.861874 0.728074 0.276398 0.901349 0.217254 0.874569 0.319176 0.926588 0.276398 0.901349 0.369932 0.920336 0.861874 0.728074 0.369932 0.920336 0.276398 0.901349 0.319176 0.926588 0.212749 0.899359 0.276398 0.901349 0.861874 0.728074 0.217254 0.874569 0.18129 0.84293 0.5 0.927617 0.319176 0.926588 0.369932 0.920336 0.861874 0.728074 0.5 0.927617 0.369932 0.920336 0.07273697 0.676229 0.07932698 0.673841 0.08405297 0.678615 0.05123299 0.678812 0.08405297 0.678615 0.07932698 0.673841 0.05123299 0.678812 0.05204397 0.682997 0.08405297 0.678615 0.07273697 0.676229 0.07630699 0.668519 0.07932698 0.673841 0.05052191 0.674361 0.07932698 0.673841 0.07630699 0.668519 0.05052191 0.674361 0.05123299 0.678812 0.07932698 0.673841 0.06802499 0.637199 0.074804 0.662852 0.07630699 0.668519 0.04991996 0.669729 0.07630699 0.668519 0.074804 0.662852 0.07273697 0.676229 0.06802499 0.637199 0.07630699 0.668519 0.04991996 0.669729 0.05052191 0.674361 0.07630699 0.668519 0.06802499 0.637199 0.07474899 0.657038 0.074804 0.662852 0.04943597 0.665003 0.074804 0.662852 0.07474899 0.657038 0.04943597 0.665003 0.04991996 0.669729 0.074804 0.662852 0.06802499 0.637199 0.07617199 0.651253 0.07474899 0.657038 0.04883897 0.655613 0.07474899 0.657038 0.07617199 0.651253 0.04907399 0.660269 0.04943597 0.665003 0.07474899 0.657038 0.04883897 0.655613 0.04907399 0.660269 0.07474899 0.657038 0.06802499 0.637199 0.07921898 0.645636 0.07617199 0.651253 0.0487309 0.651122 0.07617199 0.651253 0.07921898 0.645636 0.0487309 0.651122 0.04883897 0.655613 0.07617199 0.651253 0.06802499 0.637199 0.08284699 0.641496 0.07921898 0.645636 0.04875296 0.646882 0.07921898 0.645636 0.08284699 0.641496 0.04875296 0.646882 0.0487309 0.651122 0.07921898 0.645636 0.06802499 0.637199 0.07881098 0.6012 0.08284699 0.641496 0.08416998 0.640307 0.08284699 0.641496 0.07881098 0.6012 0.04875296 0.646882 0.08284699 0.641496 0.08416998 0.640307 0.064812 0.598064 0.07619595 0.56076 0.07881098 0.6012 0.09362095 0.594779 0.07881098 0.6012 0.07619595 0.56076 0.06802499 0.637199 0.064812 0.598064 0.07881098 0.6012 0.09770697 0.632429 0.07881098 0.6012 0.09362095 0.594779 0.09146296 0.635377 0.07881098 0.6012 0.09770697 0.632429 0.08416998 0.640307 0.07881098 0.6012 0.09146296 0.635377 0.06280499 0.558862 0.07493996 0.52026 0.07619595 0.56076 0.09087496 0.556915 0.07619595 0.56076 0.07493996 0.52026 0.064812 0.598064 0.06280499 0.558862 0.07619595 0.56076 0.09362095 0.594779 0.07619595 0.56076 0.09087496 0.556915 0.06183898 0.480375 0.07493996 0.47974 0.07493996 0.52026 0.08954995 0.518979 0.07493996 0.52026 0.07493996 0.47974 0.06183898 0.519625 0.06183898 0.480375 0.07493996 0.52026 0.06280499 0.558862 0.06183898 0.519625 0.07493996 0.52026 0.09087496 0.556915 0.07493996 0.52026 0.08954995 0.518979 0.06280499 0.441138 0.07619595 0.43924 0.07493996 0.47974 0.09087496 0.443085 0.07493996 0.47974 0.07619595 0.43924 0.06183898 0.480375 0.06280499 0.441138 0.07493996 0.47974 0.08954995 0.481021 0.07493996 0.47974 0.09087496 0.443085 0.08954995 0.518979 0.07493996 0.47974 0.08954995 0.481021 0.064812 0.401936 0.07881098 0.3988 0.07619595 0.43924 0.09362095 0.405221 0.07619595 0.43924 0.07881098 0.3988 0.06280499 0.441138 0.064812 0.401936 0.07619595 0.43924 0.09087496 0.443085 0.07619595 0.43924 0.09362095 0.405221 0.06802499 0.362801 0.08284699 0.358504 0.07881098 0.3988 0.08416998 0.359693 0.07881098 0.3988 0.08284699 0.358504 0.064812 0.401936 0.06802499 0.362801 0.07881098 0.3988 0.09362095 0.405221 0.07881098 0.3988 0.09770697 0.367571 0.09146296 0.364623 0.09770697 0.367571 0.07881098 0.3988 0.08416998 0.359693 0.09146296 0.364623 0.07881098 0.3988 0.06802499 0.362801 0.07921898 0.354364 0.08284699 0.358504 0.04875296 0.353118 0.08284699 0.358504 0.07921898 0.354364 0.04890292 0.357021 0.08416998 0.359693 0.08284699 0.358504 0.04875296 0.353118 0.04890292 0.357021 0.08284699 0.358504 0.06802499 0.362801 0.07617199 0.348747 0.07921898 0.354364 0.0487309 0.348878 0.07921898 0.354364 0.07617199 0.348747 0.0487309 0.348878 0.04875296 0.353118 0.07921898 0.354364 0.06802499 0.362801 0.07474899 0.342962 0.07617199 0.348747 0.04883897 0.344387 0.07617199 0.348747 0.07474899 0.342962 0.04883897 0.344387 0.0487309 0.348878 0.07617199 0.348747 0.07273697 0.323771 0.074804 0.337148 0.07474899 0.342962 0.04907399 0.339731 0.07474899 0.342962 0.074804 0.337148 0.06802499 0.362801 0.07273697 0.323771 0.07474899 0.342962 0.04907399 0.339731 0.04883897 0.344387 0.07474899 0.342962 0.07273697 0.323771 0.07630699 0.331481 0.074804 0.337148 0.04943597 0.334997 0.074804 0.337148 0.07630699 0.331481 0.04943597 0.334997 0.04907399 0.339731 0.074804 0.337148 0.07273697 0.323771 0.07932698 0.326159 0.07630699 0.331481 0.05052191 0.325639 0.07630699 0.331481 0.07932698 0.326159 0.04991996 0.330271 0.04943597 0.334997 0.07630699 0.331481 0.05052191 0.325639 0.04991996 0.330271 0.07630699 0.331481 0.07273697 0.323771 0.08405297 0.321385 0.07932698 0.326159 0.05123299 0.321188 0.07932698 0.326159 0.08405297 0.321385 0.05123299 0.321188 0.05052191 0.325639 0.07932698 0.326159 0.07943099 0.284904 0.08905798 0.31823 0.08405297 0.321385 0.05204397 0.317003 0.08405297 0.321385 0.08905798 0.31823 0.07273697 0.323771 0.07943099 0.284904 0.08405297 0.321385 0.05204397 0.317003 0.05123299 0.321188 0.08405297 0.321385 0.07943099 0.284904 0.09811198 0.278421 0.08905798 0.31823 0.090806 0.317403 0.08905798 0.31823 0.09811198 0.278421 0.05204397 0.317003 0.08905798 0.31823 0.090806 0.317403 0.08892196 0.246286 0.110849 0.238966 0.09811198 0.278421 0.118225 0.276575 0.09811198 0.278421 0.110849 0.238966 0.07943099 0.284904 0.08892196 0.246286 0.09811198 0.278421 0.107634 0.313463 0.09811198 0.278421 0.118225 0.276575 0.100049 0.314537 0.09811198 0.278421 0.107634 0.313463 0.090806 0.317403 0.09811198 0.278421 0.100049 0.314537 0.10263 0.20807 0.1294929 0.200211 0.110849 0.238966 0.132639 0.240079 0.110849 0.238966 0.1294929 0.200211 0.08892196 0.246286 0.10263 0.20807 0.110849 0.238966 0.118225 0.276575 0.110849 0.238966 0.132639 0.240079 0.123202 0.170535 0.157901 0.162672 0.1294929 0.200211 0.153093 0.2044579 0.1294929 0.200211 0.157901 0.162672 0.10263 0.20807 0.123202 0.170535 0.1294929 0.200211 0.132639 0.240079 0.1294929 0.200211 0.153093 0.2044579 0.155981 0.134264 0.203741 0.127444 0.157901 0.162672 0.228136 0.138631 0.157901 0.162672 0.203741 0.127444 0.123202 0.170535 0.155981 0.134264 0.157901 0.162672 0.18295 0.170279 0.157901 0.162672 0.228136 0.138631 0.153093 0.2044579 0.157901 0.162672 0.18295 0.170279 0.212749 0.100641 0.28232 0.09709298 0.203741 0.127444 0.298467 0.111704 0.203741 0.127444 0.28232 0.09709298 0.155981 0.134264 0.212749 0.100641 0.203741 0.127444 0.228136 0.138631 0.203741 0.127444 0.298467 0.111704 0.319176 0.073412 0.414707 0.07745295 0.28232 0.09709298 0.412081 0.07901298 0.28232 0.09709298 0.414707 0.07745295 0.212749 0.100641 0.319176 0.073412 0.28232 0.09709298 0.298467 0.111704 0.28232 0.09709298 0.404003 0.093472 0.404943 0.08705997 0.404003 0.093472 0.28232 0.09709298 0.412081 0.07901298 0.404943 0.08705997 0.28232 0.09709298 0.319176 0.073412 0.426158 0.07291197 0.414707 0.07745295 0.374421 0.04727488 0.414707 0.07745295 0.426158 0.07291197 0.352196 0.049272 0.412081 0.07901298 0.414707 0.07745295 0.374421 0.04727488 0.352196 0.049272 0.414707 0.07745295 0.319176 0.073412 0.446539 0.06857496 0.426158 0.07291197 0.400963 0.04550492 0.426158 0.07291197 0.446539 0.06857496 0.400963 0.04550492 0.374421 0.04727488 0.426158 0.07291197 0.5 0.06171995 0.471865 0.06595796 0.446539 0.06857496 0.431408 0.04410696 0.446539 0.06857496 0.471865 0.06595796 0.319176 0.073412 0.5 0.06171995 0.446539 0.06857496 0.431408 0.04410696 0.400963 0.04550492 0.446539 0.06857496 0.5 0.06171995 0.5 0.06507897 0.471865 0.06595796 0.464872 0.04320889 0.471865 0.06595796 0.5 0.06507897 0.464872 0.04320889 0.431408 0.04410696 0.471865 0.06595796 0.680824 0.073412 0.5 0.06507897 0.5 0.06171995 0.528135 0.06595796 0.5 0.06507897 0.680824 0.073412 0.5 0.04289895 0.5 0.06507897 0.528135 0.06595796 0.5 0.04289895 0.464872 0.04320889 0.5 0.06507897 0.5 0.0575369 0.5 0.06171995 0.319176 0.073412 0.5 0.927617 0.5 0.93828 0.319176 0.926588 0.630065 0.920337 0.5 0.93828 0.5 0.927617 0.680824 0.926588 0.5 0.939293 0.5 0.93828 0.630065 0.920337 0.680824 0.926588 0.5 0.93828 0.861874 0.728074 0.630065 0.920337 0.5 0.927617 0.09362095 0.405221 0.09770697 0.367571 0.101465 0.369008 0.04958397 0.363475 0.101465 0.369008 0.09770697 0.367571 0.04918098 0.360502 0.09770697 0.367571 0.09146296 0.364623 0.04918098 0.360502 0.04958397 0.363475 0.09770697 0.367571 0.101465 0.630992 0.09770697 0.632429 0.09362095 0.594779 0.04918098 0.639498 0.09770697 0.632429 0.101465 0.630992 0.04918098 0.639498 0.09146296 0.635377 0.09770697 0.632429 0.04958397 0.636525 0.04918098 0.639498 0.101465 0.630992 0.04890292 0.642979 0.08416998 0.640307 0.09146296 0.635377 0.04918098 0.639498 0.04890292 0.642979 0.09146296 0.635377 0.04890292 0.357021 0.09146296 0.364623 0.08416998 0.359693 0.04890292 0.357021 0.04918098 0.360502 0.09146296 0.364623 0.04890292 0.642979 0.04875296 0.646882 0.08416998 0.640307 0.298467 0.111704 0.404003 0.093472 0.404601 0.09719598 0.320793 0.053357 0.404601 0.09719598 0.404003 0.093472 0.334361 0.051346 0.404003 0.093472 0.404943 0.08705997 0.334361 0.051346 0.320793 0.053357 0.404003 0.093472 0.1121 0.313201 0.107634 0.313463 0.118225 0.276575 0.05391293 0.309776 0.107634 0.313463 0.1121 0.313201 0.05391293 0.309776 0.100049 0.314537 0.107634 0.313463 0.054937 0.306901 0.05391293 0.309776 0.1121 0.313201 0.05294191 0.313171 0.090806 0.317403 0.100049 0.314537 0.05391293 0.309776 0.05294191 0.313171 0.100049 0.314537 0.352196 0.049272 0.404943 0.08705997 0.412081 0.07901298 0.352196 0.049272 0.334361 0.051346 0.404943 0.08705997 0.05294191 0.313171 0.05204397 0.317003 0.090806 0.317403 0.723603 0.901349 0.787251 0.899359 0.680824 0.926588 0.630065 0.920337 0.723603 0.901349 0.680824 0.926588 0.799099 0.870914 0.844019 0.865736 0.787251 0.899359 0.723603 0.901349 0.799099 0.870914 0.787251 0.899359 0.843472 0.835892 0.876798 0.829465 0.844019 0.865736 0.799099 0.870914 0.843472 0.835892 0.844019 0.865736 0.871169 0.798665 0.89737 0.79193 0.876798 0.829465 0.843472 0.835892 0.871169 0.798665 0.876798 0.829465 0.889448 0.760267 0.911078 0.753714 0.89737 0.79193 0.871169 0.798665 0.889448 0.760267 0.89737 0.79193 0.901991 0.72119 0.920569 0.715096 0.911078 0.753714 0.889448 0.760267 0.901991 0.72119 0.911078 0.753714 0.915947 0.678615 0.927263 0.676229 0.920569 0.715096 0.910942 0.68177 0.915947 0.678615 0.920569 0.715096 0.901991 0.72119 0.910942 0.68177 0.920569 0.715096 0.925251 0.657038 0.931975 0.637199 0.927263 0.676229 0.925196 0.662852 0.925251 0.657038 0.927263 0.676229 0.923693 0.668519 0.925196 0.662852 0.927263 0.676229 0.920673 0.673841 0.923693 0.668519 0.927263 0.676229 0.915947 0.678615 0.920673 0.673841 0.927263 0.676229 0.921189 0.6012 0.935188 0.598064 0.931975 0.637199 0.917153 0.641496 0.921189 0.6012 0.931975 0.637199 0.920781 0.645636 0.917153 0.641496 0.931975 0.637199 0.923828 0.651253 0.920781 0.645636 0.931975 0.637199 0.925251 0.657038 0.923828 0.651253 0.931975 0.637199 0.923804 0.56076 0.937195 0.558862 0.935188 0.598064 0.921189 0.6012 0.923804 0.56076 0.935188 0.598064 0.92506 0.52026 0.938161 0.519625 0.937195 0.558862 0.923804 0.56076 0.92506 0.52026 0.937195 0.558862 0.92506 0.47974 0.938161 0.480375 0.938161 0.519625 0.92506 0.52026 0.92506 0.47974 0.938161 0.519625 0.92506 0.47974 0.937195 0.441138 0.938161 0.480375 0.923804 0.43924 0.935188 0.401936 0.937195 0.441138 0.92506 0.47974 0.923804 0.43924 0.937195 0.441138 0.921189 0.3988 0.931975 0.362801 0.935188 0.401936 0.923804 0.43924 0.921189 0.3988 0.935188 0.401936 0.923693 0.331481 0.927263 0.323771 0.931975 0.362801 0.925196 0.337148 0.923693 0.331481 0.931975 0.362801 0.925251 0.342962 0.925196 0.337148 0.931975 0.362801 0.923828 0.348747 0.925251 0.342962 0.931975 0.362801 0.920781 0.354364 0.923828 0.348747 0.931975 0.362801 0.917153 0.358504 0.920781 0.354364 0.931975 0.362801 0.921189 0.3988 0.917153 0.358504 0.931975 0.362801 0.910942 0.31823 0.920569 0.284904 0.927263 0.323771 0.915947 0.321385 0.910942 0.31823 0.927263 0.323771 0.920673 0.326159 0.915947 0.321385 0.927263 0.323771 0.923693 0.331481 0.920673 0.326159 0.927263 0.323771 0.901888 0.278421 0.911078 0.246286 0.920569 0.284904 0.910942 0.31823 0.901888 0.278421 0.920569 0.284904 0.889151 0.238966 0.89737 0.20807 0.911078 0.246286 0.901888 0.278421 0.889151 0.238966 0.911078 0.246286 0.870507 0.200211 0.876798 0.170535 0.89737 0.20807 0.889151 0.238966 0.870507 0.200211 0.89737 0.20807 0.842099 0.162672 0.844019 0.134264 0.876798 0.170535 0.870507 0.200211 0.842099 0.162672 0.876798 0.170535 0.796259 0.127444 0.787251 0.100641 0.844019 0.134264 0.842099 0.162672 0.796259 0.127444 0.844019 0.134264 0.71768 0.09709298 0.680824 0.073412 0.787251 0.100641 0.796259 0.127444 0.71768 0.09709298 0.787251 0.100641 0.553461 0.06857496 0.528135 0.06595796 0.680824 0.073412 0.573842 0.07291197 0.553461 0.06857496 0.680824 0.073412 0.585293 0.07745295 0.573842 0.07291197 0.680824 0.073412 0.71768 0.09709298 0.585293 0.07745295 0.680824 0.073412 0.568592 0.04410696 0.528135 0.06595796 0.553461 0.06857496 0.535128 0.04320889 0.5 0.04289895 0.528135 0.06595796 0.568592 0.04410696 0.535128 0.04320889 0.528135 0.06595796 0.599037 0.04550492 0.553461 0.06857496 0.573842 0.07291197 0.599037 0.04550492 0.568592 0.04410696 0.553461 0.06857496 0.625579 0.04727488 0.573842 0.07291197 0.585293 0.07745295 0.625579 0.04727488 0.599037 0.04550492 0.573842 0.07291197 0.587919 0.07901298 0.585293 0.07745295 0.71768 0.09709298 0.625579 0.04727488 0.585293 0.07745295 0.587919 0.07901298 0.701533 0.111704 0.71768 0.09709298 0.796259 0.127444 0.595997 0.093472 0.71768 0.09709298 0.701533 0.111704 0.595057 0.08705997 0.71768 0.09709298 0.595997 0.093472 0.587919 0.07901298 0.71768 0.09709298 0.595057 0.08705997 0.771864 0.138631 0.796259 0.127444 0.842099 0.162672 0.701533 0.111704 0.796259 0.127444 0.771864 0.138631 0.81705 0.170279 0.842099 0.162672 0.870507 0.200211 0.771864 0.138631 0.842099 0.162672 0.81705 0.170279 0.867361 0.240079 0.870507 0.200211 0.889151 0.238966 0.846907 0.2044579 0.870507 0.200211 0.867361 0.240079 0.81705 0.170279 0.870507 0.200211 0.846907 0.2044579 0.881775 0.276575 0.889151 0.238966 0.901888 0.278421 0.867361 0.240079 0.889151 0.238966 0.881775 0.276575 0.909194 0.317403 0.901888 0.278421 0.910942 0.31823 0.881775 0.276575 0.901888 0.278421 0.892366 0.313463 0.899951 0.314537 0.892366 0.313463 0.901888 0.278421 0.909194 0.317403 0.899951 0.314537 0.901888 0.278421 0.947956 0.317003 0.910942 0.31823 0.915947 0.321385 0.947058 0.313171 0.909194 0.317403 0.910942 0.31823 0.947956 0.317003 0.947058 0.313171 0.910942 0.31823 0.948767 0.321188 0.915947 0.321385 0.920673 0.326159 0.948767 0.321188 0.947956 0.317003 0.915947 0.321385 0.949478 0.325639 0.920673 0.326159 0.923693 0.331481 0.949478 0.325639 0.948767 0.321188 0.920673 0.326159 0.95008 0.330271 0.923693 0.331481 0.925196 0.337148 0.95008 0.330271 0.949478 0.325639 0.923693 0.331481 0.950564 0.334997 0.925196 0.337148 0.925251 0.342962 0.950564 0.334997 0.95008 0.330271 0.925196 0.337148 0.951161 0.344387 0.925251 0.342962 0.923828 0.348747 0.950926 0.339731 0.950564 0.334997 0.925251 0.342962 0.951161 0.344387 0.950926 0.339731 0.925251 0.342962 0.951269 0.348878 0.923828 0.348747 0.920781 0.354364 0.951269 0.348878 0.951161 0.344387 0.923828 0.348747 0.951247 0.353118 0.920781 0.354364 0.917153 0.358504 0.951247 0.353118 0.951269 0.348878 0.920781 0.354364 0.91583 0.359693 0.917153 0.358504 0.921189 0.3988 0.951247 0.353118 0.917153 0.358504 0.91583 0.359693 0.906379 0.405221 0.921189 0.3988 0.923804 0.43924 0.902293 0.367571 0.921189 0.3988 0.906379 0.405221 0.908537 0.364623 0.921189 0.3988 0.902293 0.367571 0.91583 0.359693 0.921189 0.3988 0.908537 0.364623 0.909125 0.443085 0.923804 0.43924 0.92506 0.47974 0.906379 0.405221 0.923804 0.43924 0.909125 0.443085 0.91045 0.481021 0.92506 0.47974 0.92506 0.52026 0.909125 0.443085 0.92506 0.47974 0.91045 0.481021 0.909125 0.556915 0.92506 0.52026 0.923804 0.56076 0.91045 0.518979 0.92506 0.52026 0.909125 0.556915 0.91045 0.481021 0.92506 0.52026 0.91045 0.518979 0.906379 0.594779 0.923804 0.56076 0.921189 0.6012 0.909125 0.556915 0.923804 0.56076 0.906379 0.594779 0.91583 0.640307 0.921189 0.6012 0.917153 0.641496 0.906379 0.594779 0.921189 0.6012 0.902293 0.632429 0.908537 0.635377 0.902293 0.632429 0.921189 0.6012 0.91583 0.640307 0.908537 0.635377 0.921189 0.6012 0.951247 0.646882 0.917153 0.641496 0.920781 0.645636 0.951097 0.642979 0.91583 0.640307 0.917153 0.641496 0.951247 0.646882 0.951097 0.642979 0.917153 0.641496 0.951269 0.651122 0.920781 0.645636 0.923828 0.651253 0.951269 0.651122 0.951247 0.646882 0.920781 0.645636 0.951161 0.655613 0.923828 0.651253 0.925251 0.657038 0.951161 0.655613 0.951269 0.651122 0.923828 0.651253 0.950926 0.660269 0.925251 0.657038 0.925196 0.662852 0.950926 0.660269 0.951161 0.655613 0.925251 0.657038 0.950564 0.665003 0.925196 0.662852 0.923693 0.668519 0.950564 0.665003 0.950926 0.660269 0.925196 0.662852 0.949478 0.674361 0.923693 0.668519 0.920673 0.673841 0.95008 0.669729 0.950564 0.665003 0.923693 0.668519 0.949478 0.674361 0.95008 0.669729 0.923693 0.668519 0.948767 0.678812 0.920673 0.673841 0.915947 0.678615 0.948767 0.678812 0.949478 0.674361 0.920673 0.673841 0.947956 0.682997 0.915947 0.678615 0.910942 0.68177 0.947956 0.682997 0.948767 0.678812 0.915947 0.678615 0.909194 0.682597 0.910942 0.68177 0.901991 0.72119 0.947956 0.682997 0.910942 0.68177 0.909194 0.682597 0.881374 0.724637 0.901991 0.72119 0.889448 0.760267 0.899951 0.685463 0.909194 0.682597 0.901991 0.72119 0.892366 0.686537 0.899951 0.685463 0.901991 0.72119 0.881374 0.724637 0.892366 0.686537 0.901991 0.72119 0.866226 0.762299 0.889448 0.760267 0.871169 0.798665 0.866226 0.762299 0.881374 0.724637 0.889448 0.760267 0.844469 0.799208 0.871169 0.798665 0.843472 0.835892 0.844469 0.799208 0.866226 0.762299 0.871169 0.798665 0.818709 0.84293 0.843472 0.835892 0.799099 0.870914 0.840868 0.807501 0.844469 0.799208 0.843472 0.835892 0.818709 0.84293 0.840868 0.807501 0.843472 0.835892 0.782745 0.874569 0.799099 0.870914 0.723603 0.901349 0.818709 0.84293 0.799099 0.870914 0.782745 0.874569 0.861874 0.728074 0.723603 0.901349 0.630065 0.920337 0.861874 0.728074 0.782745 0.874569 0.723603 0.901349 0.861874 0.728074 0.818709 0.84293 0.782745 0.874569 0.947058 0.686829 0.909194 0.682597 0.899951 0.685463 0.947058 0.686829 0.947956 0.682997 0.909194 0.682597 0.946087 0.690224 0.899951 0.685463 0.892366 0.686537 0.946087 0.690224 0.947058 0.686829 0.899951 0.685463 0.8879 0.686799 0.892366 0.686537 0.881374 0.724637 0.946087 0.690224 0.892366 0.686537 0.8879 0.686799 0.861874 0.728074 0.881374 0.724637 0.866226 0.762299 0.854287 0.76903 0.866226 0.762299 0.844469 0.799208 0.85868 0.748839 0.866226 0.762299 0.854287 0.76903 0.85868 0.748839 0.861874 0.728074 0.866226 0.762299 0.861874 0.728074 0.844469 0.799208 0.840868 0.807501 0.861874 0.728074 0.854287 0.76903 0.844469 0.799208 0.861874 0.728074 0.840868 0.807501 0.818709 0.84293 0.85868 0.748839 0.854287 0.76903 0.861874 0.728074 0.945063 0.693099 0.946087 0.690224 0.8879 0.686799 0.881775 0.276575 0.892366 0.313463 0.8879 0.313201 0.945063 0.306901 0.8879 0.313201 0.892366 0.313463 0.946087 0.309776 0.892366 0.313463 0.899951 0.314537 0.946087 0.309776 0.945063 0.306901 0.892366 0.313463 0.595399 0.09719598 0.595997 0.093472 0.701533 0.111704 0.665639 0.051346 0.595997 0.093472 0.595399 0.09719598 0.665639 0.051346 0.595057 0.08705997 0.595997 0.093472 0.679207 0.053357 0.665639 0.051346 0.595399 0.09719598 0.647804 0.049272 0.587919 0.07901298 0.595057 0.08705997 0.665639 0.051346 0.647804 0.049272 0.595057 0.08705997 0.947058 0.313171 0.899951 0.314537 0.909194 0.317403 0.947058 0.313171 0.946087 0.309776 0.899951 0.314537 0.647804 0.049272 0.625579 0.04727488 0.587919 0.07901298 0.906379 0.594779 0.902293 0.632429 0.898535 0.630992 0.950416 0.636525 0.898535 0.630992 0.902293 0.632429 0.950819 0.639498 0.902293 0.632429 0.908537 0.635377 0.950819 0.639498 0.950416 0.636525 0.902293 0.632429 0.898535 0.369008 0.902293 0.367571 0.906379 0.405221 0.950819 0.360502 0.902293 0.367571 0.898535 0.369008 0.950819 0.360502 0.908537 0.364623 0.902293 0.367571 0.950416 0.363475 0.950819 0.360502 0.898535 0.369008 0.951097 0.357021 0.91583 0.359693 0.908537 0.364623 0.950819 0.360502 0.951097 0.357021 0.908537 0.364623 0.951097 0.642979 0.908537 0.635377 0.91583 0.640307 0.951097 0.642979 0.950819 0.639498 0.908537 0.635377 0.951097 0.357021 0.951247 0.353118 0.91583 0.359693 0.5 0.04423195 0.5 0.05292898 0.464872 0.05317091 0.581762 0.04545098 0.535128 0.05317091 0.5 0.05292898 0.581762 0.04545098 0.5 0.05292898 0.5 0.04423195 0.5 0.04423195 0.464872 0.05317091 0.431408 0.05385088 0.418238 0.04545098 0.431408 0.05385088 0.400963 0.05484998 0.5 0.04423195 0.431408 0.05385088 0.418238 0.04545098 0.418238 0.04545098 0.400963 0.05484998 0.374421 0.0559979 0.352514 0.04828697 0.374421 0.0559979 0.352196 0.05711793 0.418238 0.04545098 0.374421 0.0559979 0.352514 0.04828697 0.352514 0.04828697 0.352196 0.05711793 0.334361 0.05804389 0.30825 0.051063 0.334361 0.05804389 0.320793 0.058649 0.352514 0.04828697 0.334361 0.05804389 0.30825 0.051063 0.30825 0.051063 0.320793 0.058649 0.311296 0.05884498 0.2836 0.05242192 0.311296 0.05884498 0.305683 0.058586 0.30825 0.051063 0.311296 0.05884498 0.2836 0.05242192 0.2836 0.05242192 0.305683 0.058586 0.303827 0.05786496 0.275753 0.051759 0.303827 0.05786496 0.305683 0.05671089 0.2836 0.05242192 0.303827 0.05786496 0.275753 0.051759 0.275753 0.051759 0.305683 0.05671089 0.311296 0.0551809 0.2836 0.04914289 0.311296 0.0551809 0.320793 0.053357 0.275753 0.051759 0.311296 0.0551809 0.2836 0.04914289 0.2836 0.04914289 0.320793 0.053357 0.334361 0.051346 0.30825 0.04514497 0.334361 0.051346 0.352196 0.049272 0.2836 0.04914289 0.334361 0.051346 0.30825 0.04514497 0.30825 0.04514497 0.352196 0.049272 0.374421 0.04727488 0.352514 0.04073399 0.374421 0.04727488 0.400963 0.04550492 0.30825 0.04514497 0.374421 0.04727488 0.352514 0.04073399 0.352514 0.04073399 0.400963 0.04550492 0.431408 0.04410696 0.418238 0.037193 0.431408 0.04410696 0.464872 0.04320889 0.352514 0.04073399 0.431408 0.04410696 0.418238 0.037193 0.418238 0.037193 0.464872 0.04320889 0.5 0.04289895 0.5 0.035815 0.5 0.04289895 0.535128 0.04320889 0.418238 0.037193 0.5 0.04289895 0.5 0.035815 0.5 0.035815 0.535128 0.04320889 0.568592 0.04410696 0.581762 0.037193 0.568592 0.04410696 0.599037 0.04550492 0.581762 0.037193 0.5 0.035815 0.568592 0.04410696 0.581762 0.037193 0.599037 0.04550492 0.625579 0.04727488 0.647486 0.04073399 0.625579 0.04727488 0.647804 0.049272 0.581762 0.037193 0.625579 0.04727488 0.647486 0.04073399 0.647486 0.04073399 0.647804 0.049272 0.665639 0.051346 0.69175 0.04514497 0.665639 0.051346 0.679207 0.053357 0.647486 0.04073399 0.665639 0.051346 0.69175 0.04514497 0.69175 0.04514497 0.679207 0.053357 0.688704 0.0551809 0.7164 0.04914289 0.688704 0.0551809 0.694317 0.05671089 0.69175 0.04514497 0.688704 0.0551809 0.7164 0.04914289 0.7164 0.04914289 0.694317 0.05671089 0.696173 0.05786496 0.724247 0.051759 0.696173 0.05786496 0.694317 0.058586 0.7164 0.04914289 0.696173 0.05786496 0.724247 0.051759 0.724247 0.051759 0.694317 0.058586 0.688704 0.05884498 0.7164 0.05242192 0.688704 0.05884498 0.679207 0.058649 0.724247 0.051759 0.688704 0.05884498 0.7164 0.05242192 0.7164 0.05242192 0.679207 0.058649 0.665639 0.05804389 0.69175 0.051063 0.665639 0.05804389 0.647804 0.05711793 0.7164 0.05242192 0.665639 0.05804389 0.69175 0.051063 0.69175 0.051063 0.647804 0.05711793 0.625579 0.0559979 0.647486 0.04828697 0.625579 0.0559979 0.599037 0.05484998 0.69175 0.051063 0.625579 0.0559979 0.647486 0.04828697 0.647486 0.04828697 0.599037 0.05484998 0.568592 0.05385088 0.581762 0.04545098 0.568592 0.05385088 0.535128 0.05317091 0.647486 0.04828697 0.568592 0.05385088 0.581762 0.04545098 0.949034 0.335102 0.939068 0.335862 0.938512 0.330053 0.950353 0.346556 0.939785 0.341658 0.939068 0.335862 0.950353 0.346556 0.939068 0.335862 0.949034 0.335102 0.949034 0.335102 0.938512 0.330053 0.938139 0.324424 0.948251 0.323609 0.938139 0.324424 0.937967 0.31916 0.949034 0.335102 0.938139 0.324424 0.948251 0.323609 0.948251 0.323609 0.937967 0.31916 0.938001 0.314422 0.948135 0.313579 0.938001 0.314422 0.938242 0.310343 0.948251 0.323609 0.938001 0.314422 0.948135 0.313579 0.948135 0.313579 0.938242 0.310343 0.938678 0.307023 0.948705 0.306183 0.938678 0.307023 0.939291 0.304527 0.948135 0.313579 0.938678 0.307023 0.948705 0.306183 0.948705 0.306183 0.939291 0.304527 0.940055 0.302888 0.949865 0.302077 0.940055 0.302888 0.940941 0.302109 0.948705 0.306183 0.940055 0.302888 0.949865 0.302077 0.949865 0.302077 0.940941 0.302109 0.941917 0.302169 0.951434 0.301406 0.941917 0.302169 0.94295 0.303026 0.949865 0.302077 0.941917 0.302169 0.951434 0.301406 0.951434 0.301406 0.94295 0.303026 0.944009 0.304626 0.953194 0.303921 0.944009 0.304626 0.945063 0.306901 0.951434 0.301406 0.944009 0.304626 0.953194 0.303921 0.953194 0.303921 0.945063 0.306901 0.946087 0.309776 0.954941 0.30913 0.946087 0.309776 0.947058 0.313171 0.953194 0.303921 0.946087 0.309776 0.954941 0.30913 0.954941 0.30913 0.947058 0.313171 0.947956 0.317003 0.956512 0.316413 0.947956 0.317003 0.948767 0.321188 0.954941 0.30913 0.947956 0.317003 0.956512 0.316413 0.956512 0.316413 0.948767 0.321188 0.949478 0.325639 0.957791 0.325097 0.949478 0.325639 0.95008 0.330271 0.956512 0.316413 0.949478 0.325639 0.957791 0.325097 0.957791 0.325097 0.95008 0.330271 0.950564 0.334997 0.958702 0.334494 0.950564 0.334997 0.950926 0.339731 0.957791 0.325097 0.950564 0.334997 0.958702 0.334494 0.958702 0.334494 0.950926 0.339731 0.951161 0.344387 0.959204 0.343914 0.951161 0.344387 0.951269 0.348878 0.959204 0.343914 0.958702 0.334494 0.951161 0.344387 0.959204 0.343914 0.951269 0.348878 0.951247 0.353118 0.959276 0.352665 0.951247 0.353118 0.951097 0.357021 0.959204 0.343914 0.951247 0.353118 0.959276 0.352665 0.959276 0.352665 0.951097 0.357021 0.950819 0.360502 0.958916 0.360057 0.950819 0.360502 0.950416 0.363475 0.959276 0.352665 0.950819 0.360502 0.958916 0.360057 0.958916 0.360057 0.950416 0.363475 0.949892 0.365862 0.958138 0.365413 0.949892 0.365862 0.949253 0.367583 0.958916 0.360057 0.949892 0.365862 0.958138 0.365413 0.958138 0.365413 0.949253 0.367583 0.948508 0.368572 0.956975 0.368106 0.948508 0.368572 0.947666 0.368768 0.958138 0.365413 0.948508 0.368572 0.956975 0.368106 0.956975 0.368106 0.947666 0.368768 0.946741 0.368128 0.955491 0.367628 0.946741 0.368128 0.94575 0.366626 0.956975 0.368106 0.946741 0.368128 0.955491 0.367628 0.955491 0.367628 0.94575 0.366626 0.944714 0.364262 0.953787 0.363712 0.944714 0.364262 0.943655 0.361064 0.955491 0.367628 0.944714 0.364262 0.953787 0.363712 0.953787 0.363712 0.943655 0.361064 0.942602 0.357093 0.95201 0.356478 0.942602 0.357093 0.941584 0.352444 0.953787 0.363712 0.942602 0.357093 0.95201 0.356478 0.95201 0.356478 0.941584 0.352444 0.940634 0.347246 0.950353 0.346556 0.940634 0.347246 0.939785 0.341658 0.95201 0.356478 0.940634 0.347246 0.950353 0.346556 0.949034 0.664898 0.939068 0.664138 0.939785 0.658342 0.948251 0.676391 0.938512 0.669947 0.939068 0.664138 0.948251 0.676391 0.939068 0.664138 0.949034 0.664898 0.949034 0.664898 0.939785 0.658342 0.940634 0.652754 0.950353 0.653444 0.940634 0.652754 0.941584 0.647556 0.949034 0.664898 0.940634 0.652754 0.950353 0.653444 0.950353 0.653444 0.941584 0.647556 0.942602 0.642907 0.95201 0.643522 0.942602 0.642907 0.943655 0.638936 0.950353 0.653444 0.942602 0.642907 0.95201 0.643522 0.95201 0.643522 0.943655 0.638936 0.944714 0.635738 0.953787 0.636288 0.944714 0.635738 0.94575 0.633374 0.95201 0.643522 0.944714 0.635738 0.953787 0.636288 0.953787 0.636288 0.94575 0.633374 0.946741 0.631872 0.955491 0.632372 0.946741 0.631872 0.947666 0.631232 0.953787 0.636288 0.946741 0.631872 0.955491 0.632372 0.955491 0.632372 0.947666 0.631232 0.948508 0.631428 0.956975 0.631894 0.948508 0.631428 0.949253 0.632417 0.955491 0.632372 0.948508 0.631428 0.956975 0.631894 0.956975 0.631894 0.949253 0.632417 0.949892 0.634138 0.958138 0.634587 0.949892 0.634138 0.950416 0.636525 0.956975 0.631894 0.949892 0.634138 0.958138 0.634587 0.958138 0.634587 0.950416 0.636525 0.950819 0.639498 0.958916 0.639943 0.950819 0.639498 0.951097 0.642979 0.958138 0.634587 0.950819 0.639498 0.958916 0.639943 0.958916 0.639943 0.951097 0.642979 0.951247 0.646882 0.959276 0.647335 0.951247 0.646882 0.951269 0.651122 0.958916 0.639943 0.951247 0.646882 0.959276 0.647335 0.959276 0.647335 0.951269 0.651122 0.951161 0.655613 0.959204 0.656086 0.951161 0.655613 0.950926 0.660269 0.959276 0.647335 0.951161 0.655613 0.959204 0.656086 0.959204 0.656086 0.950926 0.660269 0.950564 0.665003 0.958702 0.665506 0.950564 0.665003 0.95008 0.669729 0.959204 0.656086 0.950564 0.665003 0.958702 0.665506 0.958702 0.665506 0.95008 0.669729 0.949478 0.674361 0.957791 0.674903 0.949478 0.674361 0.948767 0.678812 0.957791 0.674903 0.958702 0.665506 0.949478 0.674361 0.957791 0.674903 0.948767 0.678812 0.947956 0.682997 0.956512 0.683587 0.947956 0.682997 0.947058 0.686829 0.957791 0.674903 0.947956 0.682997 0.956512 0.683587 0.956512 0.683587 0.947058 0.686829 0.946087 0.690224 0.954941 0.69087 0.946087 0.690224 0.945063 0.693099 0.956512 0.683587 0.946087 0.690224 0.954941 0.69087 0.954941 0.69087 0.945063 0.693099 0.944009 0.695374 0.953194 0.696079 0.944009 0.695374 0.94295 0.696974 0.954941 0.69087 0.944009 0.695374 0.953194 0.696079 0.953194 0.696079 0.94295 0.696974 0.941917 0.697831 0.951434 0.698594 0.941917 0.697831 0.940941 0.697891 0.953194 0.696079 0.941917 0.697831 0.951434 0.698594 0.951434 0.698594 0.940941 0.697891 0.940055 0.697112 0.949865 0.697923 0.940055 0.697112 0.939291 0.695473 0.951434 0.698594 0.940055 0.697112 0.949865 0.697923 0.949865 0.697923 0.939291 0.695473 0.938678 0.692977 0.948705 0.693817 0.938678 0.692977 0.938242 0.689657 0.949865 0.697923 0.938678 0.692977 0.948705 0.693817 0.948705 0.693817 0.938242 0.689657 0.938001 0.685578 0.948135 0.686421 0.938001 0.685578 0.937967 0.68084 0.948705 0.693817 0.938001 0.685578 0.948135 0.686421 0.948135 0.686421 0.937967 0.68084 0.938139 0.675576 0.948251 0.676391 0.938139 0.675576 0.938512 0.669947 0.948135 0.686421 0.938139 0.675576 0.948251 0.676391 0.05096596 0.664898 0.06093198 0.664138 0.06148797 0.669947 0.04964697 0.653444 0.06021493 0.658342 0.06093198 0.664138 0.04964697 0.653444 0.06093198 0.664138 0.05096596 0.664898 0.05096596 0.664898 0.06148797 0.669947 0.06186091 0.675576 0.05174899 0.676391 0.06186091 0.675576 0.06203293 0.68084 0.05096596 0.664898 0.06186091 0.675576 0.05174899 0.676391 0.05174899 0.676391 0.06203293 0.68084 0.06199896 0.685578 0.05186498 0.686421 0.06199896 0.685578 0.06175798 0.689657 0.05174899 0.676391 0.06199896 0.685578 0.05186498 0.686421 0.05186498 0.686421 0.06175798 0.689657 0.06132197 0.692977 0.05129498 0.693817 0.06132197 0.692977 0.06070894 0.695473 0.05186498 0.686421 0.06132197 0.692977 0.05129498 0.693817 0.05129498 0.693817 0.06070894 0.695473 0.05994492 0.697112 0.05013489 0.697923 0.05994492 0.697112 0.05905896 0.697891 0.05129498 0.693817 0.05994492 0.697112 0.05013489 0.697923 0.05013489 0.697923 0.05905896 0.697891 0.05808293 0.697831 0.04856598 0.698594 0.05808293 0.697831 0.05704993 0.696974 0.05013489 0.697923 0.05808293 0.697831 0.04856598 0.698594 0.04856598 0.698594 0.05704993 0.696974 0.05599099 0.695374 0.04680591 0.696079 0.05599099 0.695374 0.054937 0.693099 0.04856598 0.698594 0.05599099 0.695374 0.04680591 0.696079 0.04680591 0.696079 0.054937 0.693099 0.05391293 0.690224 0.0450589 0.69087 0.05391293 0.690224 0.05294191 0.686829 0.04680591 0.696079 0.05391293 0.690224 0.0450589 0.69087 0.0450589 0.69087 0.05294191 0.686829 0.05204397 0.682997 0.0434879 0.683587 0.05204397 0.682997 0.05123299 0.678812 0.0450589 0.69087 0.05204397 0.682997 0.0434879 0.683587 0.0434879 0.683587 0.05123299 0.678812 0.05052191 0.674361 0.0422089 0.674903 0.05052191 0.674361 0.04991996 0.669729 0.0434879 0.683587 0.05052191 0.674361 0.0422089 0.674903 0.0422089 0.674903 0.04991996 0.669729 0.04943597 0.665003 0.04129797 0.665506 0.04943597 0.665003 0.04907399 0.660269 0.0422089 0.674903 0.04943597 0.665003 0.04129797 0.665506 0.04129797 0.665506 0.04907399 0.660269 0.04883897 0.655613 0.04079598 0.656086 0.04883897 0.655613 0.0487309 0.651122 0.04079598 0.656086 0.04129797 0.665506 0.04883897 0.655613 0.04079598 0.656086 0.0487309 0.651122 0.04875296 0.646882 0.04072391 0.647335 0.04875296 0.646882 0.04890292 0.642979 0.04079598 0.656086 0.04875296 0.646882 0.04072391 0.647335 0.04072391 0.647335 0.04890292 0.642979 0.04918098 0.639498 0.04108399 0.639943 0.04918098 0.639498 0.04958397 0.636525 0.04072391 0.647335 0.04918098 0.639498 0.04108399 0.639943 0.04108399 0.639943 0.04958397 0.636525 0.05010789 0.634138 0.04186195 0.634587 0.05010789 0.634138 0.05074691 0.632417 0.04108399 0.639943 0.05010789 0.634138 0.04186195 0.634587 0.04186195 0.634587 0.05074691 0.632417 0.05149191 0.631428 0.04302489 0.631894 0.05149191 0.631428 0.05233395 0.631232 0.04186195 0.634587 0.05149191 0.631428 0.04302489 0.631894 0.04302489 0.631894 0.05233395 0.631232 0.05325895 0.631872 0.04450899 0.632372 0.05325895 0.631872 0.05425 0.633374 0.04302489 0.631894 0.05325895 0.631872 0.04450899 0.632372 0.04450899 0.632372 0.05425 0.633374 0.05528599 0.635738 0.04621297 0.636288 0.05528599 0.635738 0.05634492 0.638936 0.04450899 0.632372 0.05528599 0.635738 0.04621297 0.636288 0.04621297 0.636288 0.05634492 0.638936 0.05739796 0.642907 0.04798996 0.643522 0.05739796 0.642907 0.05841588 0.647556 0.04621297 0.636288 0.05739796 0.642907 0.04798996 0.643522 0.04798996 0.643522 0.05841588 0.647556 0.05936592 0.652754 0.04964697 0.653444 0.05936592 0.652754 0.06021493 0.658342 0.04798996 0.643522 0.05936592 0.652754 0.04964697 0.653444 0.05096596 0.335102 0.06093198 0.335862 0.06021493 0.341658 0.05174899 0.323609 0.06148797 0.330053 0.06093198 0.335862 0.05174899 0.323609 0.06093198 0.335862 0.05096596 0.335102 0.05096596 0.335102 0.06021493 0.341658 0.05936592 0.347246 0.04964697 0.346556 0.05936592 0.347246 0.05841588 0.352444 0.05096596 0.335102 0.05936592 0.347246 0.04964697 0.346556 0.04964697 0.346556 0.05841588 0.352444 0.05739796 0.357093 0.04798996 0.356478 0.05739796 0.357093 0.05634492 0.361064 0.04964697 0.346556 0.05739796 0.357093 0.04798996 0.356478 0.04798996 0.356478 0.05634492 0.361064 0.05528599 0.364262 0.04621297 0.363712 0.05528599 0.364262 0.05425 0.366626 0.04798996 0.356478 0.05528599 0.364262 0.04621297 0.363712 0.04621297 0.363712 0.05425 0.366626 0.05325895 0.368128 0.04450899 0.367628 0.05325895 0.368128 0.05233395 0.368768 0.04621297 0.363712 0.05325895 0.368128 0.04450899 0.367628 0.04450899 0.367628 0.05233395 0.368768 0.05149191 0.368572 0.04302489 0.368106 0.05149191 0.368572 0.05074691 0.367583 0.04450899 0.367628 0.05149191 0.368572 0.04302489 0.368106 0.04302489 0.368106 0.05074691 0.367583 0.05010789 0.365862 0.04186195 0.365413 0.05010789 0.365862 0.04958397 0.363475 0.04302489 0.368106 0.05010789 0.365862 0.04186195 0.365413 0.04186195 0.365413 0.04958397 0.363475 0.04918098 0.360502 0.04108399 0.360057 0.04918098 0.360502 0.04890292 0.357021 0.04186195 0.365413 0.04918098 0.360502 0.04108399 0.360057 0.04108399 0.360057 0.04890292 0.357021 0.04875296 0.353118 0.04072391 0.352665 0.04875296 0.353118 0.0487309 0.348878 0.04108399 0.360057 0.04875296 0.353118 0.04072391 0.352665 0.04072391 0.352665 0.0487309 0.348878 0.04883897 0.344387 0.04079598 0.343914 0.04883897 0.344387 0.04907399 0.339731 0.04072391 0.352665 0.04883897 0.344387 0.04079598 0.343914 0.04079598 0.343914 0.04907399 0.339731 0.04943597 0.334997 0.04129797 0.334494 0.04943597 0.334997 0.04991996 0.330271 0.04079598 0.343914 0.04943597 0.334997 0.04129797 0.334494 0.04129797 0.334494 0.04991996 0.330271 0.05052191 0.325639 0.0422089 0.325097 0.05052191 0.325639 0.05123299 0.321188 0.0422089 0.325097 0.04129797 0.334494 0.05052191 0.325639 0.0422089 0.325097 0.05123299 0.321188 0.05204397 0.317003 0.0434879 0.316413 0.05204397 0.317003 0.05294191 0.313171 0.0422089 0.325097 0.05204397 0.317003 0.0434879 0.316413 0.0434879 0.316413 0.05294191 0.313171 0.05391293 0.309776 0.0450589 0.30913 0.05391293 0.309776 0.054937 0.306901 0.0434879 0.316413 0.05391293 0.309776 0.0450589 0.30913 0.0450589 0.30913 0.054937 0.306901 0.05599099 0.304626 0.04680591 0.303921 0.05599099 0.304626 0.05704993 0.303026 0.0450589 0.30913 0.05599099 0.304626 0.04680591 0.303921 0.04680591 0.303921 0.05704993 0.303026 0.05808293 0.302169 0.04856598 0.301406 0.05808293 0.302169 0.05905896 0.302109 0.04680591 0.303921 0.05808293 0.302169 0.04856598 0.301406 0.04856598 0.301406 0.05905896 0.302109 0.05994492 0.302888 0.05013489 0.302077 0.05994492 0.302888 0.06070894 0.304527 0.04856598 0.301406 0.05994492 0.302888 0.05013489 0.302077 0.05013489 0.302077 0.06070894 0.304527 0.06132197 0.307023 0.05129498 0.306183 0.06132197 0.307023 0.06175798 0.310343 0.05013489 0.302077 0.06132197 0.307023 0.05129498 0.306183 0.05129498 0.306183 0.06175798 0.310343 0.06199896 0.314422 0.05186498 0.313579 0.06199896 0.314422 0.06203293 0.31916 0.05129498 0.306183 0.06199896 0.314422 0.05186498 0.313579 0.05186498 0.313579 0.06203293 0.31916 0.06186091 0.324424 0.05174899 0.323609 0.06186091 0.324424 0.06148797 0.330053 0.05186498 0.313579 0.06186091 0.324424 0.05174899 0.323609 0.5 0.037606 0.176712 0 0 0.005507946 0.545957 0.03811198 1 0.005507946 0.176712 0 0.5 0.037606 0.545957 0.03811198 0.176712 0 0.454043 0.03811198 0 0.005507946 0 0.01044088 0.454043 0.03811198 0.5 0.037606 0 0.005507946 0.415105 0.03943091 0 0.01044088 0 0.014256 0.415105 0.03943091 0.454043 0.03811198 0 0.01044088 0.387738 0.04107195 0 0.014256 0 0.01648592 0.387738 0.04107195 0.415105 0.03943091 0 0.014256 0.373828 0.04248493 0 0.01648592 0 0.01679295 0.373828 0.04248493 0.387738 0.04107195 0 0.01648592 0.373828 0.04326593 0 0.01679295 0 0.01503288 0.373828 0.04326593 0.373828 0.04248493 0 0.01679295 0 0.07996296 0 0.01132589 0 0.01503288 0.387738 0.0432859 0 0.01503288 0 0.01132589 0.387738 0.0432859 0.373828 0.04326593 0 0.01503288 0 0.07996296 0 0.006086945 0 0.01132589 0.415105 0.04273796 0 0.01132589 0 0.006086945 0.415105 0.04273796 0.387738 0.0432859 0 0.01132589 0 0.07360696 0.176712 0 0 0.006086945 0.454043 0.04207295 0 0.006086945 0.176712 0 0 0.07996296 0 0.07360696 0 0.006086945 0.454043 0.04207295 0.415105 0.04273796 0 0.006086945 0.5 0.04177999 0.176712 0 1 0.006086945 0 0.06839197 1 0.159153 0.176712 0 0 0.07360696 0 0.06839197 0.176712 0 0.454043 0.04207295 0.176712 0 0.5 0.04177999 0.545957 0.04207295 1 0.006086945 1 0.01132589 0.545957 0.04207295 0.5 0.04177999 1 0.006086945 0.584895 0.04273796 1 0.01132589 1 0.01503288 0.584895 0.04273796 0.545957 0.04207295 1 0.01132589 0.612262 0.0432859 1 0.01503288 1 0.01679295 0.612262 0.0432859 0.584895 0.04273796 1 0.01503288 0.626172 0.04326593 1 0.01679295 1 0.01648592 0.626172 0.04326593 0.612262 0.0432859 1 0.01679295 0.626172 0.04248493 1 0.01648592 1 0.014256 0.626172 0.04248493 0.626172 0.04326593 1 0.01648592 0.612262 0.04107195 1 0.014256 1 0.01044088 0.612262 0.04107195 0.626172 0.04248493 1 0.014256 0.584895 0.03943091 1 0.01044088 1 0.005507946 0.584895 0.03943091 0.612262 0.04107195 1 0.01044088 0.545957 0.03811198 0.584895 0.03943091 1 0.005507946 0.956644 0.334613 1 0.333333 1 0.327825 0.956938 0.340079 1 0.338841 1 0.333333 0.956644 0.334613 0.956938 0.340079 1 0.333333 0.95608 0.329163 1 0.327825 1 0.322892 0.95608 0.329163 0.956644 0.334613 1 0.327825 0.955296 0.324301 1 0.322892 1 0.319077 0.955296 0.324301 0.95608 0.329163 1 0.322892 1 0.299651 1 0.316847 1 0.319077 0.954371 0.320562 1 0.319077 1 0.316847 0.954371 0.320562 0.955296 0.324301 1 0.319077 1 0.299651 1 0.316541 1 0.316847 0.953407 0.318406 1 0.316847 1 0.316541 0.953407 0.318406 0.954371 0.320562 1 0.316847 1 0.323054 1 0.3183 1 0.316541 0.952525 0.318161 1 0.316541 1 0.3183 1 0.299651 1 0.323054 1 0.316541 0.952525 0.318161 0.953407 0.318406 1 0.316541 1 0.323054 1 0.322007 1 0.3183 0.951849 0.319958 1 0.3183 1 0.322007 0.951849 0.319958 0.952525 0.318161 1 0.3183 1 0.323054 1 0.327247 1 0.322007 0.951481 0.323671 1 0.322007 1 0.327247 0.951481 0.323671 0.951849 0.319958 1 0.322007 1 0.323054 1 0.333333 1 0.327247 0.951481 0.328882 1 0.327247 1 0.333333 0.951481 0.328882 0.951481 0.323671 1 0.327247 1 0.346458 1 0.33942 1 0.333333 0.951849 0.334912 1 0.333333 1 0.33942 1 0.323054 1 0.346458 1 0.333333 0.951481 0.328882 1 0.333333 0.951849 0.334912 1 0.346458 1 0.344659 1 0.33942 0.952525 0.340921 1 0.33942 1 0.344659 0.952525 0.340921 0.951849 0.334912 1 0.33942 1 0.346458 1 0.348366 1 0.344659 0.953407 0.346074 1 0.344659 1 0.348366 0.953407 0.346074 0.952525 0.340921 1 0.344659 0.954371 0.3497 1 0.348366 1 0.350126 0.954371 0.3497 0.953407 0.346074 1 0.348366 0.955296 0.351395 1 0.350126 1 0.34982 0.955296 0.351395 0.954371 0.3497 1 0.350126 0.95608 0.351046 1 0.34982 1 0.34759 0.95608 0.351046 0.955296 0.351395 1 0.34982 0.956644 0.348798 1 0.34759 1 0.343774 0.956644 0.348798 0.95608 0.351046 1 0.34759 0.956938 0.344987 1 0.343774 1 0.338841 0.956938 0.344987 0.956644 0.348798 1 0.343774 0.956938 0.340079 0.956938 0.344987 1 0.338841 0.956644 0.665387 1 0.666667 1 0.661159 0.95608 0.670837 1 0.672175 1 0.666667 0.956644 0.665387 0.95608 0.670837 1 0.666667 0.956938 0.659921 1 0.661159 1 0.656226 0.956938 0.659921 0.956644 0.665387 1 0.661159 0.956938 0.655013 1 0.656226 1 0.65241 0.956938 0.655013 0.956938 0.659921 1 0.656226 0.956644 0.651202 1 0.65241 1 0.65018 0.956644 0.651202 0.956938 0.655013 1 0.65241 0.95608 0.648954 1 0.65018 1 0.649874 0.95608 0.648954 0.956644 0.651202 1 0.65018 0.955296 0.648605 1 0.649874 1 0.651634 0.955296 0.648605 0.95608 0.648954 1 0.649874 1 0.656388 1 0.655341 1 0.651634 0.954371 0.6503 1 0.651634 1 0.655341 0.954371 0.6503 0.955296 0.648605 1 0.651634 1 0.656388 1 0.66058 1 0.655341 0.953407 0.653926 1 0.655341 1 0.66058 0.953407 0.653926 0.954371 0.6503 1 0.655341 1 0.679792 1 0.666667 1 0.66058 0.952525 0.659079 1 0.66058 1 0.666667 1 0.656388 1 0.679792 1 0.66058 0.952525 0.659079 0.953407 0.653926 1 0.66058 1 0.679792 1 0.672753 1 0.666667 0.951849 0.665088 1 0.666667 1 0.672753 0.952525 0.659079 1 0.666667 0.951849 0.665088 1 0.679792 1 0.677993 1 0.672753 0.951481 0.671118 1 0.672753 1 0.677993 0.951481 0.671118 0.951849 0.665088 1 0.672753 1 0.703195 1 0.6817 1 0.677993 0.951481 0.676329 1 0.677993 1 0.6817 1 0.679792 1 0.703195 1 0.677993 0.951481 0.676329 0.951481 0.671118 1 0.677993 1 0.703195 1 0.683459 1 0.6817 0.951849 0.680042 1 0.6817 1 0.683459 0.951849 0.680042 0.951481 0.676329 1 0.6817 1 0.703195 1 0.683153 1 0.683459 0.952525 0.681839 1 0.683459 1 0.683153 0.952525 0.681839 0.951849 0.680042 1 0.683459 1 0.703195 1 0.680923 1 0.683153 0.953407 0.681594 1 0.683153 1 0.680923 0.953407 0.681594 0.952525 0.681839 1 0.683153 0.954371 0.679438 1 0.680923 1 0.677108 1 0.703195 1 0.726598 1 0.680923 0.954371 0.679438 0.953407 0.681594 1 0.680923 0.955296 0.675699 1 0.677108 1 0.672175 0.955296 0.675699 0.954371 0.679438 1 0.677108 0.95608 0.670837 0.955296 0.675699 1 0.672175 0.043356 0.665387 0 0.666667 0 0.672175 0.04306197 0.659921 0 0.661159 0 0.666667 0.043356 0.665387 0.04306197 0.659921 0 0.666667 0.04391998 0.670837 0 0.672175 0 0.677108 0.04391998 0.670837 0.043356 0.665387 0 0.672175 0.04470396 0.675699 0 0.677108 0 0.680923 0.04470396 0.675699 0.04391998 0.670837 0 0.677108 0 0.700349 0 0.683153 0 0.680923 0.04562896 0.679438 0 0.680923 0 0.683153 0.04562896 0.679438 0.04470396 0.675699 0 0.680923 0 0.700349 0 0.683459 0 0.683153 0.04659295 0.681594 0 0.683153 0 0.683459 0.04659295 0.681594 0.04562896 0.679438 0 0.683153 0 0.676946 0 0.6817 0 0.683459 0.04747498 0.681839 0 0.683459 0 0.6817 0 0.700349 0 0.676946 0 0.683459 0.04747498 0.681839 0.04659295 0.681594 0 0.683459 0 0.676946 0 0.677993 0 0.6817 0.04815089 0.680042 0 0.6817 0 0.677993 0.04815089 0.680042 0.04747498 0.681839 0 0.6817 0 0.676946 0 0.672753 0 0.677993 0.04851889 0.676329 0 0.677993 0 0.672753 0.04851889 0.676329 0.04815089 0.680042 0 0.677993 0 0.676946 0 0.666667 0 0.672753 0.04851889 0.671118 0 0.672753 0 0.666667 0.04851889 0.671118 0.04851889 0.676329 0 0.672753 0 0.653542 0 0.66058 0 0.666667 0.04815089 0.665088 0 0.666667 0 0.66058 0 0.676946 0 0.653542 0 0.666667 0.04851889 0.671118 0 0.666667 0.04815089 0.665088 0 0.653542 0 0.655341 0 0.66058 0.04747498 0.659079 0 0.66058 0 0.655341 0.04747498 0.659079 0.04815089 0.665088 0 0.66058 0 0.653542 0 0.651634 0 0.655341 0.04659295 0.653926 0 0.655341 0 0.651634 0.04659295 0.653926 0.04747498 0.659079 0 0.655341 0.04562896 0.6503 0 0.651634 0 0.649874 0.04562896 0.6503 0.04659295 0.653926 0 0.651634 0.04470396 0.648605 0 0.649874 0 0.65018 0.04470396 0.648605 0.04562896 0.6503 0 0.649874 0.04391998 0.648954 0 0.65018 0 0.65241 0.04391998 0.648954 0.04470396 0.648605 0 0.65018 0.043356 0.651202 0 0.65241 0 0.656226 0.043356 0.651202 0.04391998 0.648954 0 0.65241 0.04306197 0.655013 0 0.656226 0 0.661159 0.04306197 0.655013 0.043356 0.651202 0 0.656226 0.04306197 0.659921 0.04306197 0.655013 0 0.661159 0.043356 0.334613 0 0.333333 0 0.338841 0.04391998 0.329163 0 0.327825 0 0.333333 0.043356 0.334613 0.04391998 0.329163 0 0.333333 0.04306197 0.340079 0 0.338841 0 0.343774 0.04306197 0.340079 0.043356 0.334613 0 0.338841 0.04306197 0.344987 0 0.343774 0 0.34759 0.04306197 0.344987 0.04306197 0.340079 0 0.343774 0.043356 0.348798 0 0.34759 0 0.34982 0.043356 0.348798 0.04306197 0.344987 0 0.34759 0.04391998 0.351046 0 0.34982 0 0.350126 0.04391998 0.351046 0.043356 0.348798 0 0.34982 0.04470396 0.351395 0 0.350126 0 0.348366 0.04470396 0.351395 0.04391998 0.351046 0 0.350126 0 0.343613 0 0.344659 0 0.348366 0.04562896 0.3497 0 0.348366 0 0.344659 0.04562896 0.3497 0.04470396 0.351395 0 0.348366 0 0.343613 0 0.33942 0 0.344659 0.04659295 0.346074 0 0.344659 0 0.33942 0.04659295 0.346074 0.04562896 0.3497 0 0.344659 0 0.32021 0 0.333333 0 0.33942 0.04747498 0.340921 0 0.33942 0 0.333333 0 0.343613 0 0.32021 0 0.33942 0.04747498 0.340921 0.04659295 0.346074 0 0.33942 0 0.32021 0 0.327247 0 0.333333 0.04815089 0.334912 0 0.333333 0 0.327247 0.04747498 0.340921 0 0.333333 0.04815089 0.334912 0 0.32021 0 0.322007 0 0.327247 0.04851889 0.328882 0 0.327247 0 0.322007 0.04851889 0.328882 0.04815089 0.334912 0 0.327247 0 0.296807 0 0.3183 0 0.322007 0.04851889 0.323671 0 0.322007 0 0.3183 0 0.32021 0 0.296807 0 0.322007 0.04851889 0.323671 0.04851889 0.328882 0 0.322007 0 0.296807 0 0.316541 0 0.3183 0.04815089 0.319958 0 0.3183 0 0.316541 0.04815089 0.319958 0.04851889 0.323671 0 0.3183 0 0.296807 0 0.316847 0 0.316541 0.04747498 0.318161 0 0.316541 0 0.316847 0.04747498 0.318161 0.04815089 0.319958 0 0.316541 0 0.296807 0 0.319077 0 0.316847 0.04659295 0.318406 0 0.316847 0 0.319077 0.04659295 0.318406 0.04747498 0.318161 0 0.316847 0.04562896 0.320562 0 0.319077 0 0.322892 0 0.296807 0 0.273404 0 0.319077 0.04562896 0.320562 0.04659295 0.318406 0 0.319077 0.04470396 0.324301 0 0.322892 0 0.327825 0.04470396 0.324301 0.04562896 0.320562 0 0.322892 0.04391998 0.329163 0.04470396 0.324301 0 0.327825 0.923174 0.179046 1 0.174849 1 0.179057 1 0.153544 1 0.174849 1 0.169526 0.920605 0.173936 1 0.169526 1 0.174849 0.920605 0.173936 1 0.174849 0.923174 0.179046 0.925585 0.183041 1 0.179057 1 0.1816329 0.923174 0.179046 1 0.179057 0.925585 0.183041 0.927586 0.185431 1 0.1816329 1 0.182325 0.925585 0.183041 1 0.1816329 0.927586 0.185431 0.929004 0.18598 1 0.182325 1 0.181138 0.927586 0.185431 1 0.182325 0.929004 0.18598 0.929737 0.184706 1 0.181138 1 0.1782979 0.929004 0.18598 1 0.181138 0.929737 0.184706 0.929737 0.181836 1 0.1782979 1 0.17418 0.929737 0.184706 1 0.1782979 0.929737 0.181836 0.929004 0.177748 1 0.17418 1 0.169262 0.929737 0.181836 1 0.17418 0.929004 0.177748 0.927586 0.1729159 1 0.169262 1 0.164071 0.929004 0.177748 1 0.169262 0.927586 0.1729159 0.925585 0.167863 1 0.164071 1 0.159153 0.927586 0.1729159 1 0.164071 0.925585 0.167863 0 0.01027894 1 0.155036 1 0.159153 0.923174 0.163123 1 0.159153 1 0.155036 0 0.06839197 0 0.01027894 1 0.159153 0.925585 0.167863 1 0.159153 0.923174 0.163123 1 0.036529 1 0.152195 1 0.155036 0.920605 0.159211 1 0.155036 1 0.152195 1 0.013125 1 0.036529 1 0.155036 0 0.01027894 1 0.013125 1 0.155036 0.920605 0.159211 0.923174 0.163123 1 0.155036 1 0.05993199 1 0.151009 1 0.152195 0.918202 0.156578 1 0.152195 1 0.151009 1 0.036529 1 0.05993199 1 0.152195 0.920605 0.159211 1 0.152195 0.918202 0.156578 1 0.08333498 1 0.1517 1 0.151009 0.916325 0.155576 1 0.151009 1 0.1517 1 0.05993199 1 0.08333498 1 0.151009 0.918202 0.156578 1 0.151009 0.916325 0.155576 1 0.106738 1 0.154276 1 0.1517 0.915291 0.1563979 1 0.1517 1 0.154276 1 0.08333498 1 0.106738 1 0.1517 0.916325 0.155576 1 0.1517 0.915291 0.1563979 1 0.130141 1 0.158484 1 0.154276 0.915291 0.159026 1 0.154276 1 0.158484 1 0.106738 1 0.130141 1 0.154276 0.915291 0.1563979 1 0.154276 0.915291 0.159026 1 0.130141 1 0.163807 1 0.158484 0.916325 0.163197 1 0.158484 1 0.163807 0.915291 0.159026 1 0.158484 0.916325 0.163197 1 0.153544 1 0.169526 1 0.163807 0.918202 0.168399 1 0.163807 1 0.169526 1 0.130141 1 0.153544 1 0.163807 0.916325 0.163197 1 0.163807 0.918202 0.168399 0.918202 0.168399 1 0.169526 0.920605 0.173936 0 0.489719 0 0.48761 0 0.491818 0.04069799 0.491884 0 0.491818 0 0.48761 0 0.489719 0 0.491818 0 0.49714 0.04094499 0.497164 0 0.49714 0 0.491818 0.04094499 0.497164 0 0.491818 0.04069799 0.491884 0 0.466317 0 0.485033 0 0.48761 0.040241 0.487708 0 0.48761 0 0.485033 0 0.489719 0 0.466317 0 0.48761 0.04069799 0.491884 0 0.48761 0.040241 0.487708 0 0.466317 0 0.484342 0 0.485033 0.03964096 0.485149 0 0.485033 0 0.484342 0.040241 0.487708 0 0.485033 0.03964096 0.485149 0 0.466317 0 0.485528 0 0.484342 0.03898096 0.484459 0 0.484342 0 0.485528 0.03964096 0.485149 0 0.484342 0.03898096 0.484459 0.03834092 0.485633 0 0.485528 0 0.488369 0.03898096 0.484459 0 0.485528 0.03834092 0.485633 0.03779596 0.488451 0 0.488369 0 0.492486 0.03834092 0.485633 0 0.488369 0.03779596 0.488451 0.03740197 0.492538 0 0.492486 0 0.497405 0.03779596 0.488451 0 0.492486 0.03740197 0.492538 0.0371949 0.497422 0 0.497405 0 0.502595 0.03740197 0.492538 0 0.497405 0.0371949 0.497422 0.0371949 0.502578 0 0.502595 0 0.507514 0.0371949 0.497422 0 0.502595 0.0371949 0.502578 0.03740197 0.507462 0 0.507514 0 0.511631 0.0371949 0.502578 0 0.507514 0.03740197 0.507462 0.03779596 0.511549 0 0.511631 0 0.514472 0.03779596 0.511549 0.03740197 0.507462 0 0.511631 0.03834092 0.514367 0 0.514472 0 0.515658 0.03779596 0.511549 0 0.514472 0.03834092 0.514367 0 0.513123 0 0.514967 0 0.515658 0.03898096 0.515541 0 0.515658 0 0.514967 0 0.536526 0 0.513123 0 0.515658 0.03834092 0.514367 0 0.515658 0.03898096 0.515541 0 0.513123 0 0.51239 0 0.514967 0.03964096 0.514851 0 0.514967 0 0.51239 0.03898096 0.515541 0 0.514967 0.03964096 0.514851 0 0.513123 0 0.508182 0 0.51239 0.040241 0.512292 0 0.51239 0 0.508182 0.03964096 0.514851 0 0.51239 0.040241 0.512292 0 0.489719 0 0.50286 0 0.508182 0.04069799 0.508116 0 0.508182 0 0.50286 0 0.513123 0 0.489719 0 0.508182 0.040241 0.512292 0 0.508182 0.04069799 0.508116 0 0.489719 0 0.49714 0 0.50286 0.04094499 0.502836 0 0.50286 0 0.49714 0.04069799 0.508116 0 0.50286 0.04094499 0.502836 0.04094499 0.502836 0 0.49714 0.04094499 0.497164 1 0.603405 1 0.598274 1 0.601663 0.968945 0.601212 1 0.601663 1 0.598274 0.968601 0.602937 1 0.603405 1 0.601663 0.968601 0.602937 1 0.601663 0.968945 0.601212 0.969632 0.597855 1 0.598274 1 0.59306 0.968945 0.601212 1 0.598274 0.969632 0.597855 0.9702 0.592675 1 0.59306 1 0.586704 0.969632 0.597855 1 0.59306 0.9702 0.592675 0.970586 0.586352 1 0.586704 1 0.579964 0.9702 0.592675 1 0.586704 0.970586 0.586352 0.970751 0.57964 1 0.579964 1 0.573608 0.970586 0.586352 1 0.579964 0.970751 0.57964 0.970682 0.573307 1 0.573608 1 0.568392 0.970751 0.57964 1 0.573608 0.970682 0.573307 0.970383 0.568105 1 0.568392 1 0.565004 0.970682 0.573307 1 0.568392 0.970383 0.568105 0.969884 0.564721 1 0.565004 1 0.563261 0.970383 0.568105 1 0.565004 0.969884 0.564721 0.96964 0.562981 1 0.563261 1 0.560463 0.969884 0.564721 1 0.563261 0.96964 0.562981 0.969501 0.560192 1 0.560463 1 0.557075 0.96964 0.562981 1 0.560463 0.969501 0.560192 0.969493 0.556819 1 0.557075 1 0.533683 0.969501 0.560192 1 0.557075 0.969493 0.556819 0.969811 0.533533 1 0.533683 1 0.510281 0.969493 0.556819 1 0.533683 0.969811 0.533533 0.969963 0.510235 1 0.510281 1 0.486877 0.969811 0.533533 1 0.510281 0.969963 0.510235 0.969954 0.486936 1 0.486877 1 0.463474 0.969963 0.510235 1 0.486877 0.969954 0.486936 0.969781 0.463637 1 0.463474 1 0.440071 0.969954 0.486936 1 0.463474 0.969781 0.463637 0.969442 0.440341 1 0.440071 1 0.416668 0.969781 0.463637 1 0.440071 0.969442 0.440341 0.968927 0.417047 1 0.416668 1 0.393265 0.969442 0.440341 1 0.416668 0.968927 0.417047 0.96822 0.393758 1 0.393265 1 0.369862 0.968927 0.417047 1 0.393265 0.96822 0.393758 0.967301 0.370474 1 0.369862 1 0.346458 0.96822 0.393758 1 0.369862 0.967301 0.370474 0.96614 0.347199 1 0.346458 1 0.323054 0.967301 0.370474 1 0.346458 0.96614 0.347199 0.964698 0.323933 1 0.323054 1 0.299651 0.96614 0.347199 1 0.323054 0.964698 0.323933 0.96292 0.30068 1 0.299651 1 0.276258 0.964698 0.323933 1 0.299651 0.96292 0.30068 0.960736 0.277455 1 0.276258 1 0.272871 0.96292 0.30068 1 0.276258 0.960736 0.277455 0.960468 0.274088 1 0.272871 1 0.270072 0.960736 0.277455 1 0.272871 0.960468 0.274088 0.960415 0.271295 1 0.270072 1 0.26833 0.960468 0.274088 1 0.270072 0.960415 0.271295 0.960587 0.269544 1 0.26833 1 0.264941 0.960415 0.271295 1 0.26833 0.960587 0.269544 0.960955 0.266136 1 0.264941 1 0.259726 0.960587 0.269544 1 0.264941 0.960955 0.266136 0.960906 0.260927 1 0.259726 1 0.253371 0.960955 0.266136 1 0.259726 0.960906 0.260927 0.960445 0.254602 1 0.253371 1 0.24663 0.960906 0.260927 1 0.253371 0.960445 0.254602 0.959607 0.247915 1 0.24663 1 0.240274 0.960445 0.254602 1 0.24663 0.959607 0.247915 0.958468 0.241631 1 0.240274 1 0.235059 0.959607 0.247915 1 0.240274 0.958468 0.241631 1 0.223742 1 0.23167 1 0.235059 0.95715 0.2365 1 0.235059 1 0.23167 1 0.20035 1 0.223742 1 0.235059 0.958468 0.241631 1 0.235059 0.95715 0.2365 1 0.227129 1 0.229928 1 0.23167 0.955823 0.233199 1 0.23167 1 0.229928 1 0.223742 1 0.227129 1 0.23167 0.95715 0.2365 1 0.23167 0.955823 0.233199 0.955145 0.2315019 1 0.229928 1 0.227129 0.955823 0.233199 1 0.229928 0.955145 0.2315019 0.954414 0.228751 1 0.227129 1 0.223742 0.955145 0.2315019 1 0.227129 0.954414 0.228751 0.953749 0.225406 1 0.223742 1 0.20035 0.954414 0.228751 1 0.223742 0.953749 0.225406 0.949284 0.202284 1 0.20035 1 0.1769469 0.953749 0.225406 1 0.20035 0.949284 0.202284 0.94354 0.179212 1 0.1769469 1 0.153544 0.949284 0.202284 1 0.1769469 0.94354 0.179212 0.935968 0.156224 1 0.153544 1 0.130141 0.94354 0.179212 1 0.153544 0.935968 0.156224 0.925644 0.133368 1 0.130141 1 0.106738 0.935968 0.156224 1 0.130141 0.925644 0.133368 0.910903 0.1107259 1 0.106738 1 0.08333498 0.925644 0.133368 1 0.106738 0.910903 0.1107259 0.888465 0.08846098 1 0.08333498 1 0.05993199 0.910903 0.1107259 1 0.08333498 0.888465 0.08846098 0.851046 0.06695097 1 0.05993199 1 0.036529 0.888465 0.08846098 1 0.05993199 0.851046 0.06695097 0.78022 0.04723989 1 0.036529 1 0.013125 0.851046 0.06695097 1 0.036529 0.78022 0.04723989 0.630814 0.03275698 1 0.013125 0 0.01027894 0.78022 0.04723989 1 0.013125 0.630814 0.03275698 0 0.06500399 0 0.03368192 0 0.01027894 0.395304 0.03172689 0 0.01027894 0 0.03368192 0 0.06839197 0 0.06500399 0 0.01027894 0.630814 0.03275698 0 0.01027894 0.395304 0.03172689 0 0.06046295 0 0.05707496 0 0.03368192 0.232493 0.04508197 0 0.03368192 0 0.05707496 0 0.06326097 0 0.06046295 0 0.03368192 0 0.06500399 0 0.06326097 0 0.03368192 0.395304 0.03172689 0 0.03368192 0.232493 0.04508197 0.155229 0.06441396 0 0.05707496 0 0.06046295 0.232493 0.04508197 0 0.05707496 0.155229 0.06441396 0.147554 0.06739497 0 0.06046295 0 0.06326097 0.155229 0.06441396 0 0.06046295 0.147554 0.06739497 0.141161 0.06983095 0 0.06326097 0 0.06500399 0.147554 0.06739497 0 0.06326097 0.141161 0.06983095 0.136764 0.07129698 0 0.06500399 0 0.06839197 0.141161 0.06983095 0 0.06500399 0.136764 0.07129698 0.128619 0.07417595 0 0.06839197 0 0.07360696 0.136764 0.07129698 0 0.06839197 0.128619 0.07417595 0.118999 0.07885497 0 0.07360696 0 0.07996296 0.128619 0.07417595 0 0.07360696 0.118999 0.07885497 0.10973 0.08473497 0 0.07996296 0 0.086703 0.118999 0.07885497 0 0.07996296 0.10973 0.08473497 0.101967 0.09110599 0 0.086703 0 0.093059 0.10973 0.08473497 0 0.086703 0.101967 0.09110599 0.096255 0.09721797 0 0.093059 0 0.09827399 0.101967 0.09110599 0 0.093059 0.096255 0.09721797 0.092785 0.102316 0 0.09827399 0 0.101663 0.096255 0.09721797 0 0.09827399 0.092785 0.102316 0.09158998 0.105714 0 0.101663 0 0.1034049 0.092785 0.102316 0 0.101663 0.09158998 0.105714 0.09097295 0.107458 0 0.1034049 0 0.106204 0.09158998 0.105714 0 0.1034049 0.09097295 0.107458 0.08931499 0.110195 0 0.106204 0 0.109592 0.09097295 0.107458 0 0.106204 0.08931499 0.110195 0.086977 0.113471 0 0.109592 0 0.132984 0.08931499 0.110195 0 0.109592 0.086977 0.113471 0.07291001 0.1361359 0 0.132984 0 0.156387 0.086977 0.113471 0 0.132984 0.07291001 0.1361359 0.06298798 0.159011 0 0.156387 0 0.179791 0.07291001 0.1361359 0 0.156387 0.06298798 0.159011 0.05567795 0.182012 0 0.179791 0 0.203194 0.06298798 0.159011 0 0.179791 0.05567795 0.182012 0.05011296 0.205094 0 0.203194 0 0.226597 0.05567795 0.182012 0 0.203194 0.05011296 0.205094 0.04577493 0.228233 0 0.226597 0 0.25 0.05011296 0.205094 0 0.226597 0.04577493 0.228233 0.04233098 0.251413 0 0.25 0 0.273404 0.04577493 0.228233 0 0.25 0.04233098 0.251413 0.03956395 0.274623 0 0.273404 0 0.296807 0.04233098 0.251413 0 0.273404 0.03956395 0.274623 0.03732198 0.297856 0 0.296807 0 0.32021 0.03956395 0.274623 0 0.296807 0.03732198 0.297856 0.03549891 0.321106 0 0.32021 0 0.343613 0.03732198 0.297856 0 0.32021 0.03549891 0.321106 0.03401988 0.34437 0 0.343613 0 0.367016 0.03549891 0.321106 0 0.343613 0.03401988 0.34437 0.03282696 0.367644 0 0.367016 0 0.390408 0.03401988 0.34437 0 0.367016 0.03282696 0.367644 0.03188097 0.390915 0 0.390408 0 0.393796 0.03282696 0.367644 0 0.390408 0.03188097 0.390915 0.03169095 0.394284 0 0.393796 0 0.396595 0.03188097 0.390915 0 0.393796 0.03169095 0.394284 0 0.401726 0 0.398337 0 0.396595 0.03139895 0.397063 0 0.396595 0 0.398337 0.03169095 0.394284 0 0.396595 0.03139895 0.397063 0.03105497 0.398788 0 0.398337 0 0.401726 0.03139895 0.397063 0 0.398337 0.03105497 0.398788 0.03036797 0.402145 0 0.401726 0 0.40694 0.03105497 0.398788 0 0.401726 0.03036797 0.402145 0.02979993 0.407325 0 0.40694 0 0.413296 0.03036797 0.402145 0 0.40694 0.02979993 0.407325 0.02941393 0.413648 0 0.413296 0 0.420036 0.02979993 0.407325 0 0.413296 0.02941393 0.413648 0.02924895 0.42036 0 0.420036 0 0.426392 0.02941393 0.413648 0 0.420036 0.02924895 0.42036 0.02931797 0.426693 0 0.426392 0 0.431608 0.02924895 0.42036 0 0.426392 0.02931797 0.426693 0.02961695 0.431895 0 0.431608 0 0.434996 0.02931797 0.426693 0 0.431608 0.02961695 0.431895 0.03011596 0.435279 0 0.434996 0 0.436739 0.02961695 0.431895 0 0.434996 0.03011596 0.435279 0.03035998 0.437019 0 0.436739 0 0.439537 0.03011596 0.435279 0 0.436739 0.03035998 0.437019 0.03049898 0.439808 0 0.439537 0 0.442925 0.03035998 0.437019 0 0.439537 0.03049898 0.439808 0.0305069 0.443181 0 0.442925 0 0.466317 0.03049898 0.439808 0 0.442925 0.0305069 0.443181 0.03018891 0.466468 0 0.466317 0 0.489719 0.0305069 0.443181 0 0.466317 0.03018891 0.466468 0.03003698 0.489766 0 0.489719 0 0.513123 0.03018891 0.466468 0 0.489719 0.03003698 0.489766 0.03004598 0.513066 0 0.513123 0 0.536526 0.03003698 0.489766 0 0.513123 0.03004598 0.513066 0.03021889 0.536364 0 0.536526 0 0.559929 0.03004598 0.513066 0 0.536526 0.03021889 0.536364 0.03055799 0.559661 0 0.559929 0 0.583332 0.03021889 0.536364 0 0.559929 0.03055799 0.559661 0.03107392 0.582954 0 0.583332 0 0.606736 0.03055799 0.559661 0 0.583332 0.03107392 0.582954 0.03178 0.606243 0 0.606736 0 0.630139 0.03107392 0.582954 0 0.606736 0.03178 0.606243 0.03269892 0.629527 0 0.630139 0 0.653542 0.03178 0.606243 0 0.630139 0.03269892 0.629527 0.0338599 0.652802 0 0.653542 0 0.676946 0.03269892 0.629527 0 0.653542 0.0338599 0.652802 0.03530198 0.676068 0 0.676946 0 0.700349 0.0338599 0.652802 0 0.676946 0.03530198 0.676068 0.03707993 0.69932 0 0.700349 0 0.723742 0.03530198 0.676068 0 0.700349 0.03707993 0.69932 0.03926396 0.722545 0 0.723742 0 0.727129 0.03707993 0.69932 0 0.723742 0.03926396 0.722545 0.03953188 0.725912 0 0.727129 0 0.729928 0.03926396 0.722545 0 0.727129 0.03953188 0.725912 0.03958499 0.728705 0 0.729928 0 0.73167 0.03953188 0.725912 0 0.729928 0.03958499 0.728705 0.03941297 0.730456 0 0.73167 0 0.735059 0.03958499 0.728705 0 0.73167 0.03941297 0.730456 0.03904491 0.733864 0 0.735059 0 0.740274 0.03941297 0.730456 0 0.735059 0.03904491 0.733864 0.03909397 0.739073 0 0.740274 0 0.746629 0.03904491 0.733864 0 0.740274 0.03909397 0.739073 0.03955495 0.745398 0 0.746629 0 0.75337 0.03909397 0.739073 0 0.746629 0.03955495 0.745398 0.04039299 0.752085 0 0.75337 0 0.759726 0.03955495 0.745398 0 0.75337 0.04039299 0.752085 0.04153198 0.758369 0 0.759726 0 0.764941 0.04039299 0.752085 0 0.759726 0.04153198 0.758369 0 0.776258 0 0.76833 0 0.764941 0.04284989 0.7635 0 0.764941 0 0.76833 0 0.79965 0 0.776258 0 0.764941 0.04153198 0.758369 0 0.764941 0.04284989 0.7635 0 0.772871 0 0.770072 0 0.76833 0.04417693 0.766801 0 0.76833 0 0.770072 0 0.776258 0 0.772871 0 0.76833 0.04284989 0.7635 0 0.76833 0.04417693 0.766801 0.04485493 0.768498 0 0.770072 0 0.772871 0.04417693 0.766801 0 0.770072 0.04485493 0.768498 0.04558593 0.771249 0 0.772871 0 0.776258 0.04485493 0.768498 0 0.772871 0.04558593 0.771249 0.04625093 0.774594 0 0.776258 0 0.79965 0.04558593 0.771249 0 0.776258 0.04625093 0.774594 0.05071598 0.797716 0 0.79965 0 0.823053 0.04625093 0.774594 0 0.79965 0.05071598 0.797716 0.05645996 0.820789 0 0.823053 0 0.846456 0.05071598 0.797716 0 0.823053 0.05645996 0.820789 0.06403195 0.843776 0 0.846456 0 0.869859 0.05645996 0.820789 0 0.846456 0.06403195 0.843776 0.07435697 0.866632 0 0.869859 0 0.893262 0.06403195 0.843776 0 0.869859 0.07435697 0.866632 0.08909696 0.889274 0 0.893262 0 0.916665 0.07435697 0.866632 0 0.893262 0.08909696 0.889274 0.111535 0.91154 0 0.916665 0 0.940069 0.08909696 0.889274 0 0.916665 0.111535 0.91154 0.148955 0.93305 0 0.940069 0 0.963472 0.111535 0.91154 0 0.940069 0.148955 0.93305 0.2197819 0.95276 0 0.963472 0 0.986875 0.148955 0.93305 0 0.963472 0.2197819 0.95276 0.36919 0.967243 0 0.986875 1 0.989721 0.2197819 0.95276 0 0.986875 0.36919 0.967243 1 0.934996 1 0.966318 1 0.989721 0.604699 0.968273 1 0.989721 1 0.966318 1 0.931608 1 0.934996 1 0.989721 0.36919 0.967243 1 0.989721 0.604699 0.968273 1 0.939537 1 0.942925 1 0.966318 0.767508 0.954918 1 0.966318 1 0.942925 1 0.936739 1 0.939537 1 0.966318 1 0.934996 1 0.936739 1 0.966318 0.604699 0.968273 1 0.966318 0.767508 0.954918 0.844771 0.935586 1 0.942925 1 0.939537 0.767508 0.954918 1 0.942925 0.844771 0.935586 0.852446 0.932605 1 0.939537 1 0.936739 0.844771 0.935586 1 0.939537 0.852446 0.932605 0.858839 0.930169 1 0.936739 1 0.934996 0.852446 0.932605 1 0.936739 0.858839 0.930169 0.863236 0.928703 1 0.934996 1 0.931608 0.858839 0.930169 1 0.934996 0.863236 0.928703 0.871381 0.925824 1 0.931608 1 0.926393 0.863236 0.928703 1 0.931608 0.871381 0.925824 0.881001 0.921145 1 0.926393 1 0.920037 0.871381 0.925824 1 0.926393 0.881001 0.921145 0.89027 0.915265 1 0.920037 1 0.913297 0.881001 0.921145 1 0.920037 0.89027 0.915265 0.898033 0.908894 1 0.913297 1 0.906941 0.89027 0.915265 1 0.913297 0.898033 0.908894 0.903745 0.902782 1 0.906941 1 0.901726 0.898033 0.908894 1 0.906941 0.903745 0.902782 0.907215 0.897684 1 0.901726 1 0.898337 0.903745 0.902782 1 0.901726 0.907215 0.897684 0.90841 0.894286 1 0.898337 1 0.896595 0.907215 0.897684 1 0.898337 0.90841 0.894286 0.909027 0.892542 1 0.896595 1 0.893796 0.90841 0.894286 1 0.896595 0.909027 0.892542 0.910685 0.889805 1 0.893796 1 0.890408 0.909027 0.892542 1 0.893796 0.910685 0.889805 0.913023 0.886529 1 0.890408 1 0.867016 0.910685 0.889805 1 0.890408 0.913023 0.886529 0.92709 0.863865 1 0.867016 1 0.843614 0.92709 0.863865 0.913023 0.886529 1 0.867016 0.937011 0.84099 1 0.843614 1 0.820211 0.92709 0.863865 1 0.843614 0.937011 0.84099 0.944322 0.81799 1 0.820211 1 0.796808 0.937011 0.84099 1 0.820211 0.944322 0.81799 0.949886 0.794909 1 0.796808 1 0.773405 0.944322 0.81799 1 0.796808 0.949886 0.794909 0.954225 0.77177 1 0.773405 1 0.750001 0.949886 0.794909 1 0.773405 0.954225 0.77177 0.957669 0.74859 1 0.750001 1 0.726598 0.954225 0.77177 1 0.750001 0.957669 0.74859 0.960436 0.72538 1 0.726598 1 0.703195 0.957669 0.74859 1 0.726598 0.960436 0.72538 0.962678 0.702147 1 0.703195 1 0.679792 0.960436 0.72538 1 0.703195 0.962678 0.702147 0.964501 0.678896 1 0.679792 1 0.656388 0.962678 0.702147 1 0.679792 0.964501 0.678896 0.96598 0.655631 1 0.656388 1 0.632985 0.964501 0.678896 1 0.656388 0.96598 0.655631 0.967173 0.632357 1 0.632985 1 0.609592 0.96598 0.655631 1 0.632985 0.967173 0.632357 0.968119 0.609085 1 0.609592 1 0.606204 0.967173 0.632357 1 0.609592 0.968119 0.609085 0.968309 0.605716 1 0.606204 1 0.603405 0.968119 0.609085 1 0.606204 0.968309 0.605716 0.968309 0.605716 1 0.603405 0.968601 0.602937 0.5 0.647895 0.5 0.641129 0.476394 0.63927 0.524909 0.645933 0.523606 0.63927 0.5 0.641129 0.524909 0.645933 0.5 0.641129 0.5 0.647895 0.475091 0.645933 0.476394 0.63927 0.453618 0.63377 0.475091 0.645933 0.5 0.647895 0.476394 0.63927 0.451088 0.640133 0.453618 0.63377 0.432408 0.624844 0.475091 0.645933 0.453618 0.63377 0.451088 0.640133 0.428782 0.63073 0.432408 0.624844 0.413352 0.612819 0.451088 0.640133 0.432408 0.624844 0.428782 0.63073 0.408801 0.618079 0.413352 0.612819 0.396874 0.5981 0.428782 0.63073 0.413352 0.612819 0.408801 0.618079 0.391582 0.602624 0.396874 0.5981 0.383239 0.581138 0.408801 0.618079 0.396874 0.5981 0.391582 0.602624 0.377376 0.584839 0.383239 0.581138 0.372583 0.562393 0.391582 0.602624 0.383239 0.581138 0.377376 0.584839 0.366304 0.565207 0.372583 0.562393 0.364962 0.542321 0.377376 0.584839 0.372583 0.562393 0.366304 0.565207 0.358407 0.544216 0.364962 0.542321 0.360393 0.521376 0.366304 0.565207 0.364962 0.542321 0.358407 0.544216 0.353679 0.522332 0.360393 0.521376 0.358871 0.5 0.358407 0.544216 0.360393 0.521376 0.353679 0.522332 0.352105 0.5 0.358871 0.5 0.360393 0.478624 0.353679 0.522332 0.358871 0.5 0.352105 0.5 0.353679 0.477668 0.360393 0.478624 0.364962 0.457679 0.352105 0.5 0.360393 0.478624 0.353679 0.477668 0.358407 0.455784 0.364962 0.457679 0.372583 0.437607 0.353679 0.477668 0.364962 0.457679 0.358407 0.455784 0.366304 0.434793 0.372583 0.437607 0.383239 0.418862 0.358407 0.455784 0.372583 0.437607 0.366304 0.434793 0.377376 0.415161 0.383239 0.418862 0.396874 0.4019 0.366304 0.434793 0.383239 0.418862 0.377376 0.415161 0.391582 0.397376 0.396874 0.4019 0.413352 0.387181 0.377376 0.415161 0.396874 0.4019 0.391582 0.397376 0.408801 0.381921 0.413352 0.387181 0.432408 0.375156 0.391582 0.397376 0.413352 0.387181 0.408801 0.381921 0.428782 0.36927 0.432408 0.375156 0.453618 0.36623 0.408801 0.381921 0.432408 0.375156 0.428782 0.36927 0.451088 0.359867 0.453618 0.36623 0.476394 0.36073 0.428782 0.36927 0.453618 0.36623 0.451088 0.359867 0.475091 0.354067 0.476394 0.36073 0.5 0.358871 0.451088 0.359867 0.476394 0.36073 0.475091 0.354067 0.5 0.352105 0.5 0.358871 0.523606 0.36073 0.475091 0.354067 0.5 0.358871 0.5 0.352105 0.524909 0.354067 0.523606 0.36073 0.546382 0.36623 0.5 0.352105 0.523606 0.36073 0.524909 0.354067 0.548912 0.359867 0.546382 0.36623 0.567592 0.375156 0.524909 0.354067 0.546382 0.36623 0.548912 0.359867 0.571218 0.36927 0.567592 0.375156 0.586648 0.387181 0.548912 0.359867 0.567592 0.375156 0.571218 0.36927 0.591199 0.381921 0.586648 0.387181 0.603126 0.4019 0.571218 0.36927 0.586648 0.387181 0.591199 0.381921 0.608418 0.397376 0.603126 0.4019 0.616761 0.418862 0.591199 0.381921 0.603126 0.4019 0.608418 0.397376 0.622624 0.415161 0.616761 0.418862 0.627417 0.437607 0.608418 0.397376 0.616761 0.418862 0.622624 0.415161 0.633696 0.434793 0.627417 0.437607 0.635038 0.457679 0.622624 0.415161 0.627417 0.437607 0.633696 0.434793 0.641593 0.455784 0.635038 0.457679 0.639607 0.478624 0.633696 0.434793 0.635038 0.457679 0.641593 0.455784 0.646321 0.477668 0.639607 0.478624 0.641129 0.5 0.641593 0.455784 0.639607 0.478624 0.646321 0.477668 0.647895 0.5 0.641129 0.5 0.639607 0.521376 0.646321 0.477668 0.641129 0.5 0.647895 0.5 0.646321 0.522332 0.639607 0.521376 0.635038 0.542321 0.647895 0.5 0.639607 0.521376 0.646321 0.522332 0.641593 0.544216 0.635038 0.542321 0.627417 0.562393 0.646321 0.522332 0.635038 0.542321 0.641593 0.544216 0.633696 0.565207 0.627417 0.562393 0.616761 0.581138 0.641593 0.544216 0.627417 0.562393 0.633696 0.565207 0.622624 0.584839 0.616761 0.581138 0.603126 0.5981 0.633696 0.565207 0.616761 0.581138 0.622624 0.584839 0.608418 0.602624 0.603126 0.5981 0.586648 0.612819 0.622624 0.584839 0.603126 0.5981 0.608418 0.602624 0.591199 0.618079 0.586648 0.612819 0.567592 0.624844 0.608418 0.602624 0.586648 0.612819 0.591199 0.618079 0.571218 0.63073 0.567592 0.624844 0.546382 0.63377 0.591199 0.618079 0.567592 0.624844 0.571218 0.63073 0.548912 0.640133 0.546382 0.63377 0.523606 0.63927 0.571218 0.63073 0.546382 0.63377 0.548912 0.640133 0.548912 0.640133 0.523606 0.63927 0.524909 0.645933 0.479433 0.388274 0.488756 0.377892 0.5 0.377401 0.5 0.371307 0.5 0.377401 0.488756 0.377892 0.5 0.386474 0.5 0.377401 0.511244 0.377892 0.511867 0.371825 0.511244 0.377892 0.5 0.377401 0.5 0.386474 0.479433 0.388274 0.5 0.377401 0.511867 0.371825 0.5 0.377401 0.5 0.371307 0.479433 0.388274 0.477627 0.379359 0.488756 0.377892 0.488133 0.371825 0.488756 0.377892 0.477627 0.379359 0.5 0.371307 0.488756 0.377892 0.488133 0.371825 0.459653 0.393598 0.466721 0.381786 0.477627 0.379359 0.476391 0.373374 0.477627 0.379359 0.466721 0.381786 0.479433 0.388274 0.459653 0.393598 0.477627 0.379359 0.488133 0.371825 0.477627 0.379359 0.476391 0.373374 0.459653 0.393598 0.456143 0.385146 0.466721 0.381786 0.464891 0.375934 0.466721 0.381786 0.456143 0.385146 0.476391 0.373374 0.466721 0.381786 0.464891 0.375934 0.441373 0.402224 0.445987 0.389403 0.456143 0.385146 0.453746 0.379477 0.456143 0.385146 0.445987 0.389403 0.459653 0.393598 0.441373 0.402224 0.456143 0.385146 0.464891 0.375934 0.456143 0.385146 0.453746 0.379477 0.441373 0.402224 0.43634 0.394511 0.445987 0.389403 0.443057 0.383963 0.445987 0.389403 0.43634 0.394511 0.453746 0.379477 0.445987 0.389403 0.443057 0.383963 0.425177 0.413816 0.427276 0.40042 0.43634 0.394511 0.432915 0.389344 0.43634 0.394511 0.427276 0.40042 0.441373 0.402224 0.425177 0.413816 0.43634 0.394511 0.443057 0.383963 0.43634 0.394511 0.432915 0.389344 0.425177 0.413816 0.418857 0.407073 0.427276 0.40042 0.423397 0.395565 0.427276 0.40042 0.418857 0.407073 0.432915 0.389344 0.427276 0.40042 0.423397 0.395565 0.411503 0.427949 0.411136 0.414408 0.418857 0.407073 0.414568 0.402564 0.418857 0.407073 0.411136 0.414408 0.425177 0.413816 0.411503 0.427949 0.418857 0.407073 0.423397 0.395565 0.418857 0.407073 0.414568 0.402564 0.400648 0.444146 0.404153 0.42236 0.411136 0.414408 0.406482 0.410276 0.411136 0.414408 0.404153 0.42236 0.411503 0.427949 0.400648 0.444146 0.411136 0.414408 0.414568 0.402564 0.411136 0.414408 0.406482 0.410276 0.400648 0.444146 0.397941 0.430862 0.404153 0.42236 0.399179 0.418631 0.404153 0.42236 0.397941 0.430862 0.406482 0.410276 0.404153 0.42236 0.399179 0.418631 0.392799 0.4619 0.392524 0.439847 0.397941 0.430862 0.392692 0.427557 0.397941 0.430862 0.392524 0.439847 0.400648 0.444146 0.392799 0.4619 0.397941 0.430862 0.399179 0.418631 0.397941 0.430862 0.392692 0.427557 0.388059 0.480691 0.387919 0.449245 0.392524 0.439847 0.387043 0.436983 0.392524 0.439847 0.387919 0.449245 0.392799 0.4619 0.388059 0.480691 0.392524 0.439847 0.392692 0.427557 0.392524 0.439847 0.387043 0.436983 0.38414 0.541014 0.38414 0.458986 0.387919 0.449245 0.382247 0.446835 0.387919 0.449245 0.38414 0.458986 0.386474 0.5 0.38414 0.541014 0.387919 0.449245 0.388059 0.480691 0.386474 0.5 0.387919 0.449245 0.387043 0.436983 0.387919 0.449245 0.382247 0.446835 0.381195 0.531 0.381195 0.469 0.38414 0.458986 0.378314 0.457043 0.38414 0.458986 0.381195 0.469 0.38414 0.541014 0.381195 0.531 0.38414 0.458986 0.382247 0.446835 0.38414 0.458986 0.378314 0.457043 0.379088 0.52078 0.379088 0.47922 0.381195 0.469 0.375251 0.467534 0.381195 0.469 0.379088 0.47922 0.381195 0.531 0.379088 0.52078 0.381195 0.469 0.378314 0.457043 0.381195 0.469 0.375251 0.467534 0.377823 0.510424 0.377823 0.489576 0.379088 0.47922 0.37306 0.478238 0.379088 0.47922 0.377823 0.489576 0.379088 0.52078 0.377823 0.510424 0.379088 0.47922 0.375251 0.467534 0.379088 0.47922 0.37306 0.478238 0.377823 0.510424 0.377401 0.5 0.377823 0.489576 0.371745 0.489083 0.377823 0.489576 0.377401 0.5 0.37306 0.478238 0.377823 0.489576 0.371745 0.489083 0.371307 0.5 0.377401 0.5 0.377823 0.510424 0.371745 0.489083 0.377401 0.5 0.371307 0.5 0.371745 0.510917 0.377823 0.510424 0.379088 0.52078 0.371307 0.5 0.377823 0.510424 0.371745 0.510917 0.37306 0.521762 0.379088 0.52078 0.381195 0.531 0.371745 0.510917 0.379088 0.52078 0.37306 0.521762 0.375251 0.532466 0.381195 0.531 0.38414 0.541014 0.37306 0.521762 0.381195 0.531 0.375251 0.532466 0.386474 0.5 0.387919 0.550755 0.38414 0.541014 0.378314 0.542957 0.38414 0.541014 0.387919 0.550755 0.375251 0.532466 0.38414 0.541014 0.378314 0.542957 0.388059 0.519309 0.392524 0.560153 0.387919 0.550755 0.382247 0.553165 0.387919 0.550755 0.392524 0.560153 0.386474 0.5 0.388059 0.519309 0.387919 0.550755 0.378314 0.542957 0.387919 0.550755 0.382247 0.553165 0.392799 0.5381 0.397941 0.569138 0.392524 0.560153 0.387043 0.563017 0.392524 0.560153 0.397941 0.569138 0.388059 0.519309 0.392799 0.5381 0.392524 0.560153 0.382247 0.553165 0.392524 0.560153 0.387043 0.563017 0.400648 0.555854 0.404153 0.57764 0.397941 0.569138 0.392692 0.572443 0.397941 0.569138 0.404153 0.57764 0.392799 0.5381 0.400648 0.555854 0.397941 0.569138 0.387043 0.563017 0.397941 0.569138 0.392692 0.572443 0.411503 0.572051 0.411136 0.585592 0.404153 0.57764 0.399179 0.581369 0.404153 0.57764 0.411136 0.585592 0.400648 0.555854 0.411503 0.572051 0.404153 0.57764 0.392692 0.572443 0.404153 0.57764 0.399179 0.581369 0.411503 0.572051 0.418857 0.592927 0.411136 0.585592 0.406482 0.589724 0.411136 0.585592 0.418857 0.592927 0.399179 0.581369 0.411136 0.585592 0.406482 0.589724 0.425177 0.586184 0.427276 0.59958 0.418857 0.592927 0.414568 0.597436 0.418857 0.592927 0.427276 0.59958 0.411503 0.572051 0.425177 0.586184 0.418857 0.592927 0.406482 0.589724 0.418857 0.592927 0.414568 0.597436 0.441373 0.597776 0.43634 0.605489 0.427276 0.59958 0.423397 0.604435 0.427276 0.59958 0.43634 0.605489 0.425177 0.586184 0.441373 0.597776 0.427276 0.59958 0.414568 0.597436 0.427276 0.59958 0.423397 0.604435 0.441373 0.597776 0.445987 0.610597 0.43634 0.605489 0.432915 0.610656 0.43634 0.605489 0.445987 0.610597 0.423397 0.604435 0.43634 0.605489 0.432915 0.610656 0.459653 0.606402 0.456143 0.614854 0.445987 0.610597 0.443057 0.616037 0.445987 0.610597 0.456143 0.614854 0.441373 0.597776 0.459653 0.606402 0.445987 0.610597 0.432915 0.610656 0.445987 0.610597 0.443057 0.616037 0.459653 0.606402 0.466721 0.618214 0.456143 0.614854 0.453746 0.620523 0.456143 0.614854 0.466721 0.618214 0.443057 0.616037 0.456143 0.614854 0.453746 0.620523 0.479433 0.611726 0.477627 0.620641 0.466721 0.618214 0.464891 0.624066 0.466721 0.618214 0.477627 0.620641 0.459653 0.606402 0.479433 0.611726 0.466721 0.618214 0.453746 0.620523 0.466721 0.618214 0.464891 0.624066 0.479433 0.611726 0.488756 0.622108 0.477627 0.620641 0.476391 0.626626 0.477627 0.620641 0.488756 0.622108 0.464891 0.624066 0.477627 0.620641 0.476391 0.626626 0.5 0.613526 0.5 0.622599 0.488756 0.622108 0.488133 0.628175 0.488756 0.622108 0.5 0.622599 0.479433 0.611726 0.5 0.613526 0.488756 0.622108 0.476391 0.626626 0.488756 0.622108 0.488133 0.628175 0.520567 0.611726 0.511244 0.622108 0.5 0.622599 0.5 0.628693 0.5 0.622599 0.511244 0.622108 0.520567 0.611726 0.5 0.622599 0.5 0.613526 0.488133 0.628175 0.5 0.622599 0.5 0.628693 0.520567 0.611726 0.522373 0.620641 0.511244 0.622108 0.511867 0.628175 0.511244 0.622108 0.522373 0.620641 0.511867 0.628175 0.5 0.628693 0.511244 0.622108 0.540347 0.606402 0.533279 0.618214 0.522373 0.620641 0.523609 0.626626 0.522373 0.620641 0.533279 0.618214 0.520567 0.611726 0.540347 0.606402 0.522373 0.620641 0.511867 0.628175 0.522373 0.620641 0.523609 0.626626 0.540347 0.606402 0.543857 0.614854 0.533279 0.618214 0.535109 0.624066 0.533279 0.618214 0.543857 0.614854 0.523609 0.626626 0.533279 0.618214 0.535109 0.624066 0.558627 0.597776 0.554013 0.610597 0.543857 0.614854 0.546254 0.620523 0.543857 0.614854 0.554013 0.610597 0.540347 0.606402 0.558627 0.597776 0.543857 0.614854 0.535109 0.624066 0.543857 0.614854 0.546254 0.620523 0.558627 0.597776 0.56366 0.605489 0.554013 0.610597 0.556943 0.616037 0.554013 0.610597 0.56366 0.605489 0.546254 0.620523 0.554013 0.610597 0.556943 0.616037 0.574823 0.586184 0.572724 0.59958 0.56366 0.605489 0.567085 0.610656 0.56366 0.605489 0.572724 0.59958 0.558627 0.597776 0.574823 0.586184 0.56366 0.605489 0.556943 0.616037 0.56366 0.605489 0.567085 0.610656 0.574823 0.586184 0.581143 0.592927 0.572724 0.59958 0.576603 0.604435 0.572724 0.59958 0.581143 0.592927 0.567085 0.610656 0.572724 0.59958 0.576603 0.604435 0.588497 0.572051 0.588864 0.585592 0.581143 0.592927 0.585432 0.597436 0.581143 0.592927 0.588864 0.585592 0.574823 0.586184 0.588497 0.572051 0.581143 0.592927 0.576603 0.604435 0.581143 0.592927 0.585432 0.597436 0.599352 0.555854 0.595847 0.57764 0.588864 0.585592 0.593518 0.589724 0.588864 0.585592 0.595847 0.57764 0.588497 0.572051 0.599352 0.555854 0.588864 0.585592 0.585432 0.597436 0.588864 0.585592 0.593518 0.589724 0.599352 0.555854 0.602059 0.569138 0.595847 0.57764 0.600821 0.581369 0.595847 0.57764 0.602059 0.569138 0.593518 0.589724 0.595847 0.57764 0.600821 0.581369 0.607201 0.5381 0.607476 0.560153 0.602059 0.569138 0.607308 0.572443 0.602059 0.569138 0.607476 0.560153 0.599352 0.555854 0.607201 0.5381 0.602059 0.569138 0.600821 0.581369 0.602059 0.569138 0.607308 0.572443 0.611941 0.519309 0.612081 0.550755 0.607476 0.560153 0.612957 0.563017 0.607476 0.560153 0.612081 0.550755 0.607201 0.5381 0.611941 0.519309 0.607476 0.560153 0.607308 0.572443 0.607476 0.560153 0.612957 0.563017 0.61586 0.458986 0.61586 0.541014 0.612081 0.550755 0.617753 0.553165 0.612081 0.550755 0.61586 0.541014 0.613526 0.5 0.61586 0.458986 0.612081 0.550755 0.611941 0.519309 0.613526 0.5 0.612081 0.550755 0.612957 0.563017 0.612081 0.550755 0.617753 0.553165 0.618805 0.469 0.618805 0.531 0.61586 0.541014 0.621686 0.542957 0.61586 0.541014 0.618805 0.531 0.61586 0.458986 0.618805 0.469 0.61586 0.541014 0.617753 0.553165 0.61586 0.541014 0.621686 0.542957 0.620912 0.47922 0.620912 0.52078 0.618805 0.531 0.624749 0.532466 0.618805 0.531 0.620912 0.52078 0.618805 0.469 0.620912 0.47922 0.618805 0.531 0.621686 0.542957 0.618805 0.531 0.624749 0.532466 0.622177 0.489576 0.622177 0.510424 0.620912 0.52078 0.62694 0.521762 0.620912 0.52078 0.622177 0.510424 0.620912 0.47922 0.622177 0.489576 0.620912 0.52078 0.624749 0.532466 0.620912 0.52078 0.62694 0.521762 0.622177 0.489576 0.622599 0.5 0.622177 0.510424 0.628255 0.510917 0.622177 0.510424 0.622599 0.5 0.62694 0.521762 0.622177 0.510424 0.628255 0.510917 0.628693 0.5 0.622599 0.5 0.622177 0.489576 0.628255 0.510917 0.622599 0.5 0.628693 0.5 0.628255 0.489083 0.622177 0.489576 0.620912 0.47922 0.628693 0.5 0.622177 0.489576 0.628255 0.489083 0.62694 0.478238 0.620912 0.47922 0.618805 0.469 0.628255 0.489083 0.620912 0.47922 0.62694 0.478238 0.624749 0.467534 0.618805 0.469 0.61586 0.458986 0.62694 0.478238 0.618805 0.469 0.624749 0.467534 0.613526 0.5 0.612081 0.449245 0.61586 0.458986 0.621686 0.457043 0.61586 0.458986 0.612081 0.449245 0.624749 0.467534 0.61586 0.458986 0.621686 0.457043 0.611941 0.480691 0.607476 0.439847 0.612081 0.449245 0.617753 0.446835 0.612081 0.449245 0.607476 0.439847 0.613526 0.5 0.611941 0.480691 0.612081 0.449245 0.621686 0.457043 0.612081 0.449245 0.617753 0.446835 0.607201 0.4619 0.602059 0.430862 0.607476 0.439847 0.612957 0.436983 0.607476 0.439847 0.602059 0.430862 0.611941 0.480691 0.607201 0.4619 0.607476 0.439847 0.617753 0.446835 0.607476 0.439847 0.612957 0.436983 0.599352 0.444146 0.595847 0.42236 0.602059 0.430862 0.607308 0.427557 0.602059 0.430862 0.595847 0.42236 0.607201 0.4619 0.599352 0.444146 0.602059 0.430862 0.612957 0.436983 0.602059 0.430862 0.607308 0.427557 0.588497 0.427949 0.588864 0.414408 0.595847 0.42236 0.600821 0.418631 0.595847 0.42236 0.588864 0.414408 0.599352 0.444146 0.588497 0.427949 0.595847 0.42236 0.607308 0.427557 0.595847 0.42236 0.600821 0.418631 0.588497 0.427949 0.581143 0.407073 0.588864 0.414408 0.593518 0.410276 0.588864 0.414408 0.581143 0.407073 0.600821 0.418631 0.588864 0.414408 0.593518 0.410276 0.574823 0.413816 0.572724 0.40042 0.581143 0.407073 0.585432 0.402564 0.581143 0.407073 0.572724 0.40042 0.588497 0.427949 0.574823 0.413816 0.581143 0.407073 0.593518 0.410276 0.581143 0.407073 0.585432 0.402564 0.558627 0.402224 0.56366 0.394511 0.572724 0.40042 0.576603 0.395565 0.572724 0.40042 0.56366 0.394511 0.574823 0.413816 0.558627 0.402224 0.572724 0.40042 0.585432 0.402564 0.572724 0.40042 0.576603 0.395565 0.558627 0.402224 0.554013 0.389403 0.56366 0.394511 0.567085 0.389344 0.56366 0.394511 0.554013 0.389403 0.576603 0.395565 0.56366 0.394511 0.567085 0.389344 0.540347 0.393598 0.543857 0.385146 0.554013 0.389403 0.556943 0.383963 0.554013 0.389403 0.543857 0.385146 0.558627 0.402224 0.540347 0.393598 0.554013 0.389403 0.567085 0.389344 0.554013 0.389403 0.556943 0.383963 0.540347 0.393598 0.533279 0.381786 0.543857 0.385146 0.546254 0.379477 0.543857 0.385146 0.533279 0.381786 0.556943 0.383963 0.543857 0.385146 0.546254 0.379477 0.520567 0.388274 0.522373 0.379359 0.533279 0.381786 0.535109 0.375934 0.533279 0.381786 0.522373 0.379359 0.540347 0.393598 0.520567 0.388274 0.533279 0.381786 0.546254 0.379477 0.533279 0.381786 0.535109 0.375934 0.520567 0.388274 0.511244 0.377892 0.522373 0.379359 0.523609 0.373374 0.522373 0.379359 0.511244 0.377892 0.535109 0.375934 0.522373 0.379359 0.523609 0.373374 0.520567 0.388274 0.5 0.386474 0.511244 0.377892 0.523609 0.373374 0.511244 0.377892 0.511867 0.371825 0.5 0.631153 0.5 0.613526 0.479433 0.611726 0.524113 0.629042 0.520567 0.611726 0.5 0.613526 0.524113 0.629042 0.5 0.613526 0.5 0.631153 0.475887 0.629042 0.479433 0.611726 0.459653 0.606402 0.475887 0.629042 0.5 0.631153 0.479433 0.611726 0.452769 0.62281 0.459653 0.606402 0.441373 0.597776 0.475887 0.629042 0.459653 0.606402 0.452769 0.62281 0.43152 0.612738 0.441373 0.597776 0.425177 0.586184 0.452769 0.62281 0.441373 0.597776 0.43152 0.612738 0.412826 0.599252 0.425177 0.586184 0.411503 0.572051 0.43152 0.612738 0.425177 0.586184 0.412826 0.599252 0.397163 0.58287 0.411503 0.572051 0.400648 0.555854 0.412826 0.599252 0.411503 0.572051 0.397163 0.58287 0.384825 0.564169 0.400648 0.555854 0.392799 0.5381 0.397163 0.58287 0.400648 0.555854 0.384825 0.564169 0.375959 0.543737 0.392799 0.5381 0.388059 0.519309 0.384825 0.564169 0.392799 0.5381 0.375959 0.543737 0.370626 0.522155 0.388059 0.519309 0.386474 0.5 0.375959 0.543737 0.388059 0.519309 0.370626 0.522155 0.368847 0.5 0.386474 0.5 0.388059 0.480691 0.370626 0.522155 0.386474 0.5 0.368847 0.5 0.370626 0.477845 0.388059 0.480691 0.392799 0.4619 0.368847 0.5 0.388059 0.480691 0.370626 0.477845 0.375959 0.456263 0.392799 0.4619 0.400648 0.444146 0.370626 0.477845 0.392799 0.4619 0.375959 0.456263 0.384825 0.435831 0.400648 0.444146 0.411503 0.427949 0.375959 0.456263 0.400648 0.444146 0.384825 0.435831 0.397163 0.41713 0.411503 0.427949 0.425177 0.413816 0.384825 0.435831 0.411503 0.427949 0.397163 0.41713 0.412826 0.400748 0.425177 0.413816 0.441373 0.402224 0.397163 0.41713 0.425177 0.413816 0.412826 0.400748 0.43152 0.387262 0.441373 0.402224 0.459653 0.393598 0.412826 0.400748 0.441373 0.402224 0.43152 0.387262 0.452769 0.37719 0.459653 0.393598 0.479433 0.388274 0.43152 0.387262 0.459653 0.393598 0.452769 0.37719 0.475887 0.370958 0.479433 0.388274 0.5 0.386474 0.452769 0.37719 0.479433 0.388274 0.475887 0.370958 0.5 0.368847 0.5 0.386474 0.520567 0.388274 0.475887 0.370958 0.5 0.386474 0.5 0.368847 0.524113 0.370958 0.520567 0.388274 0.540347 0.393598 0.5 0.368847 0.520567 0.388274 0.524113 0.370958 0.547231 0.37719 0.540347 0.393598 0.558627 0.402224 0.524113 0.370958 0.540347 0.393598 0.547231 0.37719 0.56848 0.387262 0.558627 0.402224 0.574823 0.413816 0.547231 0.37719 0.558627 0.402224 0.56848 0.387262 0.587174 0.400748 0.574823 0.413816 0.588497 0.427949 0.56848 0.387262 0.574823 0.413816 0.587174 0.400748 0.602837 0.41713 0.588497 0.427949 0.599352 0.444146 0.587174 0.400748 0.588497 0.427949 0.602837 0.41713 0.615175 0.435831 0.599352 0.444146 0.607201 0.4619 0.602837 0.41713 0.599352 0.444146 0.615175 0.435831 0.624041 0.456263 0.607201 0.4619 0.611941 0.480691 0.615175 0.435831 0.607201 0.4619 0.624041 0.456263 0.629374 0.477845 0.611941 0.480691 0.613526 0.5 0.624041 0.456263 0.611941 0.480691 0.629374 0.477845 0.631153 0.5 0.613526 0.5 0.611941 0.519309 0.629374 0.477845 0.613526 0.5 0.631153 0.5 0.629374 0.522155 0.611941 0.519309 0.607201 0.5381 0.631153 0.5 0.611941 0.519309 0.629374 0.522155 0.624041 0.543737 0.607201 0.5381 0.599352 0.555854 0.629374 0.522155 0.607201 0.5381 0.624041 0.543737 0.615175 0.564169 0.599352 0.555854 0.588497 0.572051 0.624041 0.543737 0.599352 0.555854 0.615175 0.564169 0.602837 0.58287 0.588497 0.572051 0.574823 0.586184 0.615175 0.564169 0.588497 0.572051 0.602837 0.58287 0.587174 0.599252 0.574823 0.586184 0.558627 0.597776 0.602837 0.58287 0.574823 0.586184 0.587174 0.599252 0.56848 0.612738 0.558627 0.597776 0.540347 0.606402 0.587174 0.599252 0.558627 0.597776 0.56848 0.612738 0.547231 0.62281 0.540347 0.606402 0.520567 0.611726 0.56848 0.612738 0.540347 0.606402 0.547231 0.62281 0.547231 0.62281 0.520567 0.611726 0.524113 0.629042 0.781071 0.744706 0.781071 0.744981 0.774906 0.741315 0.789643 0.747046 0.789642 0.74732 0.781071 0.744981 0.789643 0.747046 0.781071 0.744981 0.781071 0.744706 0.774905 0.741041 0.774906 0.741315 0.771832 0.736914 0.774905 0.741041 0.781071 0.744706 0.774906 0.741315 0.771832 0.73664 0.771832 0.736914 0.771999 0.732394 0.774905 0.741041 0.771832 0.736914 0.771832 0.73664 0.771999 0.73212 0.771999 0.732394 0.775132 0.728291 0.771832 0.73664 0.771999 0.732394 0.771999 0.73212 0.775132 0.728019 0.775132 0.728291 0.780681 0.725017 0.771999 0.73212 0.775132 0.728291 0.775132 0.728019 0.780681 0.724746 0.780681 0.725017 0.787945 0.722849 0.775132 0.728019 0.780681 0.725017 0.780681 0.724746 0.787943 0.722579 0.787945 0.722849 0.79615 0.721949 0.780681 0.724746 0.787945 0.722849 0.787943 0.722579 0.796148 0.721678 0.79615 0.721949 0.804498 0.722377 0.787943 0.722579 0.79615 0.721949 0.796148 0.721678 0.804496 0.722106 0.804498 0.722377 0.812187 0.724104 0.796148 0.721678 0.804498 0.722377 0.804496 0.722106 0.812187 0.723833 0.812187 0.724104 0.818433 0.727007 0.804496 0.722106 0.812187 0.724104 0.812187 0.723833 0.818434 0.726736 0.818433 0.727007 0.822504 0.730852 0.812187 0.723833 0.818433 0.727007 0.818434 0.726736 0.822505 0.73058 0.822504 0.730852 0.823782 0.735278 0.818434 0.726736 0.822504 0.730852 0.822505 0.73058 0.823782 0.735006 0.823782 0.735278 0.821876 0.739791 0.822505 0.73058 0.823782 0.735278 0.823782 0.735006 0.821876 0.739518 0.821876 0.739791 0.816766 0.743793 0.823782 0.735006 0.821876 0.739791 0.821876 0.739518 0.816767 0.743518 0.816766 0.743793 0.808941 0.746667 0.821876 0.739518 0.816766 0.743793 0.816767 0.743518 0.808942 0.746393 0.808941 0.746667 0.799427 0.74792 0.816767 0.743518 0.808941 0.746667 0.808942 0.746393 0.799429 0.747645 0.799427 0.74792 0.789642 0.74732 0.808942 0.746393 0.799427 0.74792 0.799429 0.747645 0.799429 0.747645 0.789642 0.74732 0.789643 0.747046 0.613709 0.675886 0.612955 0.674981 0.613419 0.67453 0.333935 0.137095 0.350175 0.119667 0.358368 0.101512 0.358368 0.138327 0.358368 0.101512 0.350175 0.119667 0.336072 0.04615491 0.333935 0.137095 0.358368 0.101512 0.336072 0.08344095 0.336072 0.04615491 0.358368 0.101512 0.346599 0.1142 0.336072 0.08344095 0.358368 0.101512 0.346599 0.1142 0.358368 0.101512 0.358368 0.138327 0.350177 0.15623 0.350175 0.119667 0.333935 0.137095 0.355256 0.147317 0.358368 0.138327 0.350175 0.119667 0.350177 0.15623 0.355256 0.147317 0.350175 0.119667 0.336072 0.04615491 0.227566 0.176816 0.333935 0.137095 0.333935 0.173372 0.333935 0.137095 0.227566 0.176816 0.343078 0.164954 0.350177 0.15623 0.333935 0.137095 0.333935 0.173372 0.343078 0.164954 0.333935 0.137095 0.317545 0.03269398 0.1847569 0.180042 0.227566 0.176816 0.227566 0.212281 0.227566 0.176816 0.1847569 0.180042 0.336072 0.04615491 0.317545 0.03269398 0.227566 0.176816 0.282938 0.1970019 0.227566 0.176816 0.227566 0.212281 0.282938 0.1970019 0.333935 0.173372 0.227566 0.176816 0.295205 0.0214039 0.141672 0.178286 0.1847569 0.180042 0.1848379 0.215431 0.1847569 0.180042 0.141672 0.178286 0.317545 0.03269398 0.295205 0.0214039 0.1847569 0.180042 0.1848379 0.215431 0.227566 0.212281 0.1847569 0.180042 0.204008 8.87e-4 0.02921998 0.1419939 0.141672 0.178286 0.141672 0.2137179 0.141672 0.178286 0.02921998 0.1419939 0.295205 0.0214039 0.204008 8.87e-4 0.141672 0.178286 0.141672 0.2137179 0.1848379 0.215431 0.141672 0.178286 0.173942 0 0.01057791 0.125002 0.02921998 0.1419939 0.02921998 0.178183 0.02921998 0.1419939 0.01057791 0.125002 0.204008 8.87e-4 0.173942 0 0.02921998 0.1419939 0.08334696 0.200248 0.141672 0.2137179 0.02921998 0.1419939 0.08334696 0.200248 0.02921998 0.1419939 0.02921998 0.178183 0.143866 0.001635909 0 0.1069329 0.01057791 0.125002 0.01055091 0.161449 0.01057791 0.125002 0 0.1069329 0.173942 0 0.143866 0.001635909 0.01057791 0.125002 0.01055091 0.161449 0.02921998 0.178183 0.01057791 0.125002 0.05453389 0.024535 0.01605898 0.05052691 0 0.1069329 0 0.143678 0 0.1069329 0.01605898 0.05052691 0.143866 0.001635909 0.05453389 0.024535 0 0.1069329 0 0.143678 0.01055091 0.161449 0 0.1069329 0.05453389 0.024535 0.03322392 0.036502 0.01605898 0.05052691 0.01605898 0.08779197 0.01605898 0.05052691 0.03322392 0.036502 0.008482992 0.119022 0 0.143678 0.01605898 0.05052691 0.008482992 0.119022 0.01605898 0.05052691 0.01605898 0.08779197 0.03322297 0.07382398 0.03322392 0.036502 0.05453389 0.024535 0.02406793 0.08056998 0.01605898 0.08779197 0.03322392 0.036502 0.03322297 0.07382398 0.02406793 0.08056998 0.03322392 0.036502 0.05453389 0.06188297 0.05453389 0.024535 0.143866 0.001635909 0.04341393 0.067586 0.03322297 0.07382398 0.05453389 0.024535 0.05453389 0.06188297 0.04341393 0.067586 0.05453389 0.024535 0.143866 0.03897297 0.143866 0.001635909 0.173942 0 0.1002179 0.05478292 0.143866 0.001635909 0.143866 0.03897297 0.1002179 0.05478292 0.05453389 0.06188297 0.143866 0.001635909 0.173886 0.03733396 0.173942 0 0.204008 8.87e-4 0.173886 0.03733396 0.143866 0.03897297 0.173942 0 0.204008 0.03822195 0.204008 8.87e-4 0.295205 0.0214039 0.204008 0.03822195 0.173886 0.03733396 0.204008 8.87e-4 0.295205 0.05875498 0.295205 0.0214039 0.317545 0.03269398 0.2486619 0.05288589 0.295205 0.0214039 0.295205 0.05875498 0.2486619 0.05288589 0.204008 0.03822195 0.295205 0.0214039 0.317583 0.07005 0.317545 0.03269398 0.336072 0.04615491 0.317583 0.07005 0.295205 0.05875498 0.317545 0.03269398 0.336072 0.08344095 0.317583 0.07005 0.336072 0.04615491 0.08078396 0.08863699 0.1172479 0.090801 0.08357697 0.107119 0.08357697 0.190131 0.08357697 0.107119 0.1172479 0.090801 0.06155788 0.09965795 0.08357697 0.107119 0.065732 0.129598 0.06574499 0.211666 0.065732 0.129598 0.08357697 0.107119 0.06155788 0.09965795 0.08078396 0.08863699 0.08357697 0.107119 0.06574499 0.211666 0.08357697 0.107119 0.08357697 0.190131 0.129029 0.07377696 0.160117 0.08267599 0.1172479 0.090801 0.117224 0.174398 0.1172479 0.090801 0.160117 0.08267599 0.103591 0.07995098 0.129029 0.07377696 0.1172479 0.090801 0.08078396 0.08863699 0.103591 0.07995098 0.1172479 0.090801 0.117224 0.174398 0.08357697 0.190131 0.1172479 0.090801 0.156136 0.07024699 0.205742 0.08360797 0.160117 0.08267599 0.160197 0.1665109 0.160117 0.08267599 0.205742 0.08360797 0.129029 0.07377696 0.156136 0.07024699 0.160117 0.08267599 0.117224 0.174398 0.160117 0.08267599 0.160197 0.1665109 0.156136 0.07024699 0.247259 0.09347897 0.205742 0.08360797 0.205662 0.1674129 0.205742 0.08360797 0.247259 0.09347897 0.160197 0.1665109 0.205742 0.08360797 0.205662 0.1674129 0.314085 0.1183969 0.278278 0.1112779 0.247259 0.09347897 0.247322 0.177003 0.247259 0.09347897 0.278278 0.1112779 0.301697 0.104713 0.314085 0.1183969 0.247259 0.09347897 0.156136 0.07024699 0.301697 0.104713 0.247259 0.09347897 0.205662 0.1674129 0.247259 0.09347897 0.247322 0.177003 0.320473 0.1334339 0.292175 0.134587 0.278278 0.1112779 0.278235 0.194094 0.278278 0.1112779 0.292175 0.134587 0.314085 0.1183969 0.320473 0.1334339 0.278278 0.1112779 0.247322 0.177003 0.278278 0.1112779 0.278235 0.194094 0.311915 0.164897 0.283919 0.15957 0.292175 0.134587 0.292169 0.216461 0.292175 0.134587 0.283919 0.15957 0.319983 0.149186 0.311915 0.164897 0.292175 0.134587 0.320473 0.1334339 0.319983 0.149186 0.292175 0.134587 0.278235 0.194094 0.292175 0.134587 0.292169 0.216461 0.295979 0.179591 0.251867 0.180778 0.283919 0.15957 0.283919 0.240176 0.283919 0.15957 0.251867 0.180778 0.295979 0.179591 0.283919 0.15957 0.311915 0.164897 0.292169 0.216461 0.283919 0.15957 0.283919 0.240176 0.242545 0.201826 0.201238 0.192508 0.251867 0.180778 0.251892 0.260161 0.251867 0.180778 0.201238 0.192508 0.272525 0.192218 0.242545 0.201826 0.251867 0.180778 0.295979 0.179591 0.272525 0.192218 0.251867 0.180778 0.283919 0.240176 0.251867 0.180778 0.251892 0.260161 0.2078509 0.207578 0.144269 0.19112 0.201238 0.192508 0.201138 0.271189 0.201238 0.192508 0.144269 0.19112 0.242545 0.201826 0.2078509 0.207578 0.201238 0.192508 0.251892 0.260161 0.201238 0.192508 0.201138 0.271189 0.2078509 0.207578 0.09662997 0.177091 0.144269 0.19112 0.1443679 0.269892 0.144269 0.19112 0.09662997 0.177091 0.201138 0.271189 0.144269 0.19112 0.1443679 0.269892 0.035703 0.142795 0.06920498 0.15461 0.09662997 0.177091 0.096565 0.256675 0.09662997 0.177091 0.06920498 0.15461 0.04064291 0.158603 0.035703 0.142795 0.09662997 0.177091 0.2078509 0.207578 0.04064291 0.158603 0.09662997 0.177091 0.1443679 0.269892 0.09662997 0.177091 0.096565 0.256675 0.03806895 0.1272439 0.065732 0.129598 0.06920498 0.15461 0.06923395 0.23552 0.06920498 0.15461 0.065732 0.129598 0.035703 0.142795 0.03806895 0.1272439 0.06920498 0.15461 0.096565 0.256675 0.06920498 0.15461 0.06923395 0.23552 0.04697996 0.1126829 0.06155788 0.09965795 0.065732 0.129598 0.03806895 0.1272439 0.04697996 0.1126829 0.065732 0.129598 0.06923395 0.23552 0.065732 0.129598 0.06574499 0.211666 0.350177 0.15623 0.311915 0.164897 0.319983 0.149186 0.333935 0.173372 0.295979 0.179591 0.311915 0.164897 0.343078 0.164954 0.311915 0.164897 0.350177 0.15623 0.333935 0.173372 0.311915 0.164897 0.343078 0.164954 0.358368 0.138327 0.319983 0.149186 0.320473 0.1334339 0.355256 0.147317 0.319983 0.149186 0.358368 0.138327 0.350177 0.15623 0.319983 0.149186 0.355256 0.147317 0.346599 0.1142 0.320473 0.1334339 0.314085 0.1183969 0.346599 0.1142 0.358368 0.138327 0.320473 0.1334339 0.336072 0.08344095 0.314085 0.1183969 0.301697 0.104713 0.346599 0.1142 0.314085 0.1183969 0.336072 0.08344095 0.18399 0.06942796 0.284279 0.09286099 0.301697 0.104713 0.317583 0.07005 0.301697 0.104713 0.284279 0.09286099 0.156136 0.07024699 0.18399 0.06942796 0.301697 0.104713 0.336072 0.08344095 0.301697 0.104713 0.317583 0.07005 0.2116799 0.07134097 0.262817 0.08319199 0.284279 0.09286099 0.295205 0.05875498 0.284279 0.09286099 0.262817 0.08319199 0.18399 0.06942796 0.2116799 0.07134097 0.284279 0.09286099 0.317583 0.07005 0.284279 0.09286099 0.295205 0.05875498 0.2116799 0.07134097 0.238285 0.07595998 0.262817 0.08319199 0.295205 0.05875498 0.262817 0.08319199 0.238285 0.07595998 0.2486619 0.05288589 0.238285 0.07595998 0.2116799 0.07134097 0.2486619 0.05288589 0.295205 0.05875498 0.238285 0.07595998 0.204008 0.03822195 0.2116799 0.07134097 0.18399 0.06942796 0.2486619 0.05288589 0.2116799 0.07134097 0.204008 0.03822195 0.173886 0.03733396 0.18399 0.06942796 0.156136 0.07024699 0.204008 0.03822195 0.18399 0.06942796 0.173886 0.03733396 0.143866 0.03897297 0.156136 0.07024699 0.129029 0.07377696 0.173886 0.03733396 0.156136 0.07024699 0.143866 0.03897297 0.1002179 0.05478292 0.129029 0.07377696 0.103591 0.07995098 0.1002179 0.05478292 0.143866 0.03897297 0.129029 0.07377696 0.1002179 0.05478292 0.103591 0.07995098 0.08078396 0.08863699 0.05453389 0.06188297 0.08078396 0.08863699 0.06155788 0.09965795 0.1002179 0.05478292 0.08078396 0.08863699 0.05453389 0.06188297 0.03322297 0.07382398 0.06155788 0.09965795 0.04697996 0.1126829 0.04341393 0.067586 0.06155788 0.09965795 0.03322297 0.07382398 0.05453389 0.06188297 0.06155788 0.09965795 0.04341393 0.067586 0.01605898 0.08779197 0.04697996 0.1126829 0.03806895 0.1272439 0.02406793 0.08056998 0.04697996 0.1126829 0.01605898 0.08779197 0.03322297 0.07382398 0.04697996 0.1126829 0.02406793 0.08056998 0.008482992 0.119022 0.03806895 0.1272439 0.035703 0.142795 0.008482992 0.119022 0.01605898 0.08779197 0.03806895 0.1272439 0 0.143678 0.035703 0.142795 0.04064291 0.158603 0.008482992 0.119022 0.035703 0.142795 0 0.143678 0.170899 0.208939 0.05334889 0.1737959 0.04064291 0.158603 0.01055091 0.161449 0.04064291 0.158603 0.05334889 0.1737959 0.2078509 0.207578 0.170899 0.208939 0.04064291 0.158603 0 0.143678 0.04064291 0.158603 0.01055091 0.161449 0.1344929 0.205772 0.07381296 0.18739 0.05334889 0.1737959 0.02921998 0.178183 0.05334889 0.1737959 0.07381296 0.18739 0.170899 0.208939 0.1344929 0.205772 0.05334889 0.1737959 0.01055091 0.161449 0.05334889 0.1737959 0.02921998 0.178183 0.1344929 0.205772 0.101366 0.198364 0.07381296 0.18739 0.02921998 0.178183 0.07381296 0.18739 0.101366 0.198364 0.08334696 0.200248 0.101366 0.198364 0.1344929 0.205772 0.08334696 0.200248 0.02921998 0.178183 0.101366 0.198364 0.141672 0.2137179 0.1344929 0.205772 0.170899 0.208939 0.08334696 0.200248 0.1344929 0.205772 0.141672 0.2137179 0.1848379 0.215431 0.170899 0.208939 0.2078509 0.207578 0.141672 0.2137179 0.170899 0.208939 0.1848379 0.215431 0.227566 0.212281 0.2078509 0.207578 0.242545 0.201826 0.1848379 0.215431 0.2078509 0.207578 0.227566 0.212281 0.282938 0.1970019 0.242545 0.201826 0.272525 0.192218 0.282938 0.1970019 0.227566 0.212281 0.242545 0.201826 0.282938 0.1970019 0.272525 0.192218 0.295979 0.179591 0.282938 0.1970019 0.295979 0.179591 0.333935 0.173372 0.251892 0.260161 0.06574499 0.211666 0.08357697 0.190131 0.283919 0.240176 0.251892 0.260161 0.08357697 0.190131 0.117224 0.174398 0.283919 0.240176 0.08357697 0.190131 0.201138 0.271189 0.06923395 0.23552 0.06574499 0.211666 0.251892 0.260161 0.201138 0.271189 0.06574499 0.211666 0.1443679 0.269892 0.096565 0.256675 0.06923395 0.23552 0.201138 0.271189 0.1443679 0.269892 0.06923395 0.23552 0.117224 0.174398 0.292169 0.216461 0.283919 0.240176 0.160197 0.1665109 0.278235 0.194094 0.292169 0.216461 0.117224 0.174398 0.160197 0.1665109 0.292169 0.216461 0.205662 0.1674129 0.247322 0.177003 0.278235 0.194094 0.160197 0.1665109 0.205662 0.1674129 0.278235 0.194094 0.570144 0.678603 0.570884 0.680087 0.572756 0.685048 0.612171 0.681313 0.610516 0.676473 0.612269 0.677237 0.615852 0.676043 0.614732 0.676094 0.614325 0.674243 0.614732 0.676094 0.613419 0.67453 0.614325 0.674243 0.523609 0.626626 0.524909 0.645933 0.5 0.647895 0.5 0.628693 0.5 0.647895 0.475091 0.645933 0.511867 0.628175 0.5 0.647895 0.5 0.628693 0.511867 0.628175 0.523609 0.626626 0.5 0.647895 0.546254 0.620523 0.548912 0.640133 0.524909 0.645933 0.535109 0.624066 0.546254 0.620523 0.524909 0.645933 0.523609 0.626626 0.535109 0.624066 0.524909 0.645933 0.567085 0.610656 0.571218 0.63073 0.548912 0.640133 0.556943 0.616037 0.567085 0.610656 0.548912 0.640133 0.546254 0.620523 0.556943 0.616037 0.548912 0.640133 0.585432 0.597436 0.591199 0.618079 0.571218 0.63073 0.576603 0.604435 0.585432 0.597436 0.571218 0.63073 0.567085 0.610656 0.576603 0.604435 0.571218 0.63073 0.607308 0.572443 0.608418 0.602624 0.591199 0.618079 0.600821 0.581369 0.607308 0.572443 0.591199 0.618079 0.593518 0.589724 0.600821 0.581369 0.591199 0.618079 0.585432 0.597436 0.593518 0.589724 0.591199 0.618079 0.621686 0.542957 0.622624 0.584839 0.608418 0.602624 0.617753 0.553165 0.621686 0.542957 0.608418 0.602624 0.612957 0.563017 0.617753 0.553165 0.608418 0.602624 0.607308 0.572443 0.612957 0.563017 0.608418 0.602624 0.628255 0.510917 0.633696 0.565207 0.622624 0.584839 0.62694 0.521762 0.628255 0.510917 0.622624 0.584839 0.624749 0.532466 0.62694 0.521762 0.622624 0.584839 0.621686 0.542957 0.624749 0.532466 0.622624 0.584839 0.641593 0.455784 0.641593 0.544216 0.633696 0.565207 0.633696 0.434793 0.641593 0.455784 0.633696 0.565207 0.628255 0.510917 0.633696 0.434793 0.633696 0.565207 0.646321 0.477668 0.646321 0.522332 0.641593 0.544216 0.641593 0.455784 0.646321 0.477668 0.641593 0.544216 0.646321 0.477668 0.647895 0.5 0.646321 0.522332 0.624749 0.467534 0.622624 0.415161 0.633696 0.434793 0.62694 0.478238 0.624749 0.467534 0.633696 0.434793 0.628255 0.489083 0.62694 0.478238 0.633696 0.434793 0.628693 0.5 0.628255 0.489083 0.633696 0.434793 0.628255 0.510917 0.628693 0.5 0.633696 0.434793 0.612957 0.436983 0.608418 0.397376 0.622624 0.415161 0.617753 0.446835 0.612957 0.436983 0.622624 0.415161 0.621686 0.457043 0.617753 0.446835 0.622624 0.415161 0.624749 0.467534 0.621686 0.457043 0.622624 0.415161 0.593518 0.410276 0.591199 0.381921 0.608418 0.397376 0.600821 0.418631 0.593518 0.410276 0.608418 0.397376 0.607308 0.427557 0.600821 0.418631 0.608418 0.397376 0.612957 0.436983 0.607308 0.427557 0.608418 0.397376 0.576603 0.395565 0.571218 0.36927 0.591199 0.381921 0.585432 0.402564 0.576603 0.395565 0.591199 0.381921 0.593518 0.410276 0.585432 0.402564 0.591199 0.381921 0.556943 0.383963 0.548912 0.359867 0.571218 0.36927 0.567085 0.389344 0.556943 0.383963 0.571218 0.36927 0.576603 0.395565 0.567085 0.389344 0.571218 0.36927 0.535109 0.375934 0.524909 0.354067 0.548912 0.359867 0.546254 0.379477 0.535109 0.375934 0.548912 0.359867 0.556943 0.383963 0.546254 0.379477 0.548912 0.359867 0.5 0.371307 0.5 0.352105 0.524909 0.354067 0.511867 0.371825 0.5 0.371307 0.524909 0.354067 0.523609 0.373374 0.511867 0.371825 0.524909 0.354067 0.535109 0.375934 0.523609 0.373374 0.524909 0.354067 0.476391 0.373374 0.475091 0.354067 0.5 0.352105 0.488133 0.371825 0.476391 0.373374 0.5 0.352105 0.5 0.371307 0.488133 0.371825 0.5 0.352105 0.453746 0.379477 0.451088 0.359867 0.475091 0.354067 0.464891 0.375934 0.453746 0.379477 0.475091 0.354067 0.476391 0.373374 0.464891 0.375934 0.475091 0.354067 0.432915 0.389344 0.428782 0.36927 0.451088 0.359867 0.443057 0.383963 0.432915 0.389344 0.451088 0.359867 0.453746 0.379477 0.443057 0.383963 0.451088 0.359867 0.414568 0.402564 0.408801 0.381921 0.428782 0.36927 0.423397 0.395565 0.414568 0.402564 0.428782 0.36927 0.432915 0.389344 0.423397 0.395565 0.428782 0.36927 0.392692 0.427557 0.391582 0.397376 0.408801 0.381921 0.399179 0.418631 0.392692 0.427557 0.408801 0.381921 0.406482 0.410276 0.399179 0.418631 0.408801 0.381921 0.414568 0.402564 0.406482 0.410276 0.408801 0.381921 0.378314 0.457043 0.377376 0.415161 0.391582 0.397376 0.382247 0.446835 0.378314 0.457043 0.391582 0.397376 0.387043 0.436983 0.382247 0.446835 0.391582 0.397376 0.392692 0.427557 0.387043 0.436983 0.391582 0.397376 0.371745 0.489083 0.366304 0.434793 0.377376 0.415161 0.37306 0.478238 0.371745 0.489083 0.377376 0.415161 0.375251 0.467534 0.37306 0.478238 0.377376 0.415161 0.378314 0.457043 0.375251 0.467534 0.377376 0.415161 0.358407 0.544216 0.358407 0.455784 0.366304 0.434793 0.366304 0.565207 0.358407 0.544216 0.366304 0.434793 0.371745 0.489083 0.366304 0.565207 0.366304 0.434793 0.353679 0.522332 0.353679 0.477668 0.358407 0.455784 0.358407 0.544216 0.353679 0.522332 0.358407 0.455784 0.353679 0.522332 0.352105 0.5 0.353679 0.477668 0.375251 0.532466 0.377376 0.584839 0.366304 0.565207 0.37306 0.521762 0.375251 0.532466 0.366304 0.565207 0.371745 0.510917 0.37306 0.521762 0.366304 0.565207 0.371307 0.5 0.371745 0.510917 0.366304 0.565207 0.371745 0.489083 0.371307 0.5 0.366304 0.565207 0.387043 0.563017 0.391582 0.602624 0.377376 0.584839 0.382247 0.553165 0.387043 0.563017 0.377376 0.584839 0.378314 0.542957 0.382247 0.553165 0.377376 0.584839 0.375251 0.532466 0.378314 0.542957 0.377376 0.584839 0.406482 0.589724 0.408801 0.618079 0.391582 0.602624 0.399179 0.581369 0.406482 0.589724 0.391582 0.602624 0.392692 0.572443 0.399179 0.581369 0.391582 0.602624 0.387043 0.563017 0.392692 0.572443 0.391582 0.602624 0.423397 0.604435 0.428782 0.63073 0.408801 0.618079 0.414568 0.597436 0.423397 0.604435 0.408801 0.618079 0.406482 0.589724 0.414568 0.597436 0.408801 0.618079 0.443057 0.616037 0.451088 0.640133 0.428782 0.63073 0.432915 0.610656 0.443057 0.616037 0.428782 0.63073 0.423397 0.604435 0.432915 0.610656 0.428782 0.63073 0.464891 0.624066 0.475091 0.645933 0.451088 0.640133 0.453746 0.620523 0.464891 0.624066 0.451088 0.640133 0.443057 0.616037 0.453746 0.620523 0.451088 0.640133 0.488133 0.628175 0.5 0.628693 0.475091 0.645933 0.476391 0.626626 0.488133 0.628175 0.475091 0.645933 0.464891 0.624066 0.476391 0.626626 0.475091 0.645933 0.524113 0.370958 0.524113 0.629042 0.5 0.631153 0.5 0.368847 0.524113 0.370958 0.5 0.631153 0.475887 0.629042 0.5 0.368847 0.5 0.631153 0.547231 0.37719 0.547231 0.62281 0.524113 0.629042 0.524113 0.370958 0.547231 0.37719 0.524113 0.629042 0.56848 0.387262 0.56848 0.612738 0.547231 0.62281 0.547231 0.37719 0.56848 0.387262 0.547231 0.62281 0.587174 0.400748 0.587174 0.599252 0.56848 0.612738 0.56848 0.387262 0.587174 0.400748 0.56848 0.612738 0.602837 0.41713 0.602837 0.58287 0.587174 0.599252 0.587174 0.400748 0.602837 0.41713 0.587174 0.599252 0.615175 0.435831 0.615175 0.564169 0.602837 0.58287 0.602837 0.41713 0.615175 0.435831 0.602837 0.58287 0.624041 0.456263 0.624041 0.543737 0.615175 0.564169 0.615175 0.435831 0.624041 0.456263 0.615175 0.564169 0.629374 0.477845 0.629374 0.522155 0.624041 0.543737 0.624041 0.456263 0.629374 0.477845 0.624041 0.543737 0.629374 0.477845 0.631153 0.5 0.629374 0.522155 0.475887 0.629042 0.475887 0.370958 0.5 0.368847 0.452769 0.62281 0.452769 0.37719 0.475887 0.370958 0.475887 0.629042 0.452769 0.62281 0.475887 0.370958 0.43152 0.612738 0.43152 0.387262 0.452769 0.37719 0.452769 0.62281 0.43152 0.612738 0.452769 0.37719 0.412826 0.599252 0.412826 0.400748 0.43152 0.387262 0.43152 0.612738 0.412826 0.599252 0.43152 0.387262 0.397163 0.58287 0.397163 0.41713 0.412826 0.400748 0.412826 0.599252 0.397163 0.58287 0.412826 0.400748 0.384825 0.564169 0.384825 0.435831 0.397163 0.41713 0.397163 0.58287 0.384825 0.564169 0.397163 0.41713 0.375959 0.543737 0.375959 0.456263 0.384825 0.435831 0.384825 0.564169 0.375959 0.543737 0.384825 0.435831 0.370626 0.522155 0.370626 0.477845 0.375959 0.456263 0.375959 0.543737 0.370626 0.522155 0.375959 0.456263 0.370626 0.522155 0.368847 0.5 0.370626 0.477845 0.5 0.04423195 0.5 0.04177999 0.545957 0.04207295 0.418238 0.04545098 0.454043 0.04207295 0.5 0.04177999 0.5 0.04423195 0.418238 0.04545098 0.5 0.04177999 0.581762 0.04545098 0.545957 0.04207295 0.584895 0.04273796 0.581762 0.04545098 0.5 0.04423195 0.545957 0.04207295 0.581762 0.04545098 0.584895 0.04273796 0.612262 0.0432859 0.581762 0.04545098 0.612262 0.0432859 0.626172 0.04326593 0.647486 0.04073399 0.626172 0.04326593 0.626172 0.04248493 0.647486 0.04828697 0.581762 0.04545098 0.626172 0.04326593 0.647486 0.04073399 0.647486 0.04828697 0.626172 0.04326593 0.647486 0.04073399 0.626172 0.04248493 0.612262 0.04107195 0.647486 0.04073399 0.612262 0.04107195 0.584895 0.03943091 0.581762 0.037193 0.584895 0.03943091 0.545957 0.03811198 0.581762 0.037193 0.647486 0.04073399 0.584895 0.03943091 0.581762 0.037193 0.545957 0.03811198 0.5 0.037606 0.5 0.035815 0.5 0.037606 0.454043 0.03811198 0.581762 0.037193 0.5 0.037606 0.5 0.035815 0.418238 0.037193 0.454043 0.03811198 0.415105 0.03943091 0.418238 0.037193 0.5 0.035815 0.454043 0.03811198 0.418238 0.037193 0.415105 0.03943091 0.387738 0.04107195 0.418238 0.037193 0.387738 0.04107195 0.373828 0.04248493 0.352514 0.04828697 0.373828 0.04248493 0.373828 0.04326593 0.352514 0.04073399 0.418238 0.037193 0.373828 0.04248493 0.352514 0.04828697 0.352514 0.04073399 0.373828 0.04248493 0.352514 0.04828697 0.373828 0.04326593 0.387738 0.0432859 0.352514 0.04828697 0.387738 0.0432859 0.415105 0.04273796 0.418238 0.04545098 0.415105 0.04273796 0.454043 0.04207295 0.418238 0.04545098 0.352514 0.04828697 0.415105 0.04273796 0.949034 0.335102 0.951849 0.334912 0.952525 0.340921 0.948251 0.323609 0.951481 0.328882 0.951849 0.334912 0.949034 0.335102 0.948251 0.323609 0.951849 0.334912 0.950353 0.346556 0.952525 0.340921 0.953407 0.346074 0.950353 0.346556 0.949034 0.335102 0.952525 0.340921 0.950353 0.346556 0.953407 0.346074 0.954371 0.3497 0.950353 0.346556 0.954371 0.3497 0.955296 0.351395 0.959276 0.352665 0.955296 0.351395 0.95608 0.351046 0.95201 0.356478 0.950353 0.346556 0.955296 0.351395 0.959276 0.352665 0.95201 0.356478 0.955296 0.351395 0.959276 0.352665 0.95608 0.351046 0.956644 0.348798 0.959276 0.352665 0.956644 0.348798 0.956938 0.344987 0.959204 0.343914 0.956938 0.344987 0.956938 0.340079 0.959204 0.343914 0.959276 0.352665 0.956938 0.344987 0.959204 0.343914 0.956938 0.340079 0.956644 0.334613 0.958702 0.334494 0.956644 0.334613 0.95608 0.329163 0.959204 0.343914 0.956644 0.334613 0.958702 0.334494 0.957791 0.325097 0.95608 0.329163 0.955296 0.324301 0.957791 0.325097 0.958702 0.334494 0.95608 0.329163 0.957791 0.325097 0.955296 0.324301 0.954371 0.320562 0.957791 0.325097 0.954371 0.320562 0.953407 0.318406 0.948135 0.313579 0.953407 0.318406 0.952525 0.318161 0.956512 0.316413 0.957791 0.325097 0.953407 0.318406 0.948135 0.313579 0.956512 0.316413 0.953407 0.318406 0.948135 0.313579 0.952525 0.318161 0.951849 0.319958 0.948135 0.313579 0.951849 0.319958 0.951481 0.323671 0.948251 0.323609 0.951481 0.323671 0.951481 0.328882 0.948251 0.323609 0.948135 0.313579 0.951481 0.323671 0.949034 0.664898 0.951849 0.665088 0.951481 0.671118 0.950353 0.653444 0.952525 0.659079 0.951849 0.665088 0.949034 0.664898 0.950353 0.653444 0.951849 0.665088 0.948251 0.676391 0.951481 0.671118 0.951481 0.676329 0.948251 0.676391 0.949034 0.664898 0.951481 0.671118 0.948251 0.676391 0.951481 0.676329 0.951849 0.680042 0.948251 0.676391 0.951849 0.680042 0.952525 0.681839 0.956512 0.683587 0.952525 0.681839 0.953407 0.681594 0.948135 0.686421 0.948251 0.676391 0.952525 0.681839 0.956512 0.683587 0.948135 0.686421 0.952525 0.681839 0.956512 0.683587 0.953407 0.681594 0.954371 0.679438 0.956512 0.683587 0.954371 0.679438 0.955296 0.675699 0.957791 0.674903 0.955296 0.675699 0.95608 0.670837 0.957791 0.674903 0.956512 0.683587 0.955296 0.675699 0.957791 0.674903 0.95608 0.670837 0.956644 0.665387 0.958702 0.665506 0.956644 0.665387 0.956938 0.659921 0.957791 0.674903 0.956644 0.665387 0.958702 0.665506 0.959204 0.656086 0.956938 0.659921 0.956938 0.655013 0.959204 0.656086 0.958702 0.665506 0.956938 0.659921 0.959204 0.656086 0.956938 0.655013 0.956644 0.651202 0.959204 0.656086 0.956644 0.651202 0.95608 0.648954 0.95201 0.643522 0.95608 0.648954 0.955296 0.648605 0.959276 0.647335 0.959204 0.656086 0.95608 0.648954 0.95201 0.643522 0.959276 0.647335 0.95608 0.648954 0.95201 0.643522 0.955296 0.648605 0.954371 0.6503 0.95201 0.643522 0.954371 0.6503 0.953407 0.653926 0.950353 0.653444 0.953407 0.653926 0.952525 0.659079 0.950353 0.653444 0.95201 0.643522 0.953407 0.653926 0.05096596 0.664898 0.04815089 0.665088 0.04747498 0.659079 0.05174899 0.676391 0.04851889 0.671118 0.04815089 0.665088 0.05096596 0.664898 0.05174899 0.676391 0.04815089 0.665088 0.04964697 0.653444 0.04747498 0.659079 0.04659295 0.653926 0.04964697 0.653444 0.05096596 0.664898 0.04747498 0.659079 0.04964697 0.653444 0.04659295 0.653926 0.04562896 0.6503 0.04964697 0.653444 0.04562896 0.6503 0.04470396 0.648605 0.04072391 0.647335 0.04470396 0.648605 0.04391998 0.648954 0.04798996 0.643522 0.04964697 0.653444 0.04470396 0.648605 0.04072391 0.647335 0.04798996 0.643522 0.04470396 0.648605 0.04072391 0.647335 0.04391998 0.648954 0.043356 0.651202 0.04072391 0.647335 0.043356 0.651202 0.04306197 0.655013 0.04079598 0.656086 0.04306197 0.655013 0.04306197 0.659921 0.04079598 0.656086 0.04072391 0.647335 0.04306197 0.655013 0.04079598 0.656086 0.04306197 0.659921 0.043356 0.665387 0.04129797 0.665506 0.043356 0.665387 0.04391998 0.670837 0.04079598 0.656086 0.043356 0.665387 0.04129797 0.665506 0.0422089 0.674903 0.04391998 0.670837 0.04470396 0.675699 0.0422089 0.674903 0.04129797 0.665506 0.04391998 0.670837 0.0422089 0.674903 0.04470396 0.675699 0.04562896 0.679438 0.0422089 0.674903 0.04562896 0.679438 0.04659295 0.681594 0.05186498 0.686421 0.04659295 0.681594 0.04747498 0.681839 0.0434879 0.683587 0.0422089 0.674903 0.04659295 0.681594 0.05186498 0.686421 0.0434879 0.683587 0.04659295 0.681594 0.05186498 0.686421 0.04747498 0.681839 0.04815089 0.680042 0.05186498 0.686421 0.04815089 0.680042 0.04851889 0.676329 0.05174899 0.676391 0.04851889 0.676329 0.04851889 0.671118 0.05174899 0.676391 0.05186498 0.686421 0.04851889 0.676329 0.05096596 0.335102 0.04815089 0.334912 0.04851889 0.328882 0.04964697 0.346556 0.04747498 0.340921 0.04815089 0.334912 0.05096596 0.335102 0.04964697 0.346556 0.04815089 0.334912 0.05174899 0.323609 0.04851889 0.328882 0.04851889 0.323671 0.05174899 0.323609 0.05096596 0.335102 0.04851889 0.328882 0.05174899 0.323609 0.04851889 0.323671 0.04815089 0.319958 0.05174899 0.323609 0.04815089 0.319958 0.04747498 0.318161 0.0434879 0.316413 0.04747498 0.318161 0.04659295 0.318406 0.05186498 0.313579 0.05174899 0.323609 0.04747498 0.318161 0.0434879 0.316413 0.05186498 0.313579 0.04747498 0.318161 0.0434879 0.316413 0.04659295 0.318406 0.04562896 0.320562 0.0434879 0.316413 0.04562896 0.320562 0.04470396 0.324301 0.0422089 0.325097 0.04470396 0.324301 0.04391998 0.329163 0.0422089 0.325097 0.0434879 0.316413 0.04470396 0.324301 0.0422089 0.325097 0.04391998 0.329163 0.043356 0.334613 0.04129797 0.334494 0.043356 0.334613 0.04306197 0.340079 0.0422089 0.325097 0.043356 0.334613 0.04129797 0.334494 0.04079598 0.343914 0.04306197 0.340079 0.04306197 0.344987 0.04079598 0.343914 0.04129797 0.334494 0.04306197 0.340079 0.04079598 0.343914 0.04306197 0.344987 0.043356 0.348798 0.04079598 0.343914 0.043356 0.348798 0.04391998 0.351046 0.04798996 0.356478 0.04391998 0.351046 0.04470396 0.351395 0.04072391 0.352665 0.04079598 0.343914 0.04391998 0.351046 0.04798996 0.356478 0.04072391 0.352665 0.04391998 0.351046 0.04798996 0.356478 0.04470396 0.351395 0.04562896 0.3497 0.04798996 0.356478 0.04562896 0.3497 0.04659295 0.346074 0.04964697 0.346556 0.04659295 0.346074 0.04747498 0.340921 0.04964697 0.346556 0.04798996 0.356478 0.04659295 0.346074 0.30825 0.051063 0.30825 0.04514497 0.352514 0.04073399 0.352514 0.04828697 0.30825 0.051063 0.352514 0.04073399 0.2836 0.05242192 0.2836 0.04914289 0.30825 0.04514497 0.30825 0.051063 0.2836 0.05242192 0.30825 0.04514497 0.2836 0.05242192 0.275753 0.051759 0.2836 0.04914289 0.69175 0.04514497 0.69175 0.051063 0.647486 0.04828697 0.647486 0.04073399 0.69175 0.04514497 0.647486 0.04828697 0.7164 0.04914289 0.7164 0.05242192 0.69175 0.051063 0.69175 0.04514497 0.7164 0.04914289 0.69175 0.051063 0.7164 0.04914289 0.724247 0.051759 0.7164 0.05242192 0.948705 0.306183 0.954941 0.30913 0.956512 0.316413 0.948135 0.313579 0.948705 0.306183 0.956512 0.316413 0.949865 0.302077 0.953194 0.303921 0.954941 0.30913 0.948705 0.306183 0.949865 0.302077 0.954941 0.30913 0.949865 0.302077 0.951434 0.301406 0.953194 0.303921 0.958916 0.360057 0.953787 0.363712 0.95201 0.356478 0.959276 0.352665 0.958916 0.360057 0.95201 0.356478 0.958138 0.365413 0.955491 0.367628 0.953787 0.363712 0.958916 0.360057 0.958138 0.365413 0.953787 0.363712 0.958138 0.365413 0.956975 0.368106 0.955491 0.367628 0.953787 0.636288 0.958916 0.639943 0.959276 0.647335 0.95201 0.643522 0.953787 0.636288 0.959276 0.647335 0.955491 0.632372 0.958138 0.634587 0.958916 0.639943 0.953787 0.636288 0.955491 0.632372 0.958916 0.639943 0.955491 0.632372 0.956975 0.631894 0.958138 0.634587 0.954941 0.69087 0.948705 0.693817 0.948135 0.686421 0.956512 0.683587 0.954941 0.69087 0.948135 0.686421 0.953194 0.696079 0.949865 0.697923 0.948705 0.693817 0.954941 0.69087 0.953194 0.696079 0.948705 0.693817 0.953194 0.696079 0.951434 0.698594 0.949865 0.697923 0.05129498 0.693817 0.0450589 0.69087 0.0434879 0.683587 0.05186498 0.686421 0.05129498 0.693817 0.0434879 0.683587 0.05013489 0.697923 0.04680591 0.696079 0.0450589 0.69087 0.05129498 0.693817 0.05013489 0.697923 0.0450589 0.69087 0.05013489 0.697923 0.04856598 0.698594 0.04680591 0.696079 0.04108399 0.639943 0.04621297 0.636288 0.04798996 0.643522 0.04072391 0.647335 0.04108399 0.639943 0.04798996 0.643522 0.04186195 0.634587 0.04450899 0.632372 0.04621297 0.636288 0.04108399 0.639943 0.04186195 0.634587 0.04621297 0.636288 0.04186195 0.634587 0.04302489 0.631894 0.04450899 0.632372 0.04621297 0.363712 0.04108399 0.360057 0.04072391 0.352665 0.04798996 0.356478 0.04621297 0.363712 0.04072391 0.352665 0.04450899 0.367628 0.04186195 0.365413 0.04108399 0.360057 0.04621297 0.363712 0.04450899 0.367628 0.04108399 0.360057 0.04450899 0.367628 0.04302489 0.368106 0.04186195 0.365413 0.0450589 0.30913 0.05129498 0.306183 0.05186498 0.313579 0.0434879 0.316413 0.0450589 0.30913 0.05186498 0.313579 0.04680591 0.303921 0.05013489 0.302077 0.05129498 0.306183 0.0450589 0.30913 0.04680591 0.303921 0.05129498 0.306183 0.04680591 0.303921 0.04856598 0.301406 0.05013489 0.302077 0.925585 0.167863 0.923174 0.163123 0.905676 0.172876 0.920605 0.159211 0.905676 0.172876 0.923174 0.163123 0.927586 0.1729159 0.925585 0.167863 0.905676 0.172876 0.929004 0.177748 0.927586 0.1729159 0.905676 0.172876 0.929737 0.181836 0.929004 0.177748 0.905676 0.172876 0.929737 0.184706 0.929737 0.181836 0.905676 0.172876 0.929004 0.18598 0.929737 0.184706 0.905676 0.172876 0.927586 0.185431 0.929004 0.18598 0.905676 0.172876 0.925585 0.183041 0.927586 0.185431 0.905676 0.172876 0.923174 0.179046 0.925585 0.183041 0.905676 0.172876 0.920605 0.173936 0.923174 0.179046 0.905676 0.172876 0.918202 0.168399 0.920605 0.173936 0.905676 0.172876 0.916325 0.163197 0.918202 0.168399 0.905676 0.172876 0.915291 0.159026 0.916325 0.163197 0.905676 0.172876 0.915291 0.1563979 0.915291 0.159026 0.905676 0.172876 0.916325 0.155576 0.915291 0.1563979 0.905676 0.172876 0.918202 0.156578 0.916325 0.155576 0.905676 0.172876 0.920605 0.159211 0.918202 0.156578 0.905676 0.172876 0.0371949 0.502578 0.03740197 0.507462 0.04821991 0.5 0.03779596 0.511549 0.04821991 0.5 0.03740197 0.507462 0.0371949 0.497422 0.0371949 0.502578 0.04821991 0.5 0.03740197 0.492538 0.0371949 0.497422 0.04821991 0.5 0.03779596 0.488451 0.03740197 0.492538 0.04821991 0.5 0.03834092 0.485633 0.03779596 0.488451 0.04821991 0.5 0.03898096 0.484459 0.03834092 0.485633 0.04821991 0.5 0.03964096 0.485149 0.03898096 0.484459 0.04821991 0.5 0.040241 0.487708 0.03964096 0.485149 0.04821991 0.5 0.04069799 0.491884 0.040241 0.487708 0.04821991 0.5 0.04094499 0.497164 0.04069799 0.491884 0.04821991 0.5 0.04094499 0.502836 0.04094499 0.497164 0.04821991 0.5 0.04069799 0.508116 0.04094499 0.502836 0.04821991 0.5 0.040241 0.512292 0.04069799 0.508116 0.04821991 0.5 0.03964096 0.514851 0.040241 0.512292 0.04821991 0.5 0.03898096 0.515541 0.03964096 0.514851 0.04821991 0.5 0.03834092 0.514367 0.03898096 0.515541 0.04821991 0.5 0.03779596 0.511549 0.03834092 0.514367 0.04821991 0.5 0.08909696 0.889274 0.910685 0.889805 0.913023 0.886529 0.07435697 0.866632 0.08909696 0.889274 0.913023 0.886529 0.92709 0.863865 0.07435697 0.866632 0.913023 0.886529 0.111535 0.91154 0.909027 0.892542 0.910685 0.889805 0.08909696 0.889274 0.111535 0.91154 0.910685 0.889805 0.111535 0.91154 0.90841 0.894286 0.909027 0.892542 0.852446 0.932605 0.907215 0.897684 0.90841 0.894286 0.844771 0.935586 0.852446 0.932605 0.90841 0.894286 0.148955 0.93305 0.844771 0.935586 0.90841 0.894286 0.111535 0.91154 0.148955 0.93305 0.90841 0.894286 0.863236 0.928703 0.903745 0.902782 0.907215 0.897684 0.858839 0.930169 0.863236 0.928703 0.907215 0.897684 0.852446 0.932605 0.858839 0.930169 0.907215 0.897684 0.871381 0.925824 0.898033 0.908894 0.903745 0.902782 0.863236 0.928703 0.871381 0.925824 0.903745 0.902782 0.881001 0.921145 0.89027 0.915265 0.898033 0.908894 0.871381 0.925824 0.881001 0.921145 0.898033 0.908894 0.2197819 0.95276 0.767508 0.954918 0.844771 0.935586 0.148955 0.93305 0.2197819 0.95276 0.844771 0.935586 0.36919 0.967243 0.604699 0.968273 0.767508 0.954918 0.2197819 0.95276 0.36919 0.967243 0.767508 0.954918 0.92709 0.863865 0.06403195 0.843776 0.07435697 0.866632 0.937011 0.84099 0.05645996 0.820789 0.06403195 0.843776 0.92709 0.863865 0.937011 0.84099 0.06403195 0.843776 0.944322 0.81799 0.05071598 0.797716 0.05645996 0.820789 0.937011 0.84099 0.944322 0.81799 0.05645996 0.820789 0.949886 0.794909 0.04625093 0.774594 0.05071598 0.797716 0.944322 0.81799 0.949886 0.794909 0.05071598 0.797716 0.954225 0.77177 0.04558593 0.771249 0.04625093 0.774594 0.949886 0.794909 0.954225 0.77177 0.04625093 0.774594 0.954225 0.77177 0.04485493 0.768498 0.04558593 0.771249 0.04039299 0.752085 0.04417693 0.766801 0.04485493 0.768498 0.03955495 0.745398 0.04039299 0.752085 0.04485493 0.768498 0.957669 0.74859 0.03955495 0.745398 0.04485493 0.768498 0.954225 0.77177 0.957669 0.74859 0.04485493 0.768498 0.04153198 0.758369 0.04284989 0.7635 0.04417693 0.766801 0.04039299 0.752085 0.04153198 0.758369 0.04417693 0.766801 0.957669 0.74859 0.03909397 0.739073 0.03955495 0.745398 0.957669 0.74859 0.03904491 0.733864 0.03909397 0.739073 0.960436 0.72538 0.03941297 0.730456 0.03904491 0.733864 0.957669 0.74859 0.960436 0.72538 0.03904491 0.733864 0.960436 0.72538 0.03958499 0.728705 0.03941297 0.730456 0.960436 0.72538 0.03953188 0.725912 0.03958499 0.728705 0.960436 0.72538 0.03926396 0.722545 0.03953188 0.725912 0.962678 0.702147 0.03707993 0.69932 0.03926396 0.722545 0.960436 0.72538 0.962678 0.702147 0.03926396 0.722545 0.964501 0.678896 0.03530198 0.676068 0.03707993 0.69932 0.962678 0.702147 0.964501 0.678896 0.03707993 0.69932 0.96598 0.655631 0.0338599 0.652802 0.03530198 0.676068 0.964501 0.678896 0.96598 0.655631 0.03530198 0.676068 0.967173 0.632357 0.03269892 0.629527 0.0338599 0.652802 0.96598 0.655631 0.967173 0.632357 0.0338599 0.652802 0.968119 0.609085 0.03178 0.606243 0.03269892 0.629527 0.967173 0.632357 0.968119 0.609085 0.03269892 0.629527 0.970751 0.57964 0.03107392 0.582954 0.03178 0.606243 0.970586 0.586352 0.970751 0.57964 0.03178 0.606243 0.9702 0.592675 0.970586 0.586352 0.03178 0.606243 0.969632 0.597855 0.9702 0.592675 0.03178 0.606243 0.968945 0.601212 0.969632 0.597855 0.03178 0.606243 0.968601 0.602937 0.968945 0.601212 0.03178 0.606243 0.968309 0.605716 0.968601 0.602937 0.03178 0.606243 0.968119 0.609085 0.968309 0.605716 0.03178 0.606243 0.969501 0.560192 0.03055799 0.559661 0.03107392 0.582954 0.96964 0.562981 0.969501 0.560192 0.03107392 0.582954 0.969884 0.564721 0.96964 0.562981 0.03107392 0.582954 0.970383 0.568105 0.969884 0.564721 0.03107392 0.582954 0.970682 0.573307 0.970383 0.568105 0.03107392 0.582954 0.970751 0.57964 0.970682 0.573307 0.03107392 0.582954 0.969493 0.556819 0.03021889 0.536364 0.03055799 0.559661 0.969501 0.560192 0.969493 0.556819 0.03055799 0.559661 0.969811 0.533533 0.03004598 0.513066 0.03021889 0.536364 0.969493 0.556819 0.969811 0.533533 0.03021889 0.536364 0.969963 0.510235 0.03003698 0.489766 0.03004598 0.513066 0.969811 0.533533 0.969963 0.510235 0.03004598 0.513066 0.969954 0.486936 0.03018891 0.466468 0.03003698 0.489766 0.969963 0.510235 0.969954 0.486936 0.03003698 0.489766 0.969781 0.463637 0.0305069 0.443181 0.03018891 0.466468 0.969954 0.486936 0.969781 0.463637 0.03018891 0.466468 0.969442 0.440341 0.03049898 0.439808 0.0305069 0.443181 0.969781 0.463637 0.969442 0.440341 0.0305069 0.443181 0.968927 0.417047 0.03035998 0.437019 0.03049898 0.439808 0.969442 0.440341 0.968927 0.417047 0.03049898 0.439808 0.968927 0.417047 0.03011596 0.435279 0.03035998 0.437019 0.968927 0.417047 0.02961695 0.431895 0.03011596 0.435279 0.968927 0.417047 0.02931797 0.426693 0.02961695 0.431895 0.968927 0.417047 0.02924895 0.42036 0.02931797 0.426693 0.96822 0.393758 0.02941393 0.413648 0.02924895 0.42036 0.968927 0.417047 0.96822 0.393758 0.02924895 0.42036 0.96822 0.393758 0.02979993 0.407325 0.02941393 0.413648 0.96822 0.393758 0.03036797 0.402145 0.02979993 0.407325 0.96822 0.393758 0.03105497 0.398788 0.03036797 0.402145 0.96822 0.393758 0.03139895 0.397063 0.03105497 0.398788 0.96822 0.393758 0.03169095 0.394284 0.03139895 0.397063 0.96822 0.393758 0.03188097 0.390915 0.03169095 0.394284 0.967301 0.370474 0.03282696 0.367644 0.03188097 0.390915 0.96822 0.393758 0.967301 0.370474 0.03188097 0.390915 0.96614 0.347199 0.03401988 0.34437 0.03282696 0.367644 0.967301 0.370474 0.96614 0.347199 0.03282696 0.367644 0.964698 0.323933 0.03549891 0.321106 0.03401988 0.34437 0.96614 0.347199 0.964698 0.323933 0.03401988 0.34437 0.96292 0.30068 0.03732198 0.297856 0.03549891 0.321106 0.964698 0.323933 0.96292 0.30068 0.03549891 0.321106 0.960736 0.277455 0.03956395 0.274623 0.03732198 0.297856 0.96292 0.30068 0.960736 0.277455 0.03732198 0.297856 0.960955 0.266136 0.04233098 0.251413 0.03956395 0.274623 0.960587 0.269544 0.960955 0.266136 0.03956395 0.274623 0.960415 0.271295 0.960587 0.269544 0.03956395 0.274623 0.960468 0.274088 0.960415 0.271295 0.03956395 0.274623 0.960736 0.277455 0.960468 0.274088 0.03956395 0.274623 0.955145 0.2315019 0.04577493 0.228233 0.04233098 0.251413 0.960445 0.254602 0.955145 0.2315019 0.04233098 0.251413 0.960906 0.260927 0.960445 0.254602 0.04233098 0.251413 0.960955 0.266136 0.960906 0.260927 0.04233098 0.251413 0.953749 0.225406 0.05011296 0.205094 0.04577493 0.228233 0.954414 0.228751 0.953749 0.225406 0.04577493 0.228233 0.955145 0.2315019 0.954414 0.228751 0.04577493 0.228233 0.949284 0.202284 0.05567795 0.182012 0.05011296 0.205094 0.953749 0.225406 0.949284 0.202284 0.05011296 0.205094 0.94354 0.179212 0.06298798 0.159011 0.05567795 0.182012 0.949284 0.202284 0.94354 0.179212 0.05567795 0.182012 0.935968 0.156224 0.07291001 0.1361359 0.06298798 0.159011 0.94354 0.179212 0.935968 0.156224 0.06298798 0.159011 0.925644 0.133368 0.086977 0.113471 0.07291001 0.1361359 0.935968 0.156224 0.925644 0.133368 0.07291001 0.1361359 0.910903 0.1107259 0.08931499 0.110195 0.086977 0.113471 0.925644 0.133368 0.910903 0.1107259 0.086977 0.113471 0.888465 0.08846098 0.09097295 0.107458 0.08931499 0.110195 0.910903 0.1107259 0.888465 0.08846098 0.08931499 0.110195 0.888465 0.08846098 0.09158998 0.105714 0.09097295 0.107458 0.147554 0.06739497 0.092785 0.102316 0.09158998 0.105714 0.155229 0.06441396 0.147554 0.06739497 0.09158998 0.105714 0.851046 0.06695097 0.155229 0.06441396 0.09158998 0.105714 0.888465 0.08846098 0.851046 0.06695097 0.09158998 0.105714 0.136764 0.07129698 0.096255 0.09721797 0.092785 0.102316 0.141161 0.06983095 0.136764 0.07129698 0.092785 0.102316 0.147554 0.06739497 0.141161 0.06983095 0.092785 0.102316 0.128619 0.07417595 0.101967 0.09110599 0.096255 0.09721797 0.136764 0.07129698 0.128619 0.07417595 0.096255 0.09721797 0.118999 0.07885497 0.10973 0.08473497 0.101967 0.09110599 0.128619 0.07417595 0.118999 0.07885497 0.101967 0.09110599 0.78022 0.04723989 0.232493 0.04508197 0.155229 0.06441396 0.851046 0.06695097 0.78022 0.04723989 0.155229 0.06441396 0.630814 0.03275698 0.395304 0.03172689 0.232493 0.04508197 0.78022 0.04723989 0.630814 0.03275698 0.232493 0.04508197 0.959607 0.247915 0.955823 0.233199 0.955145 0.2315019 0.960445 0.254602 0.959607 0.247915 0.955145 0.2315019 0.958468 0.241631 0.95715 0.2365 0.955823 0.233199 0.959607 0.247915 0.958468 0.241631 0.955823 0.233199 0.793904 0.704525 0.797654 0.704855 0.791151 0.705626 0.789631 0.707205 0.791151 0.705626 0.797654 0.704855 0.793904 0.730504 0.793904 0.704525 0.791151 0.705626 0.793904 0.730504 0.791151 0.705626 0.791151 0.731643 0.789631 0.707205 0.791151 0.731643 0.791151 0.705626 0.805754 0.708676 0.804359 0.710328 0.797654 0.704855 0.801579 0.711528 0.797654 0.704855 0.804359 0.710328 0.805526 0.706919 0.805754 0.708676 0.797654 0.704855 0.80377 0.705402 0.805526 0.706919 0.797654 0.704855 0.800859 0.704402 0.80377 0.705402 0.797654 0.704855 0.797354 0.704093 0.800859 0.704402 0.797654 0.704855 0.793904 0.704525 0.797354 0.704093 0.797654 0.704855 0.789676 0.708969 0.789631 0.707205 0.797654 0.704855 0.791329 0.710569 0.789676 0.708969 0.797654 0.704855 0.794294 0.711664 0.791329 0.710569 0.797654 0.704855 0.79797 0.712011 0.794294 0.711664 0.797654 0.704855 0.801579 0.711528 0.79797 0.712011 0.797654 0.704855 0.804359 0.736489 0.804359 0.710328 0.805754 0.708676 0.801579 0.737723 0.804359 0.710328 0.804359 0.736489 0.801579 0.737723 0.801579 0.711528 0.804359 0.710328 0.805754 0.734789 0.805754 0.708676 0.805526 0.706919 0.805754 0.734789 0.804359 0.736489 0.805754 0.708676 0.805526 0.732978 0.805526 0.706919 0.80377 0.705402 0.805526 0.732978 0.805754 0.734789 0.805526 0.706919 0.80377 0.731412 0.80377 0.705402 0.800859 0.704402 0.80377 0.731412 0.805526 0.732978 0.80377 0.705402 0.800859 0.730378 0.800859 0.704402 0.797354 0.704093 0.800859 0.730378 0.80377 0.731412 0.800859 0.704402 0.797354 0.730057 0.797354 0.704093 0.793904 0.704525 0.797354 0.730057 0.800859 0.730378 0.797354 0.704093 0.793904 0.730504 0.797354 0.730057 0.793904 0.704525 0.804496 0.722106 0.793904 0.730504 0.791151 0.731643 0.789631 0.733273 0.791151 0.731643 0.789631 0.707205 0.774905 0.741041 0.791151 0.731643 0.789631 0.733273 0.774905 0.741041 0.804496 0.722106 0.791151 0.731643 0.818434 0.726736 0.804359 0.736489 0.805754 0.734789 0.789643 0.747046 0.801579 0.737723 0.804359 0.736489 0.818434 0.726736 0.789643 0.747046 0.804359 0.736489 0.818434 0.726736 0.805754 0.734789 0.805526 0.732978 0.818434 0.726736 0.805526 0.732978 0.80377 0.731412 0.812187 0.723833 0.80377 0.731412 0.800859 0.730378 0.812187 0.723833 0.818434 0.726736 0.80377 0.731412 0.812187 0.723833 0.800859 0.730378 0.797354 0.730057 0.812187 0.723833 0.797354 0.730057 0.793904 0.730504 0.804496 0.722106 0.812187 0.723833 0.793904 0.730504 0.789631 0.733273 0.789631 0.707205 0.789676 0.708969 0.789676 0.735091 0.789676 0.708969 0.791329 0.710569 0.789676 0.735091 0.789631 0.733273 0.789676 0.708969 0.791329 0.736737 0.791329 0.710569 0.794294 0.711664 0.791329 0.736737 0.789676 0.735091 0.791329 0.710569 0.794294 0.737862 0.794294 0.711664 0.79797 0.712011 0.794294 0.737862 0.791329 0.736737 0.794294 0.711664 0.79797 0.738218 0.79797 0.712011 0.801579 0.711528 0.79797 0.738218 0.794294 0.737862 0.79797 0.712011 0.801579 0.737723 0.79797 0.738218 0.801579 0.711528 0.774905 0.741041 0.789631 0.733273 0.789676 0.735091 0.774905 0.741041 0.789676 0.735091 0.791329 0.736737 0.781071 0.744706 0.791329 0.736737 0.794294 0.737862 0.774905 0.741041 0.791329 0.736737 0.781071 0.744706 0.781071 0.744706 0.794294 0.737862 0.79797 0.738218 0.781071 0.744706 0.79797 0.738218 0.801579 0.737723 0.789643 0.747046 0.781071 0.744706 0.801579 0.737723 0.822505 0.73058 0.799429 0.747645 0.789643 0.747046 0.818434 0.726736 0.822505 0.73058 0.789643 0.747046 0.823782 0.735006 0.808942 0.746393 0.799429 0.747645 0.822505 0.73058 0.823782 0.735006 0.799429 0.747645 0.821876 0.739518 0.816767 0.743518 0.808942 0.746393 0.823782 0.735006 0.821876 0.739518 0.808942 0.746393 0.771832 0.73664 0.796148 0.721678 0.804496 0.722106 0.774905 0.741041 0.771832 0.73664 0.804496 0.722106 0.771999 0.73212 0.787943 0.722579 0.796148 0.721678 0.771832 0.73664 0.771999 0.73212 0.796148 0.721678 0.775132 0.728019 0.780681 0.724746 0.787943 0.722579 0.771999 0.73212 0.775132 0.728019 0.787943 0.722579 0.612171 0.681313 0.617035 0.677427 0.626503 0.675721 0.613709 0.675886 0.613059 0.675478 0.612955 0.674981 0.592691 0.684276 0.593424 0.682522 0.594431 0.684035 0.606345 0.673989 0.609942 0.674382 0.609692 0.675451 0.570884 0.680087 0.586475 0.683443 0.572756 0.685048 0.5917 0.682757 0.576058 0.679537 0.588474 0.678057 0.612171 0.681313 0.606345 0.673989 0.609692 0.675451 0.612171 0.681313 0.612269 0.677237 0.614602 0.677581 0.612171 0.681313 0.614602 0.677581 0.617035 0.677427 0.588474 0.678057 0.587567 0.676623 0.596519 0.675432 0.5917 0.682757 0.588474 0.678057 0.596519 0.675432 0.615852 0.676043 0.623617 0.672628 0.625244 0.674377 0.342309 0.05052691 0.325144 0.036502 0.303833 0.024535 0.303833 0.06188297 0.303833 0.024535 0.325144 0.036502 0.214502 0.001635909 0.342309 0.05052691 0.303833 0.024535 0.214502 0.03897297 0.214502 0.001635909 0.303833 0.024535 0.258136 0.05477899 0.214502 0.03897297 0.303833 0.024535 0.258136 0.05477899 0.303833 0.024535 0.303833 0.06188297 0.325145 0.07382398 0.325144 0.036502 0.342309 0.05052691 0.314953 0.067586 0.303833 0.06188297 0.325144 0.036502 0.325145 0.07382398 0.314953 0.067586 0.325144 0.036502 0.214502 0.001635909 0.358368 0.1069329 0.342309 0.05052691 0.342309 0.08779197 0.342309 0.05052691 0.358368 0.1069329 0.3343 0.08056998 0.325145 0.07382398 0.342309 0.05052691 0.342309 0.08779197 0.3343 0.08056998 0.342309 0.05052691 0.184426 0 0.34779 0.125002 0.358368 0.1069329 0.358368 0.143678 0.358368 0.1069329 0.34779 0.125002 0.214502 0.001635909 0.184426 0 0.358368 0.1069329 0.349882 0.119013 0.358368 0.1069329 0.358368 0.143678 0.349882 0.119013 0.342309 0.08779197 0.358368 0.1069329 0.154359 8.87e-4 0.329148 0.1419939 0.34779 0.125002 0.347817 0.161449 0.34779 0.125002 0.329148 0.1419939 0.184426 0 0.154359 8.87e-4 0.34779 0.125002 0.347817 0.161449 0.358368 0.143678 0.34779 0.125002 0.06316298 0.0214039 0.216696 0.178286 0.329148 0.1419939 0.329148 0.178183 0.329148 0.1419939 0.216696 0.178286 0.154359 8.87e-4 0.06316298 0.0214039 0.329148 0.1419939 0.329148 0.178183 0.347817 0.161449 0.329148 0.1419939 0.04082298 0.03269398 0.173611 0.180042 0.216696 0.178286 0.216696 0.2137179 0.216696 0.178286 0.173611 0.180042 0.06316298 0.0214039 0.04082298 0.03269398 0.216696 0.178286 0.275039 0.200242 0.329148 0.178183 0.216696 0.178286 0.275039 0.200242 0.216696 0.178286 0.216696 0.2137179 0.02229595 0.04615491 0.130801 0.176816 0.173611 0.180042 0.17353 0.215431 0.173611 0.180042 0.130801 0.176816 0.04082298 0.03269398 0.02229595 0.04615491 0.173611 0.180042 0.17353 0.215431 0.216696 0.2137179 0.173611 0.180042 0 0.101512 0.024432 0.137095 0.130801 0.176816 0.130801 0.212281 0.130801 0.176816 0.024432 0.137095 0.02229595 0.04615491 0 0.101512 0.130801 0.176816 0.130801 0.212281 0.17353 0.215431 0.130801 0.176816 0 0.101512 0.008192956 0.119667 0.024432 0.137095 0.024432 0.173372 0.024432 0.137095 0.008192956 0.119667 0.07544696 0.197008 0.130801 0.212281 0.024432 0.137095 0.07544696 0.197008 0.024432 0.137095 0.024432 0.173372 0.008190989 0.15623 0.008192956 0.119667 0 0.101512 0.01528996 0.164954 0.024432 0.173372 0.008192956 0.119667 0.008190989 0.15623 0.01528996 0.164954 0.008192956 0.119667 0 0.138327 0 0.101512 0.02229595 0.04615491 0.003111958 0.147317 0.008190989 0.15623 0 0.101512 0 0.138327 0.003111958 0.147317 0 0.101512 0.02229595 0.08344095 0.02229595 0.04615491 0.04082298 0.03269398 0.011765 0.1142089 0.02229595 0.04615491 0.02229595 0.08344095 0.011765 0.1142089 0 0.138327 0.02229595 0.04615491 0.04078495 0.07005 0.04082298 0.03269398 0.06316298 0.0214039 0.04078495 0.07005 0.02229595 0.08344095 0.04082298 0.03269398 0.06316298 0.05875498 0.06316298 0.0214039 0.154359 8.87e-4 0.06316298 0.05875498 0.04078495 0.07005 0.06316298 0.0214039 0.154359 0.03822195 0.154359 8.87e-4 0.184426 0 0.109691 0.05288892 0.154359 8.87e-4 0.154359 0.03822195 0.109691 0.05288892 0.06316298 0.05875498 0.154359 8.87e-4 0.184482 0.03733396 0.184426 0 0.214502 0.001635909 0.184482 0.03733396 0.154359 0.03822195 0.184426 0 0.214502 0.03897297 0.184482 0.03733396 0.214502 0.001635909 0.03838497 0.149186 0.06619298 0.134587 0.074449 0.15957 0.074449 0.240176 0.074449 0.15957 0.06619298 0.134587 0.04645293 0.164897 0.074449 0.15957 0.1065 0.180778 0.106475 0.260161 0.1065 0.180778 0.074449 0.15957 0.04645293 0.164897 0.03838497 0.149186 0.074449 0.15957 0.106475 0.260161 0.074449 0.15957 0.074449 0.240176 0.04428297 0.1183969 0.08008998 0.1112779 0.06619298 0.134587 0.06619799 0.216461 0.06619298 0.134587 0.08008998 0.1112779 0.03789496 0.1334339 0.04428297 0.1183969 0.06619298 0.134587 0.03838497 0.149186 0.03789496 0.1334339 0.06619298 0.134587 0.06619799 0.216461 0.074449 0.240176 0.06619298 0.134587 0.05666995 0.104713 0.111109 0.09347897 0.08008998 0.1112779 0.08013296 0.194094 0.08008998 0.1112779 0.111109 0.09347897 0.04428297 0.1183969 0.05666995 0.104713 0.08008998 0.1112779 0.06619799 0.216461 0.08008998 0.1112779 0.08013296 0.194094 0.05666995 0.104713 0.152626 0.08360797 0.111109 0.09347897 0.111045 0.177003 0.111109 0.09347897 0.152626 0.08360797 0.08013296 0.194094 0.111109 0.09347897 0.111045 0.177003 0.229339 0.07377696 0.198251 0.08267599 0.152626 0.08360797 0.152706 0.1674129 0.152626 0.08360797 0.198251 0.08267599 0.202231 0.07024598 0.229339 0.07377696 0.152626 0.08360797 0.05666995 0.104713 0.202231 0.07024598 0.152626 0.08360797 0.111045 0.177003 0.152626 0.08360797 0.152706 0.1674129 0.254777 0.07995098 0.24112 0.090801 0.198251 0.08267599 0.198171 0.1665109 0.198251 0.08267599 0.24112 0.090801 0.229339 0.07377696 0.254777 0.07995098 0.198251 0.08267599 0.152706 0.1674129 0.198251 0.08267599 0.198171 0.1665109 0.296809 0.09965795 0.274791 0.107119 0.24112 0.090801 0.241144 0.174398 0.24112 0.090801 0.274791 0.107119 0.277583 0.08863699 0.296809 0.09965795 0.24112 0.090801 0.254777 0.07995098 0.277583 0.08863699 0.24112 0.090801 0.198171 0.1665109 0.24112 0.090801 0.241144 0.174398 0.311388 0.1126829 0.292636 0.129598 0.274791 0.107119 0.274791 0.190131 0.274791 0.107119 0.292636 0.129598 0.311388 0.1126829 0.274791 0.107119 0.296809 0.09965795 0.241144 0.174398 0.274791 0.107119 0.274791 0.190131 0.322665 0.142795 0.289163 0.15461 0.292636 0.129598 0.292623 0.211666 0.292636 0.129598 0.289163 0.15461 0.320298 0.1272439 0.322665 0.142795 0.292636 0.129598 0.311388 0.1126829 0.320298 0.1272439 0.292636 0.129598 0.274791 0.190131 0.292636 0.129598 0.292623 0.211666 0.317725 0.158603 0.261738 0.177091 0.289163 0.15461 0.289134 0.23552 0.289163 0.15461 0.261738 0.177091 0.322665 0.142795 0.317725 0.158603 0.289163 0.15461 0.292623 0.211666 0.289163 0.15461 0.289134 0.23552 0.317725 0.158603 0.214099 0.19112 0.261738 0.177091 0.261803 0.256675 0.261738 0.177091 0.214099 0.19112 0.289134 0.23552 0.261738 0.177091 0.261803 0.256675 0.115823 0.201826 0.15713 0.192508 0.214099 0.19112 0.214 0.269892 0.214099 0.19112 0.15713 0.192508 0.150517 0.207578 0.115823 0.201826 0.214099 0.19112 0.317725 0.158603 0.150517 0.207578 0.214099 0.19112 0.261803 0.256675 0.214099 0.19112 0.214 0.269892 0.08584296 0.192218 0.1065 0.180778 0.15713 0.192508 0.15723 0.271189 0.15713 0.192508 0.1065 0.180778 0.115823 0.201826 0.08584296 0.192218 0.15713 0.192508 0.214 0.269892 0.15713 0.192508 0.15723 0.271189 0.06238889 0.179591 0.04645293 0.164897 0.1065 0.180778 0.08584296 0.192218 0.06238889 0.179591 0.1065 0.180778 0.15723 0.271189 0.1065 0.180778 0.106475 0.260161 0.325145 0.07382398 0.296809 0.09965795 0.277583 0.08863699 0.342309 0.08779197 0.311388 0.1126829 0.296809 0.09965795 0.3343 0.08056998 0.296809 0.09965795 0.325145 0.07382398 0.342309 0.08779197 0.296809 0.09965795 0.3343 0.08056998 0.303833 0.06188297 0.277583 0.08863699 0.254777 0.07995098 0.314953 0.067586 0.277583 0.08863699 0.303833 0.06188297 0.325145 0.07382398 0.277583 0.08863699 0.314953 0.067586 0.258136 0.05477899 0.254777 0.07995098 0.229339 0.07377696 0.258136 0.05477899 0.303833 0.06188297 0.254777 0.07995098 0.214502 0.03897297 0.229339 0.07377696 0.202231 0.07024598 0.258136 0.05477899 0.229339 0.07377696 0.214502 0.03897297 0.07408797 0.09286099 0.174377 0.06942796 0.202231 0.07024598 0.184482 0.03733396 0.202231 0.07024598 0.174377 0.06942796 0.05666995 0.104713 0.07408797 0.09286099 0.202231 0.07024598 0.214502 0.03897297 0.202231 0.07024598 0.184482 0.03733396 0.09555095 0.08319199 0.146687 0.07134097 0.174377 0.06942796 0.154359 0.03822195 0.174377 0.06942796 0.146687 0.07134097 0.07408797 0.09286099 0.09555095 0.08319199 0.174377 0.06942796 0.184482 0.03733396 0.174377 0.06942796 0.154359 0.03822195 0.09555095 0.08319199 0.120083 0.07595998 0.146687 0.07134097 0.154359 0.03822195 0.146687 0.07134097 0.120083 0.07595998 0.109691 0.05288892 0.120083 0.07595998 0.09555095 0.08319199 0.109691 0.05288892 0.154359 0.03822195 0.120083 0.07595998 0.06316298 0.05875498 0.09555095 0.08319199 0.07408797 0.09286099 0.109691 0.05288892 0.09555095 0.08319199 0.06316298 0.05875498 0.04078495 0.07005 0.07408797 0.09286099 0.05666995 0.104713 0.06316298 0.05875498 0.07408797 0.09286099 0.04078495 0.07005 0.02229595 0.08344095 0.05666995 0.104713 0.04428297 0.1183969 0.04078495 0.07005 0.05666995 0.104713 0.02229595 0.08344095 0.011765 0.1142089 0.04428297 0.1183969 0.03789496 0.1334339 0.011765 0.1142089 0.02229595 0.08344095 0.04428297 0.1183969 0.011765 0.1142089 0.03789496 0.1334339 0.03838497 0.149186 0 0.138327 0.03838497 0.149186 0.04645293 0.164897 0.011765 0.1142089 0.03838497 0.149186 0 0.138327 0.008190989 0.15623 0.04645293 0.164897 0.06238889 0.179591 0.003111958 0.147317 0.04645293 0.164897 0.008190989 0.15623 0 0.138327 0.04645293 0.164897 0.003111958 0.147317 0.024432 0.173372 0.06238889 0.179591 0.08584296 0.192218 0.01528996 0.164954 0.06238889 0.179591 0.024432 0.173372 0.008190989 0.15623 0.06238889 0.179591 0.01528996 0.164954 0.07544696 0.197008 0.08584296 0.192218 0.115823 0.201826 0.07544696 0.197008 0.024432 0.173372 0.08584296 0.192218 0.130801 0.212281 0.115823 0.201826 0.150517 0.207578 0.07544696 0.197008 0.115823 0.201826 0.130801 0.212281 0.305019 0.1737959 0.187469 0.208939 0.150517 0.207578 0.17353 0.215431 0.150517 0.207578 0.187469 0.208939 0.317725 0.158603 0.305019 0.1737959 0.150517 0.207578 0.130801 0.212281 0.150517 0.207578 0.17353 0.215431 0.284555 0.18739 0.223875 0.205772 0.187469 0.208939 0.216696 0.2137179 0.187469 0.208939 0.223875 0.205772 0.305019 0.1737959 0.284555 0.18739 0.187469 0.208939 0.17353 0.215431 0.187469 0.208939 0.216696 0.2137179 0.284555 0.18739 0.257002 0.198364 0.223875 0.205772 0.216696 0.2137179 0.223875 0.205772 0.257002 0.198364 0.275039 0.200242 0.257002 0.198364 0.284555 0.18739 0.275039 0.200242 0.216696 0.2137179 0.257002 0.198364 0.329148 0.178183 0.284555 0.18739 0.305019 0.1737959 0.275039 0.200242 0.284555 0.18739 0.329148 0.178183 0.347817 0.161449 0.305019 0.1737959 0.317725 0.158603 0.329148 0.178183 0.305019 0.1737959 0.347817 0.161449 0.358368 0.143678 0.317725 0.158603 0.322665 0.142795 0.347817 0.161449 0.317725 0.158603 0.358368 0.143678 0.349882 0.119013 0.322665 0.142795 0.320298 0.1272439 0.349882 0.119013 0.358368 0.143678 0.322665 0.142795 0.349882 0.119013 0.320298 0.1272439 0.311388 0.1126829 0.349882 0.119013 0.311388 0.1126829 0.342309 0.08779197 0.292623 0.211666 0.106475 0.260161 0.074449 0.240176 0.274791 0.190131 0.292623 0.211666 0.074449 0.240176 0.06619799 0.216461 0.274791 0.190131 0.074449 0.240176 0.289134 0.23552 0.15723 0.271189 0.106475 0.260161 0.292623 0.211666 0.289134 0.23552 0.106475 0.260161 0.261803 0.256675 0.214 0.269892 0.15723 0.271189 0.289134 0.23552 0.261803 0.256675 0.15723 0.271189 0.06619799 0.216461 0.241144 0.174398 0.274791 0.190131 0.08013296 0.194094 0.198171 0.1665109 0.241144 0.174398 0.06619799 0.216461 0.08013296 0.194094 0.241144 0.174398 0.111045 0.177003 0.152706 0.1674129 0.198171 0.1665109 0.08013296 0.194094 0.111045 0.177003 0.198171 0.1665109 0.596519 0.675432 0.600809 0.681464 0.593424 0.682522 0.605456 0.6824 0.602798 0.674527 0.60846 0.681922 0.5917 0.682757 0.596519 0.675432 0.593424 0.682522 0.592691 0.684276 0.5917 0.682757 0.593424 0.682522 0.606345 0.673989 0.611195 0.673475 0.609942 0.674382 0.605456 0.6824 0.599929 0.674948 0.602798 0.674527 0.614732 0.676094 0.613709 0.675886 0.613419 0.67453 0.612171 0.681313 0.609692 0.675451 0.610516 0.676473 0.221676 0.076415 0.228778 0.06542396 0.231067 0.05431389 0.231067 0.09010797 0.231067 0.05431389 0.228778 0.06542396 0.2084169 0.02196598 0.221676 0.076415 0.231067 0.05431389 0.2084169 0.05698388 0.2084169 0.02196598 0.231067 0.05431389 0.219349 0.07703197 0.2084169 0.05698388 0.231067 0.05431389 0.219349 0.07703197 0.231067 0.05431389 0.231067 0.09010797 0.228779 0.101449 0.228778 0.06542396 0.221676 0.076415 0.230514 0.09576499 0.231067 0.09010797 0.228778 0.06542396 0.228779 0.101449 0.230514 0.09576499 0.228778 0.06542396 0.2084169 0.02196598 0.165968 0.105017 0.221676 0.076415 0.221676 0.11265 0.221676 0.076415 0.165968 0.105017 0.225836 0.1070989 0.228779 0.101449 0.221676 0.076415 0.221676 0.11265 0.225836 0.1070989 0.221676 0.076415 0.1941699 0.01452893 0.141587 0.109355 0.165968 0.105017 0.165968 0.141715 0.165968 0.105017 0.141587 0.109355 0.2084169 0.02196598 0.1941699 0.01452893 0.165968 0.105017 0.1946499 0.13104 0.165968 0.105017 0.165968 0.141715 0.1946499 0.13104 0.221676 0.11265 0.165968 0.105017 0.177541 0.008550941 0.115783 0.110963 0.141587 0.109355 0.141635 0.146107 0.141587 0.109355 0.115783 0.110963 0.1941699 0.01452893 0.177541 0.008550941 0.141587 0.109355 0.141635 0.146107 0.165968 0.141715 0.141587 0.109355 0.112595 0 0.03735792 0.09701299 0.115783 0.110963 0.115783 0.147741 0.115783 0.110963 0.03735792 0.09701299 0.177541 0.008550941 0.112595 0 0.115783 0.110963 0.115783 0.147741 0.141635 0.146107 0.115783 0.110963 0.09207201 9.39e-4 0.02028298 0.08810698 0.03735792 0.09701299 0.03735792 0.133594 0.03735792 0.09701299 0.02028298 0.08810698 0.112595 0 0.09207201 9.39e-4 0.03735792 0.09701299 0.07601499 0.144931 0.115783 0.147741 0.03735792 0.09701299 0.07601499 0.144931 0.03735792 0.09701299 0.03735792 0.133594 0.072084 0.003530979 0.007672965 0.077874 0.02028298 0.08810698 0.0202549 0.124527 0.02028298 0.08810698 0.007672965 0.077874 0.09207201 9.39e-4 0.072084 0.003530979 0.02028298 0.08810698 0.0202549 0.124527 0.03735792 0.133594 0.02028298 0.08810698 0.01787292 0.02307999 0 0.04186993 0.007672965 0.077874 0.007672965 0.114136 0.007672965 0.077874 0 0.04186993 0.072084 0.003530979 0.01787292 0.02307999 0.007672965 0.077874 0.007672965 0.114136 0.0202549 0.124527 0.007672965 0.077874 0.01787292 0.02307999 0.007120907 0.03195095 0 0.04186993 0 0.07738399 0 0.04186993 0.007120907 0.03195095 0.003691971 0.09920495 0.007672965 0.114136 0 0.04186993 0.003691971 0.09920495 0 0.04186993 0 0.07738399 0.007119953 0.06722599 0.007120907 0.03195095 0.01787292 0.02307999 0.003072977 0.07218897 0 0.07738399 0.007120907 0.03195095 0.007119953 0.06722599 0.003072977 0.07218897 0.007120907 0.03195095 0.01787292 0.05812793 0.01787292 0.02307999 0.072084 0.003530979 0.01207488 0.06252896 0.007119953 0.06722599 0.01787292 0.02307999 0.01787292 0.05812793 0.01207488 0.06252896 0.01787292 0.02307999 0.072084 0.0380389 0.072084 0.003530979 0.09207201 9.39e-4 0.04555189 0.05188 0.072084 0.003530979 0.072084 0.0380389 0.04555189 0.05188 0.01787292 0.05812793 0.072084 0.003530979 0.09203398 0.03537493 0.09207201 9.39e-4 0.112595 0 0.09203398 0.03537493 0.072084 0.0380389 0.09207201 9.39e-4 0.112595 0.03440499 0.112595 0 0.177541 0.008550941 0.112595 0.03440499 0.09203398 0.03537493 0.112595 0 0.177541 0.04320293 0.177541 0.008550941 0.1941699 0.01452893 0.144758 0.04276198 0.177541 0.008550941 0.177541 0.04320293 0.144758 0.04276198 0.112595 0.03440499 0.177541 0.008550941 0.194199 0.04935991 0.1941699 0.01452893 0.2084169 0.02196598 0.194199 0.04935991 0.177541 0.04320293 0.1941699 0.01452893 0.2084169 0.05698388 0.194199 0.04935991 0.2084169 0.02196598 0.03849589 0.07850599 0.06323999 0.07756197 0.04547095 0.09017497 0.04547095 0.174154 0.04547095 0.09017497 0.06323999 0.07756197 0.0288819 0.08688497 0.04547095 0.09017497 0.04032593 0.105791 0.04032999 0.190173 0.04032593 0.105791 0.04547095 0.09017497 0.0288819 0.08688497 0.03849589 0.07850599 0.04547095 0.09017497 0.04032999 0.190173 0.04547095 0.09017497 0.04547095 0.174154 0.06674897 0.06594896 0.08962798 0.06983798 0.06323999 0.07756197 0.06322699 0.161152 0.06323999 0.07756197 0.08962798 0.06983798 0.05133491 0.07146096 0.06674897 0.06594896 0.06323999 0.07756197 0.03849589 0.07850599 0.05133491 0.07146096 0.06323999 0.07756197 0.06322699 0.161152 0.04547095 0.174154 0.06323999 0.07756197 0.08403599 0.06212395 0.120066 0.06797796 0.08962798 0.06983798 0.08967995 0.15314 0.08962798 0.06983798 0.120066 0.06797796 0.06674897 0.06594896 0.08403599 0.06212395 0.08962798 0.06983798 0.06322699 0.161152 0.08962798 0.06983798 0.08967995 0.15314 0.08403599 0.06212395 0.14944 0.07219898 0.120066 0.06797796 0.120012 0.151219 0.120066 0.06797796 0.14944 0.07219898 0.08967995 0.15314 0.120066 0.06797796 0.120012 0.151219 0.197353 0.08498495 0.173032 0.08201897 0.14944 0.07219898 0.149487 0.1556079 0.14944 0.07219898 0.173032 0.08201897 0.187016 0.07688599 0.197353 0.08498495 0.14944 0.07219898 0.08403599 0.06212395 0.187016 0.07688599 0.14944 0.07219898 0.120012 0.151219 0.14944 0.07219898 0.149487 0.1556079 0.20397 0.09416896 0.186221 0.09607499 0.173032 0.08201897 0.172998 0.165726 0.173032 0.08201897 0.186221 0.09607499 0.197353 0.08498495 0.20397 0.09416896 0.173032 0.08201897 0.149487 0.1556079 0.173032 0.08201897 0.172998 0.165726 0.2040629 0.114252 0.1857039 0.112134 0.186221 0.09607499 0.186221 0.180233 0.186221 0.09607499 0.1857039 0.112134 0.206341 0.104068 0.2040629 0.114252 0.186221 0.09607499 0.20397 0.09416896 0.206341 0.104068 0.186221 0.09607499 0.172998 0.165726 0.186221 0.09607499 0.186221 0.180233 0.196956 0.124158 0.170198 0.1269879 0.1857039 0.112134 0.1857039 0.196672 0.1857039 0.112134 0.170198 0.1269879 0.196956 0.124158 0.1857039 0.112134 0.2040629 0.114252 0.186221 0.180233 0.1857039 0.112134 0.1857039 0.196672 0.169111 0.1407 0.14199 0.137073 0.170198 0.1269879 0.17021 0.2117969 0.170198 0.1269879 0.14199 0.137073 0.185159 0.133168 0.169111 0.1407 0.170198 0.1269879 0.196956 0.124158 0.185159 0.133168 0.170198 0.1269879 0.1857039 0.196672 0.170198 0.1269879 0.17021 0.2117969 0.149623 0.146199 0.1069779 0.1396279 0.14199 0.137073 0.1419309 0.222053 0.14199 0.137073 0.1069779 0.1396279 0.169111 0.1407 0.149623 0.146199 0.14199 0.137073 0.17021 0.2117969 0.14199 0.137073 0.1419309 0.222053 0.149623 0.146199 0.07377398 0.133904 0.1069779 0.1396279 0.107041 0.2246299 0.1069779 0.1396279 0.07377398 0.133904 0.1419309 0.222053 0.1069779 0.1396279 0.107041 0.2246299 0.025074 0.116427 0.04997491 0.121523 0.07377398 0.133904 0.07372295 0.218811 0.07377398 0.133904 0.04997491 0.121523 0.03318893 0.126172 0.025074 0.116427 0.07377398 0.133904 0.149623 0.146199 0.03318893 0.126172 0.07377398 0.133904 0.107041 0.2246299 0.07377398 0.133904 0.07372295 0.218811 0.021761 0.106279 0.04032593 0.105791 0.04997491 0.121523 0.05000597 0.206275 0.04997491 0.121523 0.04032593 0.105791 0.025074 0.116427 0.021761 0.106279 0.04997491 0.121523 0.07372295 0.218811 0.04997491 0.121523 0.05000597 0.206275 0.02313596 0.09628099 0.0288819 0.08688497 0.04032593 0.105791 0.021761 0.106279 0.02313596 0.09628099 0.04032593 0.105791 0.05000597 0.206275 0.04032593 0.105791 0.04032999 0.190173 0.228779 0.101449 0.2040629 0.114252 0.206341 0.104068 0.221676 0.11265 0.196956 0.124158 0.2040629 0.114252 0.225836 0.1070989 0.2040629 0.114252 0.228779 0.101449 0.221676 0.11265 0.2040629 0.114252 0.225836 0.1070989 0.231067 0.09010797 0.206341 0.104068 0.20397 0.09416896 0.230514 0.09576499 0.206341 0.104068 0.231067 0.09010797 0.228779 0.101449 0.206341 0.104068 0.230514 0.09576499 0.219349 0.07703197 0.20397 0.09416896 0.197353 0.08498495 0.219349 0.07703197 0.231067 0.09010797 0.20397 0.09416896 0.2084169 0.05698388 0.197353 0.08498495 0.187016 0.07688599 0.219349 0.07703197 0.197353 0.08498495 0.2084169 0.05698388 0.102491 0.06008398 0.173574 0.070149 0.187016 0.07688599 0.194199 0.04935991 0.187016 0.07688599 0.173574 0.070149 0.08403599 0.06212395 0.102491 0.06008398 0.187016 0.07688599 0.2084169 0.05698388 0.187016 0.07688599 0.194199 0.04935991 0.121402 0.05988097 0.157689 0.06497997 0.173574 0.070149 0.177541 0.04320293 0.173574 0.070149 0.157689 0.06497997 0.102491 0.06008398 0.121402 0.05988097 0.173574 0.070149 0.194199 0.04935991 0.173574 0.070149 0.177541 0.04320293 0.121402 0.05988097 0.140052 0.06152492 0.157689 0.06497997 0.177541 0.04320293 0.157689 0.06497997 0.140052 0.06152492 0.144758 0.04276198 0.140052 0.06152492 0.121402 0.05988097 0.144758 0.04276198 0.177541 0.04320293 0.140052 0.06152492 0.112595 0.03440499 0.121402 0.05988097 0.102491 0.06008398 0.144758 0.04276198 0.121402 0.05988097 0.112595 0.03440499 0.09203398 0.03537493 0.102491 0.06008398 0.08403599 0.06212395 0.112595 0.03440499 0.102491 0.06008398 0.09203398 0.03537493 0.072084 0.0380389 0.08403599 0.06212395 0.06674897 0.06594896 0.09203398 0.03537493 0.08403599 0.06212395 0.072084 0.0380389 0.04555189 0.05188 0.06674897 0.06594896 0.05133491 0.07146096 0.04555189 0.05188 0.072084 0.0380389 0.06674897 0.06594896 0.04555189 0.05188 0.05133491 0.07146096 0.03849589 0.07850599 0.01787292 0.05812793 0.03849589 0.07850599 0.0288819 0.08688497 0.04555189 0.05188 0.03849589 0.07850599 0.01787292 0.05812793 0.007119953 0.06722599 0.0288819 0.08688497 0.02313596 0.09628099 0.01207488 0.06252896 0.0288819 0.08688497 0.007119953 0.06722599 0.01787292 0.05812793 0.0288819 0.08688497 0.01207488 0.06252896 0 0.07738399 0.02313596 0.09628099 0.021761 0.106279 0.003072977 0.07218897 0.02313596 0.09628099 0 0.07738399 0.007119953 0.06722599 0.02313596 0.09628099 0.003072977 0.07218897 0.003691971 0.09920495 0.021761 0.106279 0.025074 0.116427 0.003691971 0.09920495 0 0.07738399 0.021761 0.106279 0.007672965 0.114136 0.025074 0.116427 0.03318893 0.126172 0.003691971 0.09920495 0.025074 0.116427 0.007672965 0.114136 0.127829 0.149228 0.045937 0.13492 0.03318893 0.126172 0.0202549 0.124527 0.03318893 0.126172 0.045937 0.13492 0.149623 0.146199 0.127829 0.149228 0.03318893 0.126172 0.007672965 0.114136 0.03318893 0.126172 0.0202549 0.124527 0.105107 0.149534 0.06281095 0.1420699 0.045937 0.13492 0.03735792 0.133594 0.045937 0.13492 0.06281095 0.1420699 0.127829 0.149228 0.105107 0.149534 0.045937 0.13492 0.0202549 0.124527 0.045937 0.13492 0.03735792 0.133594 0.105107 0.149534 0.082946 0.14708 0.06281095 0.1420699 0.03735792 0.133594 0.06281095 0.1420699 0.082946 0.14708 0.07601499 0.144931 0.082946 0.14708 0.105107 0.149534 0.07601499 0.144931 0.03735792 0.133594 0.082946 0.14708 0.115783 0.147741 0.105107 0.149534 0.127829 0.149228 0.07601499 0.144931 0.105107 0.149534 0.115783 0.147741 0.141635 0.146107 0.127829 0.149228 0.149623 0.146199 0.115783 0.147741 0.127829 0.149228 0.141635 0.146107 0.165968 0.141715 0.149623 0.146199 0.169111 0.1407 0.141635 0.146107 0.149623 0.146199 0.165968 0.141715 0.1946499 0.13104 0.169111 0.1407 0.185159 0.133168 0.1946499 0.13104 0.165968 0.141715 0.169111 0.1407 0.1946499 0.13104 0.185159 0.133168 0.196956 0.124158 0.1946499 0.13104 0.196956 0.124158 0.221676 0.11265 0.17021 0.2117969 0.04032999 0.190173 0.04547095 0.174154 0.1857039 0.196672 0.17021 0.2117969 0.04547095 0.174154 0.06322699 0.161152 0.1857039 0.196672 0.04547095 0.174154 0.1419309 0.222053 0.05000597 0.206275 0.04032999 0.190173 0.17021 0.2117969 0.1419309 0.222053 0.04032999 0.190173 0.107041 0.2246299 0.07372295 0.218811 0.05000597 0.206275 0.1419309 0.222053 0.107041 0.2246299 0.05000597 0.206275 0.06322699 0.161152 0.186221 0.180233 0.1857039 0.196672 0.08967995 0.15314 0.172998 0.165726 0.186221 0.180233 0.06322699 0.161152 0.08967995 0.15314 0.186221 0.180233 0.120012 0.151219 0.149487 0.1556079 0.172998 0.165726 0.08967995 0.15314 0.120012 0.151219 0.172998 0.165726 0.615852 0.676043 0.614325 0.674243 0.623617 0.672628 0.623617 0.673838 0.623617 0.672628 0.614325 0.674243 0.623617 0.673838 0.625244 0.675594 0.623617 0.672628 0.573558 0.687887 0.572756 0.685048 0.572756 0.686304 0.586475 0.684694 0.586475 0.683443 0.570884 0.680087 0.572756 0.686304 0.586475 0.683443 0.586475 0.684694 0.570884 0.681325 0.570884 0.680087 0.570144 0.678603 0.586475 0.684694 0.570884 0.680087 0.570884 0.681325 0.570884 0.681325 0.570144 0.678603 0.570144 0.679836 0.623617 0.673838 0.614325 0.674243 0.614325 0.67546 0.609942 0.675599 0.609942 0.674382 0.611195 0.673475 0.609692 0.676672 0.609942 0.674382 0.609942 0.675599 0.611194 0.674689 0.611195 0.673475 0.613193 0.672899 0.609942 0.675599 0.611195 0.673475 0.611194 0.674689 0.613193 0.67411 0.613193 0.672899 0.625597 0.670745 0.611194 0.674689 0.613193 0.672899 0.613193 0.67411 0.613193 0.67411 0.625597 0.670745 0.625597 0.671948 0.617035 0.678656 0.617035 0.677427 0.614602 0.677581 0.626503 0.676944 0.617035 0.677427 0.617035 0.678656 0.614325 0.67546 0.613419 0.67453 0.613419 0.675748 0.614325 0.67546 0.614325 0.674243 0.613419 0.67453 0.610516 0.677697 0.610516 0.676473 0.609692 0.675451 0.612268 0.678465 0.610516 0.676473 0.610516 0.677697 0.572756 0.686304 0.572756 0.685048 0.586475 0.683443 0.610516 0.677697 0.609692 0.675451 0.609692 0.676672 0.628939 0.679527 0.625597 0.671948 0.632255 0.678876 0.614325 0.67546 0.613193 0.67411 0.625597 0.671948 0.628939 0.679527 0.626503 0.676944 0.625597 0.671948 0.625244 0.675594 0.625597 0.671948 0.626503 0.676944 0.623617 0.673838 0.625597 0.671948 0.625244 0.675594 0.623617 0.673838 0.614325 0.67546 0.625597 0.671948 0.612955 0.6762 0.611194 0.674689 0.613193 0.67411 0.613419 0.675748 0.612955 0.6762 0.613193 0.67411 0.614325 0.67546 0.613419 0.675748 0.613193 0.67411 0.612268 0.678465 0.609942 0.675599 0.611194 0.674689 0.614601 0.67881 0.612268 0.678465 0.611194 0.674689 0.613059 0.676699 0.614601 0.67881 0.611194 0.674689 0.612955 0.6762 0.613059 0.676699 0.611194 0.674689 0.610516 0.677697 0.609692 0.676672 0.609942 0.675599 0.612268 0.678465 0.610516 0.677697 0.609942 0.675599 0.615852 0.677267 0.617035 0.678656 0.614601 0.67881 0.614732 0.677317 0.615852 0.677267 0.614601 0.67881 0.61371 0.677109 0.614732 0.677317 0.614601 0.67881 0.613059 0.676699 0.61371 0.677109 0.614601 0.67881 0.625244 0.675594 0.626503 0.676944 0.617035 0.678656 0.615852 0.677267 0.625244 0.675594 0.617035 0.678656 0.60846 0.683168 0.602798 0.675745 0.606345 0.675205 0.612171 0.682556 0.60846 0.683168 0.606345 0.675205 0.600809 0.682707 0.596519 0.676654 0.599929 0.676167 0.605456 0.683647 0.600809 0.682707 0.599929 0.676167 0.594431 0.685288 0.593424 0.683769 0.600809 0.682707 0.605456 0.683647 0.594431 0.685288 0.600809 0.682707 0.570884 0.681325 0.570144 0.679836 0.587567 0.677849 0.576058 0.680774 0.570884 0.681325 0.587567 0.677849 0.588474 0.679288 0.576058 0.680774 0.587567 0.677849 0.576058 0.680774 0.586475 0.684694 0.570884 0.681325 0.573558 0.687887 0.572756 0.686304 0.586475 0.684694 0.5917 0.684006 0.573558 0.687887 0.586475 0.684694 0.576058 0.680774 0.5917 0.684006 0.586475 0.684694 0.5917 0.684006 0.592691 0.68553 0.573558 0.687887 0.613419 0.675748 0.613419 0.67453 0.612955 0.674981 0.626503 0.676944 0.626503 0.675721 0.617035 0.677427 0.628939 0.679527 0.626503 0.675721 0.626503 0.676944 0.632255 0.678876 0.632255 0.677647 0.628939 0.678295 0.625597 0.671948 0.625597 0.670745 0.632255 0.677647 0.625597 0.671948 0.632255 0.677647 0.632255 0.678876 0.628939 0.679527 0.628939 0.678295 0.626503 0.675721 0.628939 0.679527 0.632255 0.678876 0.628939 0.678295 0.625244 0.675594 0.625244 0.674377 0.623617 0.672628 0.615852 0.677267 0.615852 0.676043 0.625244 0.674377 0.615852 0.677267 0.625244 0.674377 0.625244 0.675594 0.609692 0.676672 0.609692 0.675451 0.609942 0.674382 0.612268 0.678465 0.612269 0.677237 0.610516 0.676473 0.614601 0.67881 0.612269 0.677237 0.612268 0.678465 0.612955 0.6762 0.612955 0.674981 0.613059 0.675478 0.613419 0.675748 0.612955 0.674981 0.612955 0.6762 0.613059 0.676699 0.613059 0.675478 0.613709 0.675886 0.612955 0.6762 0.613059 0.675478 0.613059 0.676699 0.61371 0.677109 0.613709 0.675886 0.614732 0.676094 0.613059 0.676699 0.613709 0.675886 0.61371 0.677109 0.614732 0.677317 0.614732 0.676094 0.615852 0.676043 0.61371 0.677109 0.614732 0.676094 0.614732 0.677317 0.614732 0.677317 0.615852 0.676043 0.615852 0.677267 0.606345 0.675205 0.606345 0.673989 0.612171 0.681313 0.602798 0.675745 0.602798 0.674527 0.606345 0.673989 0.602798 0.675745 0.606345 0.673989 0.606345 0.675205 0.612171 0.682556 0.612171 0.681313 0.60846 0.681922 0.612171 0.682556 0.606345 0.675205 0.612171 0.681313 0.60846 0.683168 0.60846 0.681922 0.602798 0.674527 0.612171 0.682556 0.60846 0.681922 0.60846 0.683168 0.588474 0.679288 0.588474 0.678057 0.576058 0.679537 0.588474 0.679288 0.587567 0.677849 0.588474 0.678057 0.576058 0.680774 0.576058 0.679537 0.5917 0.682757 0.588474 0.679288 0.576058 0.679537 0.576058 0.680774 0.5917 0.684006 0.5917 0.682757 0.592691 0.684276 0.576058 0.680774 0.5917 0.682757 0.5917 0.684006 0.592691 0.68553 0.592691 0.684276 0.573558 0.686626 0.5917 0.684006 0.592691 0.684276 0.592691 0.68553 0.573558 0.687887 0.573558 0.686626 0.572756 0.685048 0.592691 0.68553 0.573558 0.686626 0.573558 0.687887 0.593424 0.683769 0.593424 0.682522 0.600809 0.681464 0.594431 0.685288 0.594431 0.684035 0.593424 0.682522 0.605456 0.683647 0.594431 0.684035 0.594431 0.685288 0.60846 0.683168 0.602798 0.674527 0.602798 0.675745 0.599929 0.676167 0.599929 0.674948 0.605456 0.6824 0.596519 0.676654 0.596519 0.675432 0.599929 0.674948 0.596519 0.676654 0.599929 0.674948 0.599929 0.676167 0.605456 0.683647 0.605456 0.6824 0.594431 0.684035 0.605456 0.683647 0.599929 0.676167 0.605456 0.6824 0.600809 0.682707 0.596519 0.675432 0.596519 0.676654 0.587567 0.677849 0.587567 0.676623 0.588474 0.678057 0.570144 0.679836 0.570144 0.678603 0.587567 0.676623 0.570144 0.679836 0.587567 0.676623 0.587567 0.677849 0.594431 0.685288 0.593424 0.682522 0.593424 0.683769 0.600809 0.682707 0.600809 0.681464 0.596519 0.675432 0.593424 0.683769 0.600809 0.681464 0.600809 0.682707 0.614601 0.67881 0.614602 0.677581 0.612269 0.677237 0.617035 0.678656 0.614602 0.677581 0.614601 0.67881 + + + + + + + + + + + + + + +

0 0 0 1 0 1 2 0 2 3 1 3 4 2 4 5 3 5 6 4 6 1 4 7 0 4 8 7 5 9 1 5 10 6 5 11 8 6 12 1 6 13 7 6 14 9 7 15 1 7 16 8 7 17 10 8 18 3 1 19 5 3 20 11 9 21 10 8 22 5 3 23 12 10 24 11 9 25 5 3 26 13 11 27 14 11 28 15 11 29 16 12 30 1 12 31 9 12 32 17 13 33 1 13 34 16 13 35 18 14 36 1 14 37 17 14 38 19 15 39 1 15 40 18 15 41 20 11 42 15 11 43 21 11 44 22 11 45 13 11 46 15 11 47 20 11 48 22 11 49 15 11 50 23 16 51 24 17 52 4 2 53 3 1 54 23 16 55 4 2 56 25 18 57 26 19 58 24 17 59 27 20 60 25 18 61 24 17 62 23 16 63 27 20 64 24 17 65 28 21 66 29 22 67 26 19 68 30 23 69 28 21 70 26 19 71 25 18 72 30 23 73 26 19 74 31 24 75 32 25 76 29 22 77 33 26 78 31 24 79 29 22 80 28 21 81 33 26 82 29 22 83 34 27 84 35 28 85 36 29 86 37 30 87 35 28 88 34 27 89 38 31 90 39 31 91 40 31 92 41 32 93 42 32 94 39 32 95 41 31 96 39 31 97 38 31 98 43 31 99 40 31 100 44 31 101 43 33 102 38 33 103 40 33 104 43 31 105 44 31 106 45 31 107 46 31 108 45 31 109 47 31 110 46 31 111 43 31 112 45 31 113 46 31 114 47 31 115 48 31 116 49 31 117 48 31 118 50 31 119 49 31 120 46 31 121 48 31 122 49 31 123 50 31 124 51 31 125 52 31 126 51 31 127 53 31 128 52 31 129 49 31 130 51 31 131 52 31 132 53 31 133 54 31 134 12 10 135 55 34 136 11 9 137 56 31 138 54 31 139 57 31 140 56 35 141 52 35 142 54 35 143 58 36 144 59 37 145 55 34 146 56 38 147 57 38 148 60 38 149 12 10 150 58 36 151 55 34 152 61 39 153 62 40 154 59 37 155 63 41 156 60 41 157 64 41 158 58 36 159 61 39 160 59 37 161 63 42 162 56 42 163 60 42 164 65 43 165 66 44 166 62 40 167 63 31 168 64 31 169 67 31 170 68 45 171 65 43 172 62 40 173 69 46 174 68 45 175 62 40 176 70 47 177 69 46 178 62 40 179 71 48 180 70 47 181 62 40 182 72 49 183 71 48 184 62 40 185 73 50 186 72 49 187 62 40 188 74 51 189 73 50 190 62 40 191 75 52 192 74 51 193 62 40 194 76 53 195 75 52 196 62 40 197 77 54 198 76 53 199 62 40 200 78 55 201 77 54 202 62 40 203 79 56 204 78 55 205 62 40 206 80 57 207 79 56 208 62 40 209 61 39 210 80 57 211 62 40 212 81 58 213 82 59 214 66 44 215 83 60 216 67 60 217 84 60 218 85 61 219 81 58 220 66 44 221 86 62 222 85 61 223 66 44 224 87 63 225 86 62 226 66 44 227 88 64 228 87 63 229 66 44 230 89 65 231 88 64 232 66 44 233 90 66 234 89 65 235 66 44 236 91 67 237 90 66 238 66 44 239 92 68 240 91 67 241 66 44 242 93 69 243 92 68 244 66 44 245 94 70 246 93 69 247 66 44 248 95 71 249 94 70 250 66 44 251 96 72 252 95 71 253 66 44 254 97 73 255 96 72 256 66 44 257 65 43 258 97 73 259 66 44 260 83 31 261 63 31 262 67 31 263 98 74 264 99 75 265 82 59 266 100 31 267 84 31 268 101 31 269 102 76 270 98 74 271 82 59 272 103 77 273 102 76 274 82 59 275 104 78 276 103 77 277 82 59 278 105 79 279 104 78 280 82 59 281 106 80 282 105 79 283 82 59 284 107 81 285 106 80 286 82 59 287 108 82 288 107 81 289 82 59 290 109 83 291 108 82 292 82 59 293 110 84 294 109 83 295 82 59 296 111 85 297 110 84 298 82 59 299 112 86 300 111 85 301 82 59 302 113 87 303 112 86 304 82 59 305 81 58 306 113 87 307 82 59 308 100 31 309 83 31 310 84 31 311 114 88 312 115 89 313 99 75 314 116 31 315 101 31 316 117 31 317 118 90 318 114 88 319 99 75 320 119 91 321 118 90 322 99 75 323 120 92 324 119 91 325 99 75 326 121 93 327 120 92 328 99 75 329 122 94 330 121 93 331 99 75 332 123 95 333 122 94 334 99 75 335 124 96 336 123 95 337 99 75 338 125 97 339 124 96 340 99 75 341 98 74 342 125 97 343 99 75 344 116 98 345 100 98 346 101 98 347 126 99 348 127 100 349 115 89 350 128 101 351 117 101 352 129 101 353 130 102 354 126 99 355 115 89 356 131 103 357 130 102 358 115 89 359 132 104 360 131 103 361 115 89 362 133 105 363 132 104 364 115 89 365 114 88 366 133 105 367 115 89 368 128 106 369 116 106 370 117 106 371 134 31 372 129 31 373 135 31 374 136 107 375 137 108 376 127 100 377 138 31 378 129 31 379 134 31 380 128 109 381 129 109 382 138 109 383 126 99 384 136 107 385 127 100 386 139 31 387 135 31 388 140 31 389 136 107 390 141 110 391 137 108 392 134 31 393 135 31 394 139 31 395 142 31 396 140 31 397 143 31 398 144 111 399 145 112 400 141 110 401 139 31 402 140 31 403 142 31 404 136 107 405 144 111 406 141 110 407 146 31 408 143 31 409 147 31 410 144 111 411 148 113 412 145 112 413 142 31 414 143 31 415 146 31 416 149 114 417 150 115 418 148 113 419 144 111 420 149 114 421 148 113 422 151 116 423 152 117 424 150 115 425 149 114 426 151 116 427 150 115 428 151 116 429 153 118 430 152 117 431 154 119 432 155 120 433 153 118 434 151 116 435 154 119 436 153 118 437 154 119 438 156 121 439 155 120 440 157 122 441 158 123 442 156 121 443 159 31 444 138 31 445 160 31 446 161 124 447 157 122 448 156 121 449 162 125 450 161 124 451 156 121 452 163 126 453 162 125 454 156 121 455 164 127 456 163 126 457 156 121 458 165 128 459 164 127 460 156 121 461 166 129 462 165 128 463 156 121 464 167 130 465 166 129 466 156 121 467 168 131 468 167 130 469 156 121 470 169 132 471 168 131 472 156 121 473 170 133 474 169 132 475 156 121 476 171 134 477 170 133 478 156 121 479 172 135 480 171 134 481 156 121 482 173 136 483 172 135 484 156 121 485 154 119 486 173 136 487 156 121 488 159 137 489 128 137 490 138 137 491 174 138 492 175 139 493 158 123 494 176 31 495 160 31 496 177 31 497 178 140 498 174 138 499 158 123 500 179 141 501 178 140 502 158 123 503 180 142 504 179 141 505 158 123 506 181 143 507 180 142 508 158 123 509 182 144 510 181 143 511 158 123 512 183 145 513 182 144 514 158 123 515 184 146 516 183 145 517 158 123 518 185 147 519 184 146 520 158 123 521 186 148 522 185 147 523 158 123 524 187 149 525 186 148 526 158 123 527 188 150 528 187 149 529 158 123 530 189 151 531 188 150 532 158 123 533 190 152 534 189 151 535 158 123 536 157 122 537 190 152 538 158 123 539 176 31 540 159 31 541 160 31 542 191 153 543 192 154 544 175 139 545 193 155 546 177 155 547 194 155 548 195 156 549 191 153 550 175 139 551 196 157 552 195 156 553 175 139 554 197 158 555 196 157 556 175 139 557 198 159 558 197 158 559 175 139 560 199 160 561 198 159 562 175 139 563 200 161 564 199 160 565 175 139 566 201 162 567 200 161 568 175 139 569 202 163 570 201 162 571 175 139 572 203 164 573 202 163 574 175 139 575 204 165 576 203 164 577 175 139 578 205 166 579 204 165 580 175 139 581 206 167 582 205 166 583 175 139 584 174 138 585 206 167 586 175 139 587 193 31 588 176 31 589 177 31 590 207 168 591 208 169 592 192 154 593 193 31 594 194 31 595 209 31 596 210 170 597 207 168 598 192 154 599 211 171 600 210 170 601 192 154 602 212 172 603 211 171 604 192 154 605 213 173 606 212 172 607 192 154 608 214 174 609 213 173 610 192 154 611 215 175 612 214 174 613 192 154 614 216 176 615 215 175 616 192 154 617 217 177 618 216 176 619 192 154 620 191 153 621 217 177 622 192 154 623 218 178 624 219 179 625 208 169 626 220 180 627 209 180 628 221 180 629 222 181 630 218 178 631 208 169 632 223 182 633 222 181 634 208 169 635 224 183 636 223 182 637 208 169 638 225 184 639 224 183 640 208 169 641 207 168 642 225 184 643 208 169 644 220 185 645 193 185 646 209 185 647 226 186 648 227 187 649 219 179 650 220 31 651 221 31 652 228 31 653 218 178 654 226 186 655 219 179 656 226 186 657 229 188 658 227 187 659 230 31 660 228 31 661 231 31 662 230 31 663 220 31 664 228 31 665 232 189 666 233 190 667 229 188 668 230 31 669 231 31 670 234 31 671 226 186 672 232 189 673 229 188 674 232 189 675 235 191 676 233 190 677 236 31 678 234 31 679 237 31 680 236 31 681 230 31 682 234 31 683 238 192 684 239 193 685 235 191 686 236 31 687 237 31 688 240 31 689 232 189 690 238 192 691 235 191 692 241 194 693 242 195 694 239 193 695 243 31 696 240 31 697 244 31 698 238 192 699 241 194 700 239 193 701 243 31 702 236 31 703 240 31 704 241 194 705 245 196 706 242 195 707 243 197 708 244 197 709 246 197 710 247 198 711 248 199 712 245 196 713 249 31 714 246 31 715 250 31 716 241 194 717 247 198 718 245 196 719 249 200 720 243 200 721 246 200 722 247 198 723 251 201 724 248 199 725 249 31 726 250 31 727 252 31 728 253 202 729 254 203 730 251 201 731 255 31 732 252 31 733 256 31 734 257 204 735 253 202 736 251 201 737 258 205 738 257 204 739 251 201 740 259 206 741 258 205 742 251 201 743 260 207 744 259 206 745 251 201 746 261 208 747 260 207 748 251 201 749 262 209 750 261 208 751 251 201 752 263 210 753 262 209 754 251 201 755 264 211 756 263 210 757 251 201 758 265 212 759 264 211 760 251 201 761 266 213 762 265 212 763 251 201 764 267 214 765 266 213 766 251 201 767 268 215 768 267 214 769 251 201 770 269 216 771 268 215 772 251 201 773 247 198 774 269 216 775 251 201 776 255 31 777 249 31 778 252 31 779 270 217 780 271 218 781 254 203 782 255 219 783 256 219 784 272 219 785 273 220 786 270 217 787 254 203 788 274 221 789 273 220 790 254 203 791 275 222 792 274 221 793 254 203 794 276 223 795 275 222 796 254 203 797 277 224 798 276 223 799 254 203 800 278 225 801 277 224 802 254 203 803 279 226 804 278 225 805 254 203 806 280 227 807 279 226 808 254 203 809 281 228 810 280 227 811 254 203 812 282 229 813 281 228 814 254 203 815 283 230 816 282 229 817 254 203 818 284 231 819 283 230 820 254 203 821 285 232 822 284 231 823 254 203 824 253 202 825 285 232 826 254 203 827 286 233 828 287 234 829 288 235 830 289 236 831 290 237 832 287 234 833 291 238 834 287 234 835 290 237 836 292 239 837 289 236 838 287 234 839 293 240 840 292 239 841 287 234 842 294 241 843 293 240 844 287 234 845 295 242 846 294 241 847 287 234 848 296 243 849 295 242 850 287 234 851 297 244 852 296 243 853 287 234 854 298 245 855 297 244 856 287 234 857 299 246 858 298 245 859 287 234 860 300 247 861 299 246 862 287 234 863 301 248 864 300 247 865 287 234 866 286 233 867 301 248 868 287 234 869 302 31 870 272 31 871 303 31 872 302 31 873 255 31 874 272 31 875 304 249 876 305 250 877 306 251 878 307 252 879 308 253 880 309 254 881 307 252 882 309 254 883 310 255 884 304 249 885 306 251 886 311 256 887 304 249 888 311 256 889 312 257 890 304 249 891 312 257 892 313 258 893 314 259 894 313 258 895 315 260 896 314 259 897 304 249 898 313 258 899 314 259 900 315 260 901 316 261 902 314 259 903 316 261 904 317 262 905 314 259 906 317 262 907 318 263 908 319 264 909 318 263 910 320 265 911 319 264 912 314 259 913 318 263 914 319 264 915 320 265 916 321 266 917 319 264 918 321 266 919 322 267 920 319 264 921 322 267 922 323 268 923 324 269 924 323 268 925 325 270 926 324 269 927 319 264 928 323 268 929 324 269 930 325 270 931 326 271 932 324 269 933 326 271 934 327 272 935 324 269 936 327 272 937 328 273 938 329 274 939 328 273 940 330 275 941 329 274 942 324 269 943 328 273 944 329 274 945 330 275 946 331 276 947 329 274 948 331 276 949 332 277 950 333 278 951 332 277 952 334 279 953 333 278 954 329 274 955 332 277 956 333 278 957 334 279 958 335 280 959 336 281 960 335 280 961 337 282 962 336 281 963 333 278 964 335 280 965 336 281 966 337 282 967 338 283 968 339 284 969 338 283 970 340 285 971 339 284 972 336 281 973 338 283 974 339 284 975 340 285 976 341 286 977 342 287 978 341 286 979 343 288 980 342 287 981 339 284 982 341 286 983 344 289 984 343 288 985 345 290 986 344 289 987 342 287 988 343 288 989 247 198 990 346 291 991 269 216 992 347 292 993 345 290 994 348 293 995 347 292 996 344 289 997 345 290 998 247 198 999 349 294 1000 346 291 1001 350 295 1002 348 293 1003 351 296 1004 350 295 1005 347 292 1006 348 293 1007 247 198 1008 352 297 1009 349 294 1010 353 298 1011 351 296 1012 354 299 1013 353 298 1014 350 295 1015 351 296 1016 355 300 1017 356 301 1018 357 302 1019 355 300 1020 358 303 1021 356 301 1022 359 304 1023 354 299 1024 360 305 1025 359 304 1026 353 298 1027 354 299 1028 361 306 1029 357 302 1030 362 307 1031 361 306 1032 355 300 1033 357 302 1034 363 308 1035 362 307 1036 364 309 1037 363 308 1038 361 306 1039 362 307 1040 363 308 1041 364 309 1042 365 310 1043 366 311 1044 365 310 1045 367 312 1046 366 311 1047 363 308 1048 365 310 1049 368 313 1050 367 312 1051 369 314 1052 368 313 1053 366 311 1054 367 312 1055 370 315 1056 371 316 1057 218 178 1058 372 317 1059 369 314 1060 373 318 1061 374 319 1062 370 315 1063 218 178 1064 375 320 1065 374 319 1066 218 178 1067 222 181 1068 375 320 1069 218 178 1070 372 317 1071 368 313 1072 369 314 1073 376 321 1074 377 322 1075 378 323 1076 379 324 1077 372 317 1078 373 318 1079 380 325 1080 381 326 1081 377 322 1082 376 321 1083 380 325 1084 377 322 1085 382 327 1086 378 323 1087 383 328 1088 382 327 1089 376 321 1090 378 323 1091 384 329 1092 383 328 1093 385 330 1094 384 329 1095 382 327 1096 383 328 1097 386 331 1098 385 330 1099 387 332 1100 386 331 1101 384 329 1102 385 330 1103 388 333 1104 387 332 1105 389 334 1106 388 333 1107 386 331 1108 387 332 1109 388 333 1110 389 334 1111 390 335 1112 391 336 1113 390 335 1114 392 337 1115 391 336 1116 388 333 1117 390 335 1118 391 336 1119 392 337 1120 393 338 1121 394 339 1122 393 338 1123 395 340 1124 394 339 1125 391 336 1126 393 338 1127 394 339 1128 395 340 1129 396 341 1130 397 342 1131 396 341 1132 398 343 1133 397 342 1134 394 339 1135 396 341 1136 397 342 1137 398 343 1138 399 344 1139 397 342 1140 399 344 1141 400 345 1142 401 346 1143 400 345 1144 402 347 1145 401 346 1146 397 342 1147 400 345 1148 401 346 1149 402 347 1150 403 348 1151 401 346 1152 403 348 1153 404 349 1154 401 346 1155 404 349 1156 405 350 1157 406 351 1158 405 350 1159 407 352 1160 406 351 1161 401 346 1162 405 350 1163 406 351 1164 407 352 1165 408 353 1166 406 351 1167 408 353 1168 409 354 1169 406 351 1170 409 354 1171 410 355 1172 411 356 1173 410 355 1174 412 357 1175 411 356 1176 406 351 1177 410 355 1178 411 356 1179 412 357 1180 413 358 1181 411 356 1182 413 358 1183 414 359 1184 411 356 1185 414 359 1186 415 360 1187 416 361 1188 415 360 1189 417 362 1190 416 361 1191 411 356 1192 415 360 1193 416 361 1194 417 362 1195 418 363 1196 416 361 1197 418 363 1198 419 364 1199 416 361 1200 419 364 1201 420 365 1202 416 361 1203 420 365 1204 421 366 1205 422 367 1206 423 368 1207 424 369 1208 416 361 1209 421 366 1210 425 370 1211 422 367 1212 424 369 1213 426 371 1214 422 367 1215 426 371 1216 427 372 1217 422 367 1218 427 372 1219 428 373 1220 429 374 1221 428 373 1222 430 375 1223 429 374 1224 422 367 1225 428 373 1226 429 374 1227 430 375 1228 431 376 1229 429 374 1230 431 376 1231 432 377 1232 429 374 1233 432 377 1234 433 378 1235 434 379 1236 433 378 1237 435 380 1238 434 379 1239 429 374 1240 433 378 1241 434 379 1242 435 380 1243 436 381 1244 434 379 1245 436 381 1246 437 382 1247 434 379 1248 437 382 1249 438 383 1250 439 384 1251 438 383 1252 440 385 1253 439 384 1254 434 379 1255 438 383 1256 439 384 1257 440 385 1258 441 386 1259 439 384 1260 441 386 1261 442 387 1262 439 384 1263 442 387 1264 443 388 1265 444 389 1266 443 388 1267 445 390 1268 444 389 1269 439 384 1270 443 388 1271 444 389 1272 445 390 1273 446 391 1274 444 389 1275 446 391 1276 447 392 1277 448 393 1278 447 392 1279 449 394 1280 448 393 1281 444 389 1282 447 392 1283 448 393 1284 449 394 1285 450 395 1286 451 396 1287 450 395 1288 452 397 1289 451 396 1290 448 393 1291 450 395 1292 451 396 1293 452 397 1294 453 398 1295 454 399 1296 453 398 1297 455 400 1298 454 399 1299 451 396 1300 453 398 1301 454 399 1302 455 400 1303 456 401 1304 457 402 1305 456 401 1306 458 403 1307 457 402 1308 454 399 1309 456 401 1310 459 404 1311 458 403 1312 460 405 1313 459 404 1314 457 402 1315 458 403 1316 154 119 1317 461 406 1318 173 136 1319 462 407 1320 460 405 1321 463 408 1322 462 407 1323 459 404 1324 460 405 1325 154 119 1326 464 409 1327 461 406 1328 465 410 1329 463 408 1330 466 411 1331 465 410 1332 462 407 1333 463 408 1334 154 119 1335 467 412 1336 464 409 1337 468 413 1338 466 411 1339 469 414 1340 468 413 1341 465 410 1342 466 411 1343 470 415 1344 471 416 1345 472 417 1346 470 415 1347 473 418 1348 471 416 1349 474 419 1350 469 414 1351 475 420 1352 474 419 1353 468 413 1354 469 414 1355 476 421 1356 472 417 1357 477 422 1358 476 421 1359 470 415 1360 472 417 1361 478 423 1362 477 422 1363 479 424 1364 478 423 1365 476 421 1366 477 422 1367 478 423 1368 479 424 1369 480 425 1370 481 426 1371 480 425 1372 482 427 1373 481 426 1374 478 423 1375 480 425 1376 483 428 1377 482 427 1378 484 429 1379 483 428 1380 481 426 1381 482 427 1382 485 430 1383 486 431 1384 126 99 1385 487 432 1386 484 429 1387 488 433 1388 489 434 1389 485 430 1390 126 99 1391 490 435 1392 489 434 1393 126 99 1394 130 102 1395 490 435 1396 126 99 1397 487 432 1398 483 428 1399 484 429 1400 491 436 1401 492 437 1402 493 438 1403 494 439 1404 487 432 1405 488 433 1406 495 440 1407 496 441 1408 492 437 1409 491 436 1410 495 440 1411 492 437 1412 497 442 1413 493 438 1414 498 443 1415 497 442 1416 491 436 1417 493 438 1418 499 444 1419 498 443 1420 500 445 1421 499 444 1422 497 442 1423 498 443 1424 501 446 1425 500 445 1426 502 447 1427 501 446 1428 499 444 1429 500 445 1430 503 448 1431 502 447 1432 504 449 1433 503 448 1434 501 446 1435 502 447 1436 503 448 1437 504 449 1438 505 450 1439 506 451 1440 505 450 1441 507 452 1442 506 451 1443 503 448 1444 505 450 1445 506 451 1446 507 452 1447 508 453 1448 509 454 1449 508 453 1450 510 455 1451 509 454 1452 506 451 1453 508 453 1454 509 454 1455 510 455 1456 511 456 1457 512 457 1458 511 456 1459 513 458 1460 512 457 1461 509 454 1462 511 456 1463 512 457 1464 513 458 1465 514 459 1466 512 457 1467 514 459 1468 515 460 1469 516 461 1470 515 460 1471 517 462 1472 516 461 1473 512 457 1474 515 460 1475 516 461 1476 517 462 1477 518 463 1478 516 461 1479 518 463 1480 519 464 1481 516 461 1482 519 464 1483 520 465 1484 521 466 1485 520 465 1486 522 467 1487 521 466 1488 516 461 1489 520 465 1490 521 466 1491 522 467 1492 523 468 1493 521 466 1494 523 468 1495 524 469 1496 521 466 1497 524 469 1498 525 470 1499 526 471 1500 525 470 1501 527 472 1502 526 471 1503 521 466 1504 525 470 1505 526 471 1506 527 472 1507 528 473 1508 526 471 1509 528 473 1510 529 474 1511 526 471 1512 529 474 1513 530 475 1514 531 476 1515 530 475 1516 532 477 1517 531 476 1518 526 471 1519 530 475 1520 531 476 1521 532 477 1522 533 478 1523 531 476 1524 533 478 1525 534 479 1526 531 476 1527 534 479 1528 535 480 1529 531 476 1530 535 480 1531 536 481 1532 537 482 1533 538 483 1534 539 484 1535 531 476 1536 536 481 1537 540 485 1538 537 482 1539 539 484 1540 541 486 1541 537 482 1542 541 486 1543 542 487 1544 537 482 1545 542 487 1546 543 488 1547 544 489 1548 543 488 1549 545 490 1550 544 489 1551 537 482 1552 543 488 1553 544 489 1554 545 490 1555 546 491 1556 544 489 1557 546 491 1558 547 492 1559 544 489 1560 547 492 1561 548 493 1562 549 494 1563 548 493 1564 550 495 1565 549 494 1566 544 489 1567 548 493 1568 549 494 1569 550 495 1570 551 496 1571 549 494 1572 551 496 1573 552 497 1574 549 494 1575 552 497 1576 553 498 1577 554 499 1578 553 498 1579 555 500 1580 554 499 1581 549 494 1582 553 498 1583 554 499 1584 555 500 1585 556 501 1586 554 499 1587 556 501 1588 557 502 1589 554 499 1590 557 502 1591 558 503 1592 559 504 1593 558 503 1594 560 505 1595 559 504 1596 554 499 1597 558 503 1598 559 504 1599 560 505 1600 561 506 1601 559 504 1602 561 506 1603 562 507 1604 563 508 1605 562 507 1606 564 509 1607 563 508 1608 559 504 1609 562 507 1610 563 508 1611 564 509 1612 565 510 1613 566 511 1614 565 510 1615 567 512 1616 566 511 1617 563 508 1618 565 510 1619 566 511 1620 567 512 1621 568 513 1622 569 514 1623 568 513 1624 570 515 1625 569 514 1626 566 511 1627 568 513 1628 569 514 1629 570 515 1630 571 516 1631 572 517 1632 571 516 1633 573 518 1634 572 517 1635 569 514 1636 571 516 1637 574 519 1638 573 518 1639 575 520 1640 574 519 1641 572 517 1642 573 518 1643 61 39 1644 576 521 1645 80 57 1646 577 522 1647 575 520 1648 578 523 1649 577 522 1650 574 519 1651 575 520 1652 61 39 1653 579 524 1654 576 521 1655 580 525 1656 578 523 1657 581 526 1658 580 525 1659 577 522 1660 578 523 1661 61 39 1662 582 527 1663 579 524 1664 583 528 1665 581 526 1666 584 529 1667 583 528 1668 580 525 1669 581 526 1670 585 530 1671 586 531 1672 587 532 1673 588 533 1674 584 529 1675 589 534 1676 588 533 1677 583 528 1678 584 529 1679 590 535 1680 587 532 1681 591 536 1682 592 537 1683 585 530 1684 587 532 1685 590 535 1686 592 537 1687 587 532 1688 13 11 1689 593 11 1690 14 11 1691 594 11 1692 595 538 1693 591 536 1694 590 535 1695 591 536 1696 595 538 1697 596 539 1698 597 540 1699 598 541 1700 599 542 1701 600 542 1702 601 542 1703 602 541 1704 596 539 1705 598 541 1706 603 543 1707 604 544 1708 605 544 1709 606 545 1710 607 545 1711 597 540 1712 599 542 1713 601 542 1714 608 542 1715 596 539 1716 606 545 1717 597 540 1718 609 546 1719 610 546 1720 607 545 1721 611 542 1722 608 542 1723 612 542 1724 606 545 1725 609 546 1726 607 545 1727 599 542 1728 608 542 1729 611 542 1730 613 547 1731 614 547 1732 610 546 1733 615 542 1734 612 542 1735 616 542 1736 609 546 1737 613 547 1738 610 546 1739 611 542 1740 612 542 1741 617 542 1742 615 542 1743 617 542 1744 612 542 1745 618 548 1746 619 548 1747 614 547 1748 620 542 1749 616 542 1750 621 542 1751 613 547 1752 618 548 1753 614 547 1754 622 542 1755 615 542 1756 616 542 1757 623 542 1758 622 542 1759 616 542 1760 624 542 1761 623 542 1762 616 542 1763 625 542 1764 624 542 1765 616 542 1766 620 542 1767 625 542 1768 616 542 1769 626 549 1770 627 549 1771 619 548 1772 628 542 1773 621 542 1774 629 542 1775 618 548 1776 626 549 1777 619 548 1778 630 542 1779 620 542 1780 621 542 1781 631 542 1782 630 542 1783 621 542 1784 632 542 1785 631 542 1786 621 542 1787 633 542 1788 632 542 1789 621 542 1790 628 542 1791 633 542 1792 621 542 1793 634 550 1794 635 550 1795 627 549 1796 636 542 1797 629 542 1798 637 542 1799 626 549 1800 634 550 1801 627 549 1802 638 542 1803 628 542 1804 629 542 1805 639 542 1806 638 542 1807 629 542 1808 640 542 1809 639 542 1810 629 542 1811 641 542 1812 640 542 1813 629 542 1814 642 542 1815 641 542 1816 629 542 1817 636 542 1818 642 542 1819 629 542 1820 643 551 1821 644 551 1822 635 550 1823 645 542 1824 637 542 1825 646 542 1826 634 550 1827 643 551 1828 635 550 1829 647 542 1830 636 542 1831 637 542 1832 648 542 1833 647 542 1834 637 542 1835 645 542 1836 648 542 1837 637 542 1838 649 552 1839 650 552 1840 644 551 1841 651 542 1842 646 542 1843 652 542 1844 643 551 1845 649 552 1846 644 551 1847 651 542 1848 653 542 1849 646 542 1850 654 542 1851 646 542 1852 653 542 1853 655 542 1854 645 542 1855 646 542 1856 654 542 1857 655 542 1858 646 542 1859 656 553 1860 657 553 1861 650 552 1862 658 542 1863 652 542 1864 659 542 1865 649 552 1866 656 553 1867 650 552 1868 660 542 1869 661 542 1870 652 542 1871 662 542 1872 652 542 1873 661 542 1874 663 542 1875 660 542 1876 652 542 1877 664 542 1878 663 542 1879 652 542 1880 665 542 1881 664 542 1882 652 542 1883 666 542 1884 665 542 1885 652 542 1886 667 542 1887 666 542 1888 652 542 1889 658 542 1890 667 542 1891 652 542 1892 662 542 1893 651 542 1894 652 542 1895 668 554 1896 669 554 1897 657 553 1898 670 542 1899 659 542 1900 671 542 1901 656 553 1902 668 554 1903 657 553 1904 672 542 1905 658 542 1906 659 542 1907 673 542 1908 672 542 1909 659 542 1910 674 542 1911 673 542 1912 659 542 1913 675 542 1914 674 542 1915 659 542 1916 670 542 1917 675 542 1918 659 542 1919 676 555 1920 677 555 1921 669 554 1922 678 542 1923 671 542 1924 679 542 1925 668 554 1926 676 555 1927 669 554 1928 680 542 1929 670 542 1930 671 542 1931 681 542 1932 680 542 1933 671 542 1934 682 542 1935 681 542 1936 671 542 1937 683 542 1938 682 542 1939 671 542 1940 684 542 1941 683 542 1942 671 542 1943 685 542 1944 684 542 1945 671 542 1946 686 542 1947 685 542 1948 671 542 1949 687 542 1950 686 542 1951 671 542 1952 688 542 1953 687 542 1954 671 542 1955 678 542 1956 688 542 1957 671 542 1958 689 556 1959 690 557 1960 677 555 1961 691 542 1962 679 542 1963 692 542 1964 676 555 1965 689 556 1966 677 555 1967 693 542 1968 694 542 1969 679 542 1970 678 542 1971 679 542 1972 694 542 1973 695 542 1974 693 542 1975 679 542 1976 696 542 1977 695 542 1978 679 542 1979 691 542 1980 696 542 1981 679 542 1982 697 558 1983 698 558 1984 690 557 1985 699 542 1986 692 542 1987 700 542 1988 689 556 1989 697 558 1990 690 557 1991 701 542 1992 691 542 1993 692 542 1994 702 542 1995 701 542 1996 692 542 1997 703 542 1998 702 542 1999 692 542 2000 704 542 2001 703 542 2002 692 542 2003 705 542 2004 704 542 2005 692 542 2006 699 542 2007 705 542 2008 692 542 2009 706 559 2010 707 559 2011 698 558 2012 708 542 2013 700 542 2014 709 542 2015 697 558 2016 706 559 2017 698 558 2018 710 542 2019 699 542 2020 700 542 2021 708 542 2022 710 542 2023 700 542 2024 711 560 2025 712 560 2026 707 559 2027 713 542 2028 709 542 2029 714 542 2030 706 559 2031 711 560 2032 707 559 2033 715 542 2034 716 542 2035 709 542 2036 717 542 2037 709 542 2038 716 542 2039 713 542 2040 715 542 2041 709 542 2042 718 542 2043 708 542 2044 709 542 2045 717 542 2046 718 542 2047 709 542 2048 719 561 2049 720 561 2050 712 560 2051 721 542 2052 714 542 2053 722 542 2054 711 560 2055 719 561 2056 712 560 2057 723 542 2058 724 542 2059 714 542 2060 725 542 2061 714 542 2062 724 542 2063 726 542 2064 723 542 2065 714 542 2066 727 542 2067 726 542 2068 714 542 2069 728 542 2070 727 542 2071 714 542 2072 729 542 2073 713 542 2074 714 542 2075 730 542 2076 729 542 2077 714 542 2078 725 542 2079 730 542 2080 714 542 2081 721 542 2082 728 542 2083 714 542 2084 731 562 2085 732 562 2086 720 561 2087 733 542 2088 722 542 2089 734 542 2090 719 561 2091 731 562 2092 720 561 2093 735 542 2094 721 542 2095 722 542 2096 736 542 2097 735 542 2098 722 542 2099 737 542 2100 736 542 2101 722 542 2102 738 542 2103 737 542 2104 722 542 2105 739 542 2106 738 542 2107 722 542 2108 740 542 2109 739 542 2110 722 542 2111 741 542 2112 740 542 2113 722 542 2114 733 542 2115 741 542 2116 722 542 2117 742 563 2118 743 563 2119 732 562 2120 744 542 2121 734 542 2122 745 542 2123 731 562 2124 742 563 2125 732 562 2126 746 542 2127 733 542 2128 734 542 2129 747 542 2130 746 542 2131 734 542 2132 748 542 2133 747 542 2134 734 542 2135 749 542 2136 748 542 2137 734 542 2138 744 542 2139 749 542 2140 734 542 2141 750 564 2142 751 564 2143 743 563 2144 752 542 2145 745 542 2146 753 542 2147 742 563 2148 750 564 2149 743 563 2150 754 542 2151 744 542 2152 745 542 2153 755 542 2154 754 542 2155 745 542 2156 756 542 2157 755 542 2158 745 542 2159 757 542 2160 756 542 2161 745 542 2162 752 542 2163 757 542 2164 745 542 2165 758 565 2166 759 565 2167 751 564 2168 760 542 2169 753 542 2170 761 542 2171 750 564 2172 758 565 2173 751 564 2174 762 542 2175 753 542 2176 760 542 2177 763 542 2178 753 542 2179 762 542 2180 764 542 2181 752 542 2182 753 542 2183 765 542 2184 764 542 2185 753 542 2186 766 542 2187 765 542 2188 753 542 2189 763 542 2190 766 542 2191 753 542 2192 767 566 2193 768 566 2194 759 565 2195 769 542 2196 761 542 2197 770 542 2198 758 565 2199 767 566 2200 759 565 2201 760 542 2202 761 542 2203 769 542 2204 771 567 2205 772 567 2206 768 566 2207 773 542 2208 770 542 2209 774 542 2210 767 566 2211 771 567 2212 768 566 2213 769 542 2214 770 542 2215 773 542 2216 775 568 2217 776 568 2218 772 567 2219 777 542 2220 774 542 2221 778 542 2222 771 567 2223 775 568 2224 772 567 2225 773 542 2226 774 542 2227 777 542 2228 779 569 2229 780 570 2230 781 570 2231 779 569 2232 782 571 2233 780 570 2234 783 572 2235 784 573 2236 785 574 2237 786 575 2238 787 576 2239 788 577 2240 786 575 2241 788 577 2242 789 578 2243 790 579 2244 785 574 2245 791 580 2246 792 581 2247 785 574 2248 790 579 2249 793 582 2250 785 574 2251 792 581 2252 783 572 2253 785 574 2254 793 582 2255 794 583 2256 791 580 2257 795 584 2258 790 579 2259 791 580 2260 794 583 2261 796 585 2262 795 584 2263 797 586 2264 794 583 2265 795 584 2266 796 585 2267 798 587 2268 797 586 2269 799 588 2270 796 585 2271 797 586 2272 798 587 2273 800 589 2274 799 588 2275 801 590 2276 798 587 2277 799 588 2278 800 589 2279 802 591 2280 801 590 2281 803 592 2282 800 589 2283 801 590 2284 802 591 2285 804 593 2286 803 592 2287 805 594 2288 802 591 2289 803 592 2290 804 593 2291 806 595 2292 805 594 2293 807 596 2294 804 593 2295 805 594 2296 806 595 2297 808 597 2298 807 596 2299 809 598 2300 806 595 2301 807 596 2302 808 597 2303 810 599 2304 809 598 2305 811 600 2306 808 597 2307 809 598 2308 810 599 2309 812 601 2310 811 600 2311 813 602 2312 810 599 2313 811 600 2314 812 601 2315 814 603 2316 813 602 2317 815 604 2318 812 601 2319 813 602 2320 814 603 2321 816 605 2322 815 604 2323 817 606 2324 814 603 2325 815 604 2326 816 605 2327 818 607 2328 817 606 2329 819 608 2330 816 605 2331 817 606 2332 818 607 2333 820 609 2334 819 608 2335 821 610 2336 818 607 2337 819 608 2338 820 609 2339 822 611 2340 821 610 2341 823 612 2342 820 609 2343 821 610 2344 822 611 2345 824 613 2346 823 612 2347 825 614 2348 822 611 2349 823 612 2350 824 613 2351 826 615 2352 825 614 2353 827 616 2354 824 613 2355 825 614 2356 826 615 2357 828 617 2358 827 616 2359 829 618 2360 826 615 2361 827 616 2362 828 617 2363 830 619 2364 829 618 2365 831 620 2366 828 617 2367 829 618 2368 830 619 2369 832 621 2370 831 620 2371 833 622 2372 830 619 2373 831 620 2374 832 621 2375 834 623 2376 833 622 2377 835 624 2378 832 621 2379 833 622 2380 834 623 2381 836 625 2382 835 624 2383 837 626 2384 834 623 2385 835 624 2386 836 625 2387 838 543 2388 604 544 2389 603 543 2390 839 627 2391 840 628 2392 841 629 2393 842 630 2394 836 625 2395 837 626 2396 843 631 2397 844 632 2398 845 633 2399 846 634 2400 847 635 2401 848 636 2402 849 637 2403 843 631 2404 845 633 2405 850 638 2406 849 637 2407 845 633 2408 851 11 2409 852 11 2410 853 11 2411 854 11 2412 855 11 2413 853 11 2414 856 639 2415 853 639 2416 855 639 2417 857 11 2418 851 11 2419 853 11 2420 858 11 2421 857 11 2422 853 11 2423 859 11 2424 858 11 2425 853 11 2426 860 11 2427 859 11 2428 853 11 2429 856 11 2430 860 11 2431 853 11 2432 861 640 2433 862 641 2434 844 632 2435 863 642 2436 848 636 2437 864 643 2438 865 644 2439 861 640 2440 844 632 2441 866 645 2442 865 644 2443 844 632 2444 867 646 2445 866 645 2446 844 632 2447 868 647 2448 867 646 2449 844 632 2450 843 631 2451 868 647 2452 844 632 2453 869 648 2454 848 636 2455 863 642 2456 869 648 2457 846 634 2458 848 636 2459 870 649 2460 871 650 2461 872 651 2462 873 652 2463 863 642 2464 864 643 2465 874 653 2466 875 654 2467 871 650 2468 870 649 2469 874 653 2470 871 650 2471 876 655 2472 872 651 2473 877 656 2474 876 655 2475 870 649 2476 872 651 2477 878 657 2478 877 656 2479 879 658 2480 878 657 2481 876 655 2482 877 656 2483 880 659 2484 879 658 2485 881 660 2486 880 659 2487 878 657 2488 879 658 2489 868 647 2490 882 661 2491 867 646 2492 883 662 2493 881 660 2494 884 663 2495 883 662 2496 880 659 2497 881 660 2498 868 647 2499 885 664 2500 882 661 2501 883 662 2502 884 663 2503 886 665 2504 868 647 2505 887 666 2506 885 664 2507 888 667 2508 886 665 2509 889 668 2510 888 667 2511 883 662 2512 886 665 2513 868 647 2514 890 669 2515 887 666 2516 888 667 2517 889 668 2518 891 670 2519 892 671 2520 893 672 2521 890 669 2522 894 673 2523 891 670 2524 895 674 2525 868 647 2526 892 671 2527 890 669 2528 894 673 2529 888 667 2530 891 670 2531 892 671 2532 896 675 2533 893 672 2534 894 673 2535 895 674 2536 897 676 2537 892 671 2538 898 677 2539 896 675 2540 899 678 2541 897 676 2542 900 679 2543 899 678 2544 894 673 2545 897 676 2546 892 671 2547 901 680 2548 898 677 2549 899 678 2550 900 679 2551 902 681 2552 892 671 2553 903 682 2554 901 680 2555 899 678 2556 902 681 2557 904 683 2558 892 671 2559 905 684 2560 903 682 2561 906 685 2562 904 683 2563 907 686 2564 906 685 2565 899 678 2566 904 683 2567 892 671 2568 908 687 2569 905 684 2570 906 685 2571 907 686 2572 909 688 2573 892 671 2574 910 689 2575 908 687 2576 906 685 2577 909 688 2578 911 690 2579 892 691 2580 912 691 2581 910 691 2582 906 685 2583 911 690 2584 913 692 2585 914 693 2586 915 694 2587 912 695 2588 916 696 2589 913 692 2590 917 697 2591 892 671 2592 914 693 2593 912 695 2594 916 696 2595 906 685 2596 913 692 2597 914 693 2598 918 698 2599 915 694 2600 916 696 2601 917 697 2602 919 699 2603 914 693 2604 920 700 2605 918 698 2606 916 696 2607 919 699 2608 921 701 2609 914 693 2610 922 702 2611 920 700 2612 916 696 2613 921 701 2614 923 703 2615 914 693 2616 924 704 2617 922 702 2618 925 705 2619 923 703 2620 926 706 2621 925 705 2622 916 696 2623 923 703 2624 914 693 2625 927 707 2626 924 704 2627 925 705 2628 926 706 2629 928 708 2630 914 693 2631 929 709 2632 927 707 2633 925 705 2634 928 708 2635 930 710 2636 914 693 2637 931 711 2638 929 709 2639 925 705 2640 930 710 2641 932 712 2642 914 693 2643 933 713 2644 931 711 2645 934 714 2646 932 712 2647 935 715 2648 934 714 2649 925 705 2650 932 712 2651 914 693 2652 936 716 2653 933 713 2654 934 714 2655 935 715 2656 937 717 2657 914 693 2658 938 718 2659 936 716 2660 934 714 2661 937 717 2662 939 719 2663 914 693 2664 940 720 2665 938 718 2666 934 714 2667 939 719 2668 941 721 2669 914 693 2670 942 722 2671 940 720 2672 934 714 2673 941 721 2674 943 723 2675 944 724 2676 945 725 2677 942 722 2678 946 726 2679 947 727 2680 948 728 2681 914 693 2682 944 724 2683 942 722 2684 934 714 2685 943 723 2686 949 729 2687 944 724 2688 950 730 2689 945 725 2690 946 726 2691 948 728 2692 951 731 2693 944 724 2694 952 732 2695 950 730 2696 946 726 2697 951 731 2698 953 733 2699 944 724 2700 954 734 2701 952 732 2702 946 726 2703 953 733 2704 955 735 2705 944 724 2706 956 736 2707 954 734 2708 957 737 2709 955 735 2710 958 738 2711 957 737 2712 946 726 2713 955 735 2714 944 724 2715 959 739 2716 956 736 2717 957 737 2718 958 738 2719 960 740 2720 944 724 2721 961 741 2722 959 739 2723 957 737 2724 960 740 2725 962 742 2726 944 724 2727 963 743 2728 961 741 2729 957 737 2730 962 742 2731 964 744 2732 944 724 2733 965 745 2734 963 743 2735 966 746 2736 964 744 2737 967 747 2738 966 746 2739 957 737 2740 964 744 2741 944 724 2742 968 748 2743 965 745 2744 966 746 2745 967 747 2746 969 749 2747 944 724 2748 970 750 2749 968 748 2750 966 746 2751 969 749 2752 971 751 2753 944 724 2754 972 752 2755 970 750 2756 966 746 2757 971 751 2758 973 753 2759 944 724 2760 974 754 2761 972 752 2762 975 755 2763 973 753 2764 976 756 2765 975 755 2766 966 746 2767 973 753 2768 944 757 2769 977 757 2770 974 757 2771 975 755 2772 976 756 2773 978 758 2774 979 759 2775 980 760 2776 977 761 2777 975 755 2778 978 758 2779 981 762 2780 944 724 2781 979 759 2782 977 761 2783 979 759 2784 982 763 2785 980 760 2786 975 755 2787 981 762 2788 983 764 2789 979 759 2790 984 765 2791 982 763 2792 985 766 2793 983 764 2794 986 767 2795 985 766 2796 975 755 2797 983 764 2798 979 759 2799 987 768 2800 984 765 2801 985 766 2802 986 767 2803 988 769 2804 979 759 2805 989 770 2806 987 768 2807 985 766 2808 988 769 2809 990 771 2810 979 759 2811 991 772 2812 989 770 2813 992 773 2814 990 771 2815 993 774 2816 992 773 2817 985 766 2818 990 771 2819 979 759 2820 994 775 2821 991 772 2822 992 773 2823 993 774 2824 995 776 2825 979 759 2826 996 777 2827 994 775 2828 997 778 2829 995 776 2830 998 779 2831 997 778 2832 992 773 2833 995 776 2834 979 759 2835 999 780 2836 996 777 2837 997 778 2838 998 779 2839 1000 781 2840 979 759 2841 1001 782 2842 999 780 2843 1002 783 2844 1000 781 2845 1003 784 2846 1002 783 2847 997 778 2848 1000 781 2849 979 759 2850 1004 785 2851 1001 782 2852 1002 783 2853 1003 784 2854 1005 786 2855 979 759 2856 1006 787 2857 1004 785 2858 1007 788 2859 1005 786 2860 1008 789 2861 1007 788 2862 1002 783 2863 1005 786 2864 979 759 2865 1009 790 2866 1006 787 2867 1010 791 2868 1008 789 2869 1011 792 2870 1010 791 2871 1007 788 2872 1008 789 2873 1012 793 2874 1013 794 2875 1009 790 2876 1014 795 2877 1011 792 2878 1015 796 2879 979 759 2880 1012 793 2881 1009 790 2882 1014 795 2883 1010 791 2884 1011 792 2885 1012 793 2886 1016 797 2887 1013 794 2888 1017 798 2889 1015 796 2890 1018 799 2891 1017 798 2892 1014 795 2893 1015 796 2894 1012 793 2895 1019 800 2896 1016 797 2897 1020 801 2898 1018 799 2899 1021 802 2900 1020 801 2901 1017 798 2902 1018 799 2903 1022 803 2904 1023 804 2905 1024 805 2906 1022 803 2907 1025 806 2908 1023 804 2909 1026 807 2910 1021 802 2911 1027 808 2912 1026 807 2913 1020 801 2914 1021 802 2915 1028 809 2916 1029 810 2917 1012 793 2918 1030 811 2919 1024 805 2920 1031 812 2921 1032 813 2922 1028 809 2923 1012 793 2924 979 759 2925 1032 813 2926 1012 793 2927 1030 811 2928 1022 803 2929 1024 805 2930 1033 814 2931 1034 815 2932 1029 810 2933 1035 816 2934 1031 812 2935 1036 817 2936 1037 818 2937 1033 814 2938 1029 810 2939 1028 809 2940 1037 818 2941 1029 810 2942 1035 816 2943 1030 811 2944 1031 812 2945 1038 819 2946 1039 820 2947 1034 815 2948 1035 816 2949 1036 817 2950 1040 821 2951 1033 814 2952 1038 819 2953 1034 815 2954 1041 822 2955 1042 823 2956 1039 820 2957 1043 824 2958 1040 821 2959 1044 825 2960 1045 826 2961 1041 822 2962 1039 820 2963 1038 819 2964 1045 826 2965 1039 820 2966 1043 824 2967 1035 816 2968 1040 821 2969 1046 827 2970 1047 828 2971 1042 823 2972 1048 829 2973 1044 825 2974 1049 830 2975 1050 831 2976 1046 827 2977 1042 823 2978 1041 822 2979 1050 831 2980 1042 823 2981 1048 829 2982 1043 824 2983 1044 825 2984 1051 832 2985 1052 833 2986 1047 828 2987 1053 834 2988 1049 830 2989 1054 835 2990 1055 836 2991 1051 832 2992 1047 828 2993 1056 837 2994 1055 836 2995 1047 828 2996 1057 838 2997 1056 837 2998 1047 828 2999 1058 839 3000 1057 838 3001 1047 828 3002 1046 827 3003 1058 839 3004 1047 828 3005 1053 834 3006 1048 829 3007 1049 830 3008 1059 840 3009 1060 841 3010 1061 842 3011 1062 843 3012 1053 834 3013 1054 835 3014 1063 844 3015 1064 845 3016 1060 841 3017 1059 840 3018 1063 844 3019 1060 841 3020 1065 846 3021 1061 842 3022 1066 847 3023 1065 846 3024 1059 840 3025 1061 842 3026 1067 848 3027 1066 847 3028 1068 849 3029 1067 848 3030 1065 846 3031 1066 847 3032 1069 850 3033 1068 849 3034 1070 851 3035 1069 850 3036 1067 848 3037 1068 849 3038 1058 839 3039 1071 852 3040 1057 838 3041 1072 853 3042 1070 851 3043 1073 854 3044 1072 853 3045 1069 850 3046 1070 851 3047 1058 839 3048 1074 855 3049 1071 852 3050 1072 853 3051 1073 854 3052 1075 856 3053 1058 839 3054 1076 857 3055 1074 855 3056 1077 858 3057 1075 856 3058 1078 859 3059 1077 858 3060 1072 853 3061 1075 856 3062 1058 839 3063 1079 860 3064 1076 857 3065 1077 858 3066 1078 859 3067 1080 861 3068 1081 862 3069 1082 863 3070 1079 860 3071 1083 864 3072 1080 861 3073 1084 865 3074 1058 839 3075 1081 862 3076 1079 860 3077 1083 864 3078 1077 858 3079 1080 861 3080 1081 862 3081 1085 866 3082 1082 863 3083 1083 864 3084 1084 865 3085 1086 867 3086 1081 862 3087 1087 868 3088 1085 866 3089 1088 869 3090 1086 867 3091 1089 870 3092 1088 869 3093 1083 864 3094 1086 867 3095 1081 862 3096 1090 871 3097 1087 868 3098 1088 869 3099 1089 870 3100 1091 872 3101 1081 862 3102 1092 873 3103 1090 871 3104 1088 869 3105 1091 872 3106 1093 874 3107 1081 862 3108 1094 875 3109 1092 873 3110 1095 876 3111 1093 874 3112 1096 877 3113 1095 876 3114 1088 869 3115 1093 874 3116 1081 862 3117 1097 878 3118 1094 875 3119 1095 876 3120 1096 877 3121 1098 879 3122 1081 862 3123 1099 880 3124 1097 878 3125 1095 876 3126 1098 879 3127 1100 881 3128 1081 882 3129 1101 882 3130 1099 882 3131 1095 876 3132 1100 881 3133 1102 883 3134 1103 884 3135 1104 885 3136 1101 886 3137 1105 887 3138 1102 883 3139 1106 888 3140 1081 862 3141 1103 884 3142 1101 886 3143 1105 887 3144 1095 876 3145 1102 883 3146 1103 884 3147 1107 889 3148 1104 885 3149 1105 887 3150 1106 888 3151 1108 890 3152 1103 884 3153 1109 891 3154 1107 889 3155 1105 887 3156 1108 890 3157 1110 892 3158 1103 884 3159 1111 893 3160 1109 891 3161 1105 887 3162 1110 892 3163 1112 894 3164 1103 884 3165 1113 895 3166 1111 893 3167 1114 896 3168 1112 894 3169 1115 897 3170 1114 896 3171 1105 887 3172 1112 894 3173 1103 884 3174 1116 898 3175 1113 895 3176 1114 896 3177 1115 897 3178 1117 899 3179 1103 884 3180 1118 900 3181 1116 898 3182 1114 896 3183 1117 899 3184 1119 901 3185 1103 884 3186 1120 902 3187 1118 900 3188 1114 896 3189 1119 901 3190 1121 903 3191 1103 884 3192 1122 904 3193 1120 902 3194 1123 905 3195 1121 903 3196 1124 906 3197 1123 905 3198 1114 896 3199 1121 903 3200 1103 884 3201 1125 907 3202 1122 904 3203 1123 905 3204 1124 906 3205 1126 908 3206 1103 884 3207 1127 909 3208 1125 907 3209 1123 905 3210 1126 908 3211 1128 910 3212 1103 884 3213 1129 911 3214 1127 909 3215 1123 905 3216 1128 910 3217 1130 912 3218 1103 884 3219 1131 913 3220 1129 911 3221 1123 905 3222 1130 912 3223 1132 914 3224 1133 915 3225 1134 916 3226 1131 913 3227 1135 917 3228 1136 918 3229 1137 919 3230 1103 884 3231 1133 915 3232 1131 913 3233 1123 905 3234 1132 914 3235 1138 920 3236 1133 915 3237 1139 921 3238 1134 916 3239 1135 917 3240 1137 919 3241 1140 922 3242 1133 915 3243 1141 923 3244 1139 921 3245 1135 917 3246 1140 922 3247 1142 924 3248 1133 915 3249 1143 925 3250 1141 923 3251 1135 917 3252 1142 924 3253 1144 926 3254 1133 915 3255 1145 927 3256 1143 925 3257 1146 928 3258 1144 926 3259 1147 929 3260 1146 928 3261 1135 917 3262 1144 926 3263 1133 915 3264 1148 930 3265 1145 927 3266 1146 928 3267 1147 929 3268 1149 931 3269 1133 915 3270 1150 932 3271 1148 930 3272 1146 928 3273 1149 931 3274 1151 933 3275 1133 915 3276 1152 934 3277 1150 932 3278 1146 928 3279 1151 933 3280 1153 935 3281 1133 915 3282 1154 936 3283 1152 934 3284 1155 937 3285 1153 935 3286 1156 938 3287 1155 937 3288 1146 928 3289 1153 935 3290 1133 915 3291 1157 939 3292 1154 936 3293 1155 937 3294 1156 938 3295 1158 940 3296 1133 915 3297 1159 941 3298 1157 939 3299 1155 937 3300 1158 940 3301 1160 942 3302 1133 915 3303 1161 943 3304 1159 941 3305 1155 937 3306 1160 942 3307 1162 944 3308 1133 915 3309 1163 945 3310 1161 943 3311 1164 946 3312 1162 944 3313 1165 947 3314 1164 946 3315 1155 937 3316 1162 944 3317 1133 948 3318 1166 948 3319 1163 948 3320 1164 946 3321 1165 947 3322 1167 949 3323 1168 950 3324 1169 951 3325 1166 952 3326 1164 946 3327 1167 949 3328 1170 953 3329 1133 915 3330 1168 950 3331 1166 952 3332 1168 950 3333 1171 954 3334 1169 951 3335 1164 946 3336 1170 953 3337 1172 955 3338 1168 950 3339 1173 956 3340 1171 954 3341 1174 957 3342 1172 955 3343 1175 958 3344 1174 957 3345 1164 946 3346 1172 955 3347 1168 950 3348 1176 959 3349 1173 956 3350 1174 957 3351 1175 958 3352 1177 960 3353 1168 950 3354 1178 961 3355 1176 959 3356 1174 957 3357 1177 960 3358 1179 962 3359 1168 950 3360 1180 963 3361 1178 961 3362 1181 964 3363 1179 962 3364 1182 965 3365 1181 964 3366 1174 957 3367 1179 962 3368 1168 950 3369 1183 966 3370 1180 963 3371 1181 964 3372 1182 965 3373 1184 967 3374 1168 950 3375 1185 968 3376 1183 966 3377 1186 969 3378 1184 967 3379 1187 970 3380 1186 969 3381 1181 964 3382 1184 967 3383 1168 950 3384 1188 971 3385 1185 968 3386 1186 969 3387 1187 970 3388 1189 972 3389 1168 950 3390 1190 973 3391 1188 971 3392 1191 974 3393 1189 972 3394 1192 975 3395 1191 974 3396 1186 969 3397 1189 972 3398 1168 950 3399 1193 976 3400 1190 973 3401 1191 974 3402 1192 975 3403 1194 977 3404 1168 950 3405 1195 978 3406 1193 976 3407 1196 979 3408 1194 977 3409 1197 980 3410 1196 979 3411 1191 974 3412 1194 977 3413 1168 950 3414 1198 981 3415 1195 978 3416 1199 982 3417 1197 980 3418 1200 983 3419 1199 982 3420 1196 979 3421 1197 980 3422 1201 984 3423 1202 985 3424 1198 981 3425 1203 986 3426 1200 983 3427 1204 987 3428 1168 950 3429 1201 984 3430 1198 981 3431 1203 986 3432 1199 982 3433 1200 983 3434 1201 984 3435 1205 988 3436 1202 985 3437 1206 989 3438 1204 987 3439 1207 990 3440 1206 989 3441 1203 986 3442 1204 987 3443 1201 984 3444 1208 991 3445 1205 988 3446 1209 992 3447 1207 990 3448 1210 993 3449 1209 992 3450 1206 989 3451 1207 990 3452 1211 994 3453 1212 995 3454 1213 996 3455 1211 994 3456 1214 997 3457 1212 995 3458 1215 998 3459 1210 993 3460 1216 999 3461 1215 998 3462 1209 992 3463 1210 993 3464 1217 1000 3465 1218 1001 3466 1201 984 3467 1219 1002 3468 1213 996 3469 1220 1003 3470 1221 1004 3471 1217 1000 3472 1201 984 3473 1168 950 3474 1221 1004 3475 1201 984 3476 1219 1002 3477 1211 994 3478 1213 996 3479 1222 1005 3480 1223 1006 3481 1218 1001 3482 1224 1007 3483 1220 1003 3484 1225 1008 3485 1226 1009 3486 1222 1005 3487 1218 1001 3488 1217 1000 3489 1226 1009 3490 1218 1001 3491 1224 1007 3492 1219 1002 3493 1220 1003 3494 1227 1010 3495 1228 1011 3496 1223 1006 3497 1224 1007 3498 1225 1008 3499 1229 1012 3500 1222 1005 3501 1227 1010 3502 1223 1006 3503 1230 1013 3504 1231 1014 3505 1228 1011 3506 1232 1015 3507 1229 1012 3508 1233 1016 3509 1234 1017 3510 1230 1013 3511 1228 1011 3512 1227 1010 3513 1234 1017 3514 1228 1011 3515 1232 1015 3516 1224 1007 3517 1229 1012 3518 1235 1018 3519 1236 1019 3520 1231 1014 3521 1237 1020 3522 1233 1016 3523 1238 1021 3524 1239 1022 3525 1235 1018 3526 1231 1014 3527 1230 1013 3528 1239 1022 3529 1231 1014 3530 1237 1020 3531 1232 1015 3532 1233 1016 3533 1240 1023 3534 1241 1024 3535 1236 1019 3536 1242 1025 3537 1238 1021 3538 1243 1026 3539 1244 1027 3540 1240 1023 3541 1236 1019 3542 1245 1028 3543 1244 1027 3544 1236 1019 3545 1246 1029 3546 1245 1028 3547 1236 1019 3548 1247 1030 3549 1246 1029 3550 1236 1019 3551 1235 1018 3552 1247 1030 3553 1236 1019 3554 1242 1025 3555 1237 1020 3556 1238 1021 3557 1248 1031 3558 1249 1032 3559 1250 1033 3560 1251 1034 3561 1242 1025 3562 1243 1026 3563 1252 1035 3564 1253 1036 3565 1249 1032 3566 1248 1031 3567 1252 1035 3568 1249 1032 3569 1254 1037 3570 1250 1033 3571 1255 1038 3572 1254 1037 3573 1248 1031 3574 1250 1033 3575 1256 1039 3576 1255 1038 3577 1257 1040 3578 1256 1039 3579 1254 1037 3580 1255 1038 3581 1258 1041 3582 1257 1040 3583 1259 1042 3584 1258 1041 3585 1256 1039 3586 1257 1040 3587 1247 1030 3588 1260 1043 3589 1246 1029 3590 1261 1044 3591 1259 1042 3592 1262 1045 3593 1261 1044 3594 1258 1041 3595 1259 1042 3596 1247 1030 3597 1263 1046 3598 1260 1043 3599 1261 1044 3600 1262 1045 3601 1264 1047 3602 1247 1030 3603 1265 1048 3604 1263 1046 3605 1266 1049 3606 1264 1047 3607 1267 1050 3608 1266 1049 3609 1261 1044 3610 1264 1047 3611 1247 1030 3612 1268 1051 3613 1265 1048 3614 1266 1049 3615 1267 1050 3616 1269 1052 3617 291 238 3618 1270 1053 3619 1268 1051 3620 1271 1054 3621 1269 1052 3622 1272 1055 3623 1247 1030 3624 291 238 3625 1268 1051 3626 1271 1054 3627 1266 1049 3628 1269 1052 3629 291 238 3630 1273 1056 3631 1270 1053 3632 1271 1054 3633 1272 1055 3634 1274 1057 3635 291 238 3636 1275 1058 3637 1273 1056 3638 1276 1059 3639 1274 1057 3640 1277 1060 3641 1276 1059 3642 1271 1054 3643 1274 1057 3644 291 238 3645 1278 1061 3646 1275 1058 3647 1276 1059 3648 1277 1060 3649 1279 1062 3650 291 238 3651 1280 1063 3652 1278 1061 3653 1276 1059 3654 1279 1062 3655 1281 1064 3656 291 238 3657 1282 1065 3658 1280 1063 3659 1283 1066 3660 1281 1064 3661 1284 1067 3662 1283 1066 3663 1276 1059 3664 1281 1064 3665 291 238 3666 1285 1068 3667 1282 1065 3668 1283 1066 3669 1284 1067 3670 1286 1069 3671 291 238 3672 1287 1070 3673 1285 1068 3674 1283 1066 3675 1286 1069 3676 1288 1071 3677 291 1072 3678 290 1072 3679 1287 1072 3680 1283 1066 3681 1288 1071 3682 1289 1073 3683 1290 1074 3684 1289 1073 3685 1291 1075 3686 1290 1074 3687 1283 1066 3688 1289 1073 3689 1290 1074 3690 1291 1075 3691 1292 1076 3692 1290 1074 3693 1292 1076 3694 1293 1077 3695 1290 1074 3696 1293 1077 3697 1294 1078 3698 1295 1079 3699 1294 1078 3700 1296 1080 3701 1295 1079 3702 1290 1074 3703 1294 1078 3704 1295 1079 3705 1296 1080 3706 1297 1081 3707 1295 1079 3708 1297 1081 3709 1298 1082 3710 1295 1079 3711 1298 1082 3712 1299 1083 3713 307 252 3714 1299 1083 3715 1300 1084 3716 307 252 3717 1295 1079 3718 1299 1083 3719 307 252 3720 1300 1084 3721 1301 1085 3722 307 252 3723 1301 1085 3724 1302 1086 3725 307 252 3726 1302 1086 3727 308 253 3728 1303 31 3729 303 31 3730 1304 31 3731 1303 1087 3732 302 1087 3733 303 1087 3734 1303 31 3735 1304 31 3736 1305 31 3737 1306 31 3738 1305 31 3739 1307 31 3740 1306 31 3741 1303 31 3742 1305 31 3743 1306 31 3744 1307 31 3745 1308 31 3746 1309 31 3747 1308 31 3748 1310 31 3749 1309 31 3750 1306 31 3751 1308 31 3752 1309 31 3753 1310 31 3754 1311 31 3755 1312 31 3756 1311 31 3757 1313 31 3758 1312 31 3759 1309 31 3760 1311 31 3761 1312 31 3762 1313 31 3763 1314 31 3764 1315 31 3765 1314 31 3766 1316 31 3767 1315 1088 3768 1312 1088 3769 1314 1088 3770 1315 1089 3771 1316 1089 3772 1317 1089 3773 1318 180 3774 1317 180 3775 1319 180 3776 1318 1090 3777 1315 1090 3778 1317 1090 3779 1318 31 3780 1319 31 3781 1320 31 3782 1321 155 3783 1320 155 3784 1322 155 3785 1321 31 3786 1318 31 3787 1320 31 3788 1323 31 3789 1322 31 3790 1324 31 3791 1323 31 3792 1321 31 3793 1322 31 3794 1325 31 3795 1324 31 3796 1326 31 3797 1325 1091 3798 1323 1091 3799 1324 1091 3800 1327 1092 3801 1326 1092 3802 1328 1092 3803 1327 1093 3804 1325 1093 3805 1326 1093 3806 1329 31 3807 1328 31 3808 1330 31 3809 1331 31 3810 1328 31 3811 1329 31 3812 1327 1094 3813 1328 1094 3814 1331 1094 3815 1332 31 3816 1330 31 3817 1333 31 3818 1329 31 3819 1330 31 3820 1332 31 3821 1334 31 3822 1333 31 3823 1335 31 3824 1332 31 3825 1333 31 3826 1334 31 3827 1336 31 3828 1335 31 3829 1337 31 3830 1334 31 3831 1335 31 3832 1336 31 3833 1338 31 3834 1331 31 3835 1339 31 3836 1338 1095 3837 1327 1095 3838 1331 1095 3839 1340 31 3840 1339 31 3841 1341 31 3842 1340 31 3843 1338 31 3844 1339 31 3845 1342 60 3846 1341 60 3847 1343 60 3848 1342 31 3849 1340 31 3850 1341 31 3851 1342 31 3852 1343 31 3853 1344 31 3854 1345 41 3855 1344 41 3856 1346 41 3857 1345 1096 3858 1342 1096 3859 1344 1096 3860 1345 31 3861 1346 31 3862 1347 31 3863 850 638 3864 1348 1097 3865 849 637 3866 1349 31 3867 1347 31 3868 1350 31 3869 1349 31 3870 1345 31 3871 1347 31 3872 1351 1098 3873 1352 1099 3874 1348 1097 3875 1349 31 3876 1350 31 3877 1353 31 3878 850 638 3879 1351 1098 3880 1348 1097 3881 1354 1100 3882 1355 1101 3883 1352 1099 3884 1356 31 3885 1353 31 3886 1357 31 3887 1351 1098 3888 1354 1100 3889 1352 1099 3890 1356 31 3891 1349 31 3892 1353 31 3893 1354 1100 3894 1358 1102 3895 1355 1101 3896 1356 31 3897 1357 31 3898 1359 31 3899 1360 1103 3900 1361 1104 3901 1358 1102 3902 1362 31 3903 1359 31 3904 1363 31 3905 1354 1100 3906 1360 1103 3907 1358 1102 3908 1362 31 3909 1356 31 3910 1359 31 3911 1364 1105 3912 1365 1106 3913 1361 1104 3914 1362 1107 3915 1363 1107 3916 1366 1107 3917 1360 1103 3918 1364 1105 3919 1361 1104 3920 1364 1105 3921 1367 1108 3922 1365 1106 3923 1368 31 3924 1366 31 3925 1369 31 3926 1368 1109 3927 1362 1109 3928 1366 1109 3929 37 30 3930 1370 1110 3931 1367 1108 3932 1368 31 3933 1369 31 3934 1371 31 3935 1364 1105 3936 37 30 3937 1367 1108 3938 37 30 3939 34 27 3940 1370 1110 3941 41 31 3942 1371 31 3943 42 31 3944 41 31 3945 1368 31 3946 1371 31 3947 1372 11 3948 21 11 3949 852 11 3950 1373 11 3951 21 11 3952 1372 11 3953 1374 11 3954 21 11 3955 1373 11 3956 1375 11 3957 1376 11 3958 21 11 3959 1377 11 3960 21 11 3961 1376 11 3962 1374 11 3963 1375 11 3964 21 11 3965 1378 11 3966 21 11 3967 1377 11 3968 1379 11 3969 21 11 3970 1378 11 3971 1380 11 3972 21 11 3973 1379 11 3974 1381 11 3975 21 11 3976 1380 11 3977 20 11 3978 21 11 3979 1381 11 3980 1382 11 3981 1372 11 3982 852 11 3983 1383 11 3984 1382 11 3985 852 11 3986 1384 11 3987 1383 11 3988 852 11 3989 1385 1111 3990 1384 1111 3991 852 1111 3992 1386 11 3993 1385 11 3994 852 11 3995 1387 1112 3996 1386 1112 3997 852 1112 3998 1388 11 3999 1387 11 4000 852 11 4001 851 11 4002 1388 11 4003 852 11 4004 1389 1113 4005 1390 1113 4006 782 571 4007 779 569 4008 1389 1113 4009 782 571 4010 1391 1114 4011 1392 1114 4012 1390 1113 4013 1389 1113 4014 1391 1114 4015 1390 1113 4016 1393 1115 4017 1394 1115 4018 1392 1114 4019 1391 1114 4020 1393 1115 4021 1392 1114 4022 1395 1116 4023 1396 1116 4024 1394 1115 4025 1393 1115 4026 1395 1116 4027 1394 1115 4028 1397 1117 4029 1398 1117 4030 1396 1116 4031 1399 542 4032 762 542 4033 1400 542 4034 1395 1116 4035 1397 1117 4036 1396 1116 4037 1401 542 4038 763 542 4039 762 542 4040 1402 542 4041 1401 542 4042 762 542 4043 1399 542 4044 1402 542 4045 762 542 4046 1403 1118 4047 1404 1118 4048 1398 1117 4049 1405 542 4050 1400 542 4051 1406 542 4052 1397 1117 4053 1403 1118 4054 1398 1117 4055 1407 542 4056 1399 542 4057 1400 542 4058 1408 542 4059 1407 542 4060 1400 542 4061 1409 542 4062 1408 542 4063 1400 542 4064 1410 542 4065 1409 542 4066 1400 542 4067 1411 542 4068 1410 542 4069 1400 542 4070 1405 542 4071 1411 542 4072 1400 542 4073 1412 1119 4074 1413 1119 4075 1404 1118 4076 1414 542 4077 1406 542 4078 1415 542 4079 1403 1118 4080 1412 1119 4081 1404 1118 4082 1416 542 4083 1405 542 4084 1406 542 4085 1417 542 4086 1416 542 4087 1406 542 4088 1414 542 4089 1417 542 4090 1406 542 4091 1418 1120 4092 1419 1120 4093 1413 1119 4094 1420 542 4095 1415 542 4096 1421 542 4097 1412 1119 4098 1418 1120 4099 1413 1119 4100 1420 542 4101 1422 542 4102 1415 542 4103 1423 542 4104 1415 542 4105 1422 542 4106 1424 542 4107 1414 542 4108 1415 542 4109 1423 542 4110 1424 542 4111 1415 542 4112 1425 1121 4113 1426 1121 4114 1419 1120 4115 1427 542 4116 1421 542 4117 1428 542 4118 1418 1120 4119 1425 1121 4120 1419 1120 4121 1429 542 4122 1430 542 4123 1421 542 4124 1431 542 4125 1421 542 4126 1430 542 4127 1432 542 4128 1429 542 4129 1421 542 4130 1433 542 4131 1432 542 4132 1421 542 4133 1434 542 4134 1433 542 4135 1421 542 4136 1435 542 4137 1434 542 4138 1421 542 4139 1436 542 4140 1435 542 4141 1421 542 4142 1427 542 4143 1436 542 4144 1421 542 4145 1431 542 4146 1420 542 4147 1421 542 4148 1437 1122 4149 1438 1122 4150 1426 1121 4151 1439 542 4152 1428 542 4153 1440 542 4154 1425 1121 4155 1437 1122 4156 1426 1121 4157 1441 542 4158 1428 542 4159 1439 542 4160 1442 542 4161 1427 542 4162 1428 542 4163 1443 542 4164 1442 542 4165 1428 542 4166 1444 542 4167 1443 542 4168 1428 542 4169 1441 542 4170 1444 542 4171 1428 542 4172 1445 1123 4173 1446 1123 4174 1438 1122 4175 1447 542 4176 1440 542 4177 1448 542 4178 1437 1122 4179 1445 1123 4180 1438 1122 4181 1449 542 4182 1439 542 4183 1440 542 4184 1450 542 4185 1449 542 4186 1440 542 4187 1451 542 4188 1450 542 4189 1440 542 4190 1452 542 4191 1451 542 4192 1440 542 4193 1453 542 4194 1452 542 4195 1440 542 4196 1454 542 4197 1453 542 4198 1440 542 4199 1455 542 4200 1454 542 4201 1440 542 4202 1456 542 4203 1455 542 4204 1440 542 4205 1457 542 4206 1456 542 4207 1440 542 4208 1447 542 4209 1457 542 4210 1440 542 4211 1458 1124 4212 1459 1125 4213 1446 1123 4214 1460 542 4215 1448 542 4216 1461 542 4217 1445 1123 4218 1458 1124 4219 1446 1123 4220 1462 542 4221 1447 542 4222 1448 542 4223 1460 542 4224 1462 542 4225 1448 542 4226 1463 1126 4227 1464 1126 4228 1459 1125 4229 1465 542 4230 1461 542 4231 1466 542 4232 1458 1124 4233 1463 1126 4234 1459 1125 4235 1467 542 4236 1460 542 4237 1461 542 4238 1465 542 4239 1467 542 4240 1461 542 4241 1468 1127 4242 1469 1127 4243 1464 1126 4244 1470 542 4245 1466 542 4246 1471 542 4247 1463 1126 4248 1468 1127 4249 1464 1126 4250 1472 542 4251 1465 542 4252 1466 542 4253 1470 542 4254 1472 542 4255 1466 542 4256 1473 1128 4257 1474 1128 4258 1469 1127 4259 1475 542 4260 1471 542 4261 1476 542 4262 1468 1127 4263 1473 1128 4264 1469 1127 4265 1477 542 4266 1478 542 4267 1471 542 4268 1479 542 4269 1471 542 4270 1478 542 4271 1475 542 4272 1477 542 4273 1471 542 4274 1480 542 4275 1470 542 4276 1471 542 4277 1479 542 4278 1480 542 4279 1471 542 4280 1481 1129 4281 1482 1129 4282 1474 1128 4283 1483 542 4284 1476 542 4285 1484 542 4286 1473 1128 4287 1481 1129 4288 1474 1128 4289 1485 542 4290 1486 542 4291 1476 542 4292 1487 542 4293 1476 542 4294 1486 542 4295 1488 542 4296 1485 542 4297 1476 542 4298 1489 542 4299 1488 542 4300 1476 542 4301 1490 542 4302 1489 542 4303 1476 542 4304 1491 542 4305 1475 542 4306 1476 542 4307 1492 542 4308 1491 542 4309 1476 542 4310 1487 542 4311 1492 542 4312 1476 542 4313 1483 542 4314 1490 542 4315 1476 542 4316 1493 1130 4317 1494 1130 4318 1482 1129 4319 1495 542 4320 1484 542 4321 1496 542 4322 1481 1129 4323 1493 1130 4324 1482 1129 4325 1497 542 4326 1483 542 4327 1484 542 4328 1498 542 4329 1497 542 4330 1484 542 4331 1499 542 4332 1498 542 4333 1484 542 4334 1500 542 4335 1499 542 4336 1484 542 4337 1501 542 4338 1500 542 4339 1484 542 4340 1502 542 4341 1501 542 4342 1484 542 4343 1503 542 4344 1502 542 4345 1484 542 4346 1495 542 4347 1503 542 4348 1484 542 4349 1504 1131 4350 1505 1131 4351 1494 1130 4352 1506 542 4353 1496 542 4354 1507 542 4355 1493 1130 4356 1504 1131 4357 1494 1130 4358 1506 542 4359 1508 542 4360 1496 542 4361 1509 542 4362 1496 542 4363 1508 542 4364 1510 542 4365 1495 542 4366 1496 542 4367 1511 542 4368 1510 542 4369 1496 542 4370 1512 542 4371 1511 542 4372 1496 542 4373 1509 542 4374 1512 542 4375 1496 542 4376 1513 1132 4377 1514 1132 4378 1505 1131 4379 1515 542 4380 1507 542 4381 1516 542 4382 1504 1131 4383 1513 1132 4384 1505 1131 4385 1517 542 4386 1506 542 4387 1507 542 4388 1518 542 4389 1517 542 4390 1507 542 4391 1519 542 4392 1518 542 4393 1507 542 4394 1520 542 4395 1519 542 4396 1507 542 4397 1521 542 4398 1520 542 4399 1507 542 4400 1522 542 4401 1521 542 4402 1507 542 4403 1515 542 4404 1522 542 4405 1507 542 4406 1523 1133 4407 1524 1133 4408 1514 1132 4409 1525 542 4410 1516 542 4411 617 542 4412 1513 1132 4413 1523 1133 4414 1514 1132 4415 1526 542 4416 1527 542 4417 1516 542 4418 1528 542 4419 1516 542 4420 1527 542 4421 1529 542 4422 1526 542 4423 1516 542 4424 1530 542 4425 1529 542 4426 1516 542 4427 1531 542 4428 1530 542 4429 1516 542 4430 1525 542 4431 1531 542 4432 1516 542 4433 1528 542 4434 1515 542 4435 1516 542 4436 1532 1134 4437 1533 1134 4438 1524 1133 4439 1523 1133 4440 1532 1134 4441 1524 1133 4442 1534 542 4443 617 542 4444 615 542 4445 1535 542 4446 1525 542 4447 617 542 4448 1536 542 4449 1535 542 4450 617 542 4451 1534 542 4452 1536 542 4453 617 542 4454 838 543 4455 603 543 4456 1533 1134 4457 1532 1134 4458 838 543 4459 1533 1134 4460 1537 1135 4461 841 629 4462 1538 1136 4463 839 627 4464 841 629 4465 1539 1137 4466 1540 1138 4467 1539 1137 4468 841 629 4469 1540 1138 4470 841 629 4471 1537 1135 4472 1541 1139 4473 1538 1136 4474 1542 1140 4475 1537 1135 4476 1538 1136 4477 1541 1139 4478 1543 1141 4479 1542 1140 4480 1544 1142 4481 1541 1139 4482 1542 1140 4483 1543 1141 4484 1545 1143 4485 1544 1142 4486 1546 1144 4487 1543 1141 4488 1544 1142 4489 1545 1143 4490 1547 1145 4491 1546 1144 4492 1548 1146 4493 1545 1143 4494 1546 1144 4495 1547 1145 4496 1549 1147 4497 1548 1146 4498 1550 1148 4499 1547 1145 4500 1548 1146 4501 1549 1147 4502 1551 1149 4503 1550 1148 4504 1552 1150 4505 1549 1147 4506 1550 1148 4507 1551 1149 4508 1553 1151 4509 1552 1150 4510 1554 1152 4511 1551 1149 4512 1552 1150 4513 1553 1151 4514 1555 1153 4515 1554 1152 4516 1556 1154 4517 1553 1151 4518 1554 1152 4519 1555 1153 4520 1557 1155 4521 1556 1154 4522 1558 1156 4523 1555 1153 4524 1556 1154 4525 1557 1155 4526 1559 1157 4527 1558 1156 4528 1560 1158 4529 1557 1155 4530 1558 1156 4531 1559 1157 4532 1561 1159 4533 1560 1158 4534 1562 1160 4535 1559 1157 4536 1560 1158 4537 1561 1159 4538 1563 1161 4539 1562 1160 4540 1564 1162 4541 1561 1159 4542 1562 1160 4543 1563 1161 4544 1565 1163 4545 1564 1162 4546 1566 1164 4547 1563 1161 4548 1564 1162 4549 1565 1163 4550 1567 1165 4551 1566 1164 4552 1568 1166 4553 1565 1163 4554 1566 1164 4555 1567 1165 4556 1569 1167 4557 1568 1166 4558 1570 1168 4559 1567 1165 4560 1568 1166 4561 1569 1167 4562 1571 1169 4563 1570 1168 4564 1572 1170 4565 1569 1167 4566 1570 1168 4567 1571 1169 4568 1573 1171 4569 1572 1170 4570 1574 1172 4571 1571 1169 4572 1572 1170 4573 1573 1171 4574 1575 1173 4575 1574 1172 4576 1576 1174 4577 1573 1171 4578 1574 1172 4579 1575 1173 4580 1577 1175 4581 1576 1174 4582 1578 1176 4583 1575 1173 4584 1576 1174 4585 1577 1175 4586 1579 1177 4587 1578 1176 4588 1580 1178 4589 1577 1175 4590 1578 1176 4591 1579 1177 4592 1581 1179 4593 1580 1178 4594 787 576 4595 1579 1177 4596 1580 1178 4597 1581 1179 4598 1581 1179 4599 787 576 4600 786 575 4601 22 1180 4602 855 1180 4603 13 1180 4604 1582 1181 4605 590 535 4606 595 538 4607 1583 1182 4608 1584 1182 4609 1585 1182 4610 1586 11 4611 855 11 4612 854 11 4613 1587 11 4614 855 11 4615 1372 11 4616 1373 11 4617 1372 11 4618 855 11 4619 1588 11 4620 856 11 4621 855 11 4622 1589 1183 4623 1588 1183 4624 855 1183 4625 1590 11 4626 1589 11 4627 855 11 4628 1587 11 4629 1590 11 4630 855 11 4631 1591 11 4632 1373 11 4633 855 11 4634 1592 11 4635 1591 11 4636 855 11 4637 1593 11 4638 1592 11 4639 855 11 4640 1594 11 4641 1593 11 4642 855 11 4643 1595 11 4644 1594 11 4645 855 11 4646 1596 11 4647 1595 11 4648 855 11 4649 1597 11 4650 1596 11 4651 855 11 4652 1598 11 4653 1597 11 4654 855 11 4655 22 11 4656 1598 11 4657 855 11 4658 588 533 4659 589 534 4660 1599 1184 4661 1600 1185 4662 592 537 4663 590 535 4664 1600 1185 4665 1601 1186 4666 592 537 4667 1602 1187 4668 1599 1184 4669 1603 1188 4670 1602 1187 4671 588 533 4672 1599 1184 4673 1582 1181 4674 1604 1189 4675 590 535 4676 1605 1190 4677 590 535 4678 1604 1189 4679 1605 1190 4680 1600 1185 4681 590 535 4682 1606 1191 4683 1607 1192 4684 1604 1189 4685 1608 1193 4686 1604 1189 4687 1607 1192 4688 1582 1181 4689 1606 1191 4690 1604 1189 4691 1608 1193 4692 1605 1190 4693 1604 1189 4694 1583 1194 4695 1609 1194 4696 1610 1194 4697 1608 1193 4698 1607 1192 4699 1611 1195 4700 1583 1196 4701 1612 1196 4702 1609 1196 4703 1583 1197 4704 1610 1197 4705 1584 1197 4706 1613 1198 4707 1608 1193 4708 1611 1195 4709 1614 1199 4710 1613 1198 4711 1611 1195 4712 1583 1200 4713 1615 1200 4714 1612 1200 4715 1600 1185 4716 1616 1201 4717 1601 1186 4718 1617 1202 4719 1603 1188 4720 1618 1203 4721 1617 1202 4722 1602 1187 4723 1603 1188 4724 1600 1185 4725 1619 1204 4726 1616 1201 4727 1617 1202 4728 1618 1203 4729 1620 1205 4730 802 591 4731 1619 1204 4732 1600 1185 4733 804 593 4734 1621 1206 4735 1619 1204 4736 1622 1207 4737 1620 1205 4738 1623 1208 4739 802 591 4740 804 593 4741 1619 1204 4742 1622 1207 4743 1617 1202 4744 1620 1205 4745 800 589 4746 1600 1185 4747 1605 1190 4748 800 589 4749 802 591 4750 1600 1185 4751 798 587 4752 1605 1190 4753 1608 1193 4754 798 587 4755 800 589 4756 1605 1190 4757 796 585 4758 1608 1193 4759 1613 1198 4760 796 585 4761 798 587 4762 1608 1193 4763 1614 1199 4764 1624 1209 4765 1613 1198 4766 794 583 4767 1613 1198 4768 1624 1209 4769 794 583 4770 796 585 4771 1613 1198 4772 1625 1210 4773 1626 1211 4774 1624 1209 4775 790 579 4776 1624 1209 4777 1626 1211 4778 1614 1199 4779 1625 1210 4780 1624 1209 4781 790 579 4782 794 583 4783 1624 1209 4784 1583 1212 4785 1627 1212 4786 1628 1212 4787 792 581 4788 1626 1211 4789 1629 1213 4790 1583 1214 4791 1630 1214 4792 1627 1214 4793 792 581 4794 790 579 4795 1626 1211 4796 1583 1215 4797 1628 1215 4798 1615 1215 4799 1631 1216 4800 792 581 4801 1629 1213 4802 1583 1217 4803 1632 1217 4804 1630 1217 4805 804 593 4806 1633 1218 4807 1621 1206 4808 1634 1219 4809 1623 1208 4810 1635 1220 4811 1634 1219 4812 1622 1207 4813 1623 1208 4814 804 593 4815 1636 1221 4816 1633 1218 4817 1637 1222 4818 1635 1220 4819 1638 1223 4820 1637 1222 4821 1634 1219 4822 1635 1220 4823 806 595 4824 1639 1224 4825 1636 1221 4826 1640 1225 4827 1638 1223 4828 1641 1226 4829 804 593 4830 806 595 4831 1636 1221 4832 1640 1225 4833 1637 1222 4834 1638 1223 4835 806 595 4836 1642 1227 4837 1639 1224 4838 1643 1228 4839 1644 1229 4840 1645 1230 4841 1646 1231 4842 1640 1225 4843 1641 1226 4844 806 595 4845 1647 1232 4846 1642 1227 4847 1648 1233 4848 1645 1230 4849 1649 1234 4850 1650 1235 4851 1643 1228 4852 1645 1230 4853 1648 1233 4854 1650 1235 4855 1645 1230 4856 806 595 4857 1651 1236 4858 1647 1232 4859 1652 1237 4860 1649 1234 4861 1653 1238 4862 1652 1237 4863 1648 1233 4864 1649 1234 4865 806 595 4866 1654 1239 4867 1651 1236 4868 1655 1240 4869 1653 1238 4870 1656 1241 4871 1655 1240 4872 1652 1237 4873 1653 1238 4874 806 595 4875 1657 1242 4876 1654 1239 4877 1658 1243 4878 1654 1239 4879 1657 1242 4880 1655 1240 4881 1656 1241 4882 1659 1244 4883 808 597 4884 1660 1245 4885 1657 1242 4886 487 432 4887 1657 1242 4888 1660 1245 4889 806 595 4890 808 597 4891 1657 1242 4892 1661 1246 4893 1657 1242 4894 487 432 4895 1662 1247 4896 1657 1242 4897 1661 1246 4898 1658 1243 4899 1657 1242 4900 1662 1247 4901 810 599 4902 1663 1248 4903 1660 1245 4904 483 428 4905 1660 1245 4906 1663 1248 4907 808 597 4908 810 599 4909 1660 1245 4910 487 432 4911 1660 1245 4912 483 428 4913 814 603 4914 1664 1249 4915 1663 1248 4916 481 426 4917 1663 1248 4918 1664 1249 4919 812 601 4920 814 603 4921 1663 1248 4922 810 599 4923 812 601 4924 1663 1248 4925 483 428 4926 1663 1248 4927 481 426 4928 816 605 4929 1665 1250 4930 1664 1249 4931 476 421 4932 1664 1249 4933 1665 1250 4934 814 603 4935 816 605 4936 1664 1249 4937 478 423 4938 1664 1249 4939 476 421 4940 481 426 4941 1664 1249 4942 478 423 4943 818 607 4944 1666 1251 4945 1665 1250 4946 470 415 4947 1665 1250 4948 1666 1251 4949 816 605 4950 818 607 4951 1665 1250 4952 476 421 4953 1665 1250 4954 470 415 4955 820 609 4956 1667 1252 4957 1666 1251 4958 1668 1253 4959 1666 1251 4960 1667 1252 4961 818 607 4962 820 609 4963 1666 1251 4964 470 415 4965 1666 1251 4966 1669 1254 4967 1670 1255 4968 1669 1254 4969 1666 1251 4970 1668 1253 4971 1670 1255 4972 1666 1251 4973 820 609 4974 1671 1256 4975 1667 1252 4976 1672 1257 4977 1673 1258 4978 1674 1259 4979 1675 1260 4980 1676 1261 4981 1673 1258 4982 1672 1257 4983 1675 1260 4984 1673 1258 4985 820 609 4986 1677 1262 4987 1671 1256 4988 1678 1263 4989 1674 1259 4990 1679 1264 4991 1678 1263 4992 1672 1257 4993 1674 1259 4994 820 609 4995 1680 1265 4996 1677 1262 4997 1681 1266 4998 1679 1264 4999 1682 1267 5000 1681 1266 5001 1678 1263 5002 1679 1264 5003 822 611 5004 1683 1268 5005 1680 1265 5006 1684 1269 5007 1682 1267 5008 1685 1270 5009 820 609 5010 822 611 5011 1680 1265 5012 1684 1269 5013 1681 1266 5014 1682 1267 5015 822 611 5016 1686 1271 5017 1683 1268 5018 1687 1272 5019 1688 1273 5020 1689 1274 5021 1690 729 5022 1684 1269 5023 1685 1270 5024 822 611 5025 1691 1275 5026 1686 1271 5027 1692 1276 5028 1689 1274 5029 1693 1277 5030 1694 1278 5031 1687 1272 5032 1689 1274 5033 1692 1276 5034 1694 1278 5035 1689 1274 5036 822 611 5037 1695 1279 5038 1691 1275 5039 1696 1280 5040 1693 1277 5041 1697 1281 5042 1696 1280 5043 1692 1276 5044 1693 1277 5045 824 613 5046 1698 1282 5047 1695 1279 5048 1699 1283 5049 1697 1281 5050 1700 1284 5051 822 611 5052 824 613 5053 1695 1279 5054 1699 1283 5055 1696 1280 5056 1697 1281 5057 824 613 5058 1701 1285 5059 1698 1282 5060 1702 1286 5061 1698 1282 5062 1701 1285 5063 1699 1283 5064 1700 1284 5065 1703 1287 5066 826 615 5067 1704 1288 5068 1701 1285 5069 372 317 5070 1701 1285 5071 1704 1288 5072 824 613 5073 826 615 5074 1701 1285 5075 1705 1289 5076 1701 1285 5077 372 317 5078 1706 1290 5079 1701 1285 5080 1705 1289 5081 1702 1286 5082 1701 1285 5083 1706 1290 5084 828 617 5085 1707 1291 5086 1704 1288 5087 368 313 5088 1704 1288 5089 1707 1291 5090 826 615 5091 828 617 5092 1704 1288 5093 372 317 5094 1704 1288 5095 368 313 5096 830 619 5097 1708 1292 5098 1707 1291 5099 366 311 5100 1707 1291 5101 1708 1292 5102 828 617 5103 830 619 5104 1707 1291 5105 368 313 5106 1707 1291 5107 366 311 5108 832 621 5109 1709 1293 5110 1708 1292 5111 361 306 5112 1708 1292 5113 1709 1293 5114 830 619 5115 832 621 5116 1708 1292 5117 363 308 5118 1708 1292 5119 361 306 5120 366 311 5121 1708 1292 5122 363 308 5123 834 623 5124 1710 1294 5125 1709 1293 5126 355 300 5127 1709 1293 5128 1710 1294 5129 832 621 5130 834 623 5131 1709 1293 5132 361 306 5133 1709 1293 5134 355 300 5135 836 625 5136 1711 1295 5137 1710 1294 5138 1712 1296 5139 1710 1294 5140 1711 1295 5141 834 623 5142 836 625 5143 1710 1294 5144 355 300 5145 1710 1294 5146 1713 1297 5147 1714 1298 5148 1713 1297 5149 1710 1294 5150 1712 1296 5151 1714 1298 5152 1710 1294 5153 836 625 5154 1715 1299 5155 1711 1295 5156 1716 1300 5157 1717 1301 5158 1718 1302 5159 1719 1303 5160 1720 1304 5161 1717 1301 5162 1716 1300 5163 1719 1303 5164 1717 1301 5165 836 625 5166 1721 1305 5167 1715 1299 5168 1722 1306 5169 1718 1302 5170 1723 1307 5171 1722 1306 5172 1716 1300 5173 1718 1302 5174 1724 1308 5175 1725 1309 5176 1721 1305 5177 1726 1310 5178 1723 1307 5179 1727 1311 5180 836 625 5181 1724 1308 5182 1721 1305 5183 1726 1310 5184 1722 1306 5185 1723 1307 5186 1724 1308 5187 1728 1312 5188 1725 1309 5189 1729 1313 5190 1727 1311 5191 1730 1314 5192 1729 1313 5193 1726 1310 5194 1727 1311 5195 1540 1138 5196 1731 1315 5197 1539 1137 5198 1732 1316 5199 1731 1315 5200 1540 1138 5201 1733 1317 5202 1734 1318 5203 1735 1319 5204 1736 1320 5205 1729 1313 5206 1730 1314 5207 842 630 5208 1724 1308 5209 836 625 5210 1631 1216 5211 793 582 5212 792 581 5213 1737 1321 5214 1738 1322 5215 1739 1323 5216 786 575 5217 789 578 5218 1738 1322 5219 1737 1321 5220 786 575 5221 1738 1322 5222 1583 1324 5223 1740 1324 5224 1632 1324 5225 470 415 5226 1669 1254 5227 473 418 5228 474 419 5229 475 420 5230 1741 1325 5231 1742 1326 5232 1741 1325 5233 1743 1327 5234 1742 1326 5235 474 419 5236 1741 1325 5237 494 439 5238 1661 1246 5239 487 432 5240 1744 1328 5241 1745 1329 5242 496 441 5243 1744 1328 5244 1746 1330 5245 1745 1329 5246 495 440 5247 1744 1328 5248 496 441 5249 1747 1331 5250 1659 1244 5251 1746 1330 5252 1744 1328 5253 1747 1331 5254 1746 1330 5255 1675 1260 5256 1743 1327 5257 1676 1261 5258 1675 1260 5259 1742 1326 5260 1743 1327 5261 1747 1331 5262 1655 1240 5263 1659 1244 5264 355 300 5265 1713 1297 5266 358 303 5267 359 304 5268 360 305 5269 1748 1332 5270 1749 1333 5271 1748 1332 5272 1750 1334 5273 1749 1333 5274 359 304 5275 1748 1332 5276 379 324 5277 1705 1289 5278 372 317 5279 1751 1335 5280 1752 1336 5281 381 326 5282 1751 1335 5283 1753 1337 5284 1752 1336 5285 380 325 5286 1751 1335 5287 381 326 5288 1754 1338 5289 1703 1287 5290 1753 1337 5291 1751 1335 5292 1754 1338 5293 1753 1337 5294 1719 1303 5295 1750 1334 5296 1720 1304 5297 1719 1303 5298 1749 1333 5299 1750 1334 5300 1754 1338 5301 1699 1283 5302 1703 1287 5303 1755 1339 5304 1581 1179 5305 786 575 5306 1737 1321 5307 1755 1339 5308 786 575 5309 1756 1340 5310 1579 1177 5311 1581 1179 5312 1755 1339 5313 1756 1340 5314 1581 1179 5315 1757 1341 5316 1577 1175 5317 1579 1177 5318 1756 1340 5319 1757 1341 5320 1579 1177 5321 1758 1342 5322 1575 1173 5323 1577 1175 5324 1757 1341 5325 1758 1342 5326 1577 1175 5327 1759 1343 5328 1573 1171 5329 1575 1173 5330 1758 1342 5331 1759 1343 5332 1575 1173 5333 1760 1344 5334 1571 1169 5335 1573 1171 5336 1759 1343 5337 1760 1344 5338 1573 1171 5339 1761 1345 5340 1569 1167 5341 1571 1169 5342 1762 1346 5343 1761 1345 5344 1571 1169 5345 1760 1344 5346 1762 1346 5347 1571 1169 5348 1763 1347 5349 1567 1165 5350 1569 1167 5351 1764 1348 5352 1763 1347 5353 1569 1167 5354 1765 1349 5355 1764 1348 5356 1569 1167 5357 1766 1350 5358 1765 1349 5359 1569 1167 5360 1761 1345 5361 1766 1350 5362 1569 1167 5363 1767 1351 5364 1565 1163 5365 1567 1165 5366 1768 1352 5367 1767 1351 5368 1567 1165 5369 1769 1353 5370 1768 1352 5371 1567 1165 5372 1770 1354 5373 1769 1353 5374 1567 1165 5375 1763 1347 5376 1770 1354 5377 1567 1165 5378 1771 1355 5379 1563 1161 5380 1565 1163 5381 1767 1351 5382 1771 1355 5383 1565 1163 5384 1772 1356 5385 1561 1159 5386 1563 1161 5387 1771 1355 5388 1772 1356 5389 1563 1161 5390 1773 1357 5391 1559 1157 5392 1561 1159 5393 1772 1356 5394 1773 1357 5395 1561 1159 5396 1773 1357 5397 1557 1155 5398 1559 1157 5399 1774 1358 5400 1555 1153 5401 1557 1155 5402 1773 1357 5403 1774 1358 5404 1557 1155 5405 1775 1359 5406 1553 1151 5407 1555 1153 5408 1774 1358 5409 1775 1359 5410 1555 1153 5411 1776 1360 5412 1551 1149 5413 1553 1151 5414 1777 1361 5415 1776 1360 5416 1553 1151 5417 1778 1362 5418 1777 1361 5419 1553 1151 5420 1779 1363 5421 1778 1362 5422 1553 1151 5423 1780 1364 5424 1779 1363 5425 1553 1151 5426 1781 1365 5427 1780 1364 5428 1553 1151 5429 1775 1359 5430 1781 1365 5431 1553 1151 5432 1782 1366 5433 1549 1147 5434 1551 1149 5435 1783 1367 5436 1782 1366 5437 1551 1149 5438 1784 1368 5439 1783 1367 5440 1551 1149 5441 1776 1360 5442 1784 1368 5443 1551 1149 5444 1785 1369 5445 1547 1145 5446 1549 1147 5447 1782 1366 5448 1785 1369 5449 1549 1147 5450 1786 1370 5451 1545 1143 5452 1547 1145 5453 1785 1369 5454 1786 1370 5455 1547 1145 5456 1787 1371 5457 1543 1141 5458 1545 1143 5459 1786 1370 5460 1787 1371 5461 1545 1143 5462 1788 1372 5463 1541 1139 5464 1543 1141 5465 1787 1371 5466 1788 1372 5467 1543 1141 5468 1789 1373 5469 1537 1135 5470 1541 1139 5471 1788 1372 5472 1789 1373 5473 1541 1139 5474 1790 1374 5475 1540 1138 5476 1537 1135 5477 1789 1373 5478 1790 1374 5479 1537 1135 5480 1791 1375 5481 1732 1316 5482 1540 1138 5483 1792 1376 5484 1791 1375 5485 1540 1138 5486 1793 1377 5487 1792 1376 5488 1540 1138 5489 1790 1374 5490 1793 1377 5491 1540 1138 5492 1794 1378 5493 1735 1319 5494 1795 1379 5495 1796 1380 5496 1733 1317 5497 1735 1319 5498 1794 1378 5499 1796 1380 5500 1735 1319 5501 1797 1381 5502 1795 1379 5503 1798 1382 5504 1797 1381 5505 1794 1378 5506 1795 1379 5507 1799 1383 5508 1798 1382 5509 1800 1384 5510 1799 1383 5511 1797 1381 5512 1798 1382 5513 1801 1385 5514 1793 1377 5515 1790 1374 5516 1799 1383 5517 1800 1384 5518 1802 1386 5519 1242 1025 5520 1790 1374 5521 1789 1373 5522 1803 1387 5523 1790 1374 5524 1242 1025 5525 1804 1388 5526 1790 1374 5527 1803 1387 5528 1801 1385 5529 1790 1374 5530 1804 1388 5531 1237 1020 5532 1789 1373 5533 1788 1372 5534 1242 1025 5535 1789 1373 5536 1237 1020 5537 1232 1015 5538 1788 1372 5539 1787 1371 5540 1237 1020 5541 1788 1372 5542 1232 1015 5543 1219 1002 5544 1787 1371 5545 1786 1370 5546 1224 1007 5547 1787 1371 5548 1219 1002 5549 1232 1015 5550 1787 1371 5551 1224 1007 5552 1211 994 5553 1786 1370 5554 1785 1369 5555 1219 1002 5556 1786 1370 5557 1211 994 5558 1805 1389 5559 1785 1369 5560 1782 1366 5561 1211 994 5562 1785 1369 5563 1806 1390 5564 1807 1391 5565 1806 1390 5566 1785 1369 5567 1805 1389 5568 1807 1391 5569 1785 1369 5570 1808 1392 5571 1809 1393 5572 1810 1394 5573 1811 1395 5574 1812 1396 5575 1809 1393 5576 1808 1392 5577 1811 1395 5578 1809 1393 5579 1813 1397 5580 1810 1394 5581 1814 1398 5582 1813 1397 5583 1808 1392 5584 1810 1394 5585 1815 1399 5586 1814 1398 5587 1816 1400 5588 1815 1399 5589 1813 1397 5590 1814 1398 5591 1817 1401 5592 1816 1400 5593 1818 1402 5594 1817 1401 5595 1815 1399 5596 1816 1400 5597 1819 1403 5598 1820 1404 5599 1821 1405 5600 1822 1406 5601 1817 1401 5602 1818 1402 5603 1823 1407 5604 1821 1405 5605 1824 1408 5606 1825 1409 5607 1819 1403 5608 1821 1405 5609 1823 1407 5610 1825 1409 5611 1821 1405 5612 1826 1410 5613 1824 1408 5614 1827 1411 5615 1826 1410 5616 1823 1407 5617 1824 1408 5618 1828 1412 5619 1827 1411 5620 1829 1413 5621 1828 1412 5622 1826 1410 5623 1827 1411 5624 1830 1414 5625 1781 1365 5626 1775 1359 5627 1828 1412 5628 1829 1413 5629 1831 1415 5630 1053 834 5631 1775 1359 5632 1774 1358 5633 1832 1416 5634 1775 1359 5635 1053 834 5636 1833 1417 5637 1775 1359 5638 1832 1416 5639 1830 1414 5640 1775 1359 5641 1833 1417 5642 1048 829 5643 1774 1358 5644 1773 1357 5645 1053 834 5646 1774 1358 5647 1048 829 5648 1043 824 5649 1773 1357 5650 1772 1356 5651 1048 829 5652 1773 1357 5653 1043 824 5654 1030 811 5655 1772 1356 5656 1771 1355 5657 1035 816 5658 1772 1356 5659 1030 811 5660 1043 824 5661 1772 1356 5662 1035 816 5663 1022 803 5664 1771 1355 5665 1767 1351 5666 1030 811 5667 1771 1355 5668 1022 803 5669 1834 1418 5670 1767 1351 5671 1768 1352 5672 1022 803 5673 1767 1351 5674 1835 1419 5675 1836 1420 5676 1835 1419 5677 1767 1351 5678 1834 1418 5679 1836 1420 5680 1767 1351 5681 1837 1421 5682 1838 1422 5683 1839 1423 5684 1840 1424 5685 1841 1425 5686 1838 1422 5687 1837 1421 5688 1840 1424 5689 1838 1422 5690 1842 1426 5691 1839 1423 5692 1843 1427 5693 1842 1426 5694 1837 1421 5695 1839 1423 5696 1844 1428 5697 1843 1427 5698 1845 1429 5699 1844 1428 5700 1842 1426 5701 1843 1427 5702 1846 1430 5703 1845 1429 5704 1847 1431 5705 1846 1430 5706 1844 1428 5707 1845 1429 5708 1848 1432 5709 1849 1433 5710 1850 1434 5711 1851 370 5712 1846 1430 5713 1847 1431 5714 1852 1435 5715 1850 1434 5716 1853 1436 5717 1854 1437 5718 1848 1432 5719 1850 1434 5720 1852 1435 5721 1854 1437 5722 1850 1434 5723 1855 1438 5724 1853 1436 5725 1856 1439 5726 1855 1438 5727 1852 1435 5728 1853 1436 5729 1857 1440 5730 1856 1439 5731 1858 1441 5732 1857 1440 5733 1855 1438 5734 1856 1439 5735 1859 1442 5736 1762 1346 5737 1760 1344 5738 1857 1440 5739 1858 1441 5740 1860 1443 5741 863 642 5742 1760 1344 5743 1759 1343 5744 1861 1444 5745 1859 1442 5746 1760 1344 5747 1862 1445 5748 1861 1444 5749 1760 1344 5750 863 642 5751 1862 1445 5752 1760 1344 5753 1863 1446 5754 1759 1343 5755 1758 1342 5756 1863 1446 5757 863 642 5758 1759 1343 5759 1864 1447 5760 1758 1342 5761 1757 1341 5762 1864 1447 5763 1863 1446 5764 1758 1342 5765 1865 1448 5766 1757 1341 5767 1756 1340 5768 1866 1449 5769 1864 1447 5770 1757 1341 5771 1865 1448 5772 1866 1449 5773 1757 1341 5774 1867 1450 5775 1756 1340 5776 1755 1339 5777 1865 1448 5778 1756 1340 5779 1867 1450 5780 1583 1451 5781 1868 1451 5782 1740 1451 5783 1583 1452 5784 1869 1452 5785 1868 1452 5786 1583 1453 5787 1870 1453 5788 1869 1453 5789 1871 1454 5790 1860 1443 5791 1872 1455 5792 1871 1454 5793 1857 1440 5794 1860 1443 5795 1873 1456 5796 1872 1455 5797 1874 1457 5798 1873 1456 5799 1871 1454 5800 1872 1455 5801 873 652 5802 1862 1445 5803 863 642 5804 1873 1456 5805 1874 1457 5806 875 654 5807 869 648 5808 863 642 5809 1863 1446 5810 1875 1458 5811 1863 1446 5812 1864 1447 5813 1876 1459 5814 1863 1446 5815 1875 1458 5816 1876 1459 5817 869 648 5818 1863 1446 5819 1583 1460 5820 1877 1460 5821 1878 1460 5822 1583 1461 5823 1879 1461 5824 1877 1461 5825 1583 1462 5826 1878 1462 5827 1870 1462 5828 1880 1463 5829 1879 1463 5830 1583 1463 5831 874 653 5832 1873 1456 5833 875 654 5834 1211 994 5835 1806 1390 5836 1214 997 5837 1215 998 5838 1216 999 5839 1881 1464 5840 1882 1465 5841 1881 1464 5842 1883 1466 5843 1882 1465 5844 1215 998 5845 1881 1464 5846 1251 1034 5847 1803 1387 5848 1242 1025 5849 1884 1467 5850 1885 1468 5851 1253 1036 5852 1884 1467 5853 1886 1469 5854 1885 1468 5855 1252 1035 5856 1884 1467 5857 1253 1036 5858 1887 1470 5859 1802 1386 5860 1886 1469 5861 1884 1467 5862 1887 1470 5863 1886 1469 5864 1811 1395 5865 1883 1466 5866 1812 1396 5867 1811 1395 5868 1882 1465 5869 1883 1466 5870 1887 1470 5871 1799 1383 5872 1802 1386 5873 1022 803 5874 1835 1419 5875 1025 806 5876 1026 807 5877 1027 808 5878 1888 1471 5879 1889 1472 5880 1888 1471 5881 1890 1473 5882 1889 1472 5883 1026 807 5884 1888 1471 5885 1062 843 5886 1832 1416 5887 1053 834 5888 1891 1474 5889 1892 1475 5890 1064 845 5891 1891 1474 5892 1893 1476 5893 1892 1475 5894 1063 844 5895 1891 1474 5896 1064 845 5897 1894 1477 5898 1831 1415 5899 1893 1476 5900 1891 1474 5901 1894 1477 5902 1893 1476 5903 1840 1424 5904 1890 1473 5905 1841 1425 5906 1840 1424 5907 1889 1472 5908 1890 1473 5909 1894 1477 5910 1828 1412 5911 1831 1415 5912 1895 1478 5913 1896 1479 5914 1897 1480 5915 1898 1481 5916 1899 1482 5917 1900 1483 5918 1898 1481 5919 1900 1483 5920 1901 1484 5921 1895 1478 5922 1897 1480 5923 1902 1485 5924 1903 1486 5925 1902 1485 5926 1904 1487 5927 1895 1478 5928 1902 1485 5929 1903 1486 5930 1903 1486 5931 1904 1487 5932 1905 1488 5933 1906 1489 5934 1905 1488 5935 1907 1490 5936 1903 1486 5937 1905 1488 5938 1906 1489 5939 1906 1489 5940 1907 1490 5941 1908 1491 5942 1909 1492 5943 1908 1491 5944 1910 1493 5945 1906 1489 5946 1908 1491 5947 1909 1492 5948 1909 1492 5949 1910 1493 5950 1911 1494 5951 1912 1495 5952 1911 1494 5953 1913 1496 5954 1909 1492 5955 1911 1494 5956 1912 1495 5957 1912 1495 5958 1913 1496 5959 1914 1497 5960 1915 1498 5961 1914 1497 5962 1916 1499 5963 1912 1495 5964 1914 1497 5965 1915 1498 5966 1915 1498 5967 1916 1499 5968 1917 1500 5969 1918 1501 5970 1917 1500 5971 1919 1502 5972 1915 1498 5973 1917 1500 5974 1918 1501 5975 1918 1501 5976 1919 1502 5977 1920 1503 5978 1921 1504 5979 1920 1503 5980 1922 1505 5981 1918 1501 5982 1920 1503 5983 1921 1504 5984 1921 1504 5985 1922 1505 5986 1923 1506 5987 1924 1507 5988 1923 1506 5989 1925 1508 5990 1921 1504 5991 1923 1506 5992 1924 1507 5993 1924 1507 5994 1925 1508 5995 1926 1509 5996 1927 1510 5997 1926 1509 5998 1928 1511 5999 1924 1507 6000 1926 1509 6001 1927 1510 6002 1927 1510 6003 1928 1511 6004 1929 1512 6005 1930 1513 6006 1931 1514 6007 1932 1515 6008 1927 1510 6009 1929 1512 6010 1933 1516 6011 1930 1513 6012 1932 1515 6013 1934 1517 6014 1935 1518 6015 1934 1517 6016 1936 1519 6017 1935 1518 6018 1930 1513 6019 1934 1517 6020 1935 1518 6021 1936 1519 6022 1937 1520 6023 1938 1521 6024 1937 1520 6025 1939 1522 6026 1935 1518 6027 1937 1520 6028 1938 1521 6029 1938 1521 6030 1939 1522 6031 1940 1523 6032 1941 1524 6033 1940 1523 6034 1942 1525 6035 1938 1521 6036 1940 1523 6037 1941 1524 6038 1941 1524 6039 1942 1525 6040 1943 1526 6041 1944 1527 6042 1943 1526 6043 1945 1528 6044 1941 1524 6045 1943 1526 6046 1944 1527 6047 1944 1527 6048 1945 1528 6049 1946 1529 6050 1947 1530 6051 1946 1529 6052 1948 1531 6053 1944 1527 6054 1946 1529 6055 1947 1530 6056 1947 1530 6057 1948 1531 6058 1949 1532 6059 1950 1533 6060 1949 1532 6061 1951 1534 6062 1947 1530 6063 1949 1532 6064 1950 1533 6065 1950 1533 6066 1951 1534 6067 1952 1535 6068 1953 1536 6069 1952 1535 6070 1954 1537 6071 1950 1533 6072 1952 1535 6073 1953 1536 6074 1953 1536 6075 1954 1537 6076 1955 1538 6077 1956 1539 6078 1955 1538 6079 1957 1540 6080 1953 1536 6081 1955 1538 6082 1956 1539 6083 1956 1539 6084 1957 1540 6085 1958 1541 6086 1898 1481 6087 1958 1541 6088 1899 1482 6089 1956 1539 6090 1958 1541 6091 1898 1481 6092 1959 1542 6093 1960 1543 6094 1961 1544 6095 1962 1545 6096 1963 1546 6097 1964 1547 6098 1962 1545 6099 1964 1547 6100 1965 1548 6101 1959 1542 6102 1961 1544 6103 1966 1549 6104 1967 1550 6105 1966 1549 6106 1968 1551 6107 1959 1542 6108 1966 1549 6109 1967 1550 6110 1967 1550 6111 1968 1551 6112 1969 1552 6113 1970 1553 6114 1969 1552 6115 1971 1554 6116 1967 1550 6117 1969 1552 6118 1970 1553 6119 1970 1553 6120 1971 1554 6121 1972 1555 6122 1973 1556 6123 1972 1555 6124 1974 1557 6125 1970 1553 6126 1972 1555 6127 1973 1556 6128 1973 1556 6129 1974 1557 6130 1975 1558 6131 1976 1559 6132 1975 1558 6133 1977 1560 6134 1973 1556 6135 1975 1558 6136 1976 1559 6137 1976 1559 6138 1977 1560 6139 1978 1561 6140 1979 1562 6141 1978 1561 6142 1980 1563 6143 1976 1559 6144 1978 1561 6145 1979 1562 6146 1979 1562 6147 1980 1563 6148 1981 1564 6149 1982 1565 6150 1981 1564 6151 1983 1566 6152 1979 1562 6153 1981 1564 6154 1982 1565 6155 1982 1565 6156 1983 1566 6157 1984 1567 6158 1985 1568 6159 1984 1567 6160 1986 1569 6161 1982 1565 6162 1984 1567 6163 1985 1568 6164 1985 1568 6165 1986 1569 6166 1987 1570 6167 1988 1571 6168 1987 1570 6169 1989 1572 6170 1985 1568 6171 1987 1570 6172 1988 1571 6173 1988 1571 6174 1989 1572 6175 1990 1573 6176 1991 1574 6177 1990 1573 6178 1992 1575 6179 1988 1571 6180 1990 1573 6181 1991 1574 6182 1991 1574 6183 1992 1575 6184 1993 1576 6185 1994 1577 6186 1995 1578 6187 1996 1579 6188 1991 1574 6189 1993 1576 6190 1997 1580 6191 1994 1577 6192 1996 1579 6193 1998 1581 6194 1999 1582 6195 1998 1581 6196 2000 1583 6197 1999 1582 6198 1994 1577 6199 1998 1581 6200 1999 1582 6201 2000 1583 6202 2001 1584 6203 2002 1585 6204 2001 1584 6205 2003 1586 6206 1999 1582 6207 2001 1584 6208 2002 1585 6209 2002 1585 6210 2003 1586 6211 2004 1587 6212 2005 1588 6213 2004 1587 6214 2006 1589 6215 2002 1585 6216 2004 1587 6217 2005 1588 6218 2005 1588 6219 2006 1589 6220 2007 1590 6221 2008 1591 6222 2007 1590 6223 2009 1592 6224 2005 1588 6225 2007 1590 6226 2008 1591 6227 2008 1591 6228 2009 1592 6229 2010 1593 6230 2011 1594 6231 2010 1593 6232 2012 1595 6233 2008 1591 6234 2010 1593 6235 2011 1594 6236 2011 1594 6237 2012 1595 6238 2013 1596 6239 2014 1597 6240 2013 1596 6241 2015 1598 6242 2011 1594 6243 2013 1596 6244 2014 1597 6245 2014 1597 6246 2015 1598 6247 2016 1599 6248 2017 1600 6249 2016 1599 6250 2018 1601 6251 2014 1597 6252 2016 1599 6253 2017 1600 6254 2017 1600 6255 2018 1601 6256 2019 1602 6257 2020 1603 6258 2019 1602 6259 2021 1604 6260 2017 1600 6261 2019 1602 6262 2020 1603 6263 2020 1603 6264 2021 1604 6265 2022 1605 6266 1962 1545 6267 2022 1605 6268 1963 1546 6269 2020 1603 6270 2022 1605 6271 1962 1545 6272 2023 1606 6273 2024 1607 6274 2025 1608 6275 2026 1609 6276 2027 1610 6277 2028 1611 6278 2026 1609 6279 2028 1611 6280 2029 1612 6281 2023 1606 6282 2025 1608 6283 2030 1613 6284 2031 1614 6285 2030 1613 6286 2032 1615 6287 2023 1606 6288 2030 1613 6289 2031 1614 6290 2031 1614 6291 2032 1615 6292 2033 1616 6293 2034 1617 6294 2033 1616 6295 2035 1618 6296 2031 1614 6297 2033 1616 6298 2034 1617 6299 2034 1617 6300 2035 1618 6301 2036 1619 6302 2037 1620 6303 2036 1619 6304 2038 1621 6305 2034 1617 6306 2036 1619 6307 2037 1620 6308 2037 1620 6309 2038 1621 6310 2039 1622 6311 2040 1623 6312 2039 1622 6313 2041 1624 6314 2037 1620 6315 2039 1622 6316 2040 1623 6317 2040 1623 6318 2041 1624 6319 2042 1625 6320 2043 1626 6321 2042 1625 6322 2044 1627 6323 2040 1623 6324 2042 1625 6325 2043 1626 6326 2043 1626 6327 2044 1627 6328 2045 1628 6329 2046 1629 6330 2045 1628 6331 2047 1630 6332 2043 1626 6333 2045 1628 6334 2046 1629 6335 2046 1629 6336 2047 1630 6337 2048 1631 6338 2049 1632 6339 2048 1631 6340 2050 1633 6341 2046 1629 6342 2048 1631 6343 2049 1632 6344 2049 1632 6345 2050 1633 6346 2051 1634 6347 2052 1635 6348 2051 1634 6349 2053 1636 6350 2049 1632 6351 2051 1634 6352 2052 1635 6353 2052 1635 6354 2053 1636 6355 2054 1637 6356 2055 1638 6357 2054 1637 6358 2056 1639 6359 2052 1635 6360 2054 1637 6361 2055 1638 6362 2055 1638 6363 2056 1639 6364 2057 1640 6365 2058 1641 6366 2059 1642 6367 2060 1643 6368 2055 1638 6369 2057 1640 6370 2061 1644 6371 2058 1641 6372 2060 1643 6373 2062 1645 6374 2063 1646 6375 2062 1645 6376 2064 1647 6377 2063 1646 6378 2058 1641 6379 2062 1645 6380 2063 1646 6381 2064 1647 6382 2065 1648 6383 2066 1649 6384 2065 1648 6385 2067 1650 6386 2063 1646 6387 2065 1648 6388 2066 1649 6389 2066 1649 6390 2067 1650 6391 2068 1651 6392 2069 1652 6393 2068 1651 6394 2070 1653 6395 2066 1649 6396 2068 1651 6397 2069 1652 6398 2069 1652 6399 2070 1653 6400 2071 1654 6401 2072 1655 6402 2071 1654 6403 2073 1656 6404 2069 1652 6405 2071 1654 6406 2072 1655 6407 2072 1655 6408 2073 1656 6409 2074 1657 6410 2075 1658 6411 2074 1657 6412 2076 1659 6413 2072 1655 6414 2074 1657 6415 2075 1658 6416 2075 1658 6417 2076 1659 6418 2077 1660 6419 2078 1661 6420 2077 1660 6421 2079 1662 6422 2075 1658 6423 2077 1660 6424 2078 1661 6425 2078 1661 6426 2079 1662 6427 2080 1663 6428 2081 1664 6429 2080 1663 6430 2082 1665 6431 2078 1661 6432 2080 1663 6433 2081 1664 6434 2081 1664 6435 2082 1665 6436 2083 1666 6437 2084 1667 6438 2083 1666 6439 2085 1668 6440 2081 1664 6441 2083 1666 6442 2084 1667 6443 2084 1667 6444 2085 1668 6445 2086 1669 6446 2026 1609 6447 2086 1669 6448 2027 1610 6449 2084 1667 6450 2086 1669 6451 2026 1609 6452 2087 1577 6453 2088 1578 6454 2089 1579 6455 2090 1574 6456 2091 1575 6457 2092 1576 6458 2090 1574 6459 2092 1576 6460 2093 1670 6461 2087 1577 6462 2089 1579 6463 2094 1581 6464 2095 1582 6465 2094 1581 6466 2096 1583 6467 2087 1577 6468 2094 1581 6469 2095 1582 6470 2095 1582 6471 2096 1583 6472 2097 1584 6473 2098 1585 6474 2097 1584 6475 2099 1586 6476 2095 1582 6477 2097 1584 6478 2098 1585 6479 2098 1585 6480 2099 1586 6481 2100 1671 6482 2101 1588 6483 2100 1671 6484 2102 1672 6485 2098 1585 6486 2100 1671 6487 2101 1588 6488 2101 1588 6489 2102 1672 6490 2103 1590 6491 2104 1591 6492 2103 1590 6493 2105 1592 6494 2101 1588 6495 2103 1590 6496 2104 1591 6497 2104 1591 6498 2105 1592 6499 2106 1593 6500 2107 1594 6501 2106 1593 6502 2108 1595 6503 2104 1591 6504 2106 1593 6505 2107 1594 6506 2107 1594 6507 2108 1595 6508 2109 1596 6509 2110 1597 6510 2109 1596 6511 2111 1598 6512 2107 1594 6513 2109 1596 6514 2110 1597 6515 2110 1597 6516 2111 1598 6517 2112 1599 6518 2113 1600 6519 2112 1599 6520 2114 1601 6521 2110 1597 6522 2112 1599 6523 2113 1600 6524 2113 1600 6525 2114 1601 6526 2115 1602 6527 2116 1603 6528 2115 1602 6529 2117 1604 6530 2113 1600 6531 2115 1602 6532 2116 1603 6533 2116 1603 6534 2117 1604 6535 2118 1605 6536 2119 1545 6537 2118 1605 6538 2120 1546 6539 2116 1603 6540 2118 1605 6541 2119 1545 6542 2119 1545 6543 2120 1546 6544 2121 1547 6545 2122 1542 6546 2123 1543 6547 2124 1544 6548 2119 1545 6549 2121 1547 6550 2125 1673 6551 2122 1542 6552 2124 1544 6553 2126 1549 6554 2127 1550 6555 2126 1549 6556 2128 1551 6557 2127 1550 6558 2122 1542 6559 2126 1549 6560 2127 1550 6561 2128 1551 6562 2129 1552 6563 2130 1553 6564 2129 1552 6565 2131 1554 6566 2127 1550 6567 2129 1552 6568 2130 1553 6569 2130 1553 6570 2131 1554 6571 2132 1674 6572 2133 1556 6573 2132 1674 6574 2134 1675 6575 2130 1553 6576 2132 1674 6577 2133 1556 6578 2133 1556 6579 2134 1675 6580 2135 1558 6581 2136 1559 6582 2135 1558 6583 2137 1560 6584 2133 1556 6585 2135 1558 6586 2136 1559 6587 2136 1559 6588 2137 1560 6589 2138 1561 6590 2139 1562 6591 2138 1561 6592 2140 1563 6593 2136 1559 6594 2138 1561 6595 2139 1562 6596 2139 1562 6597 2140 1563 6598 2141 1564 6599 2142 1565 6600 2141 1564 6601 2143 1566 6602 2139 1562 6603 2141 1564 6604 2142 1565 6605 2142 1565 6606 2143 1566 6607 2144 1567 6608 2145 1568 6609 2144 1567 6610 2146 1569 6611 2142 1565 6612 2144 1567 6613 2145 1568 6614 2145 1568 6615 2146 1569 6616 2147 1570 6617 2148 1571 6618 2147 1570 6619 2149 1572 6620 2145 1568 6621 2147 1570 6622 2148 1571 6623 2148 1571 6624 2149 1572 6625 2150 1573 6626 2090 1574 6627 2150 1573 6628 2091 1575 6629 2148 1571 6630 2150 1573 6631 2090 1574 6632 2151 1641 6633 2152 1642 6634 2153 1643 6635 2154 1638 6636 2155 1639 6637 2156 1640 6638 2154 1638 6639 2156 1640 6640 2157 1644 6641 2151 1641 6642 2153 1643 6643 2158 1645 6644 2159 1646 6645 2158 1645 6646 2160 1647 6647 2151 1641 6648 2158 1645 6649 2159 1646 6650 2159 1646 6651 2160 1647 6652 2161 1648 6653 2162 1649 6654 2161 1648 6655 2163 1650 6656 2159 1646 6657 2161 1648 6658 2162 1649 6659 2162 1649 6660 2163 1650 6661 2164 1651 6662 2165 1652 6663 2164 1651 6664 2166 1653 6665 2162 1649 6666 2164 1651 6667 2165 1652 6668 2165 1652 6669 2166 1653 6670 2167 1654 6671 2168 1655 6672 2167 1654 6673 2169 1656 6674 2165 1652 6675 2167 1654 6676 2168 1655 6677 2168 1655 6678 2169 1656 6679 2170 1657 6680 2171 1658 6681 2170 1657 6682 2172 1659 6683 2168 1655 6684 2170 1657 6685 2171 1658 6686 2171 1658 6687 2172 1659 6688 2173 1660 6689 2174 1661 6690 2173 1660 6691 2175 1662 6692 2171 1658 6693 2173 1660 6694 2174 1661 6695 2174 1661 6696 2175 1662 6697 2176 1663 6698 2177 1664 6699 2176 1663 6700 2178 1665 6701 2174 1661 6702 2176 1663 6703 2177 1664 6704 2177 1664 6705 2178 1665 6706 2179 1666 6707 2180 1667 6708 2179 1666 6709 2181 1668 6710 2177 1664 6711 2179 1666 6712 2180 1667 6713 2180 1667 6714 2181 1668 6715 2182 1669 6716 2183 1609 6717 2182 1669 6718 2184 1610 6719 2180 1667 6720 2182 1669 6721 2183 1609 6722 2183 1609 6723 2184 1610 6724 2185 1611 6725 2186 1606 6726 2187 1607 6727 2188 1608 6728 2183 1609 6729 2185 1611 6730 2189 1612 6731 2186 1606 6732 2188 1608 6733 2190 1613 6734 2191 1614 6735 2190 1613 6736 2192 1615 6737 2191 1614 6738 2186 1606 6739 2190 1613 6740 2191 1614 6741 2192 1615 6742 2193 1616 6743 2194 1617 6744 2193 1616 6745 2195 1618 6746 2191 1614 6747 2193 1616 6748 2194 1617 6749 2194 1617 6750 2195 1618 6751 2196 1619 6752 2197 1620 6753 2196 1619 6754 2198 1621 6755 2194 1617 6756 2196 1619 6757 2197 1620 6758 2197 1620 6759 2198 1621 6760 2199 1622 6761 2200 1623 6762 2199 1622 6763 2201 1624 6764 2197 1620 6765 2199 1622 6766 2200 1623 6767 2200 1623 6768 2201 1624 6769 2202 1625 6770 2203 1626 6771 2202 1625 6772 2204 1627 6773 2200 1623 6774 2202 1625 6775 2203 1626 6776 2203 1626 6777 2204 1627 6778 2205 1628 6779 2206 1629 6780 2205 1628 6781 2207 1630 6782 2203 1626 6783 2205 1628 6784 2206 1629 6785 2206 1629 6786 2207 1630 6787 2208 1631 6788 2209 1632 6789 2208 1631 6790 2210 1633 6791 2206 1629 6792 2208 1631 6793 2209 1632 6794 2209 1632 6795 2210 1633 6796 2211 1634 6797 2212 1635 6798 2211 1634 6799 2213 1636 6800 2209 1632 6801 2211 1634 6802 2212 1635 6803 2212 1635 6804 2213 1636 6805 2214 1637 6806 2154 1638 6807 2214 1637 6808 2155 1639 6809 2212 1635 6810 2214 1637 6811 2154 1638 6812 2215 1676 6813 2216 1677 6814 2217 1678 6815 2218 1679 6816 2219 1680 6817 2220 1681 6818 2221 1682 6819 2218 1679 6820 2220 1681 6821 2222 1683 6822 2217 1678 6823 2223 1684 6824 2222 1683 6825 2215 1676 6826 2217 1678 6827 2224 1685 6828 2223 1684 6829 2225 1119 6830 2224 1685 6831 2222 1683 6832 2223 1684 6833 2226 1686 6834 2225 1119 6835 2227 1687 6836 2226 1686 6837 2224 1685 6838 2225 1119 6839 2228 1688 6840 2227 1687 6841 2229 1689 6842 2228 1688 6843 2226 1686 6844 2227 1687 6845 2230 1690 6846 2229 1689 6847 2231 1128 6848 2230 1690 6849 2228 1688 6850 2229 1689 6851 631 542 6852 2232 542 6853 630 542 6854 2233 1691 6855 2231 1128 6856 2234 1692 6857 2233 1691 6858 2230 1690 6859 2231 1128 6860 631 542 6861 2235 542 6862 2232 542 6863 2236 1693 6864 2234 1692 6865 2237 1694 6866 2236 1693 6867 2233 1691 6868 2234 1692 6869 2238 542 6870 1527 542 6871 2235 542 6872 2239 1695 6873 2237 1694 6874 2240 1696 6875 631 542 6876 2238 542 6877 2235 542 6878 2239 1695 6879 2236 1693 6880 2237 1694 6881 2241 1697 6882 2242 1698 6883 2243 1699 6884 2244 542 6885 1528 542 6886 1527 542 6887 2238 542 6888 2244 542 6889 1527 542 6890 2239 1695 6891 2240 1696 6892 2245 1700 6893 2246 1701 6894 2243 1699 6895 2247 1702 6896 2246 1701 6897 2241 1697 6898 2243 1699 6899 2248 1703 6900 2247 1702 6901 2249 551 6902 2248 1703 6903 2246 1701 6904 2247 1702 6905 2250 1704 6906 2249 551 6907 2251 1705 6908 2250 1704 6909 2248 1703 6910 2249 551 6911 2252 1706 6912 2251 1705 6913 2253 1707 6914 2252 1706 6915 2250 1704 6916 2251 1705 6917 2254 1708 6918 2253 1707 6919 2255 560 6920 2254 1708 6921 2252 1706 6922 2253 1707 6923 2256 1709 6924 2255 560 6925 2257 1710 6926 2256 1709 6927 2254 1708 6928 2255 560 6929 2258 1711 6930 2257 1710 6931 2219 1680 6932 2258 1711 6933 2256 1709 6934 2257 1710 6935 2218 1679 6936 2258 1711 6937 2219 1680 6938 2259 1712 6939 2260 1713 6940 2261 1714 6941 2262 1715 6942 2263 1707 6943 2264 1716 6944 2265 1717 6945 2262 1715 6946 2264 1716 6947 2266 1718 6948 2261 1714 6949 2267 1680 6950 2266 1718 6951 2259 1712 6952 2261 1714 6953 2268 1719 6954 2267 1680 6955 2269 11 6956 2268 1719 6957 2266 1718 6958 2267 1680 6959 1490 542 6960 2270 542 6961 1489 542 6962 2271 1720 6963 2269 11 6964 2272 1721 6965 2271 1720 6966 2268 1719 6967 2269 11 6968 1490 542 6969 2273 542 6970 2270 542 6971 2274 1722 6972 2272 1721 6973 2275 1723 6974 2274 1722 6975 2271 1720 6976 2272 1721 6977 2276 542 6978 2277 542 6979 2273 542 6980 2278 1724 6981 2275 1723 6982 2279 1119 6983 1490 542 6984 2276 542 6985 2273 542 6986 2278 1724 6987 2274 1722 6988 2275 1723 6989 2276 542 6990 2280 542 6991 2277 542 6992 2281 1725 6993 2279 1119 6994 2282 1687 6995 2281 1725 6996 2278 1724 6997 2279 1119 6998 2276 542 6999 2283 542 7000 2280 542 7001 2284 1726 7002 2282 1687 7003 2285 1689 7004 2284 1726 7005 2281 1725 7006 2282 1687 7007 2276 542 7008 2286 542 7009 2283 542 7010 2287 1727 7011 2285 1689 7012 2288 1728 7013 2287 1727 7014 2284 1726 7015 2285 1689 7016 1479 542 7017 2289 542 7018 2286 542 7019 2290 1729 7020 2291 1730 7021 2292 1731 7022 2276 542 7023 1479 542 7024 2286 542 7025 2287 1727 7026 2288 1728 7027 2293 1732 7028 1479 542 7029 2294 542 7030 2289 542 7031 2295 1733 7032 2292 1731 7033 2296 1694 7034 2295 1733 7035 2290 1729 7036 2292 1731 7037 1479 542 7038 1478 542 7039 2294 542 7040 2297 1734 7041 2296 1694 7042 2298 1735 7043 2297 1734 7044 2295 1733 7045 2296 1694 7046 2299 1736 7047 2298 1735 7048 2300 1737 7049 2299 1736 7050 2297 1734 7051 2298 1735 7052 2301 1738 7053 2300 1737 7054 2302 1739 7055 2301 1738 7056 2299 1736 7057 2300 1737 7058 2303 1740 7059 2302 1739 7060 2304 551 7061 2303 1740 7062 2301 1738 7063 2302 1739 7064 2305 1741 7065 2304 551 7066 2306 1705 7067 2305 1741 7068 2303 1740 7069 2304 551 7070 2307 1742 7071 2306 1705 7072 2263 1707 7073 2307 1742 7074 2305 1741 7075 2306 1705 7076 2262 1715 7077 2307 1742 7078 2263 1707 7079 2308 1743 7080 2309 1744 7081 2310 1745 7082 2311 1746 7083 2312 1702 7084 2313 1747 7085 2314 1748 7086 2311 1746 7087 2313 1747 7088 2315 1749 7089 2310 1745 7090 2316 1750 7091 2315 1749 7092 2308 1743 7093 2310 1745 7094 2317 1751 7095 2316 1750 7096 2318 1752 7097 2317 1751 7098 2315 1749 7099 2316 1750 7100 2319 1753 7101 2318 1752 7102 2320 1710 7103 2319 1753 7104 2317 1751 7105 2318 1752 7106 2321 1754 7107 2320 1710 7108 2322 1680 7109 2321 1754 7110 2319 1753 7111 2320 1710 7112 2323 1755 7113 2322 1680 7114 2324 11 7115 2323 1755 7116 2321 1754 7117 2322 1680 7118 1427 542 7119 2325 542 7120 1436 542 7121 2326 1756 7122 2324 11 7123 2327 1678 7124 2326 1756 7125 2323 1755 7126 2324 11 7127 1427 542 7128 2328 542 7129 2325 542 7130 2329 1757 7131 2327 1678 7132 2330 1684 7133 2329 1757 7134 2326 1756 7135 2327 1678 7136 2331 542 7137 2332 542 7138 2328 542 7139 2333 1758 7140 2330 1684 7141 2334 1759 7142 1427 542 7143 2331 542 7144 2328 542 7145 2333 1758 7146 2329 1757 7147 2330 1684 7148 2331 542 7149 2335 542 7150 2332 542 7151 2336 1760 7152 2337 1761 7153 2338 1762 7154 2333 1758 7155 2334 1759 7156 2339 1763 7157 2331 542 7158 2340 542 7159 2335 542 7160 2341 1764 7161 2338 1762 7162 2342 1765 7163 2341 1764 7164 2336 1760 7165 2338 1762 7166 2343 542 7167 2344 542 7168 2340 542 7169 2345 1766 7170 2342 1765 7171 2346 1767 7172 2331 542 7173 2343 542 7174 2340 542 7175 2345 1766 7176 2341 1764 7177 2342 1765 7178 2343 542 7179 2347 542 7180 2344 542 7181 2348 1768 7182 2346 1767 7183 2349 1731 7184 2348 1768 7185 2345 1766 7186 2346 1767 7187 2343 542 7188 2350 542 7189 2347 542 7190 2351 1769 7191 2349 1731 7192 2352 1770 7193 2351 1769 7194 2348 1768 7195 2349 1731 7196 2343 542 7197 1422 542 7198 2350 542 7199 2353 1770 7200 2352 1770 7201 2354 1735 7202 2353 1770 7203 2351 1769 7204 2352 1770 7205 2355 1771 7206 2354 1735 7207 2356 1699 7208 2343 542 7209 1423 542 7210 1422 542 7211 2355 1771 7212 2353 1770 7213 2354 1735 7214 2357 1772 7215 2356 1699 7216 2312 1702 7217 2357 1772 7218 2355 1771 7219 2356 1699 7220 2311 1746 7221 2357 1772 7222 2312 1702 7223 2358 1729 7224 2359 1730 7225 2360 1692 7226 2361 1727 7227 2362 1689 7228 2363 1728 7229 2364 1732 7230 2361 1727 7231 2363 1728 7232 2365 1733 7233 2360 1692 7234 2366 1694 7235 2365 1733 7236 2358 1729 7237 2360 1692 7238 2367 1734 7239 2366 1694 7240 2368 1735 7241 2367 1734 7242 2365 1733 7243 2366 1694 7244 728 542 7245 2369 542 7246 727 542 7247 2370 1736 7248 2368 1735 7249 2371 1737 7250 2370 1736 7251 2367 1734 7252 2368 1735 7253 728 542 7254 2372 542 7255 2369 542 7256 2373 1738 7257 2371 1737 7258 2374 1739 7259 2373 1738 7260 2370 1736 7261 2371 1737 7262 2375 542 7263 2376 542 7264 2372 542 7265 2377 1740 7266 2374 1739 7267 2378 551 7268 728 542 7269 2375 542 7270 2372 542 7271 2377 1740 7272 2373 1738 7273 2374 1739 7274 2375 542 7275 2379 542 7276 2376 542 7277 2380 1741 7278 2378 551 7279 2381 1705 7280 2380 1741 7281 2377 1740 7282 2378 551 7283 2375 542 7284 2382 542 7285 2379 542 7286 2383 1742 7287 2381 1705 7288 2384 1707 7289 2383 1742 7290 2380 1741 7291 2381 1705 7292 2375 542 7293 2385 542 7294 2382 542 7295 2386 1715 7296 2384 1707 7297 2387 1716 7298 2386 1715 7299 2383 1742 7300 2384 1707 7301 717 542 7302 2388 542 7303 2385 542 7304 2389 1712 7305 2390 1713 7306 2391 1710 7307 2375 542 7308 717 542 7309 2385 542 7310 2386 1715 7311 2387 1716 7312 2392 1717 7313 717 542 7314 2393 542 7315 2388 542 7316 2394 1718 7317 2391 1710 7318 2395 1680 7319 2394 1718 7320 2389 1712 7321 2391 1710 7322 717 542 7323 716 542 7324 2393 542 7325 2396 1719 7326 2395 1680 7327 2397 11 7328 2396 1719 7329 2394 1718 7330 2395 1680 7331 2398 1720 7332 2397 11 7333 2399 1721 7334 2398 1720 7335 2396 1719 7336 2397 11 7337 2400 1722 7338 2399 1721 7339 2401 1723 7340 2400 1722 7341 2398 1720 7342 2399 1721 7343 2402 1724 7344 2401 1723 7345 2403 1119 7346 2402 1724 7347 2400 1722 7348 2401 1723 7349 2404 1725 7350 2403 1119 7351 2405 1687 7352 2404 1725 7353 2402 1724 7354 2403 1119 7355 2406 1726 7356 2405 1687 7357 2362 1689 7358 2406 1726 7359 2404 1725 7360 2405 1687 7361 2361 1727 7362 2406 1726 7363 2362 1689 7364 2407 1760 7365 2408 1761 7366 2409 1762 7367 2410 1758 7368 2411 1684 7369 2412 1759 7370 2413 1763 7371 2410 1758 7372 2412 1759 7373 2414 1764 7374 2409 1762 7375 2415 1765 7376 2414 1764 7377 2407 1760 7378 2409 1762 7379 2416 1766 7380 2415 1765 7381 2417 1767 7382 2416 1766 7383 2414 1764 7384 2415 1765 7385 2418 1768 7386 2417 1767 7387 2419 1731 7388 2418 1768 7389 2416 1766 7390 2417 1767 7391 2420 1769 7392 2419 1731 7393 2421 1694 7394 2420 1769 7395 2418 1768 7396 2419 1731 7397 2422 1773 7398 2421 1694 7399 2423 1735 7400 2422 1773 7401 2420 1769 7402 2421 1694 7403 658 542 7404 2424 542 7405 667 542 7406 2425 1771 7407 2423 1735 7408 2426 1699 7409 2425 1771 7410 2422 1773 7411 2423 1735 7412 658 542 7413 2427 542 7414 2424 542 7415 2428 1772 7416 2426 1699 7417 2429 1702 7418 2428 1772 7419 2425 1771 7420 2426 1699 7421 2430 542 7422 2431 542 7423 2427 542 7424 2432 1746 7425 2429 1702 7426 2433 1747 7427 658 542 7428 2430 542 7429 2427 542 7430 2432 1746 7431 2428 1772 7432 2429 1702 7433 2430 542 7434 2434 542 7435 2431 542 7436 2435 1743 7437 2436 1744 7438 2437 1745 7439 2432 1746 7440 2433 1747 7441 2438 1748 7442 2430 542 7443 2439 542 7444 2434 542 7445 2440 1749 7446 2437 1745 7447 2441 1750 7448 2440 1749 7449 2435 1743 7450 2437 1745 7451 2442 542 7452 2443 542 7453 2439 542 7454 2444 1751 7455 2441 1750 7456 2445 1752 7457 2430 542 7458 2442 542 7459 2439 542 7460 2444 1751 7461 2440 1749 7462 2441 1750 7463 2442 542 7464 2446 542 7465 2443 542 7466 2447 1753 7467 2445 1752 7468 2448 1710 7469 2447 1753 7470 2444 1751 7471 2445 1752 7472 2442 542 7473 2449 542 7474 2446 542 7475 2450 1754 7476 2448 1710 7477 2451 1774 7478 2450 1754 7479 2447 1753 7480 2448 1710 7481 2442 542 7482 653 542 7483 2449 542 7484 2452 1774 7485 2451 1774 7486 2453 11 7487 2452 1774 7488 2450 1754 7489 2451 1774 7490 2454 1756 7491 2453 11 7492 2455 1678 7493 2442 542 7494 654 542 7495 653 542 7496 2454 1756 7497 2452 1774 7498 2453 11 7499 2456 1757 7500 2455 1678 7501 2411 1684 7502 2456 1757 7503 2454 1756 7504 2455 1678 7505 2410 1758 7506 2456 1757 7507 2411 1684 7508 2457 1698 7509 2458 1775 7510 2459 1699 7511 1509 542 7512 1508 542 7513 2460 542 7514 2461 1694 7515 2462 1770 7516 2463 1696 7517 2461 1694 7518 2463 1696 7519 2464 1776 7520 2465 1737 7521 2459 1699 7522 2466 1739 7523 2457 1698 7524 2459 1699 7525 2465 1737 7526 2467 1739 7527 2466 1739 7528 2468 551 7529 2465 1737 7530 2466 1739 7531 2467 1739 7532 2469 551 7533 2468 551 7534 2470 1705 7535 2467 1739 7536 2468 551 7537 2469 551 7538 2471 1745 7539 2470 1705 7540 2472 1707 7541 2469 551 7542 2470 1705 7543 2471 1745 7544 2473 1707 7545 2472 1707 7546 2474 560 7547 2471 1745 7548 2472 1707 7549 2473 1707 7550 2475 560 7551 2474 560 7552 2476 1710 7553 2473 1707 7554 2474 560 7555 2475 560 7556 2477 1710 7557 2476 1710 7558 2478 1774 7559 2475 560 7560 2476 1710 7561 2477 1710 7562 2479 1774 7563 2478 1774 7564 2480 1681 7565 2477 1710 7566 2478 1774 7567 2479 1774 7568 2481 542 7569 2482 542 7570 1528 542 7571 2483 1677 7572 2484 1777 7573 2485 1721 7574 2244 542 7575 2481 542 7576 1528 542 7577 2479 1774 7578 2480 1681 7579 2486 1778 7580 2487 542 7581 2488 542 7582 2482 542 7583 2489 1721 7584 2485 1721 7585 2490 1723 7586 2491 542 7587 2487 542 7588 2482 542 7589 2481 542 7590 2491 542 7591 2482 542 7592 2489 1721 7593 2483 1677 7594 2485 1721 7595 2492 542 7596 2493 542 7597 2488 542 7598 2494 1723 7599 2490 1723 7600 2495 1119 7601 2487 542 7602 2492 542 7603 2488 542 7604 2489 1721 7605 2490 1723 7606 2494 1723 7607 2496 542 7608 2497 542 7609 2493 542 7610 2498 1119 7611 2495 1119 7612 2499 1687 7613 2492 542 7614 2496 542 7615 2493 542 7616 2494 1723 7617 2495 1119 7618 2498 1119 7619 2500 542 7620 2501 542 7621 2497 542 7622 2502 1687 7623 2499 1687 7624 2503 1765 7625 2496 542 7626 2500 542 7627 2497 542 7628 2498 1119 7629 2499 1687 7630 2502 1687 7631 2504 542 7632 2505 542 7633 2501 542 7634 2506 1689 7635 2503 1765 7636 2507 1128 7637 2500 542 7638 2504 542 7639 2501 542 7640 2502 1687 7641 2503 1765 7642 2506 1689 7643 2504 542 7644 2508 542 7645 2505 542 7646 2509 1128 7647 2507 1128 7648 2510 1731 7649 2506 1689 7650 2507 1128 7651 2509 1128 7652 1509 542 7653 2460 542 7654 2508 542 7655 2511 1731 7656 2510 1731 7657 2462 1770 7658 2504 542 7659 1509 542 7660 2508 542 7661 2509 1128 7662 2510 1731 7663 2511 1731 7664 2511 1731 7665 2462 1770 7666 2461 1694 7667 2512 542 7668 2513 542 7669 2514 542 7670 2515 1713 7671 2516 1713 7672 2517 1710 7673 2512 542 7674 2514 542 7675 2518 542 7676 2519 1707 7677 2520 1707 7678 2521 1716 7679 2519 1707 7680 2521 1716 7681 2522 1716 7682 678 542 7683 2523 542 7684 2513 542 7685 2524 1710 7686 2517 1710 7687 2525 1680 7688 2512 542 7689 678 542 7690 2513 542 7691 2515 1713 7692 2517 1710 7693 2524 1710 7694 678 542 7695 2526 542 7696 2523 542 7697 2527 1680 7698 2525 1680 7699 2528 11 7700 2524 1710 7701 2525 1680 7702 2527 1680 7703 678 542 7704 694 542 7705 2526 542 7706 2529 11 7707 2528 11 7708 2530 1678 7709 2527 1680 7710 2528 11 7711 2529 11 7712 2531 1678 7713 2530 1678 7714 2532 1684 7715 2529 11 7716 2530 1678 7717 2531 1678 7718 2533 1684 7719 2532 1684 7720 2534 1119 7721 2531 1678 7722 2532 1684 7723 2533 1684 7724 2535 1119 7725 2534 1119 7726 2536 1687 7727 2533 1684 7728 2534 1119 7729 2535 1119 7730 2537 1687 7731 2536 1687 7732 2538 1689 7733 2535 1119 7734 2536 1687 7735 2537 1687 7736 2539 1689 7737 2538 1689 7738 2540 1728 7739 2537 1687 7740 2538 1689 7741 2539 1689 7742 2541 1730 7743 2542 1730 7744 2543 1692 7745 2539 1689 7746 2540 1728 7747 2544 1728 7748 2545 1692 7749 2543 1692 7750 2546 1694 7751 2545 1692 7752 2541 1730 7753 2543 1692 7754 2547 1694 7755 2546 1694 7756 2548 1735 7757 2545 1692 7758 2546 1694 7759 2547 1694 7760 2549 542 7761 2550 542 7762 704 542 7763 2551 1735 7764 2548 1735 7765 2552 1699 7766 705 542 7767 2549 542 7768 704 542 7769 2547 1694 7770 2548 1735 7771 2551 1735 7772 2549 542 7773 2553 542 7774 2550 542 7775 2554 1699 7776 2552 1699 7777 2555 1739 7778 2551 1735 7779 2552 1699 7780 2554 1699 7781 2549 542 7782 2556 542 7783 2553 542 7784 2557 1739 7785 2555 1739 7786 2558 551 7787 2554 1699 7788 2555 1739 7789 2557 1739 7790 2512 542 7791 2559 542 7792 2556 542 7793 2560 551 7794 2558 551 7795 2561 1705 7796 2549 542 7797 2512 542 7798 2556 542 7799 2557 1739 7800 2558 551 7801 2560 551 7802 2512 542 7803 2518 542 7804 2559 542 7805 2562 1705 7806 2561 1705 7807 2520 1707 7808 2560 551 7809 2561 1705 7810 2562 1705 7811 2562 1705 7812 2520 1707 7813 2519 1707 7814 1441 542 7815 1439 542 7816 2563 542 7817 2564 1779 7818 2565 1779 7819 2566 1780 7820 2567 1781 7821 2568 1781 7822 2569 1782 7823 2567 1781 7824 2569 1782 7825 2570 1782 7826 2571 1780 7827 2566 1780 7828 2572 1783 7829 2564 1779 7830 2566 1780 7831 2571 1780 7832 2573 1783 7833 2572 1783 7834 2574 1784 7835 2571 1780 7836 2572 1783 7837 2573 1783 7838 2575 1784 7839 2574 1784 7840 2576 1785 7841 2573 1783 7842 2574 1784 7843 2575 1784 7844 2577 1785 7845 2576 1785 7846 2578 1786 7847 2575 1784 7848 2576 1785 7849 2577 1785 7850 2579 1786 7851 2578 1786 7852 2580 1787 7853 2577 1785 7854 2578 1786 7855 2579 1786 7856 2581 1787 7857 2580 1787 7858 2582 1788 7859 2579 1786 7860 2580 1787 7861 2581 1787 7862 2583 1789 7863 2584 1789 7864 2585 1790 7865 2581 1787 7866 2582 1788 7867 2586 1788 7868 2587 1790 7869 2585 1790 7870 2588 1791 7871 2583 1789 7872 2585 1790 7873 2587 1790 7874 2589 1791 7875 2588 1791 7876 2590 1792 7877 2587 1790 7878 2588 1791 7879 2589 1791 7880 2591 1793 7881 2592 1793 7882 2593 1794 7883 2589 1791 7884 2590 1792 7885 2594 1792 7886 2595 1794 7887 2593 1794 7888 2596 1795 7889 2591 1793 7890 2593 1794 7891 2595 1794 7892 2597 1795 7893 2596 1795 7894 2598 1796 7895 2595 1794 7896 2596 1795 7897 2597 1795 7898 2599 1796 7899 2598 1796 7900 2600 1797 7901 2597 1795 7902 2598 1796 7903 2599 1796 7904 2601 1797 7905 2600 1797 7906 2602 1798 7907 2599 1796 7908 2600 1797 7909 2601 1797 7910 2603 1798 7911 2602 1798 7912 2604 558 7913 2601 1797 7914 2602 1798 7915 2603 1798 7916 2605 558 7917 2604 558 7918 2606 1799 7919 2603 1798 7920 2604 558 7921 2605 558 7922 2607 1799 7923 2606 1799 7924 2608 1800 7925 2605 558 7926 2606 1799 7927 2607 1799 7928 2609 1800 7929 2608 1800 7930 2610 1801 7931 2607 1799 7932 2608 1800 7933 2609 1800 7934 2611 1801 7935 2610 1801 7936 2612 1802 7937 2609 1800 7938 2610 1801 7939 2611 1801 7940 2613 1802 7941 2612 1802 7942 2614 1803 7943 2611 1801 7944 2612 1802 7945 2613 1802 7946 2615 1803 7947 2614 1803 7948 2616 1804 7949 2613 1802 7950 2614 1803 7951 2615 1803 7952 2617 1805 7953 2618 1805 7954 2619 1806 7955 2615 1803 7956 2616 1804 7957 2620 1804 7958 2621 1806 7959 2619 1806 7960 2622 1807 7961 2617 1805 7962 2619 1806 7963 2621 1806 7964 2623 1807 7965 2622 1807 7966 2624 1808 7967 2621 1806 7968 2622 1807 7969 2623 1807 7970 2625 1809 7971 2626 1809 7972 2627 1810 7973 2623 1807 7974 2624 1808 7975 2628 1808 7976 2629 1810 7977 2627 1810 7978 2630 1811 7979 2625 1809 7980 2627 1810 7981 2629 1810 7982 2631 1811 7983 2630 1811 7984 2632 1812 7985 2629 1810 7986 2630 1811 7987 2631 1811 7988 2633 1812 7989 2632 1812 7990 2634 1813 7991 2631 1811 7992 2632 1812 7993 2633 1812 7994 2635 1813 7995 2634 1813 7996 2636 1814 7997 2633 1812 7998 2634 1813 7999 2635 1813 8000 2637 1814 8001 2636 1814 8002 2638 1815 8003 2635 1813 8004 2636 1814 8005 2637 1814 8006 2639 542 8007 2640 542 8008 1510 542 8009 2641 1815 8010 2638 1815 8011 2642 1816 8012 1511 542 8013 2639 542 8014 1510 542 8015 2637 1814 8016 2638 1815 8017 2641 1815 8018 2643 542 8019 2644 542 8020 2640 542 8021 2645 1817 8022 2646 1817 8023 2647 1818 8024 2639 542 8025 2643 542 8026 2640 542 8027 2641 1815 8028 2642 1816 8029 2648 1816 8030 2649 1818 8031 2647 1818 8032 2650 1819 8033 2645 1817 8034 2647 1818 8035 2649 1818 8036 2651 1819 8037 2650 1819 8038 2652 1820 8039 2649 1818 8040 2650 1819 8041 2651 1819 8042 2653 1821 8043 2654 1821 8044 2655 1822 8045 2651 1819 8046 2652 1820 8047 2656 1820 8048 2657 1822 8049 2655 1822 8050 2658 1823 8051 2653 1821 8052 2655 1822 8053 2657 1822 8054 2659 1823 8055 2658 1823 8056 2660 1824 8057 2657 1822 8058 2658 1823 8059 2659 1823 8060 2661 1824 8061 2660 1824 8062 2662 1825 8063 2659 1823 8064 2660 1824 8065 2661 1824 8066 2663 1825 8067 2662 1825 8068 2664 1826 8069 2661 1824 8070 2662 1825 8071 2663 1825 8072 2665 1826 8073 2664 1826 8074 2666 566 8075 2663 1825 8076 2664 1826 8077 2665 1826 8078 2667 566 8079 2666 566 8080 2668 1827 8081 2665 1826 8082 2666 566 8083 2667 566 8084 2669 1827 8085 2668 1827 8086 2670 1828 8087 2667 566 8088 2668 1827 8089 2669 1827 8090 2671 1828 8091 2670 1828 8092 2672 1829 8093 2669 1827 8094 2670 1828 8095 2671 1828 8096 2673 1829 8097 2672 1829 8098 2674 1830 8099 2671 1828 8100 2672 1829 8101 2673 1829 8102 2675 542 8103 2676 542 8104 2481 542 8105 2677 1830 8106 2674 1830 8107 2678 1831 8108 2244 542 8109 2675 542 8110 2481 542 8111 2673 1829 8112 2674 1830 8113 2677 1830 8114 2679 542 8115 2680 542 8116 2676 542 8117 2681 1831 8118 2678 1831 8119 2682 1832 8120 2683 542 8121 2679 542 8122 2676 542 8123 2675 542 8124 2683 542 8125 2676 542 8126 2677 1830 8127 2678 1831 8128 2681 1831 8129 2684 1833 8130 2685 1833 8131 2686 1834 8132 2681 1831 8133 2682 1832 8134 2687 1832 8135 2688 1834 8136 2686 1834 8137 2689 1835 8138 2684 1833 8139 2686 1834 8140 2688 1834 8141 2690 1835 8142 2689 1835 8143 2691 1836 8144 2688 1834 8145 2689 1835 8146 2690 1835 8147 2692 1837 8148 2693 1837 8149 2694 1838 8150 2690 1835 8151 2691 1836 8152 2695 1836 8153 2696 1838 8154 2694 1838 8155 2697 1839 8156 2692 1837 8157 2694 1838 8158 2696 1838 8159 2698 1839 8160 2697 1839 8161 2699 1840 8162 2696 1838 8163 2697 1839 8164 2698 1839 8165 2700 1840 8166 2699 1840 8167 2701 1841 8168 2698 1839 8169 2699 1840 8170 2700 1840 8171 2702 1841 8172 2701 1841 8173 2703 1842 8174 2700 1840 8175 2701 1841 8176 2702 1841 8177 2704 1842 8178 2703 1842 8179 2705 1843 8180 2702 1841 8181 2703 1842 8182 2704 1842 8183 2706 1844 8184 2705 1843 8185 2707 1845 8186 2704 1842 8187 2705 1843 8188 2706 1844 8189 2708 1846 8190 2709 1846 8191 2710 1847 8192 2706 1844 8193 2707 1845 8194 2711 1845 8195 2712 1848 8196 2710 1847 8197 2713 1849 8198 2708 1846 8199 2710 1847 8200 2712 1848 8201 2714 1849 8202 2713 1849 8203 2715 1850 8204 2712 1848 8205 2713 1849 8206 2714 1849 8207 2716 1851 8208 2717 1851 8209 2718 1852 8210 2714 1849 8211 2715 1850 8212 2719 1850 8213 2720 1852 8214 2718 1852 8215 2721 1853 8216 2716 1851 8217 2718 1852 8218 2720 1852 8219 2722 1853 8220 2721 1853 8221 2723 1854 8222 2720 1852 8223 2721 1853 8224 2722 1853 8225 2724 1854 8226 2723 1854 8227 2725 1855 8228 2722 1853 8229 2723 1854 8230 2724 1854 8231 2726 1855 8232 2725 1855 8233 2727 1856 8234 2724 1854 8235 2725 1855 8236 2726 1855 8237 2728 1856 8238 2727 1856 8239 2729 1117 8240 2726 1855 8241 2727 1856 8242 2728 1856 8243 2730 1117 8244 2729 1117 8245 2731 1857 8246 2728 1856 8247 2729 1117 8248 2730 1117 8249 2732 1857 8250 2731 1857 8251 2733 1858 8252 2730 1117 8253 2731 1857 8254 2732 1857 8255 2734 1859 8256 2733 1858 8257 2735 1860 8258 2732 1857 8259 2733 1858 8260 2734 1859 8261 2736 1860 8262 2735 1860 8263 2737 1861 8264 2734 1859 8265 2735 1860 8266 2736 1860 8267 2738 1861 8268 2737 1861 8269 2739 1862 8270 2736 1860 8271 2737 1861 8272 2738 1861 8273 2740 1862 8274 2739 1862 8275 2741 1863 8276 2738 1861 8277 2739 1862 8278 2740 1862 8279 2742 1864 8280 2743 1864 8281 2744 1865 8282 2740 1862 8283 2741 1863 8284 2745 1863 8285 2746 1865 8286 2744 1865 8287 2747 1866 8288 2742 1864 8289 2744 1865 8290 2746 1865 8291 670 542 8292 2748 542 8293 675 542 8294 2749 1866 8295 2747 1866 8296 2750 1867 8297 2746 1865 8298 2747 1866 8299 2749 1866 8300 2751 1868 8301 2752 1868 8302 2753 1869 8303 2749 1866 8304 2750 1867 8305 2754 1867 8306 2755 1869 8307 2753 1869 8308 2756 1870 8309 2751 1868 8310 2753 1869 8311 2755 1869 8312 2757 1870 8313 2756 1870 8314 2758 1871 8315 2755 1869 8316 2756 1870 8317 2757 1870 8318 2759 1871 8319 2758 1871 8320 2760 1872 8321 2757 1870 8322 2758 1871 8323 2759 1871 8324 2761 1872 8325 2760 1872 8326 2762 1873 8327 2759 1871 8328 2760 1872 8329 2761 1872 8330 2763 1873 8331 2762 1873 8332 2764 1874 8333 2761 1872 8334 2762 1873 8335 2763 1873 8336 2765 1874 8337 2764 1874 8338 2766 1875 8339 2763 1873 8340 2764 1874 8341 2765 1874 8342 2767 1876 8343 2768 1876 8344 2769 1877 8345 2765 1874 8346 2766 1875 8347 2770 1875 8348 2771 1877 8349 2769 1877 8350 2772 1878 8351 2767 1876 8352 2769 1877 8353 2771 1877 8354 2773 1878 8355 2772 1878 8356 2774 1879 8357 2771 1877 8358 2772 1878 8359 2773 1878 8360 2775 1880 8361 2776 1880 8362 2777 1881 8363 2773 1878 8364 2774 1879 8365 2778 1879 8366 2779 1881 8367 2777 1881 8368 2780 1882 8369 2775 1880 8370 2777 1881 8371 2779 1881 8372 2781 1882 8373 2780 1882 8374 2782 1883 8375 2779 1881 8376 2780 1882 8377 2781 1882 8378 2783 1883 8379 2782 1883 8380 2784 1884 8381 2781 1882 8382 2782 1883 8383 2783 1883 8384 2785 1884 8385 2784 1884 8386 2786 1885 8387 2783 1883 8388 2784 1884 8389 2785 1884 8390 2787 1885 8391 2786 1885 8392 2788 1126 8393 2785 1884 8394 2786 1885 8395 2787 1885 8396 2789 1126 8397 2788 1126 8398 2790 1886 8399 2787 1885 8400 2788 1126 8401 2789 1126 8402 2791 1886 8403 2790 1886 8404 2792 1887 8405 2789 1126 8406 2790 1886 8407 2791 1886 8408 2793 1887 8409 2792 1887 8410 2794 1888 8411 2791 1886 8412 2792 1887 8413 2793 1887 8414 2795 1888 8415 2794 1888 8416 2796 1889 8417 2793 1887 8418 2794 1888 8419 2795 1888 8420 2797 1889 8421 2796 1889 8422 2798 1890 8423 2795 1888 8424 2796 1889 8425 2797 1889 8426 2799 1890 8427 2798 1890 8428 2800 1891 8429 2797 1889 8430 2798 1890 8431 2799 1890 8432 2801 1892 8433 2802 1892 8434 2803 1893 8435 2799 1890 8436 2800 1891 8437 2804 1891 8438 2805 1893 8439 2803 1893 8440 2806 1894 8441 2801 1892 8442 2803 1893 8443 2805 1893 8444 2807 1894 8445 2806 1894 8446 2808 1895 8447 2805 1893 8448 2806 1894 8449 2807 1894 8450 2809 1896 8451 2810 1896 8452 2811 1897 8453 2807 1894 8454 2808 1895 8455 2812 1895 8456 2813 1897 8457 2811 1897 8458 2814 1898 8459 2809 1896 8460 2811 1897 8461 2813 1897 8462 2815 1898 8463 2814 1898 8464 2816 1899 8465 2813 1897 8466 2814 1898 8467 2815 1898 8468 2817 1899 8469 2816 1899 8470 2818 1900 8471 2815 1898 8472 2816 1899 8473 2817 1899 8474 2819 1900 8475 2818 1900 8476 2820 1901 8477 2817 1899 8478 2818 1900 8479 2819 1900 8480 2821 1901 8481 2820 1901 8482 2822 1902 8483 2819 1900 8484 2820 1901 8485 2821 1901 8486 2823 542 8487 2824 542 8488 746 542 8489 2825 1902 8490 2822 1902 8491 2826 1903 8492 747 542 8493 2823 542 8494 746 542 8495 2821 1901 8496 2822 1902 8497 2825 1902 8498 2827 542 8499 2828 542 8500 2824 542 8501 2829 1904 8502 2830 1904 8503 2831 1905 8504 2823 542 8505 2827 542 8506 2824 542 8507 2825 1902 8508 2826 1903 8509 2832 1903 8510 2833 1905 8511 2831 1905 8512 2834 1906 8513 2829 1904 8514 2831 1905 8515 2833 1905 8516 2835 1906 8517 2834 1906 8518 2836 1907 8519 2833 1905 8520 2834 1906 8521 2835 1906 8522 2837 1908 8523 2838 1908 8524 2839 1909 8525 2835 1906 8526 2836 1907 8527 2840 1907 8528 2841 1909 8529 2839 1909 8530 2842 1910 8531 2837 1908 8532 2839 1909 8533 2841 1909 8534 2843 1910 8535 2842 1910 8536 2844 1911 8537 2841 1909 8538 2842 1910 8539 2843 1910 8540 2845 1911 8541 2844 1911 8542 2846 1912 8543 2843 1910 8544 2844 1911 8545 2845 1911 8546 2847 1912 8547 2846 1912 8548 2848 1913 8549 2845 1911 8550 2846 1912 8551 2847 1912 8552 2849 1914 8553 2848 1913 8554 2850 1134 8555 2847 1912 8556 2848 1913 8557 2849 1914 8558 2851 1134 8559 2850 1134 8560 2852 1915 8561 2849 1914 8562 2850 1134 8563 2851 1134 8564 2853 1916 8565 2852 1915 8566 2854 1917 8567 2851 1134 8568 2852 1915 8569 2853 1916 8570 2855 1917 8571 2854 1917 8572 2856 1918 8573 2853 1916 8574 2854 1917 8575 2855 1917 8576 2857 1918 8577 2856 1918 8578 2858 1919 8579 2855 1917 8580 2856 1918 8581 2857 1918 8582 2859 542 8583 2860 542 8584 764 542 8585 2861 1919 8586 2858 1919 8587 2862 1920 8588 765 542 8589 2859 542 8590 764 542 8591 2857 1918 8592 2858 1919 8593 2861 1919 8594 2863 542 8595 2864 542 8596 2860 542 8597 2865 1920 8598 2862 1920 8599 2866 1921 8600 2867 542 8601 2863 542 8602 2860 542 8603 2859 542 8604 2867 542 8605 2860 542 8606 2861 1919 8607 2862 1920 8608 2865 1920 8609 2868 1922 8610 2869 1922 8611 2870 1923 8612 2865 1920 8613 2866 1921 8614 2871 1921 8615 2872 1923 8616 2870 1923 8617 2873 1924 8618 2868 1922 8619 2870 1923 8620 2872 1923 8621 2874 1924 8622 2873 1924 8623 2875 1925 8624 2872 1923 8625 2873 1924 8626 2874 1924 8627 2876 1926 8628 2877 1926 8629 2878 1927 8630 2874 1924 8631 2875 1925 8632 2879 1925 8633 2880 1927 8634 2878 1927 8635 2881 1928 8636 2876 1926 8637 2878 1927 8638 2880 1927 8639 2882 1928 8640 2881 1928 8641 2883 1929 8642 2880 1927 8643 2881 1928 8644 2882 1928 8645 2884 1929 8646 2883 1929 8647 2885 1930 8648 2882 1928 8649 2883 1929 8650 2884 1929 8651 2886 1930 8652 2885 1930 8653 2887 1931 8654 2884 1929 8655 2885 1930 8656 2886 1930 8657 2888 1931 8658 2887 1931 8659 2889 1932 8660 2886 1930 8661 2887 1931 8662 2888 1931 8663 2890 1933 8664 2889 1932 8665 2891 1934 8666 2888 1931 8667 2889 1932 8668 2890 1933 8669 2892 1935 8670 2893 1935 8671 2894 1936 8672 2890 1933 8673 2891 1934 8674 2895 1934 8675 2896 1937 8676 2894 1936 8677 2897 1938 8678 2892 1935 8679 2894 1936 8680 2896 1937 8681 2898 1938 8682 2897 1938 8683 2899 1939 8684 2896 1937 8685 2897 1938 8686 2898 1938 8687 2900 1940 8688 2901 1940 8689 2902 1941 8690 2898 1938 8691 2899 1939 8692 2903 1939 8693 2904 1941 8694 2902 1941 8695 2905 1942 8696 2904 1941 8697 2900 1940 8698 2902 1941 8699 2906 1942 8700 2905 1942 8701 2907 1943 8702 2904 1941 8703 2905 1942 8704 2906 1942 8705 2908 1943 8706 2907 1943 8707 2909 1944 8708 2906 1942 8709 2907 1943 8710 2908 1943 8711 2910 1944 8712 2909 1944 8713 2911 1945 8714 2908 1943 8715 2909 1944 8716 2910 1944 8717 2912 1945 8718 2911 1945 8719 2913 549 8720 2910 1944 8721 2911 1945 8722 2912 1945 8723 2914 549 8724 2913 549 8725 2915 1946 8726 2912 1945 8727 2913 549 8728 2914 549 8729 2916 1946 8730 2915 1946 8731 2917 1947 8732 2914 549 8733 2915 1946 8734 2916 1946 8735 2918 1947 8736 2917 1947 8737 2919 1948 8738 2916 1946 8739 2917 1947 8740 2918 1947 8741 2920 1948 8742 2919 1948 8743 2921 1949 8744 2918 1947 8745 2919 1948 8746 2920 1948 8747 2922 1949 8748 2921 1949 8749 2923 1950 8750 2920 1948 8751 2921 1949 8752 2922 1949 8753 2924 1950 8754 2923 1950 8755 2925 1951 8756 2922 1949 8757 2923 1950 8758 2924 1950 8759 2926 1952 8760 2927 1952 8761 2928 1953 8762 2924 1950 8763 2925 1951 8764 2929 1951 8765 2930 1953 8766 2928 1953 8767 2568 1781 8768 2926 1952 8769 2928 1953 8770 2930 1953 8771 2930 1953 8772 2568 1781 8773 2567 1781 8774 2931 1479 8775 2932 1479 8776 2933 1954 8777 2934 1484 8778 2935 1484 8779 2936 1955 8780 2934 1484 8781 2936 1955 8782 2937 1955 8783 2938 1954 8784 2933 1954 8785 2939 1956 8786 2938 1954 8787 2931 1479 8788 2933 1954 8789 2940 1956 8790 2939 1956 8791 2941 1957 8792 2938 1954 8793 2939 1956 8794 2940 1956 8795 2942 1957 8796 2941 1957 8797 2943 1958 8798 2940 1956 8799 2941 1957 8800 2942 1957 8801 2944 1959 8802 2943 1958 8803 2945 1960 8804 2942 1957 8805 2943 1958 8806 2944 1959 8807 2946 1130 8808 2945 1960 8809 2947 1961 8810 2944 1959 8811 2945 1960 8812 2946 1130 8813 2948 1962 8814 2947 1961 8815 2949 1963 8816 2946 1130 8817 2947 1961 8818 2948 1962 8819 2950 1964 8820 2949 1963 8821 2951 1965 8822 2948 1962 8823 2949 1963 8824 2950 1964 8825 2952 1965 8826 2951 1965 8827 2953 1966 8828 2950 1964 8829 2951 1965 8830 2952 1965 8831 2954 1967 8832 2953 1966 8833 2955 1123 8834 2952 1965 8835 2953 1966 8836 2954 1967 8837 2956 1123 8838 2955 1123 8839 2957 1968 8840 2954 1967 8841 2955 1123 8842 2956 1123 8843 2958 1969 8844 2957 1968 8845 2959 1970 8846 2956 1123 8847 2957 1968 8848 2958 1969 8849 2960 1970 8850 2959 1970 8851 2961 1971 8852 2958 1969 8853 2959 1970 8854 2960 1970 8855 2962 1972 8856 2961 1971 8857 2963 1973 8858 2960 1970 8859 2961 1971 8860 2962 1972 8861 2964 1974 8862 2963 1973 8863 2965 1117 8864 2962 1972 8865 2963 1973 8866 2964 1974 8867 2966 1117 8868 2965 1117 8869 2967 1975 8870 2964 1974 8871 2965 1117 8872 2966 1117 8873 2968 1976 8874 2967 1975 8875 2969 1977 8876 2966 1117 8877 2967 1975 8878 2968 1976 8879 2970 1977 8880 2969 1977 8881 2971 1978 8882 2968 1976 8883 2969 1977 8884 2970 1977 8885 2972 1978 8886 2971 1978 8887 2973 1979 8888 2970 1977 8889 2971 1978 8890 2972 1978 8891 2974 1979 8892 2973 1979 8893 2975 1980 8894 2972 1978 8895 2973 1979 8896 2974 1979 8897 2976 1981 8898 2977 1981 8899 2978 1982 8900 2974 1979 8901 2975 1980 8902 2979 1980 8903 2980 1982 8904 2978 1982 8905 2981 1983 8906 2976 1981 8907 2978 1982 8908 2980 1982 8909 2982 1983 8910 2981 1983 8911 2983 1984 8912 2980 1982 8913 2981 1983 8914 2982 1983 8915 2984 1984 8916 2983 1984 8917 2985 1985 8918 2982 1983 8919 2983 1984 8920 2984 1984 8921 2986 1986 8922 2985 1985 8923 2987 1987 8924 2984 1984 8925 2985 1985 8926 2986 1986 8927 2988 562 8928 2987 1987 8929 2989 1988 8930 2986 1986 8931 2987 1987 8932 2988 562 8933 2990 1989 8934 2989 1988 8935 2991 1990 8936 2988 562 8937 2989 1988 8938 2990 1989 8939 2992 1991 8940 2991 1990 8941 2993 1992 8942 2990 1989 8943 2991 1990 8944 2992 1991 8945 2994 1992 8946 2993 1992 8947 2995 1993 8948 2992 1991 8949 2993 1992 8950 2994 1992 8951 2996 1994 8952 2995 1993 8953 2997 555 8954 2994 1992 8955 2995 1993 8956 2996 1994 8957 2998 555 8958 2997 555 8959 2999 1995 8960 2996 1994 8961 2997 555 8962 2998 555 8963 3000 1996 8964 2999 1995 8965 3001 1997 8966 2998 555 8967 2999 1995 8968 3000 1996 8969 3002 1997 8970 3001 1997 8971 3003 1998 8972 3000 1996 8973 3001 1997 8974 3002 1997 8975 3004 1999 8976 3003 1998 8977 3005 2000 8978 3002 1997 8979 3003 1998 8980 3004 1999 8981 3006 2001 8982 3005 2000 8983 3007 549 8984 3004 1999 8985 3005 2000 8986 3006 2001 8987 3008 549 8988 3007 549 8989 3009 2002 8990 3006 2001 8991 3007 549 8992 3008 549 8993 3010 2003 8994 3009 2002 8995 3011 2004 8996 3008 549 8997 3009 2002 8998 3010 2003 8999 3012 2004 9000 3011 2004 9001 3013 2005 9002 3010 2003 9003 3011 2004 9004 3012 2004 9005 3014 2005 9006 3013 2005 9007 2935 1484 9008 3012 2004 9009 3013 2005 9010 3014 2005 9011 3014 2005 9012 2935 1484 9013 2934 1484 9014 3015 31 9015 3016 31 9016 3017 31 9017 3018 2006 9018 3019 2006 9019 3020 2007 9020 3021 31 9021 3017 31 9022 3022 31 9023 3023 2008 9024 3024 2008 9025 3025 2009 9026 3021 31 9027 3015 31 9028 3017 31 9029 3023 2008 9030 3025 2009 9031 3026 2009 9032 3015 31 9033 3027 31 9034 3016 31 9035 3028 2007 9036 3020 2007 9037 3029 1698 9038 3018 2006 9039 3020 2007 9040 3028 2007 9041 3030 31 9042 3031 31 9043 3027 31 9044 3032 1698 9045 3029 1698 9046 3033 2010 9047 3015 31 9048 3030 31 9049 3027 31 9050 3028 2007 9051 3029 1698 9052 3032 1698 9053 3030 2011 9054 3034 2011 9055 3031 2011 9056 3035 2010 9057 3033 2010 9058 3036 1737 9059 3032 1698 9060 3033 2010 9061 3035 2010 9062 3037 31 9063 3038 31 9064 3034 31 9065 3039 1737 9066 3036 1737 9067 3040 2012 9068 3030 31 9069 3037 31 9070 3034 31 9071 3035 2010 9072 3036 1737 9073 3039 1737 9074 3037 31 9075 3041 31 9076 3038 31 9077 3042 2013 9078 3040 2012 9079 3043 547 9080 3039 1737 9081 3040 2012 9082 3042 2013 9083 3044 31 9084 3045 31 9085 3041 31 9086 3046 547 9087 3043 547 9088 3047 2014 9089 3037 31 9090 3044 31 9091 3041 31 9092 3042 2013 9093 3043 547 9094 3046 547 9095 3044 2015 9096 3048 2015 9097 3045 2015 9098 3049 2016 9099 3047 2014 9100 3050 1740 9101 3046 547 9102 3047 2014 9103 3049 2016 9104 3051 2017 9105 3052 2017 9106 3048 2017 9107 3053 1740 9108 3050 1740 9109 3054 2018 9110 3044 31 9111 3051 31 9112 3048 31 9113 3049 2016 9114 3050 1740 9115 3053 1740 9116 3055 2019 9117 3056 2019 9118 3052 2019 9119 3057 549 9120 3054 2018 9121 3058 1747 9122 3051 2020 9123 3055 2020 9124 3052 2020 9125 3053 1740 9126 3054 2018 9127 3057 549 9128 3055 31 9129 3059 31 9130 3056 31 9131 3060 2021 9132 3058 1747 9133 3061 2022 9134 3057 549 9135 3058 1747 9136 3060 2021 9137 3062 31 9138 3063 31 9139 3059 31 9140 3064 2023 9141 3061 2022 9142 3065 551 9143 3055 31 9144 3062 31 9145 3059 31 9146 3060 2021 9147 3061 2022 9148 3064 2023 9149 3066 31 9150 3067 31 9151 3063 31 9152 3068 2024 9153 3065 551 9154 3069 2025 9155 3062 31 9156 3066 31 9157 3063 31 9158 3064 2023 9159 3065 551 9160 3068 2024 9161 3070 31 9162 3071 31 9163 3067 31 9164 3072 2025 9165 3069 2025 9166 3073 2026 9167 3074 31 9168 3070 31 9169 3067 31 9170 3066 2027 9171 3074 2027 9172 3067 2027 9173 3068 2024 9174 3069 2025 9175 3072 2025 9176 3075 31 9177 3076 31 9178 3071 31 9179 3077 1744 9180 3073 2026 9181 3078 553 9182 3070 31 9183 3075 31 9184 3071 31 9185 3072 2025 9186 3073 2026 9187 3077 1744 9188 3079 31 9189 3080 31 9190 3076 31 9191 3081 2028 9192 3078 553 9193 3082 1705 9194 3075 31 9195 3079 31 9196 3076 31 9197 3077 1744 9198 3078 553 9199 3081 2028 9200 3083 31 9201 3084 31 9202 3080 31 9203 3085 1745 9204 3082 1705 9205 3086 2029 9206 3079 31 9207 3083 31 9208 3080 31 9209 3081 2028 9210 3082 1705 9211 3085 1745 9212 3083 31 9213 3087 31 9214 3084 31 9215 3088 2030 9216 3086 2029 9217 3089 555 9218 3085 1745 9219 3086 2029 9220 3088 2030 9221 3090 555 9222 3089 555 9223 3091 2031 9224 3088 2030 9225 3089 555 9226 3090 555 9227 3092 2032 9228 3091 2031 9229 3093 1707 9230 3090 555 9231 3091 2031 9232 3092 2032 9233 3094 1750 9234 3093 1707 9235 3095 558 9236 3092 2032 9237 3093 1707 9238 3094 1750 9239 3096 2033 9240 3095 558 9241 3097 2034 9242 3094 1750 9243 3095 558 9244 3096 2033 9245 3074 31 9246 3098 31 9247 3070 31 9248 3099 2035 9249 3097 2034 9250 3100 2036 9251 3096 2033 9252 3097 2034 9253 3099 2035 9254 3101 31 9255 3102 31 9256 3098 31 9257 3103 2036 9258 3100 2036 9259 3104 560 9260 3074 2037 9261 3101 2037 9262 3098 2037 9263 3099 2035 9264 3100 2036 9265 3103 2036 9266 3105 31 9267 3106 31 9268 3102 31 9269 3107 560 9270 3104 560 9271 3108 2038 9272 3101 2039 9273 3105 2039 9274 3102 2039 9275 3103 2036 9276 3104 560 9277 3107 560 9278 3109 31 9279 3110 31 9280 3106 31 9281 3111 2040 9282 3108 2038 9283 3112 1713 9284 3105 31 9285 3109 31 9286 3106 31 9287 3107 560 9288 3108 2038 9289 3111 2040 9290 3113 31 9291 3114 31 9292 3110 31 9293 3115 2041 9294 3112 1713 9295 3116 2042 9296 3109 31 9297 3113 31 9298 3110 31 9299 3111 2040 9300 3112 1713 9301 3115 2041 9302 3113 2043 9303 3117 2043 9304 3114 2043 9305 3118 562 9306 3116 2042 9307 3119 1754 9308 3115 2041 9309 3116 2042 9310 3118 562 9311 3120 2044 9312 3121 2044 9313 3117 2044 9314 3122 1754 9315 3119 1754 9316 3123 2045 9317 3113 31 9318 3120 31 9319 3117 31 9320 3118 562 9321 3119 1754 9322 3122 1754 9323 3124 31 9324 3125 31 9325 3121 31 9326 3126 2046 9327 3123 2045 9328 3127 564 9329 3120 31 9330 3124 31 9331 3121 31 9332 3122 1754 9333 3123 2045 9334 3126 2046 9335 3124 31 9336 3128 31 9337 3125 31 9338 3129 564 9339 3127 564 9340 3130 2047 9341 3126 2046 9342 3127 564 9343 3129 564 9344 3131 31 9345 3132 31 9346 3128 31 9347 3133 2048 9348 3130 2047 9349 3134 1774 9350 3124 31 9351 3131 31 9352 3128 31 9353 3129 564 9354 3130 2047 9355 3133 2048 9356 3131 2049 9357 3135 2049 9358 3132 2049 9359 3136 1774 9360 3134 1774 9361 3137 2050 9362 3133 2048 9363 3134 1774 9364 3136 1774 9365 3138 31 9366 3139 31 9367 3135 31 9368 3140 2050 9369 3137 2050 9370 3141 1681 9371 3131 31 9372 3138 31 9373 3135 31 9374 3136 1774 9375 3137 2050 9376 3140 2050 9377 3138 31 9378 3142 31 9379 3139 31 9380 3143 1681 9381 3141 1681 9382 3144 2051 9383 3140 2050 9384 3141 1681 9385 3143 1681 9386 3145 31 9387 3146 31 9388 3142 31 9389 3147 2051 9390 3144 2051 9391 3148 2052 9392 3138 31 9393 3145 31 9394 3142 31 9395 3143 1681 9396 3144 2051 9397 3147 2051 9398 3149 31 9399 3150 31 9400 3146 31 9401 3151 2053 9402 3152 2053 9403 3153 2054 9404 3149 31 9405 3146 31 9406 3145 31 9407 3147 2051 9408 3148 2052 9409 3154 2052 9410 3149 31 9411 3155 31 9412 3150 31 9413 3156 2054 9414 3153 2054 9415 3157 1677 9416 3156 2054 9417 3151 2053 9418 3153 2054 9419 3158 31 9420 3159 31 9421 3155 31 9422 3160 1677 9423 3157 1677 9424 3161 2055 9425 3149 31 9426 3158 31 9427 3155 31 9428 3156 2054 9429 3157 1677 9430 3160 1677 9431 3158 2049 9432 3162 2049 9433 3159 2049 9434 3163 2055 9435 3161 2055 9436 3164 1721 9437 3160 1677 9438 3161 2055 9439 3163 2055 9440 3165 31 9441 3166 31 9442 3162 31 9443 3167 1721 9444 3164 1721 9445 3168 2056 9446 3158 31 9447 3165 31 9448 3162 31 9449 3163 2055 9450 3164 1721 9451 3167 1721 9452 3165 31 9453 3169 31 9454 3166 31 9455 3170 2057 9456 3168 2056 9457 3171 1115 9458 3167 1721 9459 3168 2056 9460 3170 2057 9461 3172 31 9462 3173 31 9463 3169 31 9464 3174 1115 9465 3171 1115 9466 3175 2058 9467 3165 31 9468 3172 31 9469 3169 31 9470 3170 2057 9471 3171 1115 9472 3174 1115 9473 3172 2044 9474 3176 2044 9475 3173 2044 9476 3177 2059 9477 3175 2058 9478 3178 1724 9479 3174 1115 9480 3175 2058 9481 3177 2059 9482 3179 2043 9483 3180 2043 9484 3176 2043 9485 3181 1724 9486 3178 1724 9487 3182 2060 9488 3172 31 9489 3179 31 9490 3176 31 9491 3177 2059 9492 3178 1724 9493 3181 1724 9494 3183 2061 9495 3184 2061 9496 3180 2061 9497 3185 1117 9498 3182 2060 9499 3186 1759 9500 3179 2062 9501 3183 2062 9502 3180 2062 9503 3181 1724 9504 3182 2060 9505 3185 1117 9506 3183 31 9507 3187 31 9508 3184 31 9509 3188 2063 9510 3186 1759 9511 3189 2064 9512 3185 1117 9513 3186 1759 9514 3188 2063 9515 3190 31 9516 3191 31 9517 3187 31 9518 3192 2065 9519 3189 2064 9520 3193 1119 9521 3183 31 9522 3190 31 9523 3187 31 9524 3188 2063 9525 3189 2064 9526 3192 2065 9527 3194 31 9528 3195 31 9529 3191 31 9530 3196 2066 9531 3193 1119 9532 3197 2067 9533 3190 31 9534 3194 31 9535 3191 31 9536 3192 2065 9537 3193 1119 9538 3196 2066 9539 3198 31 9540 3199 31 9541 3195 31 9542 3200 2067 9543 3197 2067 9544 3201 2068 9545 3202 31 9546 3198 31 9547 3195 31 9548 3194 2069 9549 3202 2069 9550 3195 2069 9551 3196 2066 9552 3197 2067 9553 3200 2067 9554 3203 31 9555 3204 31 9556 3199 31 9557 3205 1761 9558 3201 2068 9559 3206 1121 9560 3198 31 9561 3203 31 9562 3199 31 9563 3200 2067 9564 3201 2068 9565 3205 1761 9566 3207 31 9567 3208 31 9568 3204 31 9569 3209 2070 9570 3206 1121 9571 3210 1687 9572 3203 31 9573 3207 31 9574 3204 31 9575 3205 1761 9576 3206 1121 9577 3209 2070 9578 3211 31 9579 3212 31 9580 3208 31 9581 3213 1762 9582 3210 1687 9583 3214 2071 9584 3207 31 9585 3211 31 9586 3208 31 9587 3209 2070 9588 3210 1687 9589 3213 1762 9590 3211 31 9591 3215 31 9592 3212 31 9593 3216 2072 9594 3214 2071 9595 3217 1123 9596 3213 1762 9597 3214 2071 9598 3216 2072 9599 3218 1123 9600 3217 1123 9601 3219 2073 9602 3216 2072 9603 3217 1123 9604 3218 1123 9605 3220 2074 9606 3219 2073 9607 3221 1689 9608 3218 1123 9609 3219 2073 9610 3220 2074 9611 3222 1765 9612 3221 1689 9613 3223 1126 9614 3220 2074 9615 3221 1689 9616 3222 1765 9617 3224 2075 9618 3223 1126 9619 3225 2076 9620 3222 1765 9621 3223 1126 9622 3224 2075 9623 3202 31 9624 3226 31 9625 3198 31 9626 3227 2077 9627 3225 2076 9628 3228 2078 9629 3224 2075 9630 3225 2076 9631 3227 2077 9632 3229 31 9633 3230 31 9634 3226 31 9635 3231 2078 9636 3228 2078 9637 3232 1128 9638 3202 2079 9639 3229 2079 9640 3226 2079 9641 3227 2077 9642 3228 2078 9643 3231 2078 9644 3233 31 9645 3234 31 9646 3230 31 9647 3235 1128 9648 3232 1128 9649 3236 2080 9650 3229 2081 9651 3233 2081 9652 3230 2081 9653 3231 2078 9654 3232 1128 9655 3235 1128 9656 3237 31 9657 3238 31 9658 3234 31 9659 3239 2082 9660 3236 2080 9661 3240 1730 9662 3233 31 9663 3237 31 9664 3234 31 9665 3235 1128 9666 3236 2080 9667 3239 2082 9668 3241 31 9669 3242 31 9670 3238 31 9671 3243 2083 9672 3240 1730 9673 3244 2084 9674 3237 31 9675 3241 31 9676 3238 31 9677 3239 2082 9678 3240 1730 9679 3243 2083 9680 3241 2017 9681 3245 2017 9682 3242 2017 9683 3246 1130 9684 3244 2084 9685 3247 1769 9686 3243 2083 9687 3244 2084 9688 3246 1130 9689 3248 2015 9690 3249 2015 9691 3245 2015 9692 3250 1769 9693 3247 1769 9694 3251 2085 9695 3241 31 9696 3248 31 9697 3245 31 9698 3246 1130 9699 3247 1769 9700 3250 1769 9701 3252 31 9702 3253 31 9703 3249 31 9704 3254 2086 9705 3251 2085 9706 3255 1132 9707 3248 31 9708 3252 31 9709 3249 31 9710 3250 1769 9711 3251 2085 9712 3254 2086 9713 3252 31 9714 3256 31 9715 3253 31 9716 3257 1132 9717 3255 1132 9718 3258 2087 9719 3254 2086 9720 3255 1132 9721 3257 1132 9722 3259 31 9723 3260 31 9724 3256 31 9725 3261 2088 9726 3258 2087 9727 3262 1770 9728 3252 31 9729 3259 31 9730 3256 31 9731 3257 1132 9732 3258 2087 9733 3261 2088 9734 3259 2011 9735 3263 2011 9736 3260 2011 9737 3264 1770 9738 3262 1770 9739 3265 2089 9740 3261 2088 9741 3262 1770 9742 3264 1770 9743 3266 31 9744 3267 31 9745 3263 31 9746 3268 2089 9747 3265 2089 9748 3269 1696 9749 3259 31 9750 3266 31 9751 3263 31 9752 3264 1770 9753 3265 2089 9754 3268 2089 9755 3266 31 9756 3022 31 9757 3267 31 9758 3270 1696 9759 3269 1696 9760 3024 2008 9761 3268 2089 9762 3269 1696 9763 3270 1696 9764 3266 31 9765 3021 31 9766 3022 31 9767 3270 1696 9768 3024 2008 9769 3023 2008 9770 3271 2008 9771 3272 2008 9772 3273 1696 9773 3274 1698 9774 3275 1698 9775 3276 2007 9776 3274 1698 9777 3276 2007 9778 3277 2007 9779 3278 1696 9780 3273 1696 9781 3279 1770 9782 3278 1696 9783 3271 2008 9784 3273 1696 9785 3280 1770 9786 3279 1770 9787 3281 1132 9788 3278 1696 9789 3279 1770 9790 3280 1770 9791 3282 1132 9792 3281 1132 9793 3283 1769 9794 3280 1770 9795 3281 1132 9796 3282 1132 9797 3284 1769 9798 3283 1769 9799 3285 1730 9800 3282 1132 9801 3283 1769 9802 3284 1769 9803 3286 2083 9804 3285 1730 9805 3287 1128 9806 3284 1769 9807 3285 1730 9808 3286 2083 9809 3288 1128 9810 3287 1128 9811 3289 2076 9812 3286 2083 9813 3287 1128 9814 3288 1128 9815 3290 2077 9816 3289 2076 9817 3291 1689 9818 3288 1128 9819 3289 2076 9820 3290 2077 9821 3292 1765 9822 3291 1689 9823 3293 1123 9824 3290 2077 9825 3291 1689 9826 3292 1765 9827 3294 1123 9828 3293 1123 9829 3295 1687 9830 3292 1765 9831 3293 1123 9832 3294 1123 9833 3296 1762 9834 3295 1687 9835 3297 2068 9836 3294 1123 9837 3295 1687 9838 3296 1762 9839 3298 1761 9840 3297 2068 9841 3299 1119 9842 3296 1762 9843 3297 2068 9844 3298 1761 9845 3300 1119 9846 3299 1119 9847 3301 1759 9848 3298 1761 9849 3299 1119 9850 3300 1119 9851 3302 2063 9852 3301 1759 9853 3303 1724 9854 3300 1119 9855 3301 1759 9856 3302 2063 9857 3304 1684 9858 3303 1724 9859 3305 1115 9860 3302 2063 9861 3303 1724 9862 3304 1684 9863 3306 1115 9864 3305 1115 9865 3307 1721 9866 3304 1684 9867 3305 1115 9868 3306 1115 9869 3308 1721 9870 3307 1721 9871 3309 1677 9872 3306 1115 9873 3307 1721 9874 3308 1721 9875 3310 1677 9876 3309 1677 9877 3311 2054 9878 3308 1721 9879 3309 1677 9880 3310 1677 9881 3312 2051 9882 3313 2051 9883 3314 1681 9884 3310 1677 9885 3311 2054 9886 3315 2054 9887 3316 1681 9888 3314 1681 9889 3317 1774 9890 3312 2051 9891 3314 1681 9892 3316 1681 9893 3318 1774 9894 3317 1774 9895 3319 564 9896 3316 1681 9897 3317 1774 9898 3318 1774 9899 3320 564 9900 3319 564 9901 3321 1754 9902 3318 1774 9903 3319 564 9904 3320 564 9905 3322 1754 9906 3321 1754 9907 3323 1713 9908 3320 564 9909 3321 1754 9910 3322 1754 9911 3324 2041 9912 3323 1713 9913 3325 560 9914 3322 1754 9915 3323 1713 9916 3324 2041 9917 3326 560 9918 3325 560 9919 3327 2034 9920 3324 2041 9921 3325 560 9922 3326 560 9923 3328 2035 9924 3327 2034 9925 3329 1707 9926 3326 560 9927 3327 2034 9928 3328 2035 9929 3330 1750 9930 3329 1707 9931 3331 555 9932 3328 2035 9933 3329 1707 9934 3330 1750 9935 3332 555 9936 3331 555 9937 3333 1705 9938 3330 1750 9939 3331 555 9940 3332 555 9941 3334 1745 9942 3333 1705 9943 3335 2026 9944 3332 555 9945 3333 1705 9946 3334 1745 9947 3336 1744 9948 3335 2026 9949 3337 551 9950 3334 1745 9951 3335 2026 9952 3336 1744 9953 3338 551 9954 3337 551 9955 3339 1747 9956 3336 1744 9957 3337 551 9958 3338 551 9959 3340 2021 9960 3339 1747 9961 3341 1740 9962 3338 551 9963 3339 1747 9964 3340 2021 9965 3342 1702 9966 3341 1740 9967 3343 547 9968 3340 2021 9969 3341 1740 9970 3342 1702 9971 3344 547 9972 3343 547 9973 3345 1737 9974 3342 1702 9975 3343 547 9976 3344 547 9977 3346 1737 9978 3345 1737 9979 3275 1698 9980 3344 547 9981 3345 1737 9982 3346 1737 9983 3346 1737 9984 3275 1698 9985 3274 1698 9986 3347 2090 9987 3348 2091 9988 3349 2092 9989 3350 2093 9990 3351 2094 9991 3352 2095 9992 3350 2093 9993 3352 2095 9994 3353 2096 9995 3354 2097 9996 3349 2092 9997 3355 2098 9998 3354 2097 9999 3347 2090 10000 3349 2092 10001 3356 2099 10002 3355 2098 10003 3357 2100 10004 3354 2097 10005 3355 2098 10006 3356 2099 10007 3358 2101 10008 3357 2100 10009 3359 2102 10010 3356 2099 10011 3357 2100 10012 3358 2101 10013 3360 2103 10014 3359 2102 10015 3361 2104 10016 3358 2101 10017 3359 2102 10018 3360 2103 10019 3362 2105 10020 3361 2104 10021 3363 2106 10022 3360 2103 10023 3361 2104 10024 3362 2105 10025 3364 2107 10026 3363 2106 10027 3365 2108 10028 3362 2105 10029 3363 2106 10030 3364 2107 10031 3366 2109 10032 3365 2108 10033 3367 2110 10034 3364 2107 10035 3365 2108 10036 3366 2109 10037 3368 2111 10038 3367 2110 10039 3369 2112 10040 3366 2109 10041 3367 2110 10042 3368 2111 10043 3370 2113 10044 3371 2113 10045 3372 2114 10046 3368 2111 10047 3369 2112 10048 3373 2112 10049 3374 2115 10050 3372 2114 10051 3375 2116 10052 3370 2113 10053 3372 2114 10054 3374 2115 10055 3376 2117 10056 3375 2116 10057 3377 2118 10058 3374 2115 10059 3375 2116 10060 3376 2117 10061 3378 2119 10062 3377 2118 10063 3379 2120 10064 3376 2117 10065 3377 2118 10066 3378 2119 10067 3380 2121 10068 3379 2120 10069 3381 2122 10070 3378 2119 10071 3379 2120 10072 3380 2121 10073 3382 2123 10074 3381 2122 10075 3383 2124 10076 3380 2121 10077 3381 2122 10078 3382 2123 10079 3384 2125 10080 3383 2124 10081 3385 2126 10082 3382 2123 10083 3383 2124 10084 3384 2125 10085 3386 2127 10086 3385 2126 10087 3351 2094 10088 3384 2125 10089 3385 2126 10090 3386 2127 10091 3386 2127 10092 3351 2094 10093 3350 2093 10094 3393 11 10095 3394 11 10096 3395 11 10097 3424 2128 10098 3425 2128 10099 3426 2128 10100 3427 2129 10101 3428 2130 10102 3429 2131 10103 3430 1735 10104 3424 1735 10105 3426 1735 10106 3431 2132 10107 3432 2132 10108 3433 2132 10109 3434 2133 10110 3431 2133 10111 3433 2133 10112 3434 2134 10113 3433 2134 10114 3435 2134 10115 3436 2135 10116 3429 2131 10117 3437 2136 10118 3438 2137 10119 3427 2129 10120 3429 2131 10121 3436 2135 10122 3438 2137 10123 3429 2131 10124 3430 2138 10125 3439 2138 10126 3424 2138 10127 3440 2139 10128 3441 2139 10129 3442 2139 10130 3443 2140 10131 3436 2135 10132 3437 2136 10133 3444 2141 10134 3443 2140 10135 3437 2136 10136 3445 2142 10137 3446 2142 10138 3439 2142 10139 3447 2143 10140 3448 2144 10141 3449 2145 10142 3430 1735 10143 3445 1735 10144 3439 1735 10145 3450 2146 10146 3442 2146 10147 3451 2146 10148 3450 2147 10149 3440 2147 10150 3442 2147 10151 3452 2148 10152 3453 2148 10153 3446 2148 10154 3454 2149 10155 3449 2145 10156 3455 2150 10157 3445 2151 10158 3452 2151 10159 3446 2151 10160 3454 2149 10161 3447 2143 10162 3449 2145 10163 3456 1735 10164 3457 1735 10165 3453 1735 10166 3458 542 10167 3459 542 10168 3460 542 10169 3452 1735 10170 3456 1735 10171 3453 1735 10172 3461 2152 10173 3454 2149 10174 3455 2150 10175 3462 2153 10176 3463 2153 10177 3457 2153 10178 3464 2154 10179 3465 2155 10180 3466 2156 10181 3456 1735 10182 3462 1735 10183 3457 1735 10184 3467 542 10185 3458 542 10186 3460 542 10187 3467 542 10188 3460 542 10189 3468 542 10190 3469 2157 10191 3470 2157 10192 3463 2157 10193 3471 2158 10194 3466 2156 10195 3472 2159 10196 3462 1735 10197 3469 1735 10198 3463 1735 10199 3471 2158 10200 3464 2154 10201 3466 2156 10202 3473 1735 10203 3474 1735 10204 3470 1735 10205 3475 2160 10206 3476 2160 10207 3477 2160 10208 3469 1735 10209 3473 1735 10210 3470 1735 10211 3478 2161 10212 3471 2158 10213 3472 2159 10214 3473 2162 10215 3479 2162 10216 3474 2162 10217 3480 2163 10218 3481 2164 10219 3482 2165 10220 3483 2166 10221 3475 2166 10222 3477 2166 10223 3483 2167 10224 3477 2167 10225 3484 2167 10226 3485 2168 10227 3482 2165 10228 3486 2169 10229 3487 2170 10230 3480 2163 10231 3482 2165 10232 3485 2168 10233 3487 2170 10234 3482 2165 10235 3488 2171 10236 3489 2171 10237 3490 2171 10238 3491 2172 10239 3485 2168 10240 3486 2169 10241 3492 2173 10242 3491 2172 10243 3486 2169 10244 3493 2174 10245 3494 2175 10246 3495 2176 10247 3496 2177 10248 3490 2177 10249 3497 2177 10250 3496 2178 10251 3488 2178 10252 3490 2178 10253 3498 2179 10254 3495 2176 10255 3499 2180 10256 3498 2179 10257 3493 2174 10258 3495 2176 10259 3500 31 10260 3501 31 10261 3502 31 10262 3503 2181 10263 3498 2179 10264 3499 2180 10265 3504 2182 10266 3505 2183 10267 3506 2184 10268 3507 31 10269 3502 31 10270 3508 31 10271 3507 31 10272 3500 31 10273 3502 31 10274 3509 2185 10275 3506 2184 10276 3510 2186 10277 3509 2185 10278 3504 2182 10279 3506 2184 10280 3511 2187 10281 3509 2185 10282 3510 2186 10283 3512 11 10284 3513 11 10285 3514 11 10286 3515 2188 10287 3516 2189 10288 3517 2190 10289 3518 11 10290 3514 11 10291 3519 11 10292 3520 2191 10293 3521 2191 10294 3522 2192 10295 3518 11 10296 3512 11 10297 3514 11 10298 3520 2191 10299 3522 2192 10300 3523 2192 10301 3524 11 10302 3525 11 10303 3513 11 10304 3526 2190 10305 3517 2190 10306 3527 2193 10307 3528 11 10308 3524 11 10309 3513 11 10310 3512 2194 10311 3528 2194 10312 3513 2194 10313 3526 2190 10314 3515 2188 10315 3517 2190 10316 3529 11 10317 3530 11 10318 3525 11 10319 3531 2195 10320 3527 2193 10321 3532 2196 10322 3524 2197 10323 3529 2197 10324 3525 2197 10325 3526 2190 10326 3527 2193 10327 3531 2195 10328 3529 11 10329 3533 11 10330 3530 11 10331 3534 2198 10332 3532 2196 10333 3535 2199 10334 3531 2195 10335 3532 2196 10336 3534 2198 10337 3536 11 10338 3537 11 10339 3533 11 10340 3538 2200 10341 3535 2199 10342 3539 2201 10343 3540 2202 10344 3536 2202 10345 3533 2202 10346 3529 11 10347 3540 11 10348 3533 11 10349 3534 2198 10350 3535 2199 10351 3538 2200 10352 3541 11 10353 3542 11 10354 3537 11 10355 3543 2203 10356 3539 2201 10357 3544 2204 10358 3536 11 10359 3541 11 10360 3537 11 10361 3538 2200 10362 3539 2201 10363 3543 2203 10364 3545 11 10365 3546 11 10366 3542 11 10367 3547 2204 10368 3544 2204 10369 3548 2205 10370 3549 11 10371 3545 11 10372 3542 11 10373 3541 2206 10374 3549 2206 10375 3542 2206 10376 3543 2203 10377 3544 2204 10378 3547 2204 10379 3550 11 10380 3551 11 10381 3546 11 10382 3552 2207 10383 3553 2207 10384 3554 2208 10385 3550 11 10386 3546 11 10387 3545 11 10388 3547 2204 10389 3548 2205 10390 3555 2205 10391 3556 2209 10392 3557 2209 10393 3551 2209 10394 3558 2208 10395 3554 2208 10396 3559 2210 10397 3560 11 10398 3556 11 10399 3551 11 10400 3550 11 10401 3560 11 10402 3551 11 10403 3552 2207 10404 3554 2208 10405 3558 2208 10406 3561 11 10407 3562 11 10408 3557 11 10409 3563 2211 10410 3559 2210 10411 3564 2212 10412 3556 11 10413 3561 11 10414 3557 11 10415 3558 2208 10416 3559 2210 10417 3563 2211 10418 3561 11 10419 3565 11 10420 3562 11 10421 3566 2213 10422 3564 2212 10423 3567 2214 10424 3563 2211 10425 3564 2212 10426 3566 2213 10427 3568 11 10428 3569 11 10429 3565 11 10430 3570 2215 10431 3567 2214 10432 3571 2216 10433 3572 11 10434 3568 11 10435 3565 11 10436 3561 11 10437 3572 11 10438 3565 11 10439 3566 2213 10440 3567 2214 10441 3570 2215 10442 3573 11 10443 3519 11 10444 3569 11 10445 3574 2217 10446 3571 2216 10447 3521 2191 10448 3568 11 10449 3573 11 10450 3569 11 10451 3570 2215 10452 3571 2216 10453 3574 2217 10454 3575 11 10455 3518 11 10456 3519 11 10457 3573 11 10458 3575 11 10459 3519 11 10460 3574 2217 10461 3521 2191 10462 3520 2191 10463 3576 2218 10464 3577 2219 10465 3578 2220 10466 3579 2221 10467 3580 2222 10468 3581 2223 10469 3582 2224 10470 3581 2223 10471 3583 2225 10472 3579 2221 10473 3581 2223 10474 3582 2224 10475 3584 2226 10476 3578 2220 10477 3585 2227 10478 3586 2228 10479 3578 2220 10480 3584 2226 10481 3576 2218 10482 3578 2220 10483 3586 2228 10484 3587 2229 10485 3585 2227 10486 3588 2230 10487 3587 2229 10488 3584 2226 10489 3585 2227 10490 3589 2231 10491 3588 2230 10492 3590 2232 10493 3587 2229 10494 3588 2230 10495 3589 2231 10496 3591 11 10497 3592 11 10498 3540 11 10499 3593 2233 10500 3590 2232 10501 3594 2234 10502 3529 11 10503 3591 11 10504 3540 11 10505 3589 2231 10506 3590 2232 10507 3593 2233 10508 3595 11 10509 3596 11 10510 3592 11 10511 3597 2235 10512 3594 2234 10513 3598 2236 10514 3591 11 10515 3595 11 10516 3592 11 10517 3593 2233 10518 3594 2234 10519 3597 2235 10520 3595 11 10521 3599 11 10522 3596 11 10523 3597 2235 10524 3598 2236 10525 3600 2237 10526 3601 2238 10527 3600 2237 10528 3602 2239 10529 3601 2238 10530 3597 2235 10531 3600 2237 10532 3603 2240 10533 3602 2239 10534 3604 2241 10535 3601 2238 10536 3602 2239 10537 3603 2240 10538 3605 2242 10539 3604 2241 10540 3606 2243 10541 3603 2240 10542 3604 2241 10543 3605 2242 10544 3607 2244 10545 3606 2243 10546 3608 2245 10547 3605 2242 10548 3606 2243 10549 3607 2244 10550 3609 2246 10551 3608 2245 10552 3610 2247 10553 3609 2246 10554 3607 2244 10555 3608 2245 10556 3609 2246 10557 3610 2247 10558 3611 2248 10559 3612 2249 10560 3611 2248 10561 3613 2250 10562 3609 2246 10563 3611 2248 10564 3612 2249 10565 3614 2251 10566 3615 2252 10567 3616 2253 10568 3617 2254 10569 3613 2250 10570 3618 2255 10571 3612 2249 10572 3613 2250 10573 3617 2254 10574 3619 2256 10575 3616 2253 10576 3620 2257 10577 3621 2258 10578 3616 2253 10579 3619 2256 10580 3614 2251 10581 3616 2253 10582 3621 2258 10583 3622 2259 10584 3620 2257 10585 3623 2260 10586 3622 2259 10587 3619 2256 10588 3620 2257 10589 3624 2261 10590 3623 2260 10591 3625 2262 10592 3622 2259 10593 3623 2260 10594 3624 2261 10595 3626 11 10596 3627 11 10597 3572 11 10598 3628 2263 10599 3625 2262 10600 3629 2264 10601 3561 2265 10602 3626 2265 10603 3572 2265 10604 3624 2261 10605 3625 2262 10606 3628 2263 10607 3630 11 10608 3631 11 10609 3627 11 10610 3632 2266 10611 3629 2264 10612 3633 2267 10613 3626 11 10614 3630 11 10615 3627 11 10616 3628 2263 10617 3629 2264 10618 3632 2266 10619 3630 11 10620 3634 11 10621 3631 11 10622 3632 2266 10623 3633 2267 10624 3635 2268 10625 3636 2269 10626 3635 2268 10627 3637 2270 10628 3636 2269 10629 3632 2266 10630 3635 2268 10631 3638 2271 10632 3637 2270 10633 3639 2272 10634 3636 2269 10635 3637 2270 10636 3638 2271 10637 3640 2273 10638 3639 2272 10639 3641 2274 10640 3638 2271 10641 3639 2272 10642 3640 2273 10643 3642 2275 10644 3641 2274 10645 3643 2276 10646 3640 2273 10647 3641 2274 10648 3642 2275 10649 3644 2277 10650 3643 2276 10651 3645 2278 10652 3644 2277 10653 3642 2275 10654 3643 2276 10655 3644 2277 10656 3645 2278 10657 3580 2222 10658 3644 2277 10659 3580 2222 10660 3579 2221 10661 3646 11 10662 3647 11 10663 3648 11 10664 3649 11 10665 3646 11 10666 3648 11 10667 3650 11 10668 3649 11 10669 3648 11 10670 3651 11 10671 3652 11 10672 3647 11 10673 3646 11 10674 3651 11 10675 3647 11 10676 3653 11 10677 3654 11 10678 3652 11 10679 3651 11 10680 3653 11 10681 3652 11 10682 3650 11 10683 3655 11 10684 3649 11 10685 3656 11 10686 3657 11 10687 3655 11 10688 3650 11 10689 3656 11 10690 3655 11 10691 3658 11 10692 3659 11 10693 3657 11 10694 3656 11 10695 3658 11 10696 3657 11 10697 3660 11 10698 3661 11 10699 3662 11 10700 3663 11 10701 3664 11 10702 3665 11 10703 3666 11 10704 3667 11 10705 3668 11 10706 3675 11 10707 3676 11 10708 3677 11 10709 3688 2279 10710 3689 2279 10711 3690 2279 10712 3691 31 10713 3690 31 10714 3692 31 10715 3693 31 10716 3690 31 10717 3691 31 10718 3693 31 10719 3688 31 10720 3690 31 10721 3694 31 10722 3695 31 10723 3689 31 10724 3696 31 10725 3694 31 10726 3689 31 10727 3688 2280 10728 3696 2280 10729 3689 2280 10730 3697 31 10731 3698 31 10732 3695 31 10733 3699 31 10734 3697 31 10735 3695 31 10736 3694 2281 10737 3699 2281 10738 3695 2281 10739 3700 31 10740 3701 31 10741 3698 31 10742 3702 31 10743 3700 31 10744 3698 31 10745 3697 31 10746 3702 31 10747 3698 31 10748 3703 2282 10749 3704 2282 10750 3701 2282 10751 3705 31 10752 3703 31 10753 3701 31 10754 3706 2283 10755 3705 2283 10756 3701 2283 10757 3700 2284 10758 3706 2284 10759 3701 2284 10760 3707 31 10761 3708 31 10762 3704 31 10763 3709 2285 10764 3707 2285 10765 3704 2285 10766 3710 31 10767 3709 31 10768 3704 31 10769 3703 2286 10770 3710 2286 10771 3704 2286 10772 3711 31 10773 3712 31 10774 3708 31 10775 3713 2287 10776 3711 2287 10777 3708 2287 10778 3714 2288 10779 3713 2288 10780 3708 2288 10781 3707 31 10782 3714 31 10783 3708 31 10784 3715 31 10785 3716 31 10786 3712 31 10787 3717 31 10788 3715 31 10789 3712 31 10790 3711 31 10791 3717 31 10792 3712 31 10793 3718 31 10794 3719 31 10795 3716 31 10796 3715 31 10797 3718 31 10798 3716 31 10799 3718 31 10800 3720 31 10801 3719 31 10802 3721 31 10803 3722 31 10804 3717 31 10805 3723 31 10806 3721 31 10807 3717 31 10808 3724 31 10809 3723 31 10810 3717 31 10811 3725 31 10812 3724 31 10813 3717 31 10814 3711 31 10815 3725 31 10816 3717 31 10817 3726 2289 10818 3727 2289 10819 3722 2289 10820 3728 2290 10821 3726 2290 10822 3722 2290 10823 3729 31 10824 3728 31 10825 3722 31 10826 3721 31 10827 3729 31 10828 3722 31 10829 3730 31 10830 3731 31 10831 3727 31 10832 3732 31 10833 3730 31 10834 3727 31 10835 3733 31 10836 3732 31 10837 3727 31 10838 3726 2291 10839 3733 2291 10840 3727 2291 10841 3734 2292 10842 3735 2292 10843 3731 2292 10844 3736 2293 10845 3734 2293 10846 3731 2293 10847 3730 31 10848 3736 31 10849 3731 31 10850 3737 31 10851 3738 31 10852 3735 31 10853 3739 2294 10854 3737 2294 10855 3735 2294 10856 3734 31 10857 3739 31 10858 3735 31 10859 3740 2295 10860 3741 2295 10861 3738 2295 10862 3742 2296 10863 3740 2296 10864 3738 2296 10865 3737 2297 10866 3742 2297 10867 3738 2297 10868 3743 31 10869 3744 31 10870 3741 31 10871 3745 31 10872 3743 31 10873 3741 31 10874 3746 2298 10875 3745 2298 10876 3741 2298 10877 3740 2299 10878 3746 2299 10879 3741 2299 10880 3747 2300 10881 3748 2300 10882 3744 2300 10883 3749 31 10884 3747 31 10885 3744 31 10886 3743 31 10887 3749 31 10888 3744 31 10889 3750 31 10890 3751 31 10891 3748 31 10892 3752 31 10893 3750 31 10894 3748 31 10895 3747 2301 10896 3752 2301 10897 3748 2301 10898 3753 31 10899 3754 31 10900 3751 31 10901 3755 31 10902 3753 31 10903 3751 31 10904 3750 2297 10905 3755 2297 10906 3751 2297 10907 3756 31 10908 3757 31 10909 3754 31 10910 3758 31 10911 3756 31 10912 3754 31 10913 3753 31 10914 3758 31 10915 3754 31 10916 3759 2302 10917 3760 2302 10918 3757 2302 10919 3761 31 10920 3759 31 10921 3757 31 10922 3762 2303 10923 3761 2303 10924 3757 2303 10925 3756 2304 10926 3762 2304 10927 3757 2304 10928 3763 31 10929 3764 31 10930 3760 31 10931 3765 2305 10932 3763 2305 10933 3760 2305 10934 3766 31 10935 3765 31 10936 3760 31 10937 3759 2306 10938 3766 2306 10939 3760 2306 10940 3767 31 10941 3768 31 10942 3764 31 10943 3769 2307 10944 3767 2307 10945 3764 2307 10946 3770 2308 10947 3769 2308 10948 3764 2308 10949 3763 31 10950 3770 31 10951 3764 31 10952 3771 31 10953 3772 31 10954 3768 31 10955 3773 31 10956 3771 31 10957 3768 31 10958 3767 31 10959 3773 31 10960 3768 31 10961 3774 31 10962 3775 31 10963 3772 31 10964 3771 31 10965 3774 31 10966 3772 31 10967 3774 31 10968 3776 31 10969 3775 31 10970 3777 31 10971 3778 31 10972 3773 31 10973 3779 31 10974 3777 31 10975 3773 31 10976 3780 31 10977 3779 31 10978 3773 31 10979 3781 31 10980 3780 31 10981 3773 31 10982 3767 31 10983 3781 31 10984 3773 31 10985 3782 2309 10986 3783 2309 10987 3778 2309 10988 3784 2310 10989 3782 2310 10990 3778 2310 10991 3785 31 10992 3784 31 10993 3778 31 10994 3777 31 10995 3785 31 10996 3778 31 10997 3786 31 10998 3787 31 10999 3783 31 11000 3788 31 11001 3786 31 11002 3783 31 11003 3789 31 11004 3788 31 11005 3783 31 11006 3782 2311 11007 3789 2311 11008 3783 2311 11009 3790 2312 11010 3791 2312 11011 3787 2312 11012 3792 2313 11013 3790 2313 11014 3787 2313 11015 3786 31 11016 3792 31 11017 3787 31 11018 3793 31 11019 3794 31 11020 3791 31 11021 3795 2314 11022 3793 2314 11023 3791 2314 11024 3790 31 11025 3795 31 11026 3791 31 11027 3796 2315 11028 3692 2315 11029 3794 2315 11030 3797 2316 11031 3796 2316 11032 3794 2316 11033 3793 2281 11034 3797 2281 11035 3794 2281 11036 3798 31 11037 3691 31 11038 3692 31 11039 3799 2317 11040 3798 2317 11041 3692 2317 11042 3796 2318 11043 3799 2318 11044 3692 2318 11045 3800 31 11046 3801 31 11047 3802 31 11048 3803 31 11049 3800 31 11050 3802 31 11051 3804 31 11052 3803 31 11053 3802 31 11054 3805 31 11055 3806 31 11056 3801 31 11057 3800 31 11058 3805 31 11059 3801 31 11060 3807 31 11061 3808 31 11062 3806 31 11063 3805 31 11064 3807 31 11065 3806 31 11066 3809 31 11067 3810 31 11068 3808 31 11069 3807 31 11070 3809 31 11071 3808 31 11072 3811 31 11073 3812 31 11074 3810 31 11075 3809 31 11076 3811 31 11077 3810 31 11078 3813 31 11079 3814 31 11080 3812 31 11081 3811 31 11082 3813 31 11083 3812 31 11084 3815 31 11085 3816 31 11086 3814 31 11087 3813 31 11088 3815 31 11089 3814 31 11090 3817 31 11091 3818 31 11092 3816 31 11093 3815 31 11094 3817 31 11095 3816 31 11096 3817 31 11097 3819 31 11098 3818 31 11099 3804 31 11100 3820 31 11101 3803 31 11102 3821 31 11103 3822 31 11104 3820 31 11105 3804 31 11106 3821 31 11107 3820 31 11108 3823 31 11109 3824 31 11110 3822 31 11111 3821 31 11112 3823 31 11113 3822 31 11114 3825 31 11115 3826 31 11116 3824 31 11117 3823 31 11118 3825 31 11119 3824 31 11120 3827 31 11121 3828 31 11122 3826 31 11123 3825 31 11124 3827 31 11125 3826 31 11126 3829 31 11127 3830 31 11128 3828 31 11129 3827 31 11130 3829 31 11131 3828 31 11132 3831 31 11133 3832 31 11134 3830 31 11135 3829 31 11136 3831 31 11137 3830 31 11138 3833 31 11139 3834 31 11140 3832 31 11141 3831 31 11142 3833 31 11143 3832 31 11144 3833 31 11145 3835 31 11146 3834 31 11147 3836 31 11148 3837 31 11149 3838 31 11150 3839 31 11151 3840 31 11152 3837 31 11153 3836 31 11154 3839 31 11155 3837 31 11156 3841 31 11157 3838 31 11158 3842 31 11159 3841 31 11160 3836 31 11161 3838 31 11162 3841 31 11163 3842 31 11164 3843 31 11165 3841 2319 11166 3843 2319 11167 3844 2319 11168 3845 31 11169 3844 31 11170 3846 31 11171 3847 31 11172 3841 31 11173 3844 31 11174 3845 31 11175 3847 31 11176 3844 31 11177 3845 31 11178 3846 31 11179 3848 31 11180 3845 2320 11181 3848 2320 11182 3849 2320 11183 3850 31 11184 3849 31 11185 3851 31 11186 3850 2321 11187 3845 2321 11188 3849 2321 11189 3850 31 11190 3851 31 11191 3852 31 11192 3853 31 11193 3852 31 11194 3854 31 11195 3850 31 11196 3852 31 11197 3853 31 11198 3855 31 11199 3854 31 11200 3856 31 11201 3855 31 11202 3853 31 11203 3854 31 11204 3855 31 11205 3856 31 11206 3857 31 11207 3855 2322 11208 3857 2322 11209 3858 2322 11210 3859 31 11211 3858 31 11212 3860 31 11213 3861 31 11214 3855 31 11215 3858 31 11216 3859 31 11217 3861 31 11218 3858 31 11219 3859 31 11220 3860 31 11221 3862 31 11222 3859 2323 11223 3862 2323 11224 3863 2323 11225 3839 31 11226 3863 31 11227 3840 31 11228 3839 2324 11229 3859 2324 11230 3863 2324 11231 3864 31 11232 3865 31 11233 3866 31 11234 3867 31 11235 3868 31 11236 3865 31 11237 3864 31 11238 3867 31 11239 3865 31 11240 3869 31 11241 3866 31 11242 3870 31 11243 3869 31 11244 3864 31 11245 3866 31 11246 3869 31 11247 3870 31 11248 3871 31 11249 3869 31 11250 3871 31 11251 3872 31 11252 3873 31 11253 3872 31 11254 3874 31 11255 3875 31 11256 3869 31 11257 3872 31 11258 3873 31 11259 3875 31 11260 3872 31 11261 3873 31 11262 3874 31 11263 3876 31 11264 3873 31 11265 3876 31 11266 3877 31 11267 3878 31 11268 3877 31 11269 3879 31 11270 3878 31 11271 3873 31 11272 3877 31 11273 3878 31 11274 3879 31 11275 3880 31 11276 3881 31 11277 3880 31 11278 3882 31 11279 3878 31 11280 3880 31 11281 3881 31 11282 3883 31 11283 3882 31 11284 3884 31 11285 3883 31 11286 3881 31 11287 3882 31 11288 3883 31 11289 3884 31 11290 3885 31 11291 3883 31 11292 3885 31 11293 3886 31 11294 3887 31 11295 3886 31 11296 3888 31 11297 3889 31 11298 3883 31 11299 3886 31 11300 3887 31 11301 3889 31 11302 3886 31 11303 3887 31 11304 3888 31 11305 3890 31 11306 3887 31 11307 3890 31 11308 3891 31 11309 3867 31 11310 3891 31 11311 3868 31 11312 3867 31 11313 3887 31 11314 3891 31 11315 3892 31 11316 3893 31 11317 3894 31 11318 3895 31 11319 3896 31 11320 3893 31 11321 3892 31 11322 3895 31 11323 3893 31 11324 3897 31 11325 3894 31 11326 3898 31 11327 3897 31 11328 3892 31 11329 3894 31 11330 3897 31 11331 3898 31 11332 3899 31 11333 3897 31 11334 3899 31 11335 3900 31 11336 3901 31 11337 3900 31 11338 3902 31 11339 3903 31 11340 3897 31 11341 3900 31 11342 3901 31 11343 3903 31 11344 3900 31 11345 3901 31 11346 3902 31 11347 3904 31 11348 3901 31 11349 3904 31 11350 3905 31 11351 3906 31 11352 3905 31 11353 3907 31 11354 3906 31 11355 3901 31 11356 3905 31 11357 3906 31 11358 3907 31 11359 3908 31 11360 3909 31 11361 3908 31 11362 3910 31 11363 3906 31 11364 3908 31 11365 3909 31 11366 3911 31 11367 3910 31 11368 3912 31 11369 3911 31 11370 3909 31 11371 3910 31 11372 3911 31 11373 3912 31 11374 3913 31 11375 3911 31 11376 3913 31 11377 3914 31 11378 3915 31 11379 3914 31 11380 3916 31 11381 3917 31 11382 3911 31 11383 3914 31 11384 3915 31 11385 3917 31 11386 3914 31 11387 3915 31 11388 3916 31 11389 3918 31 11390 3915 31 11391 3918 31 11392 3919 31 11393 3895 31 11394 3919 31 11395 3896 31 11396 3895 31 11397 3915 31 11398 3919 31 11399 3920 31 11400 3921 31 11401 3922 31 11402 3923 31 11403 3924 31 11404 3921 31 11405 3920 31 11406 3923 31 11407 3921 31 11408 3925 31 11409 3922 31 11410 3926 31 11411 3925 31 11412 3920 31 11413 3922 31 11414 3925 31 11415 3926 31 11416 3927 31 11417 3925 31 11418 3927 31 11419 3928 31 11420 3929 31 11421 3928 31 11422 3930 31 11423 3931 31 11424 3925 31 11425 3928 31 11426 3929 31 11427 3931 31 11428 3928 31 11429 3929 31 11430 3930 31 11431 3932 31 11432 3929 31 11433 3932 31 11434 3933 31 11435 3934 31 11436 3933 31 11437 3935 31 11438 3934 31 11439 3929 31 11440 3933 31 11441 3934 31 11442 3935 31 11443 3936 31 11444 3937 31 11445 3936 31 11446 3938 31 11447 3934 31 11448 3936 31 11449 3937 31 11450 3939 31 11451 3938 31 11452 3940 31 11453 3939 31 11454 3937 31 11455 3938 31 11456 3939 31 11457 3940 31 11458 3941 31 11459 3939 31 11460 3941 31 11461 3942 31 11462 3943 31 11463 3942 31 11464 3944 31 11465 3945 31 11466 3939 31 11467 3942 31 11468 3943 31 11469 3945 31 11470 3942 31 11471 3943 31 11472 3944 31 11473 3946 31 11474 3943 31 11475 3946 31 11476 3947 31 11477 3923 31 11478 3947 31 11479 3924 31 11480 3923 31 11481 3943 31 11482 3947 31 11483 3948 31 11484 3949 31 11485 3950 31 11486 3951 31 11487 3952 31 11488 3949 31 11489 3948 31 11490 3951 31 11491 3949 31 11492 3953 31 11493 3950 31 11494 3954 31 11495 3953 31 11496 3948 31 11497 3950 31 11498 3953 31 11499 3954 31 11500 3955 31 11501 3953 31 11502 3955 31 11503 3956 31 11504 3957 31 11505 3956 31 11506 3958 31 11507 3959 31 11508 3953 31 11509 3956 31 11510 3957 31 11511 3959 31 11512 3956 31 11513 3957 31 11514 3958 31 11515 3960 31 11516 3957 31 11517 3960 31 11518 3961 31 11519 3962 31 11520 3961 31 11521 3963 31 11522 3962 31 11523 3957 31 11524 3961 31 11525 3962 31 11526 3963 31 11527 3964 31 11528 3965 31 11529 3964 31 11530 3966 31 11531 3962 31 11532 3964 31 11533 3965 31 11534 3967 31 11535 3966 31 11536 3968 31 11537 3967 31 11538 3965 31 11539 3966 31 11540 3967 31 11541 3968 31 11542 3969 31 11543 3967 31 11544 3969 31 11545 3970 31 11546 3971 31 11547 3970 31 11548 3972 31 11549 3973 31 11550 3967 31 11551 3970 31 11552 3971 31 11553 3973 31 11554 3970 31 11555 3971 31 11556 3972 31 11557 3974 31 11558 3971 31 11559 3974 31 11560 3975 31 11561 3951 31 11562 3975 31 11563 3952 31 11564 3951 31 11565 3971 31 11566 3975 31 11567 3976 31 11568 3977 31 11569 3861 31 11570 3859 31 11571 3976 31 11572 3861 31 11573 3978 31 11574 3979 31 11575 3977 31 11576 3976 31 11577 3978 31 11578 3977 31 11579 3978 31 11580 3980 31 11581 3979 31 11582 3981 31 11583 3982 31 11584 3847 31 11585 3845 31 11586 3981 31 11587 3847 31 11588 3983 31 11589 3984 31 11590 3982 31 11591 3981 31 11592 3983 31 11593 3982 31 11594 3983 31 11595 3985 31 11596 3984 31 11597 3986 31 11598 3987 31 11599 3889 31 11600 3887 31 11601 3986 31 11602 3889 31 11603 3988 31 11604 3989 31 11605 3987 31 11606 3986 31 11607 3988 31 11608 3987 31 11609 3988 31 11610 3990 31 11611 3989 31 11612 3991 31 11613 3992 31 11614 3875 31 11615 3873 31 11616 3991 31 11617 3875 31 11618 3993 31 11619 3994 31 11620 3992 31 11621 3991 31 11622 3993 31 11623 3992 31 11624 3993 31 11625 3995 31 11626 3994 31 11627 3996 31 11628 3997 31 11629 3917 31 11630 3915 31 11631 3996 31 11632 3917 31 11633 3998 31 11634 3999 31 11635 3997 31 11636 3996 31 11637 3998 31 11638 3997 31 11639 3998 31 11640 4000 31 11641 3999 31 11642 4001 31 11643 4002 31 11644 3903 31 11645 3901 31 11646 4001 31 11647 3903 31 11648 4003 31 11649 4004 31 11650 4002 31 11651 4001 31 11652 4003 31 11653 4002 31 11654 4003 31 11655 4005 31 11656 4004 31 11657 4006 31 11658 4007 31 11659 3945 31 11660 3943 31 11661 4006 31 11662 3945 31 11663 4008 31 11664 4009 31 11665 4007 31 11666 4006 31 11667 4008 31 11668 4007 31 11669 4008 31 11670 4010 31 11671 4009 31 11672 4011 31 11673 4012 31 11674 3931 31 11675 3929 31 11676 4011 31 11677 3931 31 11678 4013 31 11679 4014 31 11680 4012 31 11681 4011 31 11682 4013 31 11683 4012 31 11684 4013 31 11685 4015 31 11686 4014 31 11687 4016 31 11688 4017 31 11689 3973 31 11690 3971 31 11691 4016 31 11692 3973 31 11693 4018 31 11694 4019 31 11695 4017 31 11696 4016 31 11697 4018 31 11698 4017 31 11699 4018 31 11700 4020 31 11701 4019 31 11702 4021 31 11703 4022 31 11704 3959 31 11705 3957 31 11706 4021 31 11707 3959 31 11708 4023 31 11709 4024 31 11710 4022 31 11711 4021 31 11712 4023 31 11713 4022 31 11714 4023 31 11715 4025 31 11716 4024 31 11717 4026 2325 11718 4027 2326 11719 4028 2327 11720 4029 2328 11721 4030 2329 11722 4031 2330 11723 4032 2331 11724 4026 2325 11725 4028 2327 11726 4033 2332 11727 4032 2331 11728 4028 2327 11729 4034 2333 11730 4033 2332 11731 4028 2327 11732 4035 2334 11733 4034 2333 11734 4028 2327 11735 4036 2335 11736 4035 2334 11737 4028 2327 11738 4037 2336 11739 4036 2335 11740 4028 2327 11741 4038 2337 11742 4037 2336 11743 4028 2327 11744 4039 2338 11745 4038 2337 11746 4028 2327 11747 4040 2339 11748 4041 2340 11749 4030 2329 11750 4042 2341 11751 4040 2339 11752 4030 2329 11753 4043 2342 11754 4042 2341 11755 4030 2329 11756 4044 2343 11757 4043 2342 11758 4030 2329 11759 4045 2344 11760 4044 2343 11761 4030 2329 11762 4046 2345 11763 4045 2344 11764 4030 2329 11765 4047 2346 11766 4046 2345 11767 4030 2329 11768 4029 2328 11769 4047 2346 11770 4030 2329 11771 4048 2343 11772 4049 2347 11773 4050 2348 11774 4051 2341 11775 4052 2349 11776 4053 2350 11777 4054 2344 11778 4048 2343 11779 4050 2348 11780 4055 2345 11781 4054 2344 11782 4050 2348 11783 4056 2346 11784 4055 2345 11785 4050 2348 11786 4057 2351 11787 4056 2346 11788 4050 2348 11789 4058 2352 11790 4057 2351 11791 4050 2348 11792 4059 2325 11793 4058 2352 11794 4050 2348 11795 4060 2331 11796 4059 2325 11797 4050 2348 11798 4061 2353 11799 4060 2331 11800 4050 2348 11801 4062 2333 11802 4063 2354 11803 4052 2349 11804 4064 2334 11805 4062 2333 11806 4052 2349 11807 4065 2335 11808 4064 2334 11809 4052 2349 11810 4066 2336 11811 4065 2335 11812 4052 2349 11813 4067 2355 11814 4066 2336 11815 4052 2349 11816 4068 2356 11817 4067 2355 11818 4052 2349 11819 4069 2339 11820 4068 2356 11821 4052 2349 11822 4051 2341 11823 4069 2339 11824 4052 2349 11825 4070 2357 11826 4071 2357 11827 4072 2357 11828 4073 542 11829 4070 542 11830 4072 542 11831 4074 2358 11832 4073 2358 11833 4072 2358 11834 4075 2359 11835 4076 2359 11836 4071 2359 11837 4070 2360 11838 4075 2360 11839 4071 2360 11840 4075 2361 11841 4077 2361 11842 4076 2361 11843 4078 2362 11844 4079 2362 11845 4077 2362 11846 4080 542 11847 4078 542 11848 4077 542 11849 4081 2363 11850 4080 2363 11851 4077 2363 11852 4075 542 11853 4081 542 11854 4077 542 11855 4082 542 11856 4083 542 11857 4079 542 11858 4084 542 11859 4082 542 11860 4079 542 11861 4078 542 11862 4084 542 11863 4079 542 11864 4085 2364 11865 4086 2364 11866 4083 2364 11867 4082 542 11868 4085 542 11869 4083 542 11870 4087 542 11871 4088 542 11872 4086 542 11873 4085 2365 11874 4087 2365 11875 4086 2365 11876 4089 542 11877 4090 542 11878 4080 542 11879 4081 542 11880 4089 542 11881 4080 542 11882 4091 2366 11883 4092 2366 11884 4090 2366 11885 4089 2367 11886 4091 2367 11887 4090 2367 11888 4074 2368 11889 4093 2368 11890 4073 2368 11891 4094 2369 11892 4095 2369 11893 4093 2369 11894 4074 542 11895 4094 542 11896 4093 542 11897 4096 2370 11898 4097 2370 11899 4095 2370 11900 4094 542 11901 4096 542 11902 4095 542 11903 4098 2371 11904 4099 2371 11905 4097 2371 11906 4096 2372 11907 4098 2372 11908 4097 2372 11909 4100 2373 11910 4101 2373 11911 4099 2373 11912 4098 2374 11913 4100 2374 11914 4099 2374 11915 4100 2375 11916 4102 2375 11917 4101 2375 11918 4103 542 11919 4104 542 11920 4102 542 11921 4105 542 11922 4103 542 11923 4102 542 11924 4106 542 11925 4105 542 11926 4102 542 11927 4100 542 11928 4106 542 11929 4102 542 11930 4107 542 11931 4108 542 11932 4104 542 11933 4103 542 11934 4107 542 11935 4104 542 11936 4106 2376 11937 4109 2376 11938 4105 2376 11939 4106 2377 11940 4110 2377 11941 4109 2377 11942 4111 542 11943 4112 542 11944 4110 542 11945 4106 542 11946 4111 542 11947 4110 542 11948 4111 2378 11949 4113 2378 11950 4112 2378 11951 4111 2379 11952 4114 2379 11953 4113 2379 11954 4111 2380 11955 4115 2380 11956 4114 2380 11957 4116 2381 11958 4117 2381 11959 4115 2381 11960 4111 542 11961 4116 542 11962 4115 542 11963 4118 2382 11964 4119 2382 11965 4117 2382 11966 4116 542 11967 4118 542 11968 4117 542 11969 4120 2383 11970 4121 2383 11971 4119 2383 11972 4118 542 11973 4120 542 11974 4119 542 11975 4122 2384 11976 4123 2384 11977 4121 2384 11978 4120 2385 11979 4122 2385 11980 4121 2385 11981 4124 2386 11982 4125 2386 11983 4123 2386 11984 4122 2387 11985 4124 2387 11986 4123 2387 11987 4126 2388 11988 4127 2388 11989 4125 2388 11990 4128 542 11991 4126 542 11992 4125 542 11993 4129 2389 11994 4128 2389 11995 4125 2389 11996 4130 542 11997 4129 542 11998 4125 542 11999 4131 542 12000 4130 542 12001 4125 542 12002 4132 2390 12003 4131 2390 12004 4125 2390 12005 4133 2391 12006 4132 2391 12007 4125 2391 12008 4124 542 12009 4133 542 12010 4125 542 12011 4134 2392 12012 4135 2392 12013 4127 2392 12014 4136 542 12015 4134 542 12016 4127 542 12017 4137 542 12018 4136 542 12019 4127 542 12020 4138 2393 12021 4137 2393 12022 4127 2393 12023 4139 542 12024 4138 542 12025 4127 542 12026 4126 542 12027 4139 542 12028 4127 542 12029 4140 2394 12030 4141 2394 12031 4135 2394 12032 4134 2395 12033 4140 2395 12034 4135 2395 12035 4142 542 12036 4143 542 12037 4141 542 12038 4140 542 12039 4142 542 12040 4141 542 12041 4144 2396 12042 4145 2396 12043 4143 2396 12044 4142 2397 12045 4144 2397 12046 4143 2397 12047 4146 2398 12048 4147 2398 12049 4145 2398 12050 4144 542 12051 4146 542 12052 4145 542 12053 4148 2399 12054 4149 2399 12055 4147 2399 12056 4146 2400 12057 4148 2400 12058 4147 2400 12059 4150 2401 12060 4151 2401 12061 4149 2401 12062 4148 2402 12063 4150 2402 12064 4149 2402 12065 4152 2403 12066 4153 2403 12067 4151 2403 12068 4150 2404 12069 4152 2404 12070 4151 2404 12071 4152 542 12072 4154 542 12073 4153 542 12074 4152 2405 12075 4155 2405 12076 4154 2405 12077 4152 2406 12078 4156 2406 12079 4155 2406 12080 4152 2407 12081 4157 2407 12082 4156 2407 12083 4158 2408 12084 4159 2408 12085 4157 2408 12086 4152 2409 12087 4158 2409 12088 4157 2409 12089 4158 2410 12090 4160 2410 12091 4159 2410 12092 4158 2411 12093 4161 2411 12094 4160 2411 12095 4158 2412 12096 4162 2412 12097 4161 2412 12098 4158 2413 12099 4163 2413 12100 4162 2413 12101 4158 2414 12102 4164 2414 12103 4163 2414 12104 4158 2415 12105 4165 2415 12106 4164 2415 12107 4166 2416 12108 4167 2416 12109 4165 2416 12110 4158 542 12111 4166 542 12112 4165 542 12113 4168 2417 12114 4169 2417 12115 4167 2417 12116 4166 2418 12117 4168 2418 12118 4167 2418 12119 4170 2419 12120 4171 2419 12121 4169 2419 12122 4168 2420 12123 4170 2420 12124 4169 2420 12125 4172 2421 12126 4173 2421 12127 4171 2421 12128 4170 2422 12129 4172 2422 12130 4171 2422 12131 4174 2423 12132 4175 2423 12133 4173 2423 12134 4172 542 12135 4174 542 12136 4173 542 12137 4176 2424 12138 4177 2424 12139 4175 2424 12140 4178 542 12141 4176 542 12142 4175 542 12143 4179 542 12144 4178 542 12145 4175 542 12146 4180 542 12147 4179 542 12148 4175 542 12149 4174 542 12150 4180 542 12151 4175 542 12152 4181 2425 12153 4182 2425 12154 4177 2425 12155 4183 542 12156 4181 542 12157 4177 542 12158 4184 2426 12159 4183 2426 12160 4177 2426 12161 4176 2427 12162 4184 2427 12163 4177 2427 12164 4185 2428 12165 4186 2428 12166 4182 2428 12167 4187 542 12168 4185 542 12169 4182 542 12170 4181 2429 12171 4187 2429 12172 4182 2429 12173 4188 2430 12174 4189 2430 12175 4186 2430 12176 4185 542 12177 4188 542 12178 4186 542 12179 4190 2431 12180 4191 2431 12181 4189 2431 12182 4188 2432 12183 4190 2432 12184 4189 2432 12185 4192 2433 12186 4193 2433 12187 4191 2433 12188 4190 2434 12189 4192 2434 12190 4191 2434 12191 4194 2435 12192 4195 2435 12193 4193 2435 12194 4192 542 12195 4194 542 12196 4193 542 12197 4196 2436 12198 4197 2436 12199 4195 2436 12200 4194 542 12201 4196 542 12202 4195 542 12203 4198 2437 12204 4199 2437 12205 4197 2437 12206 4196 542 12207 4198 542 12208 4197 542 12209 4198 2438 12210 4200 2438 12211 4199 2438 12212 4201 2439 12213 4202 2439 12214 4200 2439 12215 4203 542 12216 4201 542 12217 4200 542 12218 4204 2440 12219 4203 2440 12220 4200 2440 12221 4198 2441 12222 4204 2441 12223 4200 2441 12224 4205 542 12225 4206 542 12226 4202 542 12227 4207 542 12228 4205 542 12229 4202 542 12230 4201 542 12231 4207 542 12232 4202 542 12233 4208 2442 12234 4209 2442 12235 4206 2442 12236 4205 542 12237 4208 542 12238 4206 542 12239 4210 542 12240 4211 542 12241 4209 542 12242 4208 2443 12243 4210 2443 12244 4209 2443 12245 4212 2444 12246 4213 2444 12247 4203 2444 12248 4204 542 12249 4212 542 12250 4203 542 12251 4214 542 12252 4215 542 12253 4213 542 12254 4212 2445 12255 4214 2445 12256 4213 2445 12257 4216 542 12258 4217 542 12259 4181 542 12260 4183 542 12261 4216 542 12262 4181 542 12263 4218 542 12264 4219 542 12265 4217 542 12266 4216 542 12267 4218 542 12268 4217 542 12269 4220 2446 12270 4221 2447 12271 4222 2448 12272 4223 2449 12273 4224 2450 12274 4225 2451 12275 4226 2452 12276 4227 2452 12277 4228 2453 12278 4226 2452 12279 4228 2453 12280 4229 2453 12281 4230 2454 12282 4231 2455 12283 4232 2455 12284 4233 2456 12285 4234 2457 12286 4221 2447 12287 4235 2458 12288 4225 2451 12289 4236 2459 12290 4237 2460 12291 4233 2456 12292 4221 2447 12293 4238 2461 12294 4237 2460 12295 4221 2447 12296 4239 2462 12297 4238 2461 12298 4221 2447 12299 4240 2463 12300 4239 2462 12301 4221 2447 12302 4220 2446 12303 4240 2463 12304 4221 2447 12305 4241 2464 12306 4223 2449 12307 4225 2451 12308 4242 2465 12309 4241 2464 12310 4225 2451 12311 4243 2466 12312 4242 2465 12313 4225 2451 12314 4244 2467 12315 4243 2466 12316 4225 2451 12317 4235 2458 12318 4244 2467 12319 4225 2451 12320 4245 2468 12321 4246 2468 12322 4247 2469 12323 4248 2470 12324 4249 2471 12325 4250 2471 12326 4248 2470 12327 4251 2470 12328 4249 2471 12329 4252 2469 12330 4247 2469 12331 4253 2472 12332 4252 2469 12333 4245 2468 12334 4247 2469 12335 4254 2472 12336 4253 2472 12337 4255 2473 12338 4254 2472 12339 4252 2469 12340 4253 2472 12341 4256 2473 12342 4255 2473 12343 4257 2474 12344 4256 2473 12345 4254 2472 12346 4255 2473 12347 4258 2474 12348 4257 2474 12349 4259 2475 12350 4258 2474 12351 4256 2473 12352 4257 2474 12353 4260 2475 12354 4259 2475 12355 4227 2452 12356 4260 2475 12357 4258 2474 12358 4259 2475 12359 4226 2452 12360 4260 2475 12361 4227 2452 12362 4261 2476 12363 4262 2476 12364 4263 2476 12365 4264 2454 12366 4231 2455 12367 4230 2454 12368 4265 2477 12369 4263 2477 12370 4266 2477 12371 4265 11 12372 4261 11 12373 4263 11 12374 4267 11 12375 4268 11 12376 4269 11 12377 4270 11 12378 4271 11 12379 4268 11 12380 4267 11 12381 4270 11 12382 4268 11 12383 4267 2478 12384 4269 2478 12385 4272 2478 12386 4267 2479 12387 4272 2479 12388 4273 2479 12389 4274 11 12390 4273 11 12391 4275 11 12392 4274 11 12393 4267 11 12394 4273 11 12395 4274 11 12396 4275 11 12397 4276 11 12398 4274 11 12399 4276 11 12400 4262 11 12401 4261 11 12402 4274 11 12403 4262 11 12404 4264 2454 12405 4230 2454 12406 4277 2480 12407 4278 2480 12408 4277 2480 12409 4279 2481 12410 4278 2480 12411 4264 2454 12412 4277 2480 12413 4280 2481 12414 4279 2481 12415 4281 2482 12416 4280 2481 12417 4278 2480 12418 4279 2481 12419 4282 2482 12420 4281 2482 12421 4283 2483 12422 4282 2482 12423 4280 2481 12424 4281 2482 12425 4284 2483 12426 4283 2483 12427 4251 2470 12428 4284 2483 12429 4282 2482 12430 4283 2483 12431 4248 2470 12432 4284 2483 12433 4251 2470 12434 4265 11 12435 4266 11 12436 4285 11 12437 4265 2484 12438 4285 2484 12439 4286 2484 12440 4287 11 12441 4286 11 12442 4288 11 12443 4265 2485 12444 4286 2485 12445 4287 2485 12446 4287 11 12447 4288 11 12448 4289 11 12449 4287 11 12450 4289 11 12451 4271 11 12452 4270 11 12453 4287 11 12454 4271 11 12455 4290 11 12456 4291 11 12457 4270 11 12458 4267 11 12459 4290 11 12460 4270 11 12461 4292 11 12462 4293 11 12463 4291 11 12464 4290 11 12465 4292 11 12466 4291 11 12467 4294 11 12468 4295 11 12469 4293 11 12470 4292 11 12471 4294 11 12472 4293 11 12473 4296 11 12474 4297 11 12475 4261 11 12476 4265 11 12477 4296 11 12478 4261 11 12479 4298 11 12480 4299 11 12481 4297 11 12482 4296 11 12483 4298 11 12484 4297 11 12485 4300 11 12486 4301 11 12487 4299 11 12488 4298 11 12489 4300 11 12490 4299 11 12491 4305 11 12492 4306 11 12493 4307 11 12494 4352 11 12495 4353 11 12496 4354 11 12497 4355 11 12498 4356 11 12499 4357 11 12500 4358 11 12501 4359 11 12502 4360 11 12503 4364 11 12504 4365 11 12505 4366 11 12506 4367 11 12507 4368 11 12508 4369 11 12509 4370 2486 12510 4371 2486 12511 4372 2486 12512 4390 11 12513 4391 11 12514 4392 11 12515 4393 11 12516 4394 11 12517 4395 11 12518 4396 11 12519 4397 11 12520 4398 11 12521 4399 11 12522 4396 11 12523 4398 11 12524 4400 11 12525 4401 11 12526 4402 11 12527 4413 2487 12528 4414 2487 12529 4415 2487 12530 4416 2129 12531 4417 2130 12532 4418 2131 12533 4419 1735 12534 4413 1735 12535 4415 1735 12536 4420 2488 12537 4421 2488 12538 4422 2488 12539 4423 2489 12540 4420 2489 12541 4422 2489 12542 4423 2490 12543 4422 2490 12544 4424 2490 12545 4425 2135 12546 4418 2131 12547 4426 2136 12548 4427 2137 12549 4416 2129 12550 4418 2131 12551 4425 2135 12552 4427 2137 12553 4418 2131 12554 4419 2491 12555 4428 2491 12556 4413 2491 12557 4429 2492 12558 4430 2492 12559 4431 2492 12560 4432 2140 12561 4425 2135 12562 4426 2136 12563 4433 2141 12564 4432 2140 12565 4426 2136 12566 4434 2142 12567 4435 2142 12568 4428 2142 12569 4436 2493 12570 4437 2144 12571 4438 2494 12572 4419 1735 12573 4434 1735 12574 4428 1735 12575 4439 2495 12576 4431 2495 12577 4440 2495 12578 4439 2496 12579 4429 2496 12580 4431 2496 12581 4441 2148 12582 4442 2148 12583 4435 2148 12584 4443 2149 12585 4438 2494 12586 4444 2150 12587 4434 2151 12588 4441 2151 12589 4435 2151 12590 4443 2149 12591 4436 2493 12592 4438 2494 12593 4445 1735 12594 4446 1735 12595 4442 1735 12596 4447 542 12597 4448 542 12598 4449 542 12599 4441 1735 12600 4445 1735 12601 4442 1735 12602 4450 2152 12603 4443 2149 12604 4444 2150 12605 4451 2153 12606 4452 2153 12607 4446 2153 12608 4453 2154 12609 4454 2155 12610 4455 2156 12611 4445 1735 12612 4451 1735 12613 4446 1735 12614 4456 542 12615 4447 542 12616 4449 542 12617 4456 542 12618 4449 542 12619 4457 542 12620 4458 2157 12621 4459 2157 12622 4452 2157 12623 4460 2497 12624 4455 2156 12625 4461 2159 12626 4451 1735 12627 4458 1735 12628 4452 1735 12629 4460 2497 12630 4453 2154 12631 4455 2156 12632 4462 1735 12633 4463 1735 12634 4459 1735 12635 4464 2498 12636 4465 2498 12637 4466 2498 12638 4458 1735 12639 4462 1735 12640 4459 1735 12641 4467 2161 12642 4460 2497 12643 4461 2159 12644 4462 2499 12645 4468 2499 12646 4463 2499 12647 4469 2163 12648 4470 2164 12649 4471 2165 12650 4472 2500 12651 4464 2500 12652 4466 2500 12653 4472 2501 12654 4466 2501 12655 4473 2501 12656 4474 2168 12657 4471 2165 12658 4475 2169 12659 4476 2170 12660 4469 2163 12661 4471 2165 12662 4474 2168 12663 4476 2170 12664 4471 2165 12665 4477 2502 12666 4478 2502 12667 4479 2502 12668 4480 2172 12669 4474 2168 12670 4475 2169 12671 4481 2173 12672 4480 2172 12673 4475 2169 12674 4482 2503 12675 4483 2175 12676 4484 2176 12677 4485 2504 12678 4479 2504 12679 4486 2504 12680 4485 2505 12681 4477 2505 12682 4479 2505 12683 4487 2179 12684 4484 2176 12685 4488 2180 12686 4487 2179 12687 4482 2503 12688 4484 2176 12689 4489 31 12690 4490 31 12691 4491 31 12692 4492 2181 12693 4487 2179 12694 4488 2180 12695 4493 2182 12696 4494 2183 12697 4495 2184 12698 4496 31 12699 4491 31 12700 4497 31 12701 4496 2506 12702 4489 2506 12703 4491 2506 12704 4498 2185 12705 4495 2184 12706 4499 2186 12707 4498 2185 12708 4493 2182 12709 4495 2184 12710 4500 2187 12711 4498 2185 12712 4499 2186 12713 4501 11 12714 4502 11 12715 4503 11 12716 4504 2188 12717 4505 2189 12718 4506 2190 12719 4507 11 12720 4503 11 12721 4508 11 12722 4509 2191 12723 4510 2191 12724 4511 2192 12725 4507 11 12726 4501 11 12727 4503 11 12728 4509 2191 12729 4511 2192 12730 4512 2192 12731 4513 11 12732 4514 11 12733 4502 11 12734 4515 2190 12735 4506 2190 12736 4516 2193 12737 4517 11 12738 4513 11 12739 4502 11 12740 4501 2194 12741 4517 2194 12742 4502 2194 12743 4515 2190 12744 4504 2188 12745 4506 2190 12746 4518 11 12747 4519 11 12748 4514 11 12749 4520 2195 12750 4516 2193 12751 4521 2196 12752 4513 2197 12753 4518 2197 12754 4514 2197 12755 4515 2190 12756 4516 2193 12757 4520 2195 12758 4518 11 12759 4522 11 12760 4519 11 12761 4523 2198 12762 4521 2196 12763 4524 2199 12764 4520 2195 12765 4521 2196 12766 4523 2198 12767 4525 11 12768 4526 11 12769 4522 11 12770 4527 2200 12771 4524 2199 12772 4528 2201 12773 4529 2202 12774 4525 2202 12775 4522 2202 12776 4518 11 12777 4529 11 12778 4522 11 12779 4523 2198 12780 4524 2199 12781 4527 2200 12782 4530 11 12783 4531 11 12784 4526 11 12785 4532 2203 12786 4528 2201 12787 4533 2204 12788 4525 11 12789 4530 11 12790 4526 11 12791 4527 2200 12792 4528 2201 12793 4532 2203 12794 4534 11 12795 4535 11 12796 4531 11 12797 4536 2204 12798 4533 2204 12799 4537 2205 12800 4538 11 12801 4534 11 12802 4531 11 12803 4530 2206 12804 4538 2206 12805 4531 2206 12806 4532 2203 12807 4533 2204 12808 4536 2204 12809 4539 11 12810 4540 11 12811 4535 11 12812 4541 2207 12813 4542 2207 12814 4543 2208 12815 4539 11 12816 4535 11 12817 4534 11 12818 4536 2204 12819 4537 2205 12820 4544 2205 12821 4545 2507 12822 4546 2507 12823 4540 2507 12824 4547 2208 12825 4543 2208 12826 4548 2210 12827 4549 11 12828 4545 11 12829 4540 11 12830 4539 11 12831 4549 11 12832 4540 11 12833 4541 2207 12834 4543 2208 12835 4547 2208 12836 4550 11 12837 4551 11 12838 4546 11 12839 4552 2211 12840 4548 2210 12841 4553 2212 12842 4545 11 12843 4550 11 12844 4546 11 12845 4547 2208 12846 4548 2210 12847 4552 2211 12848 4550 11 12849 4554 11 12850 4551 11 12851 4555 2213 12852 4553 2212 12853 4556 2214 12854 4552 2211 12855 4553 2212 12856 4555 2213 12857 4557 11 12858 4558 11 12859 4554 11 12860 4559 2215 12861 4556 2214 12862 4560 2216 12863 4561 11 12864 4557 11 12865 4554 11 12866 4550 11 12867 4561 11 12868 4554 11 12869 4555 2213 12870 4556 2214 12871 4559 2215 12872 4562 11 12873 4508 11 12874 4558 11 12875 4563 2217 12876 4560 2216 12877 4510 2191 12878 4557 11 12879 4562 11 12880 4558 11 12881 4559 2215 12882 4560 2216 12883 4563 2217 12884 4564 11 12885 4507 11 12886 4508 11 12887 4562 11 12888 4564 11 12889 4508 11 12890 4563 2217 12891 4510 2191 12892 4509 2191 12893 4565 2218 12894 4566 2219 12895 4567 2220 12896 4568 2221 12897 4569 2222 12898 4570 2223 12899 4571 2224 12900 4570 2223 12901 4572 2225 12902 4568 2221 12903 4570 2223 12904 4571 2224 12905 4573 2226 12906 4567 2220 12907 4574 2227 12908 4575 2228 12909 4567 2220 12910 4573 2226 12911 4565 2218 12912 4567 2220 12913 4575 2228 12914 4576 2229 12915 4574 2227 12916 4577 2230 12917 4576 2229 12918 4573 2226 12919 4574 2227 12920 4578 2231 12921 4577 2230 12922 4579 2232 12923 4576 2229 12924 4577 2230 12925 4578 2231 12926 4580 11 12927 4581 11 12928 4529 11 12929 4582 2233 12930 4579 2232 12931 4583 2234 12932 4518 11 12933 4580 11 12934 4529 11 12935 4578 2231 12936 4579 2232 12937 4582 2233 12938 4584 11 12939 4585 11 12940 4581 11 12941 4586 2235 12942 4583 2234 12943 4587 2236 12944 4580 11 12945 4584 11 12946 4581 11 12947 4582 2233 12948 4583 2234 12949 4586 2235 12950 4584 11 12951 4588 11 12952 4585 11 12953 4586 2235 12954 4587 2236 12955 4589 2237 12956 4590 2238 12957 4589 2237 12958 4591 2239 12959 4590 2238 12960 4586 2235 12961 4589 2237 12962 4592 2240 12963 4591 2239 12964 4593 2241 12965 4590 2238 12966 4591 2239 12967 4592 2240 12968 4594 2508 12969 4593 2241 12970 4595 2243 12971 4592 2240 12972 4593 2241 12973 4594 2508 12974 4596 2244 12975 4595 2243 12976 4597 2509 12977 4594 2508 12978 4595 2243 12979 4596 2244 12980 4598 2246 12981 4597 2509 12982 4599 2510 12983 4598 2246 12984 4596 2244 12985 4597 2509 12986 4598 2246 12987 4599 2510 12988 4600 2248 12989 4601 2249 12990 4600 2248 12991 4602 2250 12992 4598 2246 12993 4600 2248 12994 4601 2249 12995 4603 2251 12996 4604 2252 12997 4605 2253 12998 4606 2254 12999 4602 2250 13000 4607 2255 13001 4601 2249 13002 4602 2250 13003 4606 2254 13004 4608 2256 13005 4605 2253 13006 4609 2257 13007 4610 2258 13008 4605 2253 13009 4608 2256 13010 4603 2251 13011 4605 2253 13012 4610 2258 13013 4611 2259 13014 4609 2257 13015 4612 2260 13016 4611 2259 13017 4608 2256 13018 4609 2257 13019 4613 2261 13020 4612 2260 13021 4614 2262 13022 4611 2259 13023 4612 2260 13024 4613 2261 13025 4615 11 13026 4616 11 13027 4561 11 13028 4617 2263 13029 4614 2262 13030 4618 2264 13031 4550 2265 13032 4615 2265 13033 4561 2265 13034 4613 2261 13035 4614 2262 13036 4617 2263 13037 4619 11 13038 4620 11 13039 4616 11 13040 4621 2266 13041 4618 2264 13042 4622 2267 13043 4615 11 13044 4619 11 13045 4616 11 13046 4617 2263 13047 4618 2264 13048 4621 2266 13049 4619 11 13050 4623 11 13051 4620 11 13052 4621 2266 13053 4622 2267 13054 4624 2268 13055 4625 2269 13056 4624 2268 13057 4626 2270 13058 4625 2269 13059 4621 2266 13060 4624 2268 13061 4627 2271 13062 4626 2270 13063 4628 2272 13064 4625 2269 13065 4626 2270 13066 4627 2271 13067 4629 2273 13068 4628 2272 13069 4630 2274 13070 4627 2271 13071 4628 2272 13072 4629 2273 13073 4631 2275 13074 4630 2274 13075 4632 2511 13076 4629 2273 13077 4630 2274 13078 4631 2275 13079 4633 2277 13080 4632 2511 13081 4634 2512 13082 4633 2277 13083 4631 2275 13084 4632 2511 13085 4633 2277 13086 4634 2512 13087 4569 2222 13088 4633 2277 13089 4569 2222 13090 4568 2221 13091 4635 11 13092 4636 11 13093 4637 11 13094 4638 11 13095 4635 11 13096 4637 11 13097 4639 11 13098 4638 11 13099 4637 11 13100 4640 11 13101 4641 11 13102 4636 11 13103 4635 11 13104 4640 11 13105 4636 11 13106 4642 11 13107 4643 11 13108 4641 11 13109 4640 11 13110 4642 11 13111 4641 11 13112 4639 11 13113 4644 11 13114 4638 11 13115 4645 11 13116 4646 11 13117 4644 11 13118 4639 11 13119 4645 11 13120 4644 11 13121 4647 11 13122 4648 11 13123 4646 11 13124 4645 11 13125 4647 11 13126 4646 11 13127 4681 11 13128 4682 11 13129 4683 11 13130 4706 11 13131 4707 11 13132 4708 11 13133 4709 11 13134 4710 11 13135 4711 11 13136 4712 11 13137 4709 11 13138 4711 11 13139 4713 11 13140 4714 11 13141 4715 11 13142 4716 11 13143 4717 11 13144 4718 11 13145 4728 11 13146 4729 11 13147 4730 11 13148 4745 11 13149 4746 11 13150 4747 11 13151 4767 1735 13152 4768 1735 13153 4769 1735 13154 4770 2129 13155 4771 2130 13156 4772 2131 13157 4773 2513 13158 4767 2513 13159 4769 2513 13160 4774 2514 13161 4775 2514 13162 4776 2514 13163 4777 2515 13164 4774 2515 13165 4776 2515 13166 4777 2516 13167 4776 2516 13168 4778 2516 13169 4779 2135 13170 4772 2131 13171 4780 2136 13172 4781 2137 13173 4770 2129 13174 4772 2131 13175 4779 2135 13176 4781 2137 13177 4772 2131 13178 4773 1735 13179 4782 1735 13180 4767 1735 13181 4783 2517 13182 4784 2517 13183 4785 2517 13184 4786 2140 13185 4779 2135 13186 4780 2136 13187 4787 2141 13188 4786 2140 13189 4780 2136 13190 4788 2518 13191 4789 2518 13192 4782 2518 13193 4790 2143 13194 4791 2519 13195 4792 2494 13196 4773 2520 13197 4788 2520 13198 4782 2520 13199 4793 2521 13200 4785 2521 13201 4794 2521 13202 4793 2522 13203 4783 2522 13204 4785 2522 13205 4795 2523 13206 4796 2523 13207 4789 2523 13208 4797 2149 13209 4792 2494 13210 4798 2150 13211 4788 2524 13212 4795 2524 13213 4789 2524 13214 4797 2149 13215 4790 2143 13216 4792 2494 13217 4799 1735 13218 4800 1735 13219 4796 1735 13220 4801 542 13221 4802 542 13222 4803 542 13223 4795 1735 13224 4799 1735 13225 4796 1735 13226 4804 2152 13227 4797 2149 13228 4798 2150 13229 4805 2525 13230 4806 2525 13231 4800 2525 13232 4807 2154 13233 4808 2526 13234 4809 2156 13235 4799 1735 13236 4805 1735 13237 4800 1735 13238 4810 542 13239 4801 542 13240 4803 542 13241 4810 542 13242 4803 542 13243 4811 542 13244 4812 2527 13245 4813 2527 13246 4806 2527 13247 4814 2158 13248 4809 2156 13249 4815 2159 13250 4805 2528 13251 4812 2528 13252 4806 2528 13253 4814 2158 13254 4807 2154 13255 4809 2156 13256 4816 1735 13257 4817 1735 13258 4813 1735 13259 4818 2529 13260 4819 2529 13261 4820 2529 13262 4812 1735 13263 4816 1735 13264 4813 1735 13265 4821 2161 13266 4814 2158 13267 4815 2159 13268 4816 1735 13269 4822 1735 13270 4817 1735 13271 4823 2163 13272 4824 2164 13273 4825 2165 13274 4826 2530 13275 4818 2530 13276 4820 2530 13277 4826 2531 13278 4820 2531 13279 4827 2531 13280 4828 2168 13281 4825 2165 13282 4829 2169 13283 4830 2170 13284 4823 2163 13285 4825 2165 13286 4828 2168 13287 4830 2170 13288 4825 2165 13289 4831 2532 13290 4832 2532 13291 4833 2532 13292 4834 2172 13293 4828 2168 13294 4829 2169 13295 4835 2173 13296 4834 2172 13297 4829 2169 13298 4836 2503 13299 4837 2533 13300 4838 2534 13301 4839 2535 13302 4833 2535 13303 4840 2535 13304 4839 2536 13305 4831 2536 13306 4833 2536 13307 4841 2179 13308 4838 2534 13309 4842 2180 13310 4841 2179 13311 4836 2503 13312 4838 2534 13313 4843 31 13314 4844 31 13315 4845 31 13316 4846 2181 13317 4841 2179 13318 4842 2180 13319 4847 2182 13320 4848 2183 13321 4849 2184 13322 4850 31 13323 4845 31 13324 4851 31 13325 4850 31 13326 4843 31 13327 4845 31 13328 4852 2537 13329 4849 2184 13330 4853 2186 13331 4852 2537 13332 4847 2182 13333 4849 2184 13334 4854 2187 13335 4852 2537 13336 4853 2186 13337 4855 11 13338 4856 11 13339 4857 11 13340 4858 2188 13341 4859 2188 13342 4860 2190 13343 4861 11 13344 4857 11 13345 4862 11 13346 4863 2191 13347 4864 2191 13348 4865 2192 13349 4861 11 13350 4855 11 13351 4857 11 13352 4863 2191 13353 4865 2192 13354 4866 2192 13355 4867 11 13356 4868 11 13357 4856 11 13358 4869 2190 13359 4860 2190 13360 4870 2193 13361 4871 11 13362 4867 11 13363 4856 11 13364 4855 2538 13365 4871 2538 13366 4856 2538 13367 4869 2190 13368 4858 2188 13369 4860 2190 13370 4872 11 13371 4873 11 13372 4868 11 13373 4874 2195 13374 4870 2193 13375 4875 2196 13376 4867 2539 13377 4872 2539 13378 4868 2539 13379 4869 2190 13380 4870 2193 13381 4874 2195 13382 4872 11 13383 4876 11 13384 4873 11 13385 4877 2198 13386 4875 2196 13387 4878 2199 13388 4874 2195 13389 4875 2196 13390 4877 2198 13391 4879 11 13392 4880 11 13393 4876 11 13394 4881 2200 13395 4878 2199 13396 4882 2201 13397 4883 11 13398 4879 11 13399 4876 11 13400 4872 11 13401 4883 11 13402 4876 11 13403 4877 2198 13404 4878 2199 13405 4881 2200 13406 4884 11 13407 4885 11 13408 4880 11 13409 4886 2203 13410 4882 2201 13411 4887 2204 13412 4879 11 13413 4884 11 13414 4880 11 13415 4881 2200 13416 4882 2201 13417 4886 2203 13418 4888 11 13419 4889 11 13420 4885 11 13421 4890 2204 13422 4887 2204 13423 4891 2205 13424 4892 11 13425 4888 11 13426 4885 11 13427 4884 2540 13428 4892 2540 13429 4885 2540 13430 4886 2203 13431 4887 2204 13432 4890 2204 13433 4893 11 13434 4894 11 13435 4889 11 13436 4895 2207 13437 4896 2207 13438 4897 2208 13439 4893 11 13440 4889 11 13441 4888 11 13442 4890 2204 13443 4891 2205 13444 4898 2205 13445 4899 2541 13446 4900 2541 13447 4894 2541 13448 4901 2208 13449 4897 2208 13450 4902 2210 13451 4903 11 13452 4899 11 13453 4894 11 13454 4893 11 13455 4903 11 13456 4894 11 13457 4895 2207 13458 4897 2208 13459 4901 2208 13460 4904 11 13461 4905 11 13462 4900 11 13463 4906 2211 13464 4902 2210 13465 4907 2212 13466 4899 2542 13467 4904 2542 13468 4900 2542 13469 4901 2208 13470 4902 2210 13471 4906 2211 13472 4904 11 13473 4908 11 13474 4905 11 13475 4909 2213 13476 4907 2212 13477 4910 2214 13478 4906 2211 13479 4907 2212 13480 4909 2213 13481 4911 2543 13482 4912 2543 13483 4908 2543 13484 4913 2215 13485 4910 2214 13486 4914 2216 13487 4915 11 13488 4911 11 13489 4908 11 13490 4904 11 13491 4915 11 13492 4908 11 13493 4909 2213 13494 4910 2214 13495 4913 2215 13496 4916 11 13497 4862 11 13498 4912 11 13499 4917 2217 13500 4914 2216 13501 4864 2191 13502 4911 11 13503 4916 11 13504 4912 11 13505 4913 2215 13506 4914 2216 13507 4917 2217 13508 4918 11 13509 4861 11 13510 4862 11 13511 4916 11 13512 4918 11 13513 4862 11 13514 4917 2217 13515 4864 2191 13516 4863 2191 13517 4919 2218 13518 4920 2219 13519 4921 2220 13520 4922 2221 13521 4923 2222 13522 4924 2223 13523 4925 2544 13524 4924 2223 13525 4926 2225 13526 4922 2221 13527 4924 2223 13528 4925 2544 13529 4927 2226 13530 4921 2220 13531 4928 2227 13532 4929 2228 13533 4921 2220 13534 4927 2226 13535 4919 2218 13536 4921 2220 13537 4929 2228 13538 4930 2229 13539 4928 2227 13540 4931 2230 13541 4930 2229 13542 4927 2226 13543 4928 2227 13544 4932 2231 13545 4931 2230 13546 4933 2232 13547 4930 2229 13548 4931 2230 13549 4932 2231 13550 4934 11 13551 4935 11 13552 4883 11 13553 4936 2233 13554 4933 2232 13555 4937 2545 13556 4872 11 13557 4934 11 13558 4883 11 13559 4932 2231 13560 4933 2232 13561 4936 2233 13562 4938 11 13563 4939 11 13564 4935 11 13565 4940 2546 13566 4937 2545 13567 4941 2547 13568 4934 11 13569 4938 11 13570 4935 11 13571 4936 2233 13572 4937 2545 13573 4940 2546 13574 4938 11 13575 4942 11 13576 4939 11 13577 4940 2546 13578 4941 2547 13579 4943 2237 13580 4944 2238 13581 4943 2237 13582 4945 2239 13583 4944 2238 13584 4940 2546 13585 4943 2237 13586 4946 2240 13587 4945 2239 13588 4947 2548 13589 4944 2238 13590 4945 2239 13591 4946 2240 13592 4948 2242 13593 4947 2548 13594 4949 2243 13595 4946 2240 13596 4947 2548 13597 4948 2242 13598 4950 2549 13599 4949 2243 13600 4951 2509 13601 4948 2242 13602 4949 2243 13603 4950 2549 13604 4952 2246 13605 4951 2509 13606 4953 2247 13607 4952 2246 13608 4950 2549 13609 4951 2509 13610 4952 2246 13611 4953 2247 13612 4954 2248 13613 4955 2249 13614 4954 2248 13615 4956 2250 13616 4952 2246 13617 4954 2248 13618 4955 2249 13619 4957 2251 13620 4958 2252 13621 4959 2253 13622 4960 2254 13623 4956 2250 13624 4961 2255 13625 4955 2249 13626 4956 2250 13627 4960 2254 13628 4962 2256 13629 4959 2253 13630 4963 2257 13631 4964 2550 13632 4959 2253 13633 4962 2256 13634 4957 2251 13635 4959 2253 13636 4964 2550 13637 4965 2259 13638 4963 2257 13639 4966 2260 13640 4965 2259 13641 4962 2256 13642 4963 2257 13643 4967 2261 13644 4966 2260 13645 4968 2262 13646 4965 2259 13647 4966 2260 13648 4967 2261 13649 4969 11 13650 4970 11 13651 4915 11 13652 4971 2551 13653 4968 2262 13654 4972 2552 13655 4904 11 13656 4969 11 13657 4915 11 13658 4967 2261 13659 4968 2262 13660 4971 2551 13661 4973 11 13662 4974 11 13663 4970 11 13664 4975 2553 13665 4972 2552 13666 4976 2267 13667 4969 11 13668 4973 11 13669 4970 11 13670 4971 2551 13671 4972 2552 13672 4975 2553 13673 4973 11 13674 4977 11 13675 4974 11 13676 4975 2553 13677 4976 2267 13678 4978 2268 13679 4979 2269 13680 4978 2268 13681 4980 2270 13682 4979 2269 13683 4975 2553 13684 4978 2268 13685 4981 2271 13686 4980 2270 13687 4982 2554 13688 4979 2269 13689 4980 2270 13690 4981 2271 13691 4983 2555 13692 4982 2554 13693 4984 2274 13694 4981 2271 13695 4982 2554 13696 4983 2555 13697 4985 2556 13698 4984 2274 13699 4986 2511 13700 4983 2555 13701 4984 2274 13702 4985 2556 13703 4987 2277 13704 4986 2511 13705 4988 2278 13706 4987 2277 13707 4985 2556 13708 4986 2511 13709 4987 2277 13710 4988 2278 13711 4923 2222 13712 4987 2277 13713 4923 2222 13714 4922 2221 13715 4989 11 13716 4990 11 13717 4991 11 13718 4992 11 13719 4989 11 13720 4991 11 13721 4993 11 13722 4992 11 13723 4991 11 13724 4994 11 13725 4995 11 13726 4990 11 13727 4989 11 13728 4994 11 13729 4990 11 13730 4996 11 13731 4997 11 13732 4995 11 13733 4994 11 13734 4996 11 13735 4995 11 13736 4993 11 13737 4998 11 13738 4992 11 13739 4999 11 13740 5000 11 13741 4998 11 13742 4993 11 13743 4999 11 13744 4998 11 13745 5001 11 13746 5002 11 13747 5000 11 13748 4999 11 13749 5001 11 13750 5000 11 13751 5003 11 13752 5004 11 13753 5005 11 13754

+
+ + + + +

3387 542 13755 3388 542 13756 3389 542 13757 3390 555 13758 3391 555 13759 3392 555 13760 3396 555 13761 3397 555 13762 3398 555 13763 3399 2557 13764 3400 2557 13765 3401 2557 13766 3402 31 13767 3403 31 13768 3404 31 13769 3405 555 13770 3406 555 13771 3407 555 13772 3399 2557 13773 3401 2557 13774 3408 2557 13775 3405 555 13776 3407 555 13777 3409 555 13778 3410 542 13779 3411 542 13780 3412 542 13781 3413 2558 13782 3414 2559 13783 3415 2560 13784 3416 2561 13785 3414 2559 13786 3413 2558 13787 3417 2562 13788 3415 2560 13789 3418 2563 13790 3413 2558 13791 3415 2560 13792 3417 2562 13793 3419 31 13794 3420 31 13795 3421 31 13796 3417 2562 13797 3418 2563 13798 3422 2564 13799 3419 31 13800 3421 31 13801 3423 31 13802 3669 2453 13803 3670 2453 13804 3671 2453 13805 3672 542 13806 3673 542 13807 3674 542 13808 3678 2565 13809 3679 2565 13810 3680 2565 13811 3681 2566 13812 3682 2566 13813 3683 2566 13814 3684 2567 13815 3685 2568 13816 3686 2569 13817 3687 2570 13818 3685 2568 13819 3684 2567 13820 4302 31 13821 4303 31 13822 4304 31 13823 4308 2569 13824 4309 2569 13825 4310 2569 13826 4311 11 13827 4312 11 13828 4313 11 13829 4314 11 13830 4315 11 13831 4312 11 13832 4311 11 13833 4316 11 13834 4312 11 13835 4317 2571 13836 4312 2571 13837 4316 2571 13838 4318 11 13839 4312 11 13840 4317 11 13841 4318 11 13842 4314 11 13843 4312 11 13844 4319 11 13845 4320 11 13846 4315 11 13847 4321 11 13848 4319 11 13849 4315 11 13850 4314 11 13851 4321 11 13852 4315 11 13853 4322 2572 13854 4323 2572 13855 4320 2572 13856 4324 11 13857 4322 11 13858 4320 11 13859 4325 11 13860 4324 11 13861 4320 11 13862 4319 11 13863 4325 11 13864 4320 11 13865 4326 11 13866 4327 11 13867 4323 11 13868 4322 11 13869 4326 11 13870 4323 11 13871 4328 11 13872 4329 11 13873 4324 11 13874 4330 11 13875 4328 11 13876 4324 11 13877 4331 11 13878 4330 11 13879 4324 11 13880 4325 11 13881 4331 11 13882 4324 11 13883 4317 11 13884 4316 11 13885 4329 11 13886 4328 11 13887 4317 11 13888 4329 11 13889 4332 11 13890 4333 11 13891 4334 11 13892 4335 11 13893 4332 11 13894 4334 11 13895 4336 11 13896 4337 11 13897 4338 11 13898 4339 11 13899 4336 11 13900 4338 11 13901 4340 11 13902 4341 11 13903 4336 11 13904 4339 11 13905 4340 11 13906 4336 11 13907 4342 11 13908 4343 11 13909 4344 11 13910 4345 11 13911 4342 11 13912 4344 11 13913 4346 11 13914 4345 11 13915 4344 11 13916 4345 11 13917 4347 11 13918 4342 11 13919 4348 11 13920 4349 11 13921 4347 11 13922 4350 11 13923 4348 11 13924 4347 11 13925 4345 11 13926 4350 11 13927 4347 11 13928 4350 11 13929 4351 11 13930 4348 11 13931 4361 2573 13932 4362 2573 13933 4363 2573 13934 4373 542 13935 4374 542 13936 4375 542 13937 4376 555 13938 4377 555 13939 4378 555 13940 4379 542 13941 4380 542 13942 4381 542 13943 4382 1123 13944 4383 1123 13945 4384 1123 13946 4382 1123 13947 4384 1123 13948 4385 1123 13949 4386 555 13950 4387 555 13951 4388 555 13952 4389 542 13953 4379 542 13954 4381 542 13955 4403 555 13956 4404 555 13957 4405 555 13958 4406 31 13959 4407 31 13960 4408 31 13961 4406 31 13962 4408 31 13963 4409 31 13964 4410 2574 13965 4411 2574 13966 4412 2574 13967 4649 2575 13968 4650 2576 13969 4651 2577 13970 4652 2578 13971 4650 2576 13972 4649 2575 13973 4653 2579 13974 4654 2580 13975 4655 2581 13976 4656 2582 13977 4654 2580 13978 4653 2579 13979 4657 2583 13980 4655 2581 13981 4658 2584 13982 4653 2579 13983 4655 2581 13984 4657 2583 13985 4659 2585 13986 4658 2584 13987 4660 2586 13988 4657 2583 13989 4658 2584 13990 4659 2585 13991 4661 2587 13992 4660 2586 13993 4662 2588 13994 4659 2585 13995 4660 2586 13996 4661 2587 13997 4661 2587 13998 4662 2588 13999 4663 2589 14000 4664 1123 14001 4665 1123 14002 4666 1123 14003 4667 31 14004 4668 31 14005 4669 31 14006 4667 31 14007 4669 31 14008 4670 31 14009 4671 542 14010 4672 542 14011 4673 542 14012 4674 1123 14013 4664 1123 14014 4666 1123 14015 4675 555 14016 4676 555 14017 4677 555 14018 4678 542 14019 4679 542 14020 4680 542 14021 4684 542 14022 4685 542 14023 4686 542 14024 4687 1123 14025 4688 1123 14026 4689 1123 14027 4690 2590 14028 4691 2590 14029 4692 2590 14030 4684 542 14031 4686 542 14032 4693 542 14033 4694 1123 14034 4695 1123 14035 4696 1123 14036 4690 2591 14037 4692 2591 14038 4697 2591 14039 4698 542 14040 4699 542 14041 4700 542 14042 4694 1123 14043 4696 1123 14044 4701 1123 14045 4702 555 14046 4703 555 14047 4704 555 14048 4698 542 14049 4700 542 14050 4705 542 14051 4719 31 14052 4720 31 14053 4721 31 14054 4722 555 14055 4723 555 14056 4724 555 14057 4725 542 14058 4726 542 14059 4727 542 14060 4731 555 14061 4732 555 14062 4733 555 14063 4734 1123 14064 4735 1123 14065 4736 1123 14066 4737 31 14067 4738 31 14068 4739 31 14069 4737 31 14070 4739 31 14071 4740 31 14072 4741 542 14073 4742 542 14074 4743 542 14075 4744 1123 14076 4734 1123 14077 4736 1123 14078 4748 555 14079 4749 555 14080 4750 555 14081 4751 1123 14082 4752 1123 14083 4753 1123 14084 4754 31 14085 4755 31 14086 4756 31 14087 4754 31 14088 4756 31 14089 4757 31 14090 4758 555 14091 4759 555 14092 4760 555 14093 4761 555 14094 4762 555 14095 4763 555 14096 4764 31 14097 4765 31 14098 4766 31 14099 5006 2592 14100 5007 2593 14101 5008 2594 14102 5009 2595 14103 5007 2593 14104 5006 2592 14105

+
+
+
+
+ + + + + 7.54969e-11 4.01334e-10 9.99987e-4 0 9.99987e-4 -2.38416e-10 -7.54968e-11 0 2.38415e-10 9.99987e-4 -4.01334e-10 0 0 0 0 1 + + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl new file mode 100644 index 0000000000000000000000000000000000000000..bae34a09c013db51315380b61f84d8c063869b94 GIT binary patch literal 6284 zcmb7|d2Cfx5QoQ5rIY}&77i?9zJtQ@#HBbef#GOejvNo-1$Y>_w}~_^>2}^f8JFSshGGR z*5%BkXt&(!{q~+Z9C1!Iy|V27XKh8~^2W6255va{Sv+Z(_qSQks+!0O5jTsV^3}Qx zLte}{=+X3KHtXD)=+)Zd*sUUHMf$UxlS7^W>X8ZVm&Vnjirg8 z73p6Jhem$a&#jwTv52lB+KZraw9l%D`?-~-C$k>1c5!YJK`YW#${|g;Bx77YT@l?h zqd1mTS{9{p@tZ4=y~@SKpeM6W#y%WtJ-RMhdgpghT9Gc*UL4h)Bx5+@>ZrQtN)c2# zwrb(6wu?beW)D3-E_UeJ(&&~+^-)@pE>}%8sJ4j*B`d)?_$uC*>n;4Gj_y# ziJ%o}*Bd8>kJ+D$F;zs~%pGy}R8;mVkJIZm>~}Hf$?QR8e(>7T>i3j6tw_7x*q3wC zkCB&LtLmL1sC3ePJi4Vz+{K_Lvl{JSx6yUgW!gbnk#_sv*dsHZ%;R$r4WsI+7mJ|c z@3R+!p3FLL84#N@t7D?Wp)XQ(2nf4_8aN-M@sSQ)uS2D z>`C=Tw@X74otpZ?v!Y+ukCnZP{1|=@CR`6valN5F_h`mb9y%Egb)Vo7v?5)j-gvs8 z)Q^!V;(&;5ib3TuomY8hs=OHVq`FF;iC!MGB3-NAD4Vp*k1;{SpS8t_wu(XJc=Fu! zV$hS>#^l-V#h?}GyoKv4OKpW8<4Y0CCoV{IRtzfdFG<_E=hR^@20fV#s;Y@E6X8~u zR;2$>Z#)y^(OSfFB5oH!r9r*%LdHQa20iH%J-4P>?~jCgf6$6_t$JgAupi|j^!`Y6 z6+z_*^~NxNKj_J<_vrfSYJbmZMY?rXW_){4S9geTd+sWc%Ey)C<7s|f(UaMX!mLE5 zYS*n5tw{f=-Z&rhhiW&`MMS0uDyRCaiXYL>^*KG6-7D)cqI!y;73sao;n$$gvqcn% zaCuN^qa3y?7Z-z`%#JJT^P}pk-ONBM(q-C%41+|>OJUsW045g=TufJk9O;m z??J{hYf$EuIvrYzpcUy7*Bin6{8tgBB3va>iE2M)>&$X_(39DI?O={hIrmhwBE3y@ zl^M(>yF@%9;uaB98sFR;ul45=dNOOTN}Q+j-BmlSNPnx|XgM}DUpZpF2=`P}4yZTI z`12J#nLVaT&(VyPA%a$WvQmoJdb*_3Djdnk?N@(Ten1 z^+rW7?>a(V<;}ZP`l~nc{dt$3%(muV80dD%tUSgUmoqhIc(XO5W)4abR7%uAOa1Ad zvCTRZTnGp%%!BJ@HW>sJ?jS41>{5PH3@WT$_KMl~f(yG-c~D{3@{~y0rU)uLuXsM1 zoy~7rD=Ivx`DO^mpu%?)--%&@3g6D02Eqgt&Ly0K%=-HK(b!lPqr!=d6JR(770#lZ zeZvG5?ME=(bLtNhRNPagzH8jmHho8pENI#fDlYTX7ahAG9D@ogpEYf^Hup+Zk}Ho< zVI8wV&EC$v67(PyRwe7r?DgEaK}S(xjj?*dc~D`+uoldY<<1TIg9`VbI~$Hcg}cdp z^705Wr^3DAs+;|OHa#GyaHYA1O;6=&mkQU7D`HlM7*x0l%+Ktnv+2Q}Q(;bg+NP)a z=ef%#WNfpvnxb7vt~^GC@xn0%Yl>;q?MEBEKlla+trbpfvzUnMBGN_hJYTK3XRUuH zLr-S!Y3^C6TO3EQCwOy1+AJ=@-4wYQjtb+^Q)sOcBp4%ni_^rEC#diqCVXF#B2*;_ z-g59ZB7AE=f-&fqo>KPi|MCP^kvY**nBZ){cQ`$T2~I_vUg#-Ia318`Mo(dalQ1V% zdI}T#2H>ntPho;zKm1Cer!c|qK7OCkQ<&fvFTYIbDNOKNpWo#46ef7f!P^LW3KP8F z;XMpJg$dRuZ=mQYOt5}fea+V{6~=2m1{FSg^O;lOiZ;I=RJhMKt`gVhR9Jn@*De+I tMDra*g)7Z94DSaOt{Ye6hQz;aJeXgYpu(K^v|)k@pYXpu730y9+21WY#bE#d literal 0 HcmV?d00001 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae new file mode 100644 index 0000000000..c5e6720a80 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae @@ -0,0 +1,109 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T14:19:13 + 2019-01-15T14:19:13 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 66.62159 199.1908 -7.838266 73 200.4 0 67.04737 198.805 0 73 201.1355 9.366105 67.04737 198.805 0 73 200.4 0 62.35687 147.4 -4.909072 66.62159 199.1908 -7.838266 67.04737 198.805 0 62.55 147.4 0 66.65715 199.1585 7.50474 62.55 147.4 0 67.04737 198.805 0 66.65715 199.1585 7.50474 73 200.5892 -4.744023 73 201.1355 9.366105 73 200.4 0 73 200.5892 -4.744023 73 201.145 -9.425759 73 201.145 -9.425759 65.23722 200.4394 -16.08258 73 203.3566 -18.60236 73 203.3307 18.52296 73 203.3566 -18.60236 62.89741 202.5284 -24.14646 73 206.9651 -27.28928 73 205.5958 -4.636376 73 206.9651 -27.28928 73 205.5785 4.426485 59.50509 205.5042 -32.14698 73 211.8458 -35.24898 73 207.099 -13.56462 73 211.8458 -35.24898 54.97298 212.6055 -43.80249 73 217.9537 -42.40642 73 214.3578 -30.08507 73 217.9537 -42.40642 54.97298 209.3612 -39.97518 73 210.0452 -22.12212 54.97298 219.9317 -50.6487 73 225.1053 -48.5209 73 219.9292 -37.24397 73 225.1053 -48.5209 54.97298 216.1361 -47.36745 54.97298 228.2261 -56.28329 73 233.1109 -53.43502 73 226.6157 -43.40071 73 233.1109 -53.43502 54.97298 223.9698 -53.62659 54.97298 237.29 -60.57145 73 241.7791 -57.03734 73 234.1582 -48.33597 73 241.7791 -57.03734 54.97298 232.675 -58.60287 54.97298 246.9069 -63.41062 73 250.9048 -59.24386 73 242.4686 -51.99485 73 250.9048 -59.24386 54.97298 242.0435 -62.17724 54.97298 256.8465 -64.73287 73 260.2702 -59.99981 73 251.3035 -54.24254 73 260.2702 -59.99981 54.97298 251.8511 -64.2642 54.97298 266.8711 -64.50656 73 269.6504 -59.28258 73 260.4 -55 73 269.6504 -59.28258 54.97298 261.8632 -64.81381 73 255.819 -54.80755 54.97298 276.7409 -62.73711 73 278.8189 -57.10287 73 278.2565 -52.02062 73 278.8189 -57.10287 54.97298 271.8403 -63.81294 73 269.4408 -54.25185 54.97298 286.2198 -59.46686 73 287.5507 -53.50549 73 286.5788 -48.37014 73 287.5507 -53.50549 54.97298 281.5437 -61.28552 54.97298 290.7413 -57.29203 73 291.6828 -51.19839 73 291.6828 -51.19839 54.97298 295.0811 -54.77404 73 295.6245 -48.57189 73 294.1535 -43.42462 73 295.6245 -48.57189 54.97298 299.2131 -51.92798 73 299.3497 -45.63732 73 297.6402 -40.47071 73 299.3497 -45.63732 54.97298 303.1127 -48.7709 73 302.8335 -42.41926 73 300.8807 -37.23322 73 302.8335 -42.41926 54.97298 306.7564 -45.3217 73 306.05 -38.93364 73 303.833 -33.74082 73 306.05 -38.93364 54.97298 310.1225 -41.60105 73 308.9768 -35.21779 73 306.4852 -30.01914 73 308.9768 -35.21779 54.97298 315.9428 -33.43601 73 313.8686 -27.22327 73 310.8111 -21.99357 73 313.8686 -27.22327 54.97298 313.1907 -37.63123 54.97298 320.4345 -24.47112 73 317.4692 -18.52296 73 315.2215 -4.426485 73 317.4692 -18.52296 54.97298 318.3622 -29.04054 73 313.7468 -13.38335 54.97298 323.4899 -14.92082 73 319.6645 -9.366105 73 319.655 9.425759 73 319.6645 -9.366105 54.97298 322.1471 -19.75514 73 317.4434 18.60236 54.97298 325.2303 0 73 320.4 0 73 320.2108 4.744023 73 320.4 0 54.97298 325.0362 -5.013586 54.97298 324.4549 -9.997143 54.97298 325.0362 5.013586 73 320.4 0 54.97298 325.2303 0 73 320.2108 4.744023 45.97885 331.8909 0 54.97298 325.2303 0 54.97298 325.0362 -5.013586 45.97885 331.2736 9.374498 54.97298 325.2303 0 45.97885 331.8909 0 54.97298 325.0362 5.013586 45.97885 331.2736 -9.374498 54.97298 324.4549 -9.997143 54.97298 323.4899 -14.92082 45.97885 329.4324 -18.5871 54.97298 322.1471 -19.75514 54.97298 320.4345 -24.47112 45.97885 326.399 -27.47872 54.97298 318.3622 -29.04054 45.97885 322.2259 -35.8958 54.97298 315.9428 -33.43601 54.97298 313.1907 -37.63123 45.97885 316.9851 -43.69299 54.97298 310.1225 -41.60105 54.97298 306.7564 -45.3217 45.97885 310.7671 -50.73564 54.97298 303.1127 -48.7709 45.97885 303.6793 -56.90211 54.97298 299.2131 -51.92798 54.97298 295.0811 -54.77404 45.97885 295.8441 -62.08593 54.97298 290.7413 -57.29203 54.97298 286.2198 -59.46686 45.97885 287.3968 -66.19757 54.97298 281.5437 -61.28552 45.97885 278.4833 -69.16603 54.97298 276.7409 -62.73711 54.97298 271.8403 -63.81294 45.97885 269.2575 -70.94004 54.97298 266.8711 -64.50656 54.97298 261.8632 -64.81381 45.97885 259.8788 -71.48899 54.97298 256.8465 -64.73287 54.97298 251.8511 -64.2642 45.97885 250.509 -70.80335 54.97298 246.9069 -63.41062 45.97885 241.3101 -68.89499 54.97298 242.0435 -62.17724 54.97298 237.29 -60.57145 45.97885 232.4408 -65.79689 54.97298 232.675 -58.60287 54.97298 228.2261 -56.28329 45.97885 224.0544 -61.56249 54.97298 223.9698 -53.62659 45.97885 216.2956 -56.26497 54.97298 219.9317 -50.6487 54.97298 216.1361 -47.36745 46.01564 209.3612 -50.02604 54.97298 212.6055 -43.80249 50.25096 209.3612 -45.76991 54.97298 209.3612 -39.97518 50.64026 147.4 -36.716 54.97298 209.3612 -39.97518 59.50509 205.5042 -32.14698 47.58631 147.4 -40.59246 50.25096 209.3612 -45.76991 55.74084 147.4 -28.38063 62.89741 202.5284 -24.14646 53.35656 147.4 -32.64563 59.49447 147.4 -19.31087 65.23722 200.4394 -16.08258 57.79339 147.4 -23.92148 60.82553 147.4 -14.58077 61.78324 147.4 -9.763909 44.23035 147.4 -44.22867 46.01564 209.3612 -50.02604 40.59742 147.4 -47.58352 44.79955 209.3612 -51.11795 44.79955 209.3612 -51.11795 36.71356 147.4 -50.642 38.64964 209.3612 -55.91287 38.64964 209.3612 -55.91287 32.60395 147.4 -53.37942 36.0613 209.3612 -57.6162 36.0613 209.3612 -57.6162 31.84824 209.3612 -60.04776 25.46692 211.3358 -64.56887 31.84824 209.3612 -60.04776 36.0229 217.5118 -63.93712 23.81617 147.4 -57.83746 22.67369 210.4263 -64.17652 25.46692 211.3358 -64.56887 31.84824 209.3612 -60.04776 22.67369 210.4263 -64.17652 28.29614 147.4 -55.78374 14.45719 147.4 -60.85541 12.98032 211.5135 -66.9118 23.252 212.0202 -65.90705 12.98032 211.5135 -66.9118 19.19369 147.4 -59.53233 4.760062 147.4 -62.36774 2.967647 212.5878 -68.18865 14.37408 214.7581 -70.25098 2.967647 212.5878 -68.18865 9.636244 147.4 -61.80323 -5.039426 147.4 -62.3458 -7.104365 213.6084 -67.97223 4.121392 217.9103 -73.50268 -7.104365 213.6084 -67.97223 -0.141712 147.4 -62.54979 13.94689 214.8896 -70.42224 -14.70538 147.4 -60.79596 -17.00805 214.5402 -66.27647 -6.025453 221.0206 -75.08634 -17.00805 214.5402 -66.27647 -9.903903 147.4 -61.7609 3.064081 218.2349 -73.74087 -19.41596 147.4 -59.46022 -21.83266 214.9631 -64.88639 -16.28796 224.1575 -75.14109 -21.83266 214.9631 -64.88639 -8.299376 221.7165 -75.23102 -24.00643 147.4 -57.75894 -26.53528 215.3532 -63.14635 -19.51969 225.1436 -74.83963 -26.53528 215.3532 -63.14635 -28.45097 147.4 -55.70494 -31.08435 215.7065 -61.0703 -26.45742 227.2577 -73.66539 -31.08435 215.7065 -61.0703 -35.46889 216.0225 -58.66487 -36.32621 230.2588 -70.68886 -35.46889 216.0225 -58.66487 -30.39257 228.4552 -72.66928 -32.722 147.4 -53.30737 -39.67829 216.2996 -55.93358 -40.72129 231.5931 -68.82544 -39.67829 216.2996 -55.93358 -36.79549 147.4 -50.58251 -43.67799 216.5373 -52.8963 -45.69338 233.101 -66.27128 -43.67799 216.5373 -52.8963 -40.64623 147.4 -47.54211 -47.43993 216.7337 -49.57416 -50.32191 234.5033 -63.41976 -47.43993 216.7337 -49.57416 -44.2502 147.4 -44.2088 -50.94563 216.8917 -45.9846 -54.36434 235.7268 -60.50415 -50.94563 216.8917 -45.9846 -47.58338 147.4 -40.59617 -54.17495 217.0117 -42.14921 -59.0212 237.135 -56.57065 -54.17495 217.0117 -42.14921 -50.62059 147.4 -36.74311 -57.11404 217.0984 -38.08555 -62.17095 238.0867 -53.49663 -57.11404 217.0984 -38.08555 -53.32715 147.4 -32.69383 -59.7494 217.1547 -33.81137 -66.72772 239.4625 -48.31177 -59.7494 217.1547 -33.81137 -55.70747 147.4 -28.44606 -62.06512 217.1866 -29.35139 -68.79174 240.0853 -45.60712 -62.06512 217.1866 -29.35139 -57.76154 147.4 -23.99858 -64.04738 217.1991 -24.73189 -73.15702 241.4016 -38.88586 -64.04738 217.1991 -24.73189 -59.46792 147.4 -19.39247 -65.68744 217.1983 -19.97206 -76.69876 242.4687 -31.94951 -65.68744 217.1983 -19.97206 -73.581 241.5294 -38.14108 -60.80711 147.4 -14.65774 -66.97674 217.1904 -15.09123 -78.77391 243.0937 -26.83584 -66.97674 217.1904 -15.09123 -78.28528 242.9466 -28.13884 -61.77333 147.4 -9.826401 -67.90534 217.1798 -10.11759 -81.33267 243.8639 -18.34547 -67.90534 217.1798 -10.11759 -80.23657 243.534 -22.41946 -62.35276 147.4 -4.945741 -68.4663 217.1733 -5.078178 -82.53995 244.2272 -12.27183 -68.4663 217.1733 -5.078178 -82.18522 244.1205 -14.33761 -81.98159 244.0592 -15.39472 -62.55 147.4 0 -68.65397 217.1687 0 -83.31884 244.4615 -5.379289 -68.65397 217.1687 0 -83.11232 244.3994 -7.830876 -82.84999 244.3205 -10.1158 -62.35687 147.4 4.909072 -68.65397 217.1687 0 -62.55 147.4 0 -83.48104 244.5103 -1.852624 -83.50286 244.5169 0 -68.46621 217.1733 5.079516 -83.41838 244.4915 -3.64613 -68.46621 217.1733 5.079516 -62.35687 147.4 4.909072 -62.55 147.4 0 -62.35276 147.4 -4.945741 -61.78324 147.4 9.763909 -61.77333 147.4 -9.826401 -60.82553 147.4 14.58077 -60.80711 147.4 -14.65774 -59.49447 147.4 19.31087 -59.46792 147.4 -19.39247 -57.79339 147.4 23.92148 -57.76154 147.4 -23.99858 -55.74084 147.4 28.38063 -55.70747 147.4 -28.44606 -55 147.4 0 -53.32715 147.4 -32.69383 -52.02062 147.4 -17.8565 -50.62059 147.4 -36.74311 -54.25185 147.4 -9.040809 -48.37014 147.4 -26.17878 -47.58338 147.4 -40.59617 -44.2502 147.4 -44.2088 -43.42462 147.4 -33.75352 -40.64623 147.4 -47.54211 -40.47071 147.4 -37.24022 -36.79549 147.4 -50.58251 -33.74082 147.4 -43.43301 -32.722 147.4 -53.30737 -37.23322 147.4 -40.48065 -30.01914 147.4 -46.0852 -28.45097 147.4 -55.70494 -24.00643 147.4 -57.75894 -21.99357 147.4 -50.41108 -19.41596 147.4 -59.46022 -14.70538 147.4 -60.79596 -13.38335 147.4 -53.34679 -9.903903 147.4 -61.7609 -5.039426 147.4 -62.3458 -4.426485 147.4 -54.82153 -0.141712 147.4 -62.54979 4.636376 147.4 -54.80418 4.760062 147.4 -62.36774 9.636244 147.4 -61.80323 13.56462 147.4 -53.30099 14.45719 147.4 -60.85541 19.19369 147.4 -59.53233 22.12212 147.4 -50.35481 23.81617 147.4 -57.83746 28.29614 147.4 -55.78374 30.08507 147.4 -46.0422 32.60395 147.4 -53.37942 36.71356 147.4 -50.642 37.24397 147.4 -40.47077 40.59742 147.4 -47.58352 43.40071 147.4 -33.78425 44.23035 147.4 -44.22867 47.58631 147.4 -40.59246 48.33597 147.4 -26.24179 50.64026 147.4 -36.716 51.99485 147.4 -17.9314 53.35656 147.4 -32.64563 54.24254 147.4 -9.096512 55.74084 147.4 -28.38063 57.76154 147.4 23.99858 57.79339 147.4 -23.92148 55.70747 147.4 28.44606 55 147.4 0 54.80755 147.4 -4.580959 59.46792 147.4 19.39247 59.49447 147.4 -19.31087 60.80711 147.4 14.65774 60.82553 147.4 -14.58077 61.77333 147.4 9.826401 61.78324 147.4 -9.763909 62.35276 147.4 4.945741 62.35687 147.4 -4.909072 62.55 147.4 0 62.35276 147.4 4.945741 45.83531 331.983 0 36.0229 336.6877 10.36986 45.83531 331.983 0 36.0229 336.6877 -10.36986 36.0229 337.3893 0 36.0229 334.5958 -20.55073 36.0229 331.1517 -30.35706 36.0229 326.4181 -39.61013 36.0229 320.4813 -48.14131 36.0229 313.4496 -55.7951 36.0229 305.451 -62.43204 36.0229 296.6314 -67.93115 36.0229 287.1514 -72.1922 36.0229 277.1839 -75.13755 36.0229 266.9105 -76.71352 36.0229 256.5185 -76.89138 36.0229 246.1972 -75.6679 36.0229 236.1347 -73.06536 36.0229 226.5145 -69.13121 -84.24063 249.0634 0 -84.6249 252.4232 0 -85 260.4 0 -84.24063 249.1604 1.479726 -85 260.4 0 -84.6249 252.4232 0 -84.24063 249.1604 -1.479726 -84.24063 249.4497 -2.934133 -84.24063 249.9263 -4.338336 -84.24063 250.5822 -5.668309 -84.24063 251.406 -6.901296 -84.24063 252.3838 -8.016201 -84.24063 253.4987 -8.993946 -84.24063 254.7317 -9.8178 -84.24063 256.0617 -10.47367 -84.24063 257.4659 -10.95033 -84.24063 258.9203 -11.23963 -84.24063 260.4 -11.33662 -84.24063 261.8797 -11.23963 -84.24063 263.3341 -10.95033 -84.24063 264.7384 -10.47367 -84.24063 266.0683 -9.8178 -84.24063 267.3013 -8.993946 -84.24063 268.4162 -8.016201 -84.24063 269.394 -6.901296 -84.24063 270.2178 -5.668309 -84.24063 270.8737 -4.338336 -84.24063 271.3504 -2.934133 -84.24063 271.6396 -1.479726 -84.24063 271.7366 0 -84.24063 271.6396 1.479726 -84.24063 271.7366 0 -84.24063 249.4497 2.934133 -84.24063 249.9263 4.338336 -84.24063 250.5822 5.668309 -84.24063 251.406 6.901296 -84.24063 252.3838 8.016201 -84.24063 253.4987 8.993946 -84.24063 254.7317 9.8178 -84.24063 256.0617 10.47367 -84.24063 257.4659 10.95033 -84.24063 258.9203 11.23963 -84.24063 260.4 11.33662 -84.24063 261.8797 11.23963 -84.24063 263.3341 10.95033 -84.24063 264.7384 10.47367 -84.24063 266.0683 9.8178 -84.24063 267.3013 8.993946 -84.24063 268.4162 8.016201 -84.24063 269.394 6.901296 -84.24063 270.2178 5.668309 -84.24063 270.8737 4.338336 -84.24063 271.3504 2.934133 -84.24063 249.0634 0 -83.50286 244.5169 0 -83.47967 244.5099 1.909943 -83.50286 244.5169 0 -83.41838 244.4915 -3.64613 -83.48104 244.5103 -1.852624 -83.31884 244.4615 -5.379289 -83.11232 244.3994 -7.830876 -82.84999 244.3205 -10.1158 -82.18522 244.1205 -14.33761 -82.53995 244.2272 -12.27183 -81.97303 246.1615 -17.398 -81.98159 244.0592 -15.39472 -81.97303 248.5895 -19.12947 -81.97303 251.2253 -20.52435 -81.97303 254.0225 -21.5581 -81.97303 256.932 -22.21254 -81.97303 259.9024 -22.47613 -81.97303 262.8816 -22.34426 -81.97303 265.8171 -21.81924 -81.97303 268.6574 -20.9103 -81.97303 271.3523 -19.63344 -81.97303 273.8545 -18.01112 -81.97303 276.12 -16.07189 -81.97303 278.1089 -13.84988 -81.97303 279.7862 -11.38418 -81.97303 281.1224 -8.718166 -81.97303 282.094 -5.898755 -81.97303 282.6839 -2.975555 -81.97303 282.8817 0 -81.97303 282.8817 0 -78.23781 293.3311 -4.403518 -78.23781 293.6242 0 -81.97303 282.6904 2.925848 -78.23781 293.6242 0 -83.47967 244.5099 1.909943 -81.33267 243.8639 -18.34547 -80.23657 243.534 -22.41946 -78.23781 246.7565 -30.29358 -78.77391 243.0937 -26.83584 -78.28528 242.9466 -28.13884 -78.23781 250.892 -31.83462 -78.23781 255.1952 -32.81395 -78.23781 259.5903 -33.21429 -78.23781 263.9997 -33.02858 -78.23781 268.3455 -32.2601 -78.23781 272.5512 -30.9224 -78.23781 276.5424 -29.03908 -78.23781 280.2488 -26.64339 -78.23781 283.605 -23.77758 -78.23781 286.5518 -20.49222 -78.23781 289.0371 -16.84529 -78.23781 291.0171 -12.90113 -78.23781 292.4569 -8.729338 -73.10187 303.3769 -5.839935 -73.10187 303.7719 0 -78.23781 293.3636 4.152732 -73.10187 303.7719 0 -76.69876 242.4687 -31.94951 -73.10187 246.7559 -41.16983 -73.581 241.5294 -38.14108 -73.15702 241.4016 -38.88586 -73.10187 252.4235 -42.63208 -73.10187 258.2365 -43.31786 -73.10187 264.0889 -43.21469 -73.10187 269.8741 -42.32445 -73.10187 275.4867 -40.66336 -73.10187 280.8246 -38.26166 -73.10187 285.7904 -35.16311 -73.10187 290.2939 -31.42413 -73.10187 294.2528 -27.11282 -73.10187 297.5952 -22.3077 -73.10187 300.2602 -17.09629 -73.10187 302.1992 -11.57351 -66.65713 312.6834 -6.947996 -66.65713 313.143 0 -73.10187 303.4634 5.163478 -66.65713 313.143 0 -68.79174 240.0853 -45.60712 -66.65713 245.8829 -50.70582 -66.72772 239.4625 -48.31177 -66.65713 252.689 -52.17631 -66.65713 259.6296 -52.7374 -66.65713 266.5836 -52.37929 -66.65713 273.4298 -51.10824 -66.65713 280.0488 -48.9464 -66.65713 286.3255 -45.93144 -66.65713 292.1502 -42.11593 -66.65713 297.4216 -37.56635 -66.65713 302.0477 -32.36201 -66.65713 305.9479 -26.59361 -66.65713 309.0542 -20.3617 -66.65713 311.3125 -13.77489 -59.01899 321.0471 -7.980749 -59.01899 321.5699 0 -66.65713 312.6834 6.947765 -59.01899 321.5699 0 -62.17095 238.0867 -53.49663 -59.01899 244.6162 -59.09847 -59.0212 237.135 -56.57065 -59.01899 252.4616 -60.65261 -59.01899 260.4427 -61.1699 -59.01899 268.4231 -60.64147 -59.01899 276.2663 -59.07638 -59.01899 283.8383 -56.50137 -59.01899 291.0096 -52.96046 -59.01899 297.6576 -48.51419 -59.01899 303.6688 -43.23857 -59.01899 308.9402 -37.22377 -59.01899 313.3818 -30.57263 -59.01899 316.9177 -23.39885 -59.01899 319.4874 -15.82507 -50.32421 328.3179 -8.924008 -50.32421 328.9017 0 -59.01899 321.0471 7.980781 -50.32421 328.9017 0 -54.36434 235.7268 -60.50415 -50.32421 242.9059 -66.23014 -50.32191 234.5033 -63.41976 -50.32421 251.6831 -67.94475 -50.32421 260.6088 -68.50132 -50.32421 269.531 -67.89035 -50.32421 278.2976 -66.12226 -50.32421 286.7591 -63.22716 -50.32421 294.7713 -59.25444 -50.32421 302.1977 -54.27177 -50.32421 308.9118 -48.36409 -50.32421 314.7989 -41.6321 -50.32421 319.759 -34.19052 -50.32421 323.7072 -26.16621 -50.32421 326.5765 -17.69591 -40.72843 334.3656 -9.761198 -40.72843 335.0069 0 -50.32421 328.4846 7.54775 -40.72843 335.0069 0 -40.72843 240.7763 -71.97989 -45.69338 233.101 -66.27128 -40.72843 250.3624 -73.92863 -40.72843 260.1212 -74.60643 -40.72843 269.8847 -74.00159 -40.72843 279.4852 -72.12456 -40.72843 288.7575 -69.00759 -40.72843 297.5424 -64.70425 -40.72843 305.6887 -59.28853 -40.72843 313.0564 -52.85356 -40.72843 319.5189 -45.50994 -40.72843 324.965 -37.38393 -40.72843 329.3011 -28.61523 -40.72843 332.4527 -19.35458 -30.40347 339.082 -10.47772 -30.40347 339.7765 0 -40.72843 334.3656 9.761198 -30.40347 339.7765 0 -40.72129 231.5931 -68.82544 -30.40347 238.2644 -76.22757 -36.32621 230.2588 -70.68886 -30.40347 248.5201 -78.48246 -30.40347 258.9838 -79.36387 -30.40347 269.4722 -78.85636 -30.40347 279.8019 -76.96881 -30.40347 289.792 -73.73426 -30.40347 299.2678 -69.2093 -30.40347 308.0633 -63.47314 -30.40347 316.0247 -56.62616 -30.40347 323.0126 -48.78819 -30.40347 328.9048 -40.0964 -30.40347 333.5981 -30.70289 -30.40347 337.0104 -20.77207 -19.53418 342.382 -11.06179 -19.53418 343.125 0 -30.40347 339.082 10.47773 -19.53418 343.125 0 -30.39257 228.4552 -72.66928 -19.53418 235.4103 -78.86019 -26.45742 227.2577 -73.66539 -19.53418 246.1797 -81.49356 -19.53418 257.2046 -82.6632 -19.53418 268.2868 -82.34813 -19.53418 279.2274 -80.554 -19.53418 289.8298 -77.31303 -19.53418 299.9036 -72.68344 -19.53418 309.2679 -66.74836 -19.53418 317.7545 -59.61442 -19.53418 325.2109 -51.40974 -19.53418 331.5033 -42.28169 -19.53418 336.5185 -32.39421 -19.53418 340.1666 -21.9249 -8.31516 344.2063 -11.50464 -8.428314 344.9811 0 -19.53418 342.7814 7.531389 -8.428314 344.9811 0 -19.51969 225.1436 -74.83963 -8.31516 232.2584 -79.7741 -16.28796 224.1575 -75.14109 -8.31516 243.3692 -82.86019 -8.31516 254.7965 -84.40651 -8.31516 266.328 -84.38436 -8.31516 277.7492 -82.79409 -8.31516 288.8481 -79.66532 -8.31516 299.4184 -75.05615 -8.31516 309.2636 -69.05224 -8.31516 318.2007 -61.76516 -8.31516 326.0638 -53.33032 -8.31516 332.7067 -43.90446 -8.31516 338.0059 -33.66275 -8.31516 341.863 -22.7955 -8.31516 344.9923 0 -8.31516 344.9923 0 -8.299376 221.7165 -75.23102 3.052735 228.1721 -78.59418 -6.025453 221.0206 -75.08634 3.052735 238.687 -82.12324 3.052735 249.572 -84.25222 3.052735 260.6416 -84.94482 3.052735 271.7071 -84.18925 3.052735 282.5799 -81.99839 3.052735 293.0745 -78.40957 3.052735 303.012 -73.484 3.052735 312.2231 -67.30564 3.052735 320.5507 -59.97982 3.052735 327.8528 -51.63143 3.052735 334.0049 -42.40281 3.052735 338.9022 -32.45129 3.052735 342.4612 -21.94653 3.052735 344.6211 -11.06761 2.927736 345.3496 0 -8.31516 344.3271 10.58751 2.927736 345.3496 0 3.052735 345.3452 0 3.052735 345.3452 0 3.064081 218.2349 -73.74087 14.36597 224.5501 -75.71923 4.121392 217.9103 -73.50268 14.36597 235.0034 -79.83503 14.36597 245.9134 -82.5152 14.36597 257.0839 -83.71154 14.36597 268.3141 -83.40256 14.36597 279.4019 -81.59381 14.36597 290.148 -78.31779 14.36597 300.3592 -73.63343 14.36597 309.8518 -67.62498 14.36597 318.4552 -60.40046 14.36597 326.0146 -52.0898 14.36597 332.3941 -42.84244 14.36597 337.4789 -32.82468 14.36597 341.1777 -22.21665 14.36597 343.424 -11.20911 14.23147 344.2002 0 3.052735 344.5789 11.38407 14.23147 344.2002 0 14.36597 344.1772 0 14.36597 344.1772 0 13.94689 214.8896 -70.42224 14.37408 214.7581 -70.25098 25.42201 220.0784 -70.37677 23.252 212.0202 -65.90705 25.42201 229.5938 -75.03133 25.42201 239.6347 -78.40615 25.42201 250.0297 -80.44364 25.42201 260.6016 -81.10907 25.42201 271.1701 -80.39109 25.42201 281.5549 -78.30194 25.42201 291.5789 -74.87725 25.42201 301.071 -70.17543 25.42201 309.8695 -64.27668 25.42201 317.8242 -57.28162 25.42201 324.7995 -49.30954 25.42201 330.6763 -40.49644 25.42201 335.3545 -30.99262 25.42201 338.7543 -20.96018 25.42201 340.8176 -10.57023 25.28092 341.5534 0 14.36597 343.424 11.20903 25.28092 341.5534 0 25.42201 341.5093 0 25.42201 341.5093 0 35.87865 337.4566 0 25.42201 341.1587 7.533926 35.87865 337.4566 0 36.0229 337.3893 0 54.97298 324.4549 9.997143 54.97298 324.4549 9.997143 45.97885 329.4324 18.5871 54.97298 323.4899 14.92082 73 319.655 9.425759 54.97298 323.4899 14.92082 54.97298 322.1471 19.75514 58.74761 322.4311 15 54.97298 322.1471 19.75514 45.97885 326.399 27.47872 54.97298 320.4345 24.47112 58.10222 320.0225 23.24046 54.97298 320.4345 24.47112 58.45947 321.3558 19.16064 54.97298 318.3622 29.04054 58.00047 319.1929 25.33454 54.97298 318.3622 29.04054 45.97885 322.2259 35.8958 54.97298 315.9428 33.43601 58.82065 317.1844 29.08427 54.97298 315.9428 33.43601 58.11343 318.4289 26.96714 58.39733 317.754 28.2022 45.97885 316.9851 43.69299 54.97298 313.1907 37.63123 73 313.835 27.28928 54.97298 313.1907 37.63123 60.50268 316.2875 29.82695 59.34957 316.7408 29.63127 59.91502 316.4491 29.85868 54.97298 310.1225 41.60105 73 308.9542 35.24898 54.97298 310.1225 41.60105 45.97885 310.7671 50.73564 54.97298 306.7564 45.3217 54.97298 306.7564 45.3217 54.97298 303.1127 48.7709 73 302.8464 42.40642 54.97298 303.1127 48.7709 45.97885 303.6793 56.90211 54.97298 299.2131 51.92798 54.97298 299.2131 51.92798 45.97885 295.8441 62.08593 54.97298 295.0811 54.77404 73 295.6947 48.5209 54.97298 295.0811 54.77404 54.97298 290.7413 57.29203 54.97298 290.7413 57.29203 45.97885 287.3968 66.19757 54.97298 286.2198 59.46686 73 287.6891 53.43502 54.97298 286.2198 59.46686 54.97298 281.5437 61.28552 54.97298 281.5437 61.28552 45.97885 278.4833 69.16603 54.97298 276.7409 62.73711 73 279.0209 57.03734 54.97298 276.7409 62.73711 45.97885 269.2575 70.94004 54.97298 271.8403 63.81294 54.97298 271.8403 63.81294 54.97298 266.8711 64.50656 73 269.8952 59.24386 54.97298 266.8711 64.50656 45.97885 259.8788 71.48899 54.97298 261.8632 64.81381 54.97298 261.8632 64.81381 54.97298 256.8465 64.73287 73 260.5299 59.99981 54.97298 256.8465 64.73287 45.97885 250.509 70.80335 54.97298 251.8511 64.2642 54.97298 251.8511 64.2642 54.97298 246.9069 63.41062 73 251.1496 59.28258 54.97298 246.9069 63.41062 45.97885 241.3101 68.89499 54.97298 242.0435 62.17724 54.97298 242.0435 62.17724 45.97885 232.4408 65.79689 54.97298 237.29 60.57145 73 241.9811 57.10287 54.97298 237.29 60.57145 54.97298 232.675 58.60287 54.97298 232.675 58.60287 45.97885 224.0544 61.56249 54.97298 228.2261 56.28329 73 233.2493 53.50549 54.97298 228.2261 56.28329 54.97298 223.9698 53.62659 73 229.1172 51.19839 54.97298 223.9698 53.62659 45.97885 216.2956 56.26497 54.97298 219.9317 50.6487 73 225.1755 48.57189 54.97298 219.9317 50.6487 46.01564 209.3612 50.02604 54.97298 216.1361 47.36745 73 221.4503 45.63732 54.97298 216.1361 47.36745 54.97298 212.6055 43.80249 73 217.9665 42.41926 54.97298 212.6055 43.80249 50.25096 209.3612 45.76991 54.97298 209.3612 39.97518 73 214.75 38.93364 54.97298 209.3612 39.97518 47.58338 147.4 40.59617 54.97298 209.3612 39.97518 50.25096 209.3612 45.76991 73 211.8232 35.21779 58.96675 205.9713 33.20747 53.32715 147.4 32.69383 58.96675 205.9713 33.20747 50.62059 147.4 36.74311 44.2502 147.4 44.2088 46.01564 209.3612 50.02604 44.79955 209.3612 51.11795 44.79955 209.3612 51.11795 36.0229 217.5118 63.93712 38.64964 209.3612 55.91287 36.0613 209.3612 57.6162 36.0229 226.5145 69.13121 36.0229 236.1347 73.06536 36.0229 246.1972 75.6679 36.0229 256.5185 76.89138 36.0229 266.9105 76.71352 36.0229 277.1839 75.13755 36.0229 287.1514 72.1922 36.0229 296.6314 67.93115 36.0229 305.451 62.43204 36.0229 313.4496 55.7951 36.0229 320.4813 48.14131 36.0229 326.4181 39.61013 36.0229 331.1517 30.35706 36.0229 334.5958 20.55073 40.64623 147.4 47.54211 38.64964 209.3612 55.91287 36.79549 147.4 50.58251 36.0613 209.3612 57.6162 31.84824 209.3612 60.04776 32.722 147.4 53.30737 31.84824 209.3612 60.04776 25.42201 220.4664 70.59769 25.46656 211.3359 64.5691 25.42201 230.4212 75.36573 25.42201 240.9311 78.73809 25.42201 251.8016 80.65227 25.42201 262.8313 81.07287 25.42201 273.816 79.99208 25.42201 284.5522 77.42992 25.42201 294.8412 73.43383 25.42201 304.4923 68.07783 25.42201 313.3269 61.46109 25.42201 321.1813 53.70615 25.42201 327.9102 44.95663 25.57312 333.3515 35.34251 25.41586 333.3784 35.40033 28.474 334.6242 30.08337 26.19396 333.3273 34.93535 26.82431 333.4365 34.2218 27.42864 333.683 33.2005 27.98837 334.0746 31.8388 29.92763 338.5303 15 28.83818 335.349 27.85681 29.4645 337.1779 21.49406 27.10688 339.5531 15 25.42221 340.1102 15 22.65575 210.4284 64.18304 31.84824 209.3612 60.04776 25.46656 211.3359 64.5691 28.45097 147.4 55.70494 22.65575 210.4284 64.18304 23.26391 212.0165 65.90013 23.26391 212.0165 65.90013 14.36597 224.5512 75.71976 14.37355 214.7582 70.25119 14.36597 235.0045 79.83538 14.36597 245.9144 82.51538 14.36597 257.0849 83.71158 14.36597 268.315 83.40248 14.36597 279.4027 81.59362 14.36597 290.1487 78.31752 14.36597 300.3598 73.63312 14.36597 309.8523 67.62464 14.36597 318.4555 60.40012 14.36597 326.0148 52.08948 14.36597 332.3942 42.84217 24.88469 333.5363 15 25.41586 333.3784 35.40033 25.57312 333.3515 35.34251 25.01062 333.4888 35.46117 25.01062 333.4888 35.46117 26 333.321 15 26.19396 333.3273 34.93535 26.82431 333.4365 34.2218 26.92034 333.4657 15 27.42864 333.683 33.2005 27.74413 333.8801 15 27.98837 334.0746 31.8388 28.40313 334.5252 15 28.474 334.6242 30.08337 28.83818 335.349 27.85681 29.92763 338.5303 15 28.83818 335.349 27.85681 29.4645 337.1779 21.49406 28.83818 335.349 15 28.83818 335.349 15 23.16182 337.293 15 29.92763 338.5303 15 27.10688 339.5531 15 23.00412 336.168 15 28.83818 335.349 15 25.42221 340.1102 15 24.25127 340.4742 15 24.25127 340.4742 15 12.97491 211.5141 66.91291 14.37355 214.7582 70.25119 13.9719 214.8819 70.4123 13.9719 214.8819 70.4123 3.052735 227.9267 78.49311 4.160076 217.8985 73.49363 3.064656 218.2347 73.74074 3.052735 238.1753 81.98625 3.052735 248.785 84.14733 3.052735 259.5834 84.94124 7.289701 272.8429 83.76763 3.072762 270.3597 84.35865 5.208437 271.2829 84.13998 10.49642 280.1259 82.01036 8.963376 274.9312 83.26812 10.05761 277.3843 82.67627 3.052735 300.7836 74.73183 10.19036 282.9311 81.32331 9.149246 285.5518 80.67596 7.458848 287.7902 80.11924 5.250816 289.4928 79.69322 3.067632 290.4419 79.45475 3.052735 310.4346 68.6456 3.052735 319.1829 61.32088 3.052735 326.8706 52.88983 3.052735 333.3591 43.50454 23.24802 335.1266 33.17328 14.36597 337.479 32.82445 3.052735 338.5313 33.33435 23.56841 334.5639 34.19424 23.99023 334.0937 34.90988 24.48425 333.7321 35.32608 23.16182 337.293 27.85681 14.36597 341.1778 22.21649 3.052735 342.2939 22.56274 23.00553 336.503 30.0679 23.05001 335.7755 31.81557 23.7881 339.1217 21.49443 23.16182 337.293 15 24.25127 340.4742 15 23.7881 339.1217 21.49443 23.16182 337.293 27.85681 23.16182 337.293 15 23.16182 337.293 27.85681 23.00553 336.503 30.0679 23.00412 336.168 15 23.05001 335.7755 31.81557 23.24802 335.1266 33.17328 23.27465 335.0685 15 23.56841 334.5639 34.19424 23.93215 334.1484 15 23.99023 334.0937 34.90988 24.48425 333.7321 35.32608 2.991063 212.5854 68.18741 4.160076 217.8985 73.49363 3.064656 218.2347 73.74074 -5.97312 221.0046 75.08213 -7.022048 213.6004 67.98007 -5.97312 221.0046 75.08213 -8.31516 231.5675 79.52701 -8.298602 221.7162 75.23098 -8.31516 241.9352 82.55247 -8.31516 252.604 84.2323 -8.31516 263.3998 84.5391 2.976411 270.3312 66 3.072762 270.3597 84.35865 5.208437 271.2829 84.13998 2.725606 270.2599 84.38233 2.725606 270.2599 84.38233 5.718314 271.5951 66 7.289701 272.8429 83.76763 7.976566 273.5722 66 8.963376 274.9312 83.26812 9.574053 276.0903 66 10.05761 277.3843 82.67627 10.39938 278.9509 66 10.49642 280.1259 82.01036 10.38881 281.9227 66 10.19036 282.9311 81.32331 9.541881 284.7805 66 9.149246 285.5518 80.67596 7.932786 287.279 66 7.458848 287.7902 80.11924 5.684371 289.2271 66 5.250816 289.4928 79.69322 3.067632 290.4419 79.45475 2.711331 290.5439 79.4291 2.964506 290.4726 66 2.711331 290.5439 79.4291 -8.31516 305.827 71.36 -8.31516 296.5384 76.48448 0 290.9 79.33946 -8.31516 314.4011 65.11328 -8.31516 322.126 57.84251 -8.31516 328.8802 49.66209 -8.31516 334.5574 40.70066 -8.31516 339.0683 31.09913 -8.31516 342.3421 21.00852 -8.298602 221.7162 75.23098 -16.22254 224.1375 75.1456 -16.91499 214.5318 66.29953 -16.22254 224.1375 75.1456 -19.53418 235.0348 78.74023 -19.51857 225.1432 74.83975 -19.53418 245.4043 81.35445 -19.53418 256.0245 82.60914 -7.449712 273.0006 83.73033 -8.393984 274.092 83.46841 -19.53418 266.7177 82.48336 -5.227266 271.2937 84.13688 -2.676414 270.2468 84.38526 0 269.9 84.46746 -7.932786 273.521 66 -8.393984 274.092 83.46841 -7.449712 273.0006 83.73033 -9.142182 275.2357 83.19493 -9.541881 276.0195 66 -9.142182 275.2357 83.19493 -5.684371 271.5729 66 -5.227266 271.2937 84.13688 -2.964506 270.3274 66 -2.676414 270.2468 84.38526 0 269.9 84.46746 0 269.9 66 0 269.9 84.46746 0 269.9 66 -19.51857 225.1432 74.83975 -26.38088 227.2343 73.68235 -21.74006 214.9552 64.91675 -26.38088 227.2343 73.68235 -30.40347 238.2641 76.2275 -30.39124 228.4548 72.66967 -30.40347 248.5199 78.48243 -30.40347 258.9836 79.36386 -19.53418 277.3053 80.97917 -30.40347 269.472 78.85637 -8.37976 286.7269 80.38486 -19.53418 287.6105 78.12174 -30.40347 279.8017 76.96884 -8.970254 285.8575 80.60015 -10.06673 283.3851 81.21176 -10.49715 280.6447 81.88391 -10.18462 277.8459 82.56465 -19.53418 297.4609 73.95881 -30.40347 289.7919 73.73431 -19.53418 306.692 68.55995 -30.40347 299.2677 69.20938 -19.53418 315.1495 62.01538 -30.40347 308.0632 63.47321 -19.53418 322.6921 54.43446 -30.40347 316.0246 56.62623 -19.53418 329.1937 45.94388 -30.40347 323.0126 48.78826 -19.53418 334.5457 36.68554 -30.40347 328.9048 40.09646 -18.93985 338.4953 27.7022 -19.53418 338.6587 26.81414 -30.40347 333.5981 30.70294 -18.67436 337.7337 29.92946 -18.26704 337.1282 31.68762 -17.7672 336.6687 33.05159 -17.20581 336.346 34.0759 -16.60405 336.1545 34.79317 -15.99508 336.093 35.20982 -15.41759 336.1501 35.34444 -14.86158 336.3174 35.22336 -19.31847 340.3575 21.41501 -19.54294 341.4615 16.49574 -30.40347 337.0104 20.7721 -18.93985 338.4953 15 -19.54294 341.4615 16.49574 -19.31847 340.3575 21.41501 -19.59917 341.738 15 -19.59917 341.738 15 -18.93985 338.4953 27.7022 -18.93985 338.4953 15 -18.93985 338.4953 27.7022 -18.67436 337.7337 29.92946 -18.56493 337.5371 15 -18.26704 337.1282 31.68762 -17.89824 336.77 15 -17.7672 336.6687 33.05159 -17.20581 336.346 34.0759 -17.01372 336.2695 15 -16.60405 336.1545 34.79317 -16 336.093 15 -15.99508 336.093 35.20982 -15.41759 336.1501 35.34444 -14.95741 336.2802 15 -14.86158 336.3174 35.22336 -14.31213 336.6129 34.81024 -14.31213 336.6129 34.81024 -13.82404 337.0278 34.08932 -14.04724 336.8162 15 -13.82404 337.0278 34.08932 -13.42886 337.5473 33.06001 -13.42886 337.5473 33.06001 -13.14613 338.1681 31.69074 -13.37965 337.6332 15 -13.14613 338.1681 31.69074 -13.00714 338.8861 29.92901 -13.03582 338.6318 15 -13.00714 338.8861 29.92901 -13.06015 339.6907 27.7022 -13.06015 339.6907 27.7022 -13.71947 342.9335 15 -13.06015 339.6907 27.7022 -13.43876 341.5529 21.4152 -13.43876 341.5529 21.4152 -13.06015 339.6907 15 -13.06015 339.6907 15 -13.71947 342.9335 15 -19.53418 341.7536 15 -13.71947 342.9335 15 -16.67004 342.3885 15 -16.67004 342.3885 15 -19.59917 341.738 15 -13.06015 339.6907 15 -19.53418 341.7536 15 -7.309887 287.9376 80.08237 -2.67668 290.5531 79.42676 -5.165318 289.5416 79.68093 -7.976566 287.2278 66 -8.37976 286.7269 80.38486 -8.970254 285.8575 80.60015 -7.309887 287.9376 80.08237 -9.574053 284.7098 66 -10.06673 283.3851 81.21176 -10.39938 281.8491 66 -10.49715 280.6447 81.88391 -10.38881 278.8774 66 -10.18462 277.8459 82.56465 -26.44347 215.3458 63.18416 -30.39124 228.4548 72.66967 -36.2395 230.2324 70.72212 -30.98949 215.6994 61.1178 -36.2395 230.2324 70.72212 -40.72843 240.7762 71.97988 -40.71991 231.5927 68.82608 -40.72843 250.3624 73.92863 -40.72843 260.1212 74.60643 -40.72843 269.8847 74.0016 -40.72843 279.4851 72.12456 -40.72843 288.7575 69.00759 -40.72843 297.5424 64.70426 -40.72843 305.6887 59.28854 -40.72843 313.0564 52.85356 -40.72843 319.5189 45.50995 -40.72843 324.965 37.38394 -40.72843 329.3011 28.61523 -40.72843 332.4527 19.35458 -18.93985 338.4953 15 -35.37036 216.0157 58.72362 -40.71991 231.5927 68.82608 -45.60571 233.0745 66.3207 -39.57728 216.2932 56.00443 -45.60571 233.0745 66.3207 -50.32421 242.9856 66.25113 -50.32326 234.5037 63.41885 -50.32421 251.8456 67.96541 -50.32421 260.8541 68.50013 -50.32421 269.8547 67.84603 -50.32421 278.6913 66.01443 -50.32421 287.2103 63.03713 -50.32421 295.2641 58.96582 -50.32421 302.7128 53.87113 -50.32421 309.4272 47.84151 -50.32421 315.2907 40.98158 -47.37823 321.7118 34.9451 -48.64122 320.4954 35.32114 -48.15489 320.8045 35.45994 -47.73599 321.2017 35.34735 -48.85761 326.5509 21.49412 -47.12776 322.3038 34.23291 -47.00813 322.9493 33.20876 -47.03627 323.6351 31.8421 -47.23842 324.3421 30.08234 -47.65346 325.0392 27.85547 -49.74824 327.669 15 -50.32455 327.2389 15 -43.57526 216.5315 52.98031 -50.32326 234.5037 63.41885 -54.25997 235.6952 60.58491 -47.33538 216.7287 49.67338 -54.25997 235.6952 60.58491 -59.01899 252.4612 60.65256 -59.01899 244.6157 59.09835 -59.01899 260.4423 61.1699 -59.01899 268.4227 60.64152 -59.01899 276.266 59.07646 -59.01899 283.838 56.50148 -59.01899 291.0094 52.96059 -59.01899 297.6575 48.51433 -59.01899 303.6686 43.2387 -59.01899 308.9401 37.2239 -49.82639 320.175 34.19471 -50.32241 320.1874 33.43838 -59.01899 313.3818 30.57275 -49.20775 320.2765 34.90557 -50 320.17 15 -50.32241 320.1874 33.43838 -49.82639 320.175 34.19471 -50.46897 320.2069 33.18165 -50.88472 320.3034 15 -50.46897 320.2069 33.18165 -49.20775 320.2765 34.90557 -48.89626 320.3805 15 -48.64122 320.4954 35.32114 -48.15489 320.8045 35.45994 -47.95515 320.9755 15 -47.73599 321.2017 35.34735 -47.37823 321.7118 34.9451 -47.29803 321.8679 15 -47.12776 322.3038 34.23291 -47.00945 322.9378 15 -47.00813 322.9493 33.20876 -47.03627 323.6351 31.8421 -47.13042 324.0447 15 -47.23842 324.3421 30.08234 -47.65346 325.0392 27.85547 -49.74824 327.669 15 -47.65346 325.0392 27.85547 -48.85761 326.5509 21.49412 -47.65346 325.0392 15 -47.65346 325.0392 15 -47.65346 325.0392 15 -49.74824 327.669 15 -50.32455 327.2389 15 -52.12831 325.8419 15 -52.12831 325.8419 15 -59.01144 237.1321 56.57963 -50.84238 216.8874 46.09818 -59.01144 237.1321 56.57963 -66.65713 245.886 50.70672 -62.11941 238.0711 53.54995 -54.07727 217.0084 42.27401 -62.11941 238.0711 53.54995 -66.65713 252.692 52.17676 -66.65713 259.6324 52.73744 -66.65713 266.5861 52.37899 -66.65713 273.432 51.10767 -66.65713 280.0508 48.94562 -66.65713 286.3271 45.93053 -66.65713 292.1515 42.11494 -66.65713 297.4226 37.56537 -66.65713 302.0484 32.36109 -66.65713 305.9483 26.5928 -52.34654 321.3009 27.85547 -59.01899 316.9177 23.39894 -66.65713 309.0545 20.36105 -51.75972 320.7403 30.08286 -51.1209 320.3873 31.83053 -53.5509 322.8128 21.49283 -59.01899 319.4874 15.82513 -66.65713 311.3126 13.77444 -54.44132 323.9306 15 -54.44132 323.9306 15 -52.34654 321.3009 15 -54.44132 323.9306 15 -53.5509 322.8128 21.49283 -47.13042 324.0447 15 -47.00945 322.9378 15 -52.34654 321.3009 15 -52.34654 321.3009 27.85547 -52.34654 321.3009 15 -52.34654 321.3009 27.85547 -51.75972 320.7403 30.08286 -51.69094 320.692 15 -51.1209 320.3873 31.83053 -66.74029 239.4663 48.29607 -57.0279 217.0962 38.21406 -66.74029 239.4663 48.29607 -73.10187 246.7829 41.17878 -68.7149 240.0621 45.7125 -68.7149 240.0621 45.7125 -73.10187 252.4646 42.63973 -73.10187 258.2914 43.32056 -73.10187 264.1568 43.20884 -73.10187 269.9535 42.30659 -73.10187 275.5754 40.63033 -73.10187 280.9197 38.21073 -73.10187 285.8886 35.09205 -73.10187 290.3911 31.33135 -68.61811 296.01 35.33395 -69.55603 294.5506 34.9384 -69.13723 294.9883 35.337 -68.8292 295.4726 35.46077 -70.14102 299.506 27.85601 -68.51029 296.6239 34.91642 -68.53386 297.2622 34.19489 -68.69622 297.8923 33.1687 -69.00685 298.4971 31.80676 -69.48138 299.0495 30.05915 -71.87532 300.3897 21.44201 -73.10494 301.0162 15.19895 -72.56456 300.7409 18.22215 -73.10187 302.5424 10.25351 -73.14265 241.3973 38.91081 -59.68402 217.1535 33.92643 -73.14265 241.3973 38.91081 -78.23781 246.4476 30.15256 -73.44529 241.4885 38.38162 -65.49497 225.2262 33.05176 -73.44529 241.4885 38.38162 -63.52895 223.9257 35.26662 -63.88613 224.3694 35.14942 -64.34738 224.756 34.75216 -64.89223 225.0492 34.05331 -78.23781 250.2254 31.62788 -78.23593 258.1766 33.15414 -78.23781 254.1548 32.63193 -77.484 259.2384 34.92664 9.541881 284.7805 66 9.574053 276.0903 66 10.38881 281.9227 66 -77.79296 258.6787 34.20954 -78.23781 266.7493 32.61183 -77.30403 259.8332 35.3379 -77.25003 260.4114 35.46038 -77.30847 260.9894 35.32788 -77.48976 261.5752 34.9135 -77.79761 262.1279 34.19865 -78.22615 262.6145 33.17785 7.932786 287.279 66 7.976566 273.5722 66 -78.23781 270.7757 31.56249 -78.23781 274.6394 30.0181 -78.23781 278.2797 28.0029 -78.23781 281.6396 25.5485 -72.86499 294.16 27.85601 -73.1229 294.2914 27.00598 -78.23781 284.6664 22.69338 -72.08062 293.8891 30.13078 -71.34262 293.8373 31.8933 -70.67078 293.9508 33.24143 -70.07318 294.1957 34.24331 -72.86499 294.16 15 -73.1229 294.2914 27.00598 -72.86499 294.16 27.85601 -78.23781 287.3125 19.48233 -74.60461 295.0464 21.41913 -74.60461 295.0464 21.41913 -72.86499 294.16 15 -72.86499 294.16 27.85601 -72.08062 293.8891 30.13078 -71.503 293.833 15 -71.34262 293.8373 31.8933 -72.20333 293.9159 15 -70.67078 293.9508 33.24143 -70.38233 294.0503 15 -70.07318 294.1957 34.24331 -69.55603 294.5506 34.9384 -69.42726 294.6678 15 -69.13723 294.9883 35.337 -68.8292 295.4726 35.46077 -68.77169 295.5941 15 -68.61811 296.01 35.33395 -68.51029 296.6239 34.91642 -68.50691 296.6967 15 -68.53386 297.2622 34.19489 -68.67044 297.8197 15 -68.69622 297.8923 33.1687 -69.00685 298.4971 31.80676 -69.24109 298.8035 15 -69.48138 299.0495 30.05915 -70.14102 299.506 27.85601 -72.56456 300.7409 18.22215 -70.14102 299.506 27.85601 -71.87532 300.3897 21.44201 -73.10494 301.0162 15.19895 -73.13687 301.0325 15 -70.14102 299.506 15 -70.14102 299.506 15 -73.13687 301.0325 15 -78.23781 292.5861 8.240331 -76.54758 242.4232 32.28474 -66.1454 225.2729 31.72018 -76.54758 242.4232 32.28474 -78.27421 242.9432 28.16753 -67.53401 224.8731 27.85184 -78.27421 242.9432 28.16753 -66.83155 225.167 30.01048 -81.97303 248.7533 19.22962 -81.97303 246.2453 17.46622 -78.6286 243.0499 27.23086 -78.6286 243.0499 27.23086 -81.97303 251.4779 20.6354 -81.97303 254.3684 21.65742 -78.77436 257.788 31.82419 -81.9843 257.4 22.24155 -80.25 257.4 27.85566 -79.44992 257.5087 30.07241 10.39938 278.9509 66 -79.08889 257.6344 15 -78.77436 257.788 31.82419 -78.23593 258.1766 33.15414 -78.11267 258.2955 15 -77.79296 258.6787 34.20954 -77.484 259.2384 34.92664 -77.47212 259.2678 15 -77.30403 259.8332 35.3379 -77.25003 260.4114 35.46038 -77.25006 260.4119 15 -77.30847 260.9894 35.32788 -77.48125 261.5544 15 -77.48976 261.5752 34.9135 -77.79761 262.1279 34.19865 -78.12545 262.5177 15 -78.22615 262.6145 33.17785 -78.77622 263.013 31.81953 -78.77622 263.013 31.81953 -81.97303 266.3024 21.693 -81.9843 263.4 22.24155 -80.25 263.4 27.85566 -79.45053 263.2915 30.07079 -81.97303 269.0754 20.74035 -81.97303 271.7008 19.43491 -81.97303 274.134 17.79888 -81.97303 276.3337 15.8601 -81.97303 278.2622 13.65154 -78.23781 289.5366 15.96571 -81.97303 279.887 11.21078 -75.86083 295.6865 15 -78.23781 291.3037 12.19869 -81.97303 281.1803 8.57932 -75.29203 295.3966 18.20484 -81.97303 282.1201 5.801929 -74.54679 298.3839 15 -72.86499 294.16 15 -73.13687 301.0325 15 -74.54679 298.3839 15 -72.20333 293.9159 15 -71.503 293.833 15 -70.38233 294.0503 15 -70.14102 299.506 15 -75.86083 295.6865 15 -75.86083 295.6865 15 -75.29203 295.3966 18.20484 -80.11442 243.4972 22.82492 -69.17012 223.9284 21.48612 -80.11442 243.4972 22.82492 -81.24094 243.8363 18.72312 -70.40156 223.2175 15 -81.24094 243.8363 18.72312 -81.97932 244.0585 15.40611 -81.97932 244.0585 15.40611 -82.12406 244.1021 14.66349 -82.12406 244.1021 14.66349 -80.25 257.4 15 -81.9843 257.4 22.24155 -80.25 257.4 27.85566 -83.6122 257.4 15 -82.25606 257.4 21.21201 -82.25606 257.4 21.21201 -80.25 257.4 15 -80.25 257.4 27.85566 -79.44992 257.5087 30.07241 -82.49318 244.2131 12.5643 -67.90335 217.1798 10.13094 -82.49318 244.2131 12.5643 -82.81657 244.3104 10.37024 -82.81657 244.3104 10.37024 -83.0912 244.3931 8.03926 -83.0912 244.3931 8.03926 -83.3083 244.4584 5.530963 -83.3083 244.4584 5.530963 -83.41331 244.49 3.754015 -83.41331 244.49 3.754015 -83.666 260.4 15 -83.65255 258.8998 15 -83.65255 261.9002 15 -83.6122 263.4 15 -82.25606 263.4 21.21201 -83.6122 263.4 15 -81.9843 263.4 22.24155 -82.25606 263.4 21.21201 -80.25 263.4 27.85566 -83.6122 257.4 15 -83.6122 263.4 15 -83.65255 261.9002 15 -80.25 257.4 15 -80.25 263.4 15 -80.25 263.4 15 -83.65255 258.8998 15 -83.666 260.4 15 -83.6122 257.4 15 -79.09465 263.1682 15 -79.45053 263.2915 30.07079 -80.25 263.4 27.85566 -80.25 263.4 15 0 290.9 79.33946 0 290.9 66 0 290.9 79.33946 -2.67668 290.5531 79.42676 0 290.9 66 -2.976411 290.4688 66 -5.165318 289.5416 79.68093 -5.718314 289.2049 66 66.77414 200.5839 15 65.47537 200.2252 15 64.513 202.9981 15 65.47537 200.2252 15 66.77414 200.5839 15 61.77333 147.4 9.826401 65.47537 200.2252 15 65.27436 197.9858 15 65.27436 197.9858 15 68.07296 200.9427 15 68.07296 200.9427 15 73 203.3307 18.52296 66.52468 201.8366 19.53368 64.513 202.9981 15 68.07296 200.9427 15 66.52468 201.8366 19.53368 73 206.9314 27.22327 64.513 202.9981 24.14707 64.513 202.9981 24.14707 63.78588 203.2987 25.334 64.513 202.9981 15 64.513 202.9981 24.14707 63.78588 203.2987 25.334 63.013 203.4 26.06299 63.78944 203.2977 15 63.013 203.4 26.06299 62.52994 203.3609 26.28821 63.013 203.4 15 62.52994 203.3609 26.28821 62.08028 203.2513 26.33821 62.08028 203.2513 26.33821 61.40267 202.9312 27.81363 62.08028 203.2513 26.33821 61.91339 203.1911 15 61.40267 202.9312 27.81363 55.825 159.3945 30.47047 60.84769 202.4764 28.9151 60.42607 201.9191 29.67563 60.15242 201.3039 30.10651 60.02756 200.6952 30.23656 56.89847 161.6997 28.86414 56.41777 161.1903 29.69723 56.07861 160.6072 30.22544 55.88602 160.002 30.46962 64.24816 319.7772 19.00672 73 317.4434 18.60236 61.63955 321.6336 15 64.53171 320.8354 15 62.46699 316.6292 28.01657 73 315.2042 4.636376 73 313.835 27.28928 63.06182 317.0668 26.74917 63.55799 317.6786 25.08306 63.89778 318.4696 22.94665 73 313.701 13.56462 73 308.9542 35.24898 61.14128 316.2493 29.53398 61.8148 316.3588 28.93522 73 306.4422 30.08507 73 302.8464 42.40642 73 310.7548 22.12212 73 300.8708 37.24397 73 295.6947 48.5209 73 294.1843 43.40071 73 287.6891 53.43502 73 286.6418 48.33597 73 279.0209 57.03734 73 278.3314 51.99485 73 269.8952 59.24386 73 269.4965 54.24254 73 260.5299 59.99981 73 260.4 55 73 251.1496 59.28258 73 264.981 54.80755 73 242.5435 52.02062 73 241.9811 57.10287 73 251.3592 54.25185 73 234.2212 48.37014 73 233.2493 53.50549 73 229.1172 51.19839 73 226.6465 43.42462 73 225.1755 48.57189 73 223.1598 40.47071 73 221.4503 45.63732 73 219.9193 37.23322 73 217.9665 42.41926 73 216.967 33.74082 73 214.75 38.93364 73 214.3148 30.01914 73 211.8232 35.21779 73 209.9889 21.99357 73 206.9314 27.22327 73 207.0532 13.38335 63.89778 318.4696 15 64.53171 320.8354 15 61.63955 321.6336 15 64.24816 319.7772 19.00672 64.53171 320.8354 15 63.89778 318.4696 22.94665 63.89778 318.4696 15 61 316.246 15 58.74761 322.4311 15 63.49127 317.5747 15 62.82626 316.866 15 61.96962 316.4071 15 58.10222 320.0225 15 58.74761 322.4311 15 58.45947 321.3558 19.16064 59.92296 316.4462 15 58.99216 317.0177 15 58.32799 317.8832 15 58.10222 320.0225 15 58.10222 320.0225 23.24046 58.10222 320.0225 15 58.10222 320.0225 23.24046 58.00047 319.1929 25.33454 58.01685 318.9302 15 58.11343 318.4289 26.96714 58.32799 317.8832 15 58.39733 317.754 28.2022 58.82065 317.1844 29.08427 58.99216 317.0177 15 59.34957 316.7408 29.63127 59.91502 316.4491 29.85868 59.92296 316.4462 15 60.50268 316.2875 29.82695 61 316.246 15 61.14128 316.2493 29.53398 61.8148 316.3588 28.93522 61.96962 316.4071 15 62.46699 316.6292 28.01657 62.82626 316.866 15 63.06182 317.0668 26.74917 63.49127 317.5747 15 63.55799 317.6786 25.08306 63.89778 318.4696 22.94665 63.89778 318.4696 15 61.91339 203.1911 15 61.513 197.8019 15 65.07332 195.7464 15 61.513 197.8019 26.45257 65.07332 195.7464 15 61.513 197.8019 15 63.013 203.4 15 63.78944 203.2977 15 65.07332 195.7464 15 60.80711 147.4 14.65774 62.05136 162.1292 15 63.53199 196.6363 20.82528 63.53199 196.6363 20.82528 60.97 202.5962 15 60.66511 198.5327 15 61.513 197.8019 26.45257 61.513 197.8019 15 60.66511 198.5327 15 60.31014 201.7 15 60.14557 199.5197 15 60.46973 198.8088 28.96215 60.14557 199.5197 15 60.91719 198.2535 27.89223 60.02226 200.6258 15 60.0303 200.0783 30.11092 60.02226 200.6258 15 60.17288 199.4337 29.69762 60.02756 200.6952 30.23656 60.31014 201.7 15 60.42607 201.9191 29.67563 60.97 202.5962 15 60.15242 201.3039 30.10651 60.84769 202.4764 28.9151 60.21032 156.2673 19.61899 59.46792 147.4 19.39247 61.78239 159.1413 15 61.51335 156.1533 15 58.56353 156.4114 24.12603 57.76154 147.4 23.99858 57.02877 156.9972 27.67609 55.70747 147.4 28.44606 57.72047 156.6107 26.12105 53.32715 147.4 32.69383 55.89368 158.7617 30.22811 56.11378 158.1157 29.69692 56.49275 157.513 28.85377 52.02062 147.4 17.8565 50.62059 147.4 36.74311 54.25185 147.4 9.040809 48.37014 147.4 26.17878 47.58338 147.4 40.59617 44.2502 147.4 44.2088 43.42462 147.4 33.75352 40.64623 147.4 47.54211 40.47071 147.4 37.24022 36.79549 147.4 50.58251 33.74082 147.4 43.43301 32.722 147.4 53.30737 37.23322 147.4 40.48065 30.01914 147.4 46.0852 28.45097 147.4 55.70494 24.00643 147.4 57.75894 24.00643 147.4 57.75894 19.41596 147.4 59.46022 21.99357 147.4 50.41108 19.41596 147.4 59.46022 12.97491 211.5141 66.91291 14.70538 147.4 60.79596 14.70538 147.4 60.79596 9.903903 147.4 61.7609 13.38335 147.4 53.34679 9.903903 147.4 61.7609 2.991063 212.5854 68.18741 5.039426 147.4 62.3458 5.039426 147.4 62.3458 0.141712 147.4 62.54979 4.426485 147.4 54.82153 0.141712 147.4 62.54979 -7.022048 213.6004 67.98007 -4.760062 147.4 62.36774 -4.636376 147.4 54.80418 -4.760062 147.4 62.36774 -9.636244 147.4 61.80323 -9.636244 147.4 61.80323 -16.91499 214.5318 66.29953 -14.45719 147.4 60.85541 -13.56462 147.4 53.30099 -14.45719 147.4 60.85541 -19.19369 147.4 59.53233 -19.19369 147.4 59.53233 -21.74006 214.9552 64.91675 -23.81617 147.4 57.83746 -22.12212 147.4 50.35481 -23.81617 147.4 57.83746 -30.98949 215.6994 61.1178 -28.29614 147.4 55.78374 -28.29614 147.4 55.78374 -26.44347 215.3458 63.18416 -35.37036 216.0157 58.72362 -32.60395 147.4 53.37942 -30.08507 147.4 46.0422 -32.60395 147.4 53.37942 -39.57728 216.2932 56.00443 -36.71356 147.4 50.642 -36.71356 147.4 50.642 -43.57526 216.5315 52.98031 -40.59742 147.4 47.58352 -37.24397 147.4 40.47077 -40.59742 147.4 47.58352 -47.33538 216.7287 49.67338 -44.23035 147.4 44.22867 -43.40071 147.4 33.78425 -44.23035 147.4 44.22867 -50.84238 216.8874 46.09818 -47.58631 147.4 40.59246 -47.58631 147.4 40.59246 -54.07727 217.0084 42.27401 -50.64026 147.4 36.716 -48.33597 147.4 26.24179 -50.64026 147.4 36.716 -57.0279 217.0962 38.21406 -53.35656 147.4 32.64563 -51.99485 147.4 17.9314 -53.35656 147.4 32.64563 -56.50516 157.4978 28.82653 -55.74084 147.4 28.38063 -54.24254 147.4 9.096512 -59.68402 217.1535 33.92643 -55.82515 159.3696 30.46566 -56.12449 158.0934 29.67248 -55.89961 158.7351 30.21225 -57.72749 156.608 26.10494 -57.79339 147.4 23.92148 -57.03991 156.9889 27.65146 -54.80755 147.4 4.580959 -60.21032 156.2673 19.61899 -59.49447 147.4 19.31087 -58.56353 156.4114 24.12603 -61.51335 156.1533 15 -60.82553 147.4 14.58077 -66.96784 217.1905 15.13074 -61.78324 147.4 9.763909 -64.91617 193.9962 15 -61.78239 159.1413 15 -62.05136 162.1292 15 -64.37945 188.0202 15 -64.64785 191.0083 15 -67.90335 217.1798 10.13094 -67.45172 217.9924 15 -66.96784 217.1905 15.13074 -68.9284 220.6046 15 -63.80868 194.0931 19.2013 -65.66699 217.1984 20.03924 -65.66699 217.1984 20.03924 -62.43146 194.2136 23.32286 -64.01552 217.1991 24.81422 -66.19934 218.7154 21.19382 -64.01552 217.1991 24.81422 -60.23333 193.5161 28.38066 -62.01995 217.1862 29.44663 -64.534 219.6769 27.33045 -62.01995 217.1862 29.44663 -60.84842 193.9182 27.12327 -61.58626 194.1677 25.4606 -59.22356 191.7893 30.09981 -63.39606 220.8463 31.51821 -59.41082 192.4027 29.848 -59.75036 192.9985 29.28105 -63.85037 220.2179 29.6858 -55.88095 159.9767 30.4743 -63.13394 221.5071 32.92467 -63.03585 222.1698 33.97367 -63.08317 222.8159 34.70653 -63.25925 223.4155 35.13185 57.5103 162.0966 27.7051 60.0303 200.0783 30.11092 60.17288 199.4337 29.69762 60.46973 198.8088 28.96215 58.24418 162.3432 26.17974 60.91719 198.2535 27.89223 61.513 197.8019 26.45257 59.08647 162.3886 24.2293 60.7432 162.2436 19.67009 -56.7467 161.5628 15 -62.05136 162.1292 15 -61.78239 159.1413 15 -60.7432 162.2436 19.67009 -62.05136 162.1292 15 -59.08647 162.3886 24.2293 -59.08647 162.3886 15 -63.27686 188.1167 19.15429 -60.7432 162.2436 19.67009 -57.70272 162.182 15 -59.08647 162.3886 15 -55.9944 158.4085 15 -61.51335 156.1533 15 -56.09166 160.6346 15 -55.82877 159.5309 15 -58.56353 156.4114 15 -61.51335 156.1533 15 -60.21032 156.2673 19.61899 -56.56599 157.4267 15 -57.46443 156.7264 15 -58.56353 156.4114 15 -58.56353 156.4114 24.12603 -58.56353 156.4114 15 -58.56353 156.4114 24.12603 -57.72749 156.608 26.10494 -57.46443 156.7264 15 -57.03991 156.9889 27.65146 -56.56599 157.4267 15 -56.50516 157.4978 28.82653 -56.12449 158.0934 29.67248 -55.9944 158.4085 15 -55.89961 158.7351 30.21225 -55.82515 159.3696 30.46566 -55.82877 159.5309 15 -55.88095 159.9767 30.4743 -56.06707 160.5806 30.24195 -56.06707 160.5806 30.24195 -56.40243 161.1695 29.72246 -56.09166 160.6346 15 -56.40243 161.1695 29.72246 -59.17039 191.1763 30.08591 -56.88293 161.6865 28.89224 -56.7467 161.5628 15 -56.88293 161.6865 28.89224 -59.48099 189.8949 29.21359 -57.49756 162.0903 27.73027 -57.49756 162.0903 27.73027 -59.25 190.5368 29.8045 -59.86483 189.305 28.29827 -58.2367 162.3417 26.19606 -57.70272 162.182 15 -58.2367 162.3417 26.19606 -61.08219 188.4292 25.36558 -59.08647 162.3886 24.2293 -58.825 162.4 15 -59.08647 162.3886 24.2293 -60.39896 188.8035 27.03231 -61.90853 188.2364 23.22817 -58.95586 162.3971 15 -59.08647 162.3886 15 58.56353 156.4114 15 61.51335 156.1533 15 61.78239 159.1413 15 60.21032 156.2673 19.61899 61.51335 156.1533 15 58.56353 156.4114 24.12603 58.56353 156.4114 15 55.82876 159.5307 15 62.05136 162.1292 15 57.46452 156.7263 15 56.5661 157.4265 15 55.99446 158.4084 15 59.08647 162.3886 15 62.05136 162.1292 15 60.7432 162.2436 19.67009 56.09157 160.6344 15 56.74657 161.5627 15 57.70262 162.182 15 59.08647 162.3886 15 59.08647 162.3886 24.2293 59.08647 162.3886 15 59.08647 162.3886 24.2293 58.24418 162.3432 26.17974 57.70262 162.182 15 57.5103 162.0966 27.7051 58.825 162.4 15 58.95586 162.3971 15 56.89847 161.6997 28.86414 56.74657 161.5627 15 56.41777 161.1903 29.69723 56.09157 160.6344 15 56.07861 160.6072 30.22544 55.88602 160.002 30.46962 55.82876 159.5307 15 55.825 159.3945 30.47047 55.89368 158.7617 30.22811 55.99446 158.4084 15 56.11378 158.1157 29.69692 56.49275 157.513 28.85377 56.5661 157.4265 15 57.02877 156.9972 27.67609 57.46452 156.7263 15 57.72047 156.6107 26.12105 58.56353 156.4114 24.12603 58.56353 156.4114 15 -60.09169 193.3878 15 -64.91617 193.9962 15 -64.64785 191.0083 15 -63.80868 194.0931 19.2013 -64.91617 193.9962 15 -62.43146 194.2136 23.32286 -62.43146 194.2136 15 -61.04772 194.007 15 -62.43146 194.2136 15 -59.3394 190.2335 15 -64.37945 188.0202 15 -59.43666 192.4596 15 -59.17377 191.3559 15 -61.90853 188.2364 15 -64.37945 188.0202 15 -63.27686 188.1167 19.15429 -59.91099 189.2517 15 -60.80943 188.5514 15 -61.90853 188.2364 15 -61.90853 188.2364 23.22817 -61.90853 188.2364 15 -61.90853 188.2364 23.22817 -61.08219 188.4292 25.36558 -60.80943 188.5514 15 -60.39896 188.8035 27.03231 -59.91099 189.2517 15 -59.86483 189.305 28.29827 -59.48099 189.8949 29.21359 -59.3394 190.2335 15 -59.25 190.5368 29.8045 -59.17039 191.1763 30.08591 -59.17377 191.3559 15 -59.22356 191.7893 30.09981 -59.41082 192.4027 29.848 -59.43666 192.4596 15 -59.75036 192.9985 29.28105 -60.09169 193.3878 15 -60.23333 193.5161 28.38066 -60.84842 193.9182 27.12327 -61.04772 194.007 15 -61.58626 194.1677 25.4606 -62.17 194.225 15 -62.43146 194.2136 23.32286 -62.30086 194.2221 15 -62.43146 194.2136 15 -55 146.4 0 -55 147.4 0 -54.25185 147.4 -9.040809 -54.25185 146.4 9.040809 -54.80755 147.4 4.580959 -55 147.4 0 -55 146.4 0 -54.24254 146.4 -9.096512 -52.02062 147.4 -17.8565 -54.80755 146.4 -4.580959 -51.99485 146.4 -17.9314 -48.37014 147.4 -26.17878 -48.33597 146.4 -26.24179 -43.42462 147.4 -33.75352 -43.40071 146.4 -33.78425 -40.47071 147.4 -37.24022 -37.24397 146.4 -40.47077 -37.23322 147.4 -40.48065 -33.74082 147.4 -43.43301 -30.08507 146.4 -46.0422 -30.01914 147.4 -46.0852 -22.12212 146.4 -50.35481 -21.99357 147.4 -50.41108 -13.56462 146.4 -53.30099 -13.38335 147.4 -53.34679 -4.636376 146.4 -54.80418 -4.426485 147.4 -54.82153 4.426485 146.4 -54.82153 4.636376 147.4 -54.80418 13.38335 146.4 -53.34679 13.56462 147.4 -53.30099 21.99357 146.4 -50.41108 22.12212 147.4 -50.35481 30.01914 146.4 -46.0852 30.08507 147.4 -46.0422 33.74082 146.4 -43.43301 37.24397 147.4 -40.47077 40.47071 146.4 -37.24022 43.40071 147.4 -33.78425 37.23322 146.4 -40.48065 43.42462 146.4 -33.75352 48.33597 147.4 -26.24179 48.37014 146.4 -26.17878 51.99485 147.4 -17.9314 52.02062 146.4 -17.8565 54.24254 147.4 -9.096512 54.25185 146.4 -9.040809 54.80755 147.4 -4.580959 55 147.4 0 55 146.4 0 55 147.4 0 54.25185 147.4 9.040809 55 146.4 0 54.24254 146.4 9.096512 52.02062 147.4 17.8565 54.80755 146.4 4.580959 51.99485 146.4 17.9314 48.37014 147.4 26.17878 48.33597 146.4 26.24179 43.42462 147.4 33.75352 43.40071 146.4 33.78425 40.47071 147.4 37.24022 37.24397 146.4 40.47077 37.23322 147.4 40.48065 33.74082 147.4 43.43301 30.08507 146.4 46.0422 30.01914 147.4 46.0852 22.12212 146.4 50.35481 21.99357 147.4 50.41108 13.56462 146.4 53.30099 13.38335 147.4 53.34679 4.636376 146.4 54.80418 4.426485 147.4 54.82153 -4.426485 146.4 54.82153 -4.636376 147.4 54.80418 -13.38335 146.4 53.34679 -13.56462 147.4 53.30099 -21.99357 146.4 50.41108 -22.12212 147.4 50.35481 -30.01914 146.4 46.0852 -30.08507 147.4 46.0422 -33.74082 146.4 43.43301 -37.24397 147.4 40.47077 -40.47071 146.4 37.24022 -43.40071 147.4 33.78425 -37.23322 146.4 40.48065 -43.42462 146.4 33.75352 -48.33597 147.4 26.24179 -48.37014 146.4 26.17878 -51.99485 147.4 17.9314 -52.02062 146.4 17.8565 -54.24254 147.4 9.096512 -55.85556 146.4 -28.4391 -55 146.4 0 -54.80755 146.4 -4.580959 -55.82222 146.4 28.50449 -54.25185 146.4 9.040809 -54.24254 146.4 -9.096512 -51.99485 146.4 -17.9314 -50.74445 146.4 -36.79166 -48.33597 146.4 -26.24179 -47.68409 146.4 -40.67623 -43.40071 146.4 -33.78425 -40.68064 146.4 -47.68179 -37.24397 146.4 -40.47077 -44.32109 146.4 -44.32004 -36.78876 146.4 -50.74653 -30.08507 146.4 -46.0422 -28.35401 146.4 -55.89877 -22.12212 146.4 -50.35481 -32.67069 146.4 -53.48954 -19.23284 146.4 -59.65501 -13.56462 146.4 -53.30099 -9.655741 146.4 -61.93051 -4.636376 146.4 -54.80418 0.142315 146.4 -62.67855 4.426485 146.4 -54.82153 9.924565 146.4 -61.888 13.38335 146.4 -53.34679 19.45614 146.4 -59.58256 21.99357 146.4 -50.41108 28.50967 146.4 -55.81954 30.01914 146.4 -46.0852 33.74082 146.4 -43.43301 36.87129 146.4 -50.68659 37.23322 146.4 -40.48065 40.47071 146.4 -37.24022 43.42462 146.4 -33.75352 44.3413 146.4 -44.29981 48.37014 146.4 -26.17878 50.72493 146.4 -36.81856 52.02062 146.4 -17.8565 54.25185 146.4 -9.040809 55.82222 146.4 -28.50449 55 146.4 0 55.85556 146.4 28.4391 54.80755 146.4 4.580959 54.24254 146.4 9.096512 51.99485 146.4 17.9314 50.74445 146.4 36.79166 48.33597 146.4 26.24179 47.68409 146.4 40.67623 43.40071 146.4 33.78425 40.68064 146.4 47.68179 37.24397 146.4 40.47077 44.32109 146.4 44.32004 36.78876 146.4 50.74653 30.08507 146.4 46.0422 28.35401 146.4 55.89877 22.12212 146.4 50.35481 32.67069 146.4 53.48954 19.23284 146.4 59.65501 13.56462 146.4 53.30099 9.655741 146.4 61.93051 4.636376 146.4 54.80418 -0.142315 146.4 62.67855 -4.426485 146.4 54.82153 -9.924565 146.4 61.888 -13.38335 146.4 53.34679 -19.45614 146.4 59.58256 -21.99357 146.4 50.41108 -28.50967 146.4 55.81954 -30.01914 146.4 46.0852 -33.74082 146.4 43.43301 -36.87129 146.4 50.68659 -37.23322 146.4 40.48065 -40.47071 146.4 37.24022 -43.42462 146.4 33.75352 -44.3413 146.4 44.29981 -48.37014 146.4 26.17878 -50.72493 146.4 36.81856 -52.02062 146.4 17.8565 -62.48111 146.4 4.955946 -61.91042 146.4 -9.784027 -62.67877 146.4 0 -65.5 130.4 0 -62.67877 146.4 0 -61.91042 146.4 -9.784027 -64.7713 130.4 9.743709 -62.48111 146.4 4.955946 -62.67877 146.4 0 -65.5 130.4 0 -61.90049 146.4 9.846662 -59.61693 146.4 -19.35069 -62.56806 130.4 -19.37624 -59.61693 146.4 -19.35069 -64.76152 130.4 -9.807445 -59.59034 146.4 19.43241 -58.98452 130.4 -28.47751 -55.85556 146.4 -28.4391 -54.13003 130.4 -36.88257 -50.74445 146.4 -36.79166 -47.68409 146.4 -40.67623 -48.03369 130.4 -44.5292 -44.32109 146.4 -44.32004 -40.68064 146.4 -47.68179 -40.86348 130.4 -51.18907 -36.78876 146.4 -50.74653 -32.67069 146.4 -53.48954 -32.79672 130.4 -56.69684 -28.35401 146.4 -55.89877 -24.00988 130.4 -60.93996 -19.23284 146.4 -59.65501 -14.69078 130.4 -63.83041 -9.655741 146.4 -61.93051 -5.040033 130.4 -65.30491 0.142315 146.4 -62.67855 4.732599 130.4 -65.32788 9.924565 146.4 -61.888 14.41347 130.4 -63.89348 19.45614 146.4 -59.58256 23.78907 130.4 -61.02622 28.50967 146.4 -55.81954 32.64857 130.4 -56.78203 36.87129 146.4 -50.68659 40.78843 130.4 -51.24872 44.3413 146.4 -44.29981 48.01821 130.4 -44.5459 50.72493 146.4 -36.81856 54.15135 130.4 -36.8515 55.82222 146.4 -28.50449 59.59034 146.4 -19.43241 59.01793 130.4 -28.40861 59.59034 146.4 -19.43241 59.61693 146.4 19.35069 61.90049 146.4 -9.846662 62.59423 130.4 -19.29223 61.90049 146.4 -9.846662 61.91042 146.4 9.784027 62.48111 146.4 -4.955946 64.7713 130.4 -9.743709 62.48111 146.4 -4.955946 62.67877 146.4 0 62.67877 146.4 0 65.5 130.4 0 62.67877 146.4 0 61.91042 146.4 9.784027 65.5 130.4 0 62.56806 130.4 19.37624 59.61693 146.4 19.35069 64.76152 130.4 9.807445 58.98452 130.4 28.47751 55.85556 146.4 28.4391 54.13003 130.4 36.88257 50.74445 146.4 36.79166 47.68409 146.4 40.67623 48.03369 130.4 44.5292 44.32109 146.4 44.32004 40.68064 146.4 47.68179 40.86348 130.4 51.18907 36.78876 146.4 50.74653 32.67069 146.4 53.48954 32.79672 130.4 56.69684 28.35401 146.4 55.89877 24.00988 130.4 60.93996 19.23284 146.4 59.65501 14.69078 130.4 63.83041 9.655741 146.4 61.93051 5.040033 130.4 65.30491 -0.142315 146.4 62.67855 -4.732599 130.4 65.32788 -9.924565 146.4 61.888 -14.41347 130.4 63.89348 -19.45614 146.4 59.58256 -23.78907 130.4 61.02622 -28.50967 146.4 55.81954 -32.64857 130.4 56.78203 -36.87129 146.4 50.68659 -40.78843 130.4 51.24872 -44.3413 146.4 44.29981 -48.01821 130.4 44.5459 -50.72493 146.4 36.81856 -54.15135 130.4 36.8515 -55.82222 146.4 28.50449 -59.01793 130.4 28.40861 -59.59034 146.4 19.43241 -62.59423 130.4 19.29223 -61.90049 146.4 9.846662 -64.7713 130.4 9.743709 -65.5 130.4 0 -64.76152 130.4 -9.807445 -62.59423 130.4 19.29223 -62.56806 130.4 -19.37624 -59.01793 130.4 28.40861 -58.98452 130.4 -28.47751 -54.15135 130.4 36.8515 -54.13003 130.4 -36.88257 -48.03369 130.4 -44.5292 -45 130.4 0 -40.86348 130.4 -51.18907 -48.01821 130.4 44.5459 -38.25572 130.4 -23.6968 -32.79672 130.4 -56.69684 -44.23486 130.4 -8.262195 -41.95843 130.4 -16.26262 -30.2992 130.4 -33.2694 -24.00988 130.4 -60.93996 -33.26306 130.4 -30.30535 -19.99404 130.4 -40.31335 -14.69078 130.4 -63.83041 -27.08792 130.4 -35.93297 -12.23404 130.4 -43.30418 -5.040033 130.4 -65.30491 -4.077956 130.4 -44.81395 4.732599 130.4 -65.32788 12.33043 130.4 -43.27685 14.41347 130.4 -63.89348 4.200896 130.4 -44.80258 20.04465 130.4 -40.28836 23.78907 130.4 -61.02622 27.09093 130.4 -35.93096 32.64857 130.4 -56.78203 33.23467 130.4 -30.33682 40.78843 130.4 -51.24872 41.93266 130.4 -16.3294 48.01821 130.4 -44.5459 38.21961 130.4 -23.75533 48.03369 130.4 44.5292 54.15135 130.4 -36.8515 45 130.4 0 43.26216 130.4 -12.37978 44.22597 130.4 -8.310162 44.80353 130.4 -4.189214 58.98452 130.4 28.47751 59.01793 130.4 -28.40861 54.13003 130.4 36.88257 62.56806 130.4 19.37624 62.59423 130.4 -19.29223 64.76152 130.4 9.807445 64.7713 130.4 -9.743709 65.5 130.4 0 40.86348 130.4 51.18907 38.25572 130.4 23.6968 32.79672 130.4 56.69684 44.23486 130.4 8.262195 41.95843 130.4 16.26262 30.2992 130.4 33.2694 24.00988 130.4 60.93996 33.26306 130.4 30.30535 19.99404 130.4 40.31335 14.69078 130.4 63.83041 27.08792 130.4 35.93297 12.23404 130.4 43.30418 5.040033 130.4 65.30491 4.077956 130.4 44.81395 -4.732599 130.4 65.32788 -12.33043 130.4 43.27685 -14.41347 130.4 63.89348 -4.200896 130.4 44.80258 -20.04465 130.4 40.28836 -23.78907 130.4 61.02622 -27.09093 130.4 35.93096 -32.64857 130.4 56.78203 -33.23467 130.4 30.33682 -40.78843 130.4 51.24872 -41.93266 130.4 16.3294 -38.21961 130.4 23.75533 -44.80353 130.4 4.189214 -43.26216 130.4 12.37978 -44.22597 130.4 8.310162 -45 110.4 0 -45 130.4 0 -44.23486 130.4 -8.262195 -44.23486 110.4 8.262195 -44.80353 130.4 4.189214 -45 130.4 0 -45 110.4 0 -44.22597 110.4 -8.310162 -41.95843 130.4 -16.26262 -44.80353 110.4 -4.189214 -41.93266 110.4 -16.3294 -38.25572 130.4 -23.6968 -43.26216 110.4 -12.37978 -38.21961 110.4 -23.75533 -33.26306 130.4 -30.30535 -33.23467 110.4 -30.33682 -30.2992 130.4 -33.2694 -27.09093 110.4 -35.93096 -27.08792 130.4 -35.93297 -20.04465 110.4 -40.28836 -19.99404 130.4 -40.31335 -12.33043 110.4 -43.27685 -12.23404 130.4 -43.30418 -4.200896 110.4 -44.80258 -4.077956 130.4 -44.81395 4.077956 110.4 -44.81395 4.200896 130.4 -44.80258 12.23404 110.4 -43.30418 12.33043 130.4 -43.27685 19.99404 110.4 -40.31335 20.04465 130.4 -40.28836 27.08792 110.4 -35.93297 27.09093 130.4 -35.93096 30.2992 110.4 -33.2694 33.23467 130.4 -30.33682 33.26306 110.4 -30.30535 38.21961 130.4 -23.75533 38.25572 110.4 -23.6968 41.93266 130.4 -16.3294 41.95843 110.4 -16.26262 43.26216 130.4 -12.37978 44.22597 130.4 -8.310162 44.23486 110.4 -8.262195 44.80353 130.4 -4.189214 45 130.4 0 45 110.4 0 45 130.4 0 44.23486 130.4 8.262195 45 110.4 0 44.22597 110.4 8.310162 41.95843 130.4 16.26262 44.80353 110.4 4.189214 41.93266 110.4 16.3294 38.25572 130.4 23.6968 43.26216 110.4 12.37978 38.21961 110.4 23.75533 33.26306 130.4 30.30535 33.23467 110.4 30.33682 30.2992 130.4 33.2694 27.09093 110.4 35.93096 27.08792 130.4 35.93297 20.04465 110.4 40.28836 19.99404 130.4 40.31335 12.33043 110.4 43.27685 12.23404 130.4 43.30418 4.200896 110.4 44.80258 4.077956 130.4 44.81395 -4.077956 110.4 44.81395 -4.200896 130.4 44.80258 -12.23404 110.4 43.30418 -12.33043 130.4 43.27685 -19.99404 110.4 40.31335 -20.04465 130.4 40.28836 -27.08792 110.4 35.93297 -27.09093 130.4 35.93096 -30.2992 110.4 33.2694 -33.23467 130.4 30.33682 -33.26306 110.4 30.30535 -38.21961 130.4 23.75533 -38.25572 110.4 23.6968 -41.93266 130.4 16.3294 -41.95843 110.4 16.26262 -43.26216 130.4 12.37978 -44.22597 130.4 8.310162 -44.23486 110.4 8.262195 -45 110.4 0 -44.80353 110.4 -4.189214 -44.22597 110.4 -8.310162 -43.26216 110.4 -12.37978 -41.95843 110.4 16.26262 -41.93266 110.4 -16.3294 -38.25572 110.4 23.6968 -38.21961 110.4 -23.75533 -33.26306 110.4 30.30535 -33.23467 110.4 -30.33682 -30.2992 110.4 33.2694 -27.09093 110.4 -35.93096 -27.08792 110.4 35.93297 -20.04465 110.4 -40.28836 -19.99404 110.4 40.31335 -12.33043 110.4 -43.27685 -12.23404 110.4 43.30418 -4.200896 110.4 -44.80258 -4.077956 110.4 44.81395 4.077956 110.4 -44.81395 4.200896 110.4 44.80258 12.23404 110.4 -43.30418 12.33043 110.4 43.27685 19.99404 110.4 -40.31335 20.04465 110.4 40.28836 27.08792 110.4 -35.93297 27.09093 110.4 35.93096 30.2992 110.4 -33.2694 33.23467 110.4 30.33682 33.26306 110.4 -30.30535 38.21961 110.4 23.75533 38.25572 110.4 -23.6968 41.93266 110.4 16.3294 41.95843 110.4 -16.26262 43.26216 110.4 12.37978 44.23486 110.4 -8.262195 44.80353 110.4 4.189214 45 110.4 0 44.22597 110.4 8.310162 -67.53401 224.8731 15 -70.40156 223.2175 15 -68.9284 220.6046 15 -69.17012 223.9284 21.48612 -70.40156 223.2175 15 -67.53401 224.8731 27.85184 -67.53401 224.8731 15 -67.45172 217.9924 15 -64.534 219.6769 15 -67.45172 217.9924 15 -66.19934 218.7154 21.19382 -66.81045 225.1727 15 -64.534 219.6769 15 -64.534 219.6769 27.33045 -64.534 219.6769 15 -64.534 219.6769 27.33045 -63.85037 220.2179 29.6858 -63.68617 220.4077 15 -63.39606 220.8463 31.51821 -63.16662 221.3945 15 -63.13394 221.5071 32.92467 -63.03585 222.1698 33.97367 -63.04324 222.5006 15 -63.08317 222.8159 34.70653 -63.25925 223.4155 35.13185 -63.33105 223.5748 15 -63.52895 223.9257 35.26662 -63.88613 224.3694 35.14942 -63.99087 224.4711 15 -64.34738 224.756 34.75216 -64.89223 225.0492 34.05331 -64.93429 225.066 15 -65.49497 225.2262 33.05176 -66.034 225.275 15 -66.1454 225.2729 31.72018 -66.81045 225.1727 15 -66.83155 225.167 30.01048 -67.53401 224.8731 27.85184 -67.53401 224.8731 15 -66.034 225.275 15 -64.93429 225.066 15 -63.99087 224.4711 15 -63.68617 220.4077 15 -63.33105 223.5748 15 -63.16662 221.3945 15 -63.04324 222.5006 15 -58.825 162.4 15 -58.95586 162.3971 15 58.95586 162.3971 15 58.825 162.4 15 -62.17 194.225 15 -62.30086 194.2221 15 110 260.4 -55 73 260.4 -55 73 269.4408 -54.25185 110 251.3592 -54.25185 73 255.819 -54.80755 73 260.4 -55 110 260.4 -55 110 269.4965 -54.24254 73 278.2565 -52.02062 110 264.981 -54.80755 110 278.3314 -51.99485 73 286.5788 -48.37014 110 286.6418 -48.33597 73 294.1535 -43.42462 110 294.1843 -43.40071 73 297.6402 -40.47071 110 300.8708 -37.24397 73 300.8807 -37.23322 73 303.833 -33.74082 110 306.4422 -30.08507 73 306.4852 -30.01914 110 310.7548 -22.12212 73 310.8111 -21.99357 110 313.701 -13.56462 73 313.7468 -13.38335 110 315.2042 -4.636376 73 315.2215 -4.426485 110 315.2215 4.426485 73 315.2042 4.636376 110 313.7468 13.38335 73 313.701 13.56462 110 310.8111 21.99357 73 310.7548 22.12212 110 306.4852 30.01914 73 306.4422 30.08507 110 303.833 33.74082 73 300.8708 37.24397 110 297.6402 40.47071 73 294.1843 43.40071 110 300.8807 37.23322 110 294.1535 43.42462 73 286.6418 48.33597 110 286.5788 48.37014 73 278.3314 51.99485 110 278.2565 52.02062 73 269.4965 54.24254 110 269.4408 54.25185 73 264.981 54.80755 73 260.4 55 110 260.4 55 73 260.4 55 73 251.3592 54.25185 110 260.4 55 110 251.3035 54.24254 73 242.5435 52.02062 110 255.819 54.80755 110 242.4686 51.99485 73 234.2212 48.37014 110 234.1582 48.33597 73 226.6465 43.42462 110 226.6157 43.40071 73 223.1598 40.47071 110 219.9292 37.24397 73 219.9193 37.23322 73 216.967 33.74082 110 214.3578 30.08507 73 214.3148 30.01914 110 210.0452 22.12212 73 209.9889 21.99357 110 207.099 13.56462 73 207.0532 13.38335 110 205.5958 4.636376 73 205.5785 4.426485 110 205.5785 -4.426485 73 205.5958 -4.636376 110 207.0532 -13.38335 73 207.099 -13.56462 110 209.9889 -21.99357 73 210.0452 -22.12212 110 214.3148 -30.01914 73 214.3578 -30.08507 110 216.967 -33.74082 73 219.9292 -37.24397 110 223.1598 -40.47071 73 226.6157 -43.40071 110 219.9193 -37.23322 110 226.6465 -43.42462 73 234.1582 -48.33597 110 234.2212 -48.37014 73 242.4686 -51.99485 110 242.5435 -52.02062 73 251.3035 -54.24254 110 260.4 55 110 260.4 -55 110 264.981 -54.80755 110 255.819 54.80755 110 251.3592 -54.25185 110 269.4408 54.25185 110 269.4965 -54.24254 110 278.2565 52.02062 110 278.3314 -51.99485 110 286.5788 48.37014 110 286.6418 -48.33597 110 294.1535 43.42462 110 294.1843 -43.40071 110 297.6402 40.47071 110 300.8708 -37.24397 110 300.8807 37.23322 110 306.4422 -30.08507 110 306.4852 30.01914 110 310.7548 -22.12212 110 303.833 33.74082 110 310.8111 21.99357 110 313.701 -13.56462 110 313.7468 13.38335 110 315.2042 -4.636376 110 315.2215 4.426485 110 251.3035 54.24254 110 242.5435 -52.02062 110 242.4686 51.99485 110 234.2212 -48.37014 110 234.1582 48.33597 110 226.6465 -43.42462 110 226.6157 43.40071 110 223.1598 -40.47071 110 219.9292 37.24397 110 219.9193 -37.23322 110 214.3578 30.08507 110 214.3148 -30.01914 110 210.0452 22.12212 110 216.967 -33.74082 110 209.9889 -21.99357 110 207.099 13.56462 110 207.0532 -13.38335 110 205.5958 4.636376 110 205.5785 -4.426485 58.01685 318.9302 15 23.27465 335.0685 15 28.40313 334.5252 15 23.93215 334.1484 15 27.74413 333.8801 15 24.88469 333.5363 15 26.92034 333.4657 15 26 333.321 15 -13.03582 338.6318 15 -13.37965 337.6332 15 -18.56493 337.5371 15 -14.04724 336.8162 15 -17.89824 336.77 15 -14.95741 336.2802 15 -17.01372 336.2695 15 -16 336.093 15 -79.08889 257.6344 15 -78.12545 262.5177 15 -78.11267 258.2955 15 -79.09465 263.1682 15 -77.48125 261.5544 15 -77.47212 259.2678 15 -77.25006 260.4119 15 -69.42726 294.6678 15 -69.24109 298.8035 15 -68.77169 295.5941 15 -68.67044 297.8197 15 -68.50691 296.6967 15 -47.29803 321.8679 15 -47.95515 320.9755 15 -51.69094 320.692 15 -48.89626 320.3805 15 -50.88472 320.3034 15 -50 320.17 15 0 269.9 66 0 290.9 66 -2.976411 290.4688 66 2.976411 270.3312 66 2.964506 290.4726 66 -5.684371 271.5729 66 -5.718314 289.2049 66 -2.964506 270.3274 66 -7.932786 273.521 66 -7.976566 287.2278 66 -9.541881 276.0195 66 -9.574053 284.7098 66 -10.38881 278.8774 66 -10.39938 281.8491 66 5.684371 289.2271 66 5.718314 271.5951 66 -7.408469 279.2319 66 -7.408469 281.5682 66 -4.715887 286.2319 66 -4.715887 286.2319 70.15 -4.715887 286.2319 66 -7.408469 281.5682 66 -4.715887 274.5682 66 -3.749989 286.8952 66 -3.749989 286.8952 70.15 -3.749989 286.8952 66 -4.715887 286.2319 66 -4.715887 286.2319 70.15 -7.477081 279.8141 66 -7.477081 280.9859 66 -7.408469 281.5682 70.15 -7.408469 281.5682 66 -7.477081 280.9859 66 -7.408469 281.5682 70.15 -7.5 280.4 66 -7.477081 280.9859 70.15 -7.5 280.4 66 -7.5 280.4 70.15 -7.477081 279.8141 66 -7.477081 279.8141 70.15 -7.408469 279.2319 66 -7.408469 279.2319 70.15 -7.408469 279.2319 66 -4.715887 274.5682 66 -7.408469 279.2319 70.15 -3.749989 273.9048 66 -4.715887 274.5682 70.15 -4.715887 274.5682 66 -3.749989 273.9048 66 -4.715887 274.5682 70.15 -2.692582 287.4 66 -2.692582 273.4 66 -3.749989 273.9048 70.15 -2.692582 273.4 66 2.692582 287.4 66 2.692582 273.4 66 -2.692582 273.4 70.15 -2.692582 273.4 66 2.692582 273.4 66 -2.692582 273.4 70.15 3.749989 286.8952 66 3.749989 273.9048 66 2.692582 273.4 70.15 2.692582 273.4 66 3.749989 273.9048 66 2.692582 273.4 70.15 4.715887 286.2319 66 4.715887 274.5682 66 3.749989 273.9048 70.15 4.715887 274.5682 66 7.408469 281.5682 66 7.408469 279.2319 66 4.715887 274.5682 70.15 4.715887 274.5682 66 7.408469 279.2319 66 4.715887 274.5682 70.15 7.477081 280.9859 66 7.477081 279.8141 66 7.408469 279.2319 70.15 7.408469 279.2319 66 7.477081 279.8141 66 7.408469 279.2319 70.15 7.5 280.4 66 7.477081 279.8141 70.15 7.5 280.4 66 7.5 280.4 70.15 7.477081 280.9859 66 7.477081 280.9859 70.15 7.408469 281.5682 66 7.408469 281.5682 70.15 7.408469 281.5682 66 4.715887 286.2319 66 7.408469 281.5682 70.15 4.715887 286.2319 70.15 4.715887 286.2319 66 3.749989 286.8952 66 4.715887 286.2319 70.15 3.749989 286.8952 70.15 2.692582 287.4 66 2.692582 287.4 70.15 2.692582 287.4 66 -2.692582 287.4 66 2.692582 287.4 70.15 -2.692582 287.4 70.15 -2.692582 287.4 66 -2.692582 287.4 70.15 -5.40263 283.01 70.15 -4.715887 286.2319 70.15 -7.408469 281.5682 70.15 -3.737038 285.0941 70.15 -3.749989 286.8952 70.15 -7.408469 279.2319 70.15 -4.715887 274.5682 70.15 -6 280.4 70.15 -7.477081 280.9859 70.15 -5.848591 281.7391 70.15 -2.692582 287.4 70.15 1.33716 286.249 70.15 2.692582 287.4 70.15 -1.332669 286.2501 70.15 3.740951 285.091 70.15 3.749989 286.8952 70.15 5.405448 283.0041 70.15 4.715887 286.2319 70.15 7.408469 279.2319 70.15 7.408469 281.5682 70.15 6 280.4 70.15 7.477081 279.8141 70.15 7.477081 280.9859 70.15 5.40263 277.7901 70.15 4.715887 274.5682 70.15 5.848591 279.061 70.15 7.5 280.4 70.15 3.737038 275.706 70.15 3.749989 273.9048 70.15 2.692582 273.4 70.15 -1.33716 274.551 70.15 -2.692582 273.4 70.15 1.332669 274.5499 70.15 -3.740951 275.7091 70.15 -3.749989 273.9048 70.15 -5.405448 277.7959 70.15 -7.477081 279.8141 70.15 -7.5 280.4 70.15 6 280.4 73.5 6 280.4 70.15 5.405448 283.0041 70.15 5.405448 277.7959 73.5 5.848591 279.061 70.15 6 280.4 70.15 6 280.4 73.5 5.40263 283.01 73.5 3.740951 285.091 70.15 5.848591 281.7391 73.5 3.737038 285.0941 73.5 1.33716 286.249 70.15 1.332669 286.2501 73.5 -1.332669 286.2501 70.15 -1.33716 286.249 73.5 -3.737038 285.0941 70.15 -3.740951 285.091 73.5 -5.40263 283.01 70.15 -5.405448 283.0041 73.5 -5.848591 281.7391 70.15 -6 280.4 70.15 -6 280.4 73.5 -6 280.4 70.15 -5.405448 277.7959 70.15 -6 280.4 73.5 -5.40263 277.7901 73.5 -3.740951 275.7091 70.15 -5.848591 279.061 73.5 -3.737038 275.706 73.5 -1.33716 274.551 70.15 -1.332669 274.5499 73.5 1.332669 274.5499 70.15 1.33716 274.551 73.5 3.737038 275.706 70.15 3.740951 275.7091 73.5 5.40263 277.7901 70.15 5.405448 277.7959 73.5 6 280.4 73.5 5.848591 281.7391 73.5 5.40263 283.01 73.5 4.85 280.4 73.5 3.737038 285.0941 73.5 3.428239 283.8307 73.5 1.332669 286.2501 73.5 4.201514 282.8229 73.5 1.24319 285.0879 73.5 -1.33716 286.249 73.5 2.416737 284.6049 73.5 -2.429053 284.5978 73.5 -3.740951 285.091 73.5 -0.01238989 285.25 73.5 -4.199618 282.8263 73.5 -5.405448 283.0041 73.5 -5.848591 279.061 73.5 -6 280.4 73.5 -5.40263 277.7901 73.5 -4.85 280.4 73.5 -3.737038 275.706 73.5 -3.428239 276.9693 73.5 -1.332669 274.5499 73.5 -4.201514 277.9771 73.5 -1.24319 275.7121 73.5 1.33716 274.551 73.5 -2.416737 276.1951 73.5 2.429053 276.2022 73.5 3.740951 275.7091 73.5 0.01238989 275.55 73.5 4.199618 277.9738 73.5 4.85 280.4 77 4.85 280.4 73.5 4.201514 282.8229 73.5 4.201514 277.9771 77 4.199618 277.9738 73.5 4.85 280.4 73.5 4.85 280.4 77 4.199618 282.8263 77 3.428239 283.8307 73.5 2.429053 284.5978 77 2.416737 284.6049 73.5 1.24319 285.0879 73.5 0.01238989 285.25 77 -0.01238989 285.25 73.5 -1.24319 285.0879 77 -2.429053 284.5978 73.5 -3.428239 283.8307 77 -4.199618 282.8263 73.5 -2.416737 284.6049 77 -4.201514 282.8229 77 -4.85 280.4 73.5 -4.85 280.4 77 -4.85 280.4 73.5 -4.201514 277.9771 73.5 -4.85 280.4 77 -4.199618 277.9738 77 -3.428239 276.9693 73.5 -2.429053 276.2022 77 -2.416737 276.1951 73.5 -1.24319 275.7121 73.5 -0.01238989 275.55 77 0.01238989 275.55 73.5 1.24319 275.7121 77 2.429053 276.2022 73.5 3.428239 276.9693 77 2.416737 276.1951 77 4.201514 277.9771 77 4.85 280.4 77 4.199618 282.8263 77 3.428239 276.9693 77 2.429053 284.5978 77 2.416737 276.1951 77 0.01238989 285.25 77 -0.01238989 275.55 77 -1.24319 285.0879 77 1.24319 275.7121 77 -2.416737 284.6049 77 -2.429053 276.2022 77 -3.428239 283.8307 77 -4.199618 277.9738 77 -4.201514 282.8229 77 -4.85 280.4 77 + + + + + + + + + + 0.2507784 -0.9598676 -0.125557 0.2466572 -0.9677374 -0.05142503 0.258315 -0.9641034 -0.06146574 0.2683825 -0.9523704 0.1447812 0.267103 -0.9611681 0.06936985 0.2580719 -0.9631612 0.07562702 0.9931222 -0.08752876 -0.07776266 0.9887596 -0.08606398 -0.1222597 0.9947177 -0.08530157 -0.05710172 0.9954324 -0.08707016 -0.0391556 0.9897111 -0.08615601 0.1142338 0.9955331 -0.08496516 0.04117023 0.9946442 -0.0870096 0.05578869 0.2661256 -0.9576251 0.110143 0.2442142 -0.9674572 -0.06622654 1 2.32011e-5 0 0.2631071 -0.9501275 -0.167429 1 -5.86874e-6 0 0.2560229 -0.932535 -0.2546191 0.2688121 -0.9154505 -0.2994838 1 -1.49105e-6 0 1 -5.90581e-6 0 0.2548357 -0.8882628 -0.382162 0.2677744 -0.8575861 -0.439139 1 0 0 0.2551705 -0.826214 -0.5022534 0.2656996 -0.7793671 -0.5674422 1 1.11856e-5 0 0.2613697 -0.7134561 -0.650128 0.2658523 -0.6820116 -0.6813097 1 2.46506e-6 0 0.2607275 -0.7604223 -0.5947933 1 -2.88767e-6 0 0.2612432 -0.6045521 -0.7525084 0.2659756 -0.5671399 -0.7794932 0.2608498 -0.6572365 -0.7071053 1 -2.84517e-6 0 0.2611222 -0.4811656 -0.8368363 0.2660983 -0.4384717 -0.8584488 0.2606034 -0.540495 -0.7999693 0.2610283 -0.3462371 -0.9011017 0.2662211 -0.2991516 -0.9163158 0.2603916 -0.4108217 -0.8737401 1 -2.79796e-6 0 0.260937 -0.2030121 -0.943768 0.2663106 -0.152535 -0.9517415 1 -1.28393e-6 0 0.2602056 -0.2713146 -0.9266507 1 2.74761e-6 0 0.2608737 -0.05490309 -0.9638106 0.2664595 -0.002044737 -0.9638441 0.2600567 -0.1253131 -0.9574275 0.2608193 0.0944882 -0.9607525 0.2665843 0.1485975 -0.9522876 1 -1.63e-7 0 0.2598712 0.02365237 -0.9653536 0.2607593 0.2416845 -0.9346622 0.2667383 0.2958842 -0.9172258 0.2596863 0.1720662 -0.9502401 0.2606944 0.3831066 -0.8861534 0.2635976 0.4216889 -0.8675799 1 1.2627e-6 0 0.2595074 0.3163957 -0.9124417 1 -1.37625e-6 0 0.2575496 0.4522606 -0.8538903 0.2602391 0.5034485 -0.8239024 0.2576418 0.5169011 -0.816354 0.2601492 0.5669324 -0.7816073 0.2577634 0.578518 -0.7738701 0.2600547 0.6268658 -0.7344462 0.2578606 0.6365789 -0.7268255 0.2599303 0.6830154 -0.6825881 1 -1.25322e-6 0 1 2.73983e-6 0 0.2579791 0.6908946 -0.6753603 0.2598152 0.7347035 -0.6266634 1 2.49835e-6 0 1 -2.75795e-6 0 0.2581258 0.7409902 -0.6199231 0.2633203 0.7902355 -0.5533449 1 -2.49388e-6 0 1 2.7714e-6 0 0.2603631 0.8268991 -0.4984467 0.267075 0.8588458 -0.4370985 0.2589269 0.7868828 -0.5601539 0.2603935 0.8939201 -0.3648317 0.2671356 0.9165866 -0.2975023 1 -1.73613e-6 0 0.2588963 0.8637914 -0.4322467 1 1.46443e-6 0 1 5.67752e-6 0 0.26039 0.9395343 -0.2224241 0.2644535 0.9530091 -0.1477765 1 2.95281e-6 0 0.2588315 0.9200862 -0.2940198 1 2.98206e-6 0 0.2715299 0.9612044 -0.04855614 0.2580719 0.9631612 -0.07562702 1 -2.32011e-5 0 0.269633 0.9605162 -0.06860607 0.2588033 0.9543982 -0.1488119 0.2587687 0.9630506 0.07464891 0.2588599 0.9651553 0.03830099 0.2586185 0.965257 0.0373553 0.2590763 0.9628459 0.07620608 0.5636213 0.824435 -0.05136311 0.5948505 0.8032358 -0.03106856 0.5939663 0.8021688 -0.06106907 0.5374981 0.8361252 0.1095016 0.5863862 0.8089895 0.04107815 0.5507431 0.8315165 0.07254326 0.5871087 0.8075834 0.05579012 0.5366798 0.8364697 -0.1108762 0.5936374 0.7946397 -0.1270532 0.593295 0.7841016 -0.1821696 0.537626 0.8141299 -0.219433 0.5891708 0.7677683 -0.2518129 0.5917427 0.7482467 -0.2999457 0.5379842 0.778777 -0.3226135 0.594031 0.719405 -0.3599772 0.5372928 0.7294731 -0.4233031 0.5944572 0.6878772 -0.416468 0.5936 0.6568054 -0.4650223 0.5380517 0.6671171 -0.5152235 0.5909401 0.6155079 -0.5214787 0.592377 0.5790707 -0.5601488 0.538275 0.5946753 -0.5971779 0.5940492 0.5297459 -0.6053717 0.5378125 0.5106503 -0.670816 0.5949441 0.4803439 -0.6444464 0.5938117 0.4320295 -0.6787771 0.5383591 0.4178082 -0.731851 0.5923768 0.3734629 -0.7138735 0.5928645 0.3242046 -0.7371588 0.5384839 0.3191411 -0.7798616 0.5939875 0.2613631 -0.7608339 0.5382124 0.2135758 -0.8152993 0.5951238 0.2024336 -0.77772 0.5939562 0.1431635 -0.7916567 0.5385407 0.1044365 -0.8361023 0.5935155 0.07721465 -0.80111 0.5932596 0.02142435 -0.8047261 0.5393625 -0.006317377 -0.84205 0.5889271 -0.05029547 -0.8066198 0.5916705 -0.101628 -0.7997486 0.5395492 -0.1150269 -0.8340597 0.5940239 -0.1669395 -0.7869352 0.5386641 -0.2249571 -0.8119331 0.5943622 -0.2297793 -0.7706719 0.593576 -0.2843818 -0.7528578 0.5392755 -0.3296082 -0.7749454 0.5907384 -0.3496637 -0.7271613 0.5922937 -0.3960833 -0.7016454 0.539345 -0.4272154 -0.725668 0.5940485 -0.4522276 -0.6652793 0.5410904 -0.5154841 -0.6644526 0.5948833 -0.5026843 -0.6272338 0.5939762 -0.5477387 -0.5892152 0.5802332 -0.5466925 -0.6037026 0.610422 -0.5774303 -0.5421802 0.6110334 -0.5361688 -0.5823755 0.621589 -0.5975397 -0.5065308 0.8071141 -0.08530151 -0.5842009 0.8041126 -0.08642953 -0.5881606 0.8686337 -0.08649098 -0.4878473 0.7580117 -0.08752977 -0.646341 0.7401229 -0.08609485 -0.6669377 0.8882952 -0.08670532 -0.4510144 0.9257644 -0.0855143 -0.3683037 0.8490619 -0.08536088 -0.5213516 0.9475458 -0.08758878 -0.3073847 0.9657109 -0.08578872 -0.2450366 0.9202075 -0.08673483 -0.3817005 0.9691027 -0.08591115 -0.2312125 0.9838479 -0.08606415 -0.1569603 0.704475 -0.08792585 -0.7042614 0.6858261 -0.0867964 -0.7225711 0.6462125 -0.0872237 -0.7581567 0.6398062 -0.0867663 -0.7636228 0.5357011 -0.5601164 -0.6318972 0.5851143 -0.08713233 -0.8062564 0.58017 -0.08679658 -0.8098576 0.4790979 -0.5414801 -0.6908435 0.5192264 -0.08777374 -0.8501176 0.5231986 -0.08713364 -0.8477447 0.4383427 -0.5375596 -0.7203372 0.449065 -0.08579051 -0.8893709 0.3495391 -0.5281387 -0.7738812 0.4691709 -0.3450495 -0.8129081 0.423177 -0.5045407 -0.7525689 0.379846 -0.0869196 -0.9209572 0.3272901 -0.084966 -0.9410963 0.1685249 -0.7784435 -0.6046694 0.1739004 -0.7885645 -0.5898516 0.133612 -0.7587931 -0.6374802 0.4502258 -0.08695048 -0.8886711 0.2310308 -0.08667469 -0.9690781 0.1848264 -0.08524113 -0.9790675 0.1227785 -0.7479631 -0.6522856 0.05459916 -0.7284671 -0.6829016 0.3050118 -0.08670586 -0.9483934 0.07678544 -0.08639883 -0.9932972 0.03854519 -0.08560514 -0.9955832 0.05447655 -0.7361204 -0.6746549 -0.04077321 -0.7035217 -0.7095034 0.1525045 -0.08639985 -0.984519 -0.07910501 -0.0860328 -0.9931469 -0.1080086 -0.08603459 -0.9904204 -0.04144471 -0.7077952 -0.705201 -0.1428906 -0.6773116 -0.7216864 -0.003418087 -0.08600223 -0.9962891 0.02182096 -0.7479566 -0.6633889 -0.2329248 -0.08560717 -0.9687196 -0.2330119 -0.08661264 -0.9686093 -0.1417009 -0.6796334 -0.7197357 -0.2316116 -0.6526877 -0.7213563 -0.1591279 -0.0855152 -0.9835473 -0.07605355 -0.7081041 -0.7020003 -0.3092501 -0.08749824 -0.9469469 -0.3194755 -0.08697986 -0.9435942 -0.2381429 -0.6485679 -0.7229437 -0.2949349 -0.632871 -0.7158825 -0.1803987 -0.6744429 -0.715949 -0.3823707 -0.08737546 -0.9198686 -0.3875029 -0.08710193 -0.9177444 -0.2875839 -0.6357182 -0.7163504 -0.3439503 -0.6200566 -0.7051439 -0.4530813 -0.08734464 -0.8871799 -0.4532356 -0.08713132 -0.8871222 -0.3397961 -0.6217285 -0.7056857 -0.3958343 -0.6068748 -0.6892157 -0.5165991 -0.08704084 -0.8517919 -0.4370722 -0.5950114 -0.6744846 -0.4456664 -0.5938965 -0.6698273 -0.387777 -0.6087055 -0.6921755 -0.5211074 -0.08743613 -0.8490006 -0.5773326 -0.08688825 -0.811873 -0.483124 -0.5827092 -0.653484 -0.4952386 -0.5808761 -0.6460046 -0.5860037 -0.08759075 -0.8055604 -0.6350417 -0.08679634 -0.7675862 -0.5282921 -0.570348 -0.6289759 -0.5433064 -0.5681188 -0.6181095 -0.6473191 -0.0876826 -0.757159 -0.6893309 -0.08670425 -0.7192394 -0.5712385 -0.558878 -0.6011174 -0.5896652 -0.5558803 -0.5859113 -0.7047896 -0.08777439 -0.7039655 -0.7399446 -0.08664476 -0.6670642 -0.6119088 -0.5478491 -0.5704638 -0.6340676 -0.5439442 -0.5496209 -0.7577809 -0.08783298 -0.6465706 -0.7865732 -0.08661365 -0.6113926 -0.6507325 -0.5375974 -0.5362241 -0.6761894 -0.5324733 -0.5091564 -0.8058664 -0.08783501 -0.5855464 -0.8290524 -0.08658277 -0.5524269 -0.6865316 -0.5280143 -0.4998756 -0.7150483 -0.5218885 -0.4651217 -0.8492332 -0.08783483 -0.5206612 -0.867164 -0.08658212 -0.4904387 -0.7201334 -0.519469 -0.4599564 -0.752064 -0.5109592 -0.4163179 -0.8873462 -0.08783429 -0.452661 -0.9006589 -0.08661413 -0.4258071 -0.7496727 -0.5118063 -0.4195774 -0.7834342 -0.5024111 -0.3658061 -0.9199294 -0.0878027 -0.3821264 -0.9293856 -0.08667588 -0.3587895 -0.775774 -0.505982 -0.3770373 -0.811081 -0.4959082 -0.3101982 -0.9470732 -0.0877428 -0.3087937 -0.9531739 -0.08673536 -0.2897182 -0.8141974 -0.4943537 -0.3044618 -0.8349173 -0.4894995 -0.2516013 -0.7931343 -0.5013703 -0.3457831 -0.9684275 -0.08765041 -0.2333784 -0.9718674 -0.0868256 -0.218941 -0.8379301 -0.4885484 -0.2432976 -0.8533914 -0.4847441 -0.1916941 -0.8286007 -0.4908124 -0.2693029 -0.983797 -0.08752727 -0.1564688 -0.9853423 -0.08694911 -0.1467667 -0.8583506 -0.4827822 -0.1736539 -0.8670312 -0.4813856 -0.1285485 -0.8483214 -0.4856576 -0.2109206 -0.993068 -0.08740729 -0.07858723 -0.9934789 -0.08707016 -0.07361137 -0.8697406 -0.4802221 -0.1137456 -0.875397 -0.4790513 -0.06473004 -0.8671795 -0.4802845 -0.1316304 -0.8638114 -0.4814687 -0.1483836 -0.9954007 -0.08725321 -0.03955233 -0.9955199 -0.0870698 -0.03686654 -0.8766078 -0.4784827 -0.05111992 -0.8784967 -0.4777483 4.27269e-4 -0.8752343 -0.4781774 -0.0728802 -0.8723049 -0.4797341 -0.094549 -0.9931269 -0.08728504 0.07797664 -0.995503 -0.08722358 0.03695863 -0.9954324 -0.08707016 0.0391556 -0.87844 -0.4775371 -0.01736551 -0.8779799 -0.4786956 0.001342833 -0.8757561 -0.4784231 0.06451815 -0.8773308 -0.4786607 -0.03427284 -0.9934705 -0.08716362 0.07361298 0 -1 1.98318e-6 0 -1 1.34999e-6 0 -1 0 0 -1 1.08366e-6 0 -1 -2.08568e-7 0 -1 5.32651e-7 0 -1 -1.34993e-6 0 -1 2.1061e-6 0 -1 -1.96617e-6 0 -1 4.48956e-7 0 -1 1.79267e-6 0 -1 1.80369e-6 0 -1 3.11534e-6 0 -1 3.2954e-6 0 -1 -3.13845e-6 0 -1 3.57465e-6 0 -1 -1.74101e-6 0 -1 -1.74374e-6 0 -1 1.74613e-6 0 -1 -3.29909e-6 0 -1 1.74744e-6 0 -1 -1.74737e-6 0 -1 1.49157e-6 0 -1 1.06197e-6 0 -1 1.16548e-6 0 -1 -6.76612e-7 0 -1 2.08568e-7 0 -1 -1.72795e-6 0 -1 -1.08367e-6 0 -1 -1.34999e-6 0 -1 -1.98318e-6 0.993233 -0.08642911 0.07757866 0.5097994 0.8583942 -0.05713266 0.4306564 0.8950061 0.1161866 0.522923 0.8450574 0.1114881 0.4226933 0.898063 -0.1217112 0.4514384 0.8902724 -0.06015312 0.4229948 0.8732737 -0.2418028 0.4230842 0.8326485 -0.3573464 0.4231497 0.7768376 -0.4663345 0.4232137 0.7068618 -0.5667774 0.4232712 0.6240267 -0.6568349 0.4232736 0.5298169 -0.7349379 0.4232984 0.425984 -0.7995975 0.423301 0.3144086 -0.8496845 0.4232977 0.1971218 -0.8842863 0.4232704 0.07626736 -0.9027876 0.423247 -0.04596263 -0.9048477 0.4232138 -0.1673689 -0.8904368 0.4231823 -0.2856923 -0.8598237 0.4231227 -0.3988596 -0.813559 -0.9930505 -0.1155136 -0.0225228 0 0 -1 -0.9987967 0 -0.04904407 -0.9921168 -0.1231753 0.02307248 -0.9987978 8.24015e-4 0.04901361 -0.9893726 -0.05554497 0.1343762 -0.9932499 -0.1149661 -0.01541221 -0.9931061 -0.113102 -0.03079324 -0.9928202 -0.1101133 -0.04672485 -0.9923942 -0.1059628 -0.06265598 -0.9916169 -0.100773 -0.0808748 -0.9908885 -0.09460866 -0.09585994 -0.9907274 -0.08270555 -0.1077919 -0.9907252 -0.06793439 -0.1176797 -0.990724 -0.05197465 -0.1255572 -0.9907239 -0.03515845 -0.1312643 -0.9907218 -0.01773178 -0.1347433 -0.9907181 0 -0.135933 -0.9907178 0.01773166 -0.1347733 -0.9907147 0.03518861 -0.1313242 -0.9907134 0.05203515 -0.1256169 -0.9907099 0.06799644 -0.1177731 -0.9907096 0.08279818 -0.1078848 -0.9907062 0.09619569 -0.09616518 -0.9907063 0.107915 -0.08279788 -0.9907007 0.117833 -0.06802636 -0.9907004 0.1257068 -0.05206501 -0.9906949 0.1314741 -0.0351879 -0.9906929 0.1349571 -0.01773178 -0.9906485 0.1361455 -0.008942067 -0.9906923 0.134957 0.0177623 -0.9906529 0.1361156 0.00891155 -0.9930902 -0.1132257 0.03085476 -0.9927974 -0.1102667 0.04684734 -0.9923567 -0.1062062 0.06283867 -0.9914649 -0.1012309 0.08215665 -0.9907329 -0.09601223 0.09607326 -0.9907235 -0.08270776 0.1078253 -0.9907155 -0.06796634 0.1177432 -0.9907111 -0.05200451 0.1256471 -0.9917491 -0.04025471 0.1217102 -0.9935972 -0.01483207 0.1120036 -0.9936284 -6.10374e-5 0.1127056 -0.9936064 0.01489323 0.1119131 -0.9919708 0.04010242 0.1199411 -0.9906966 0.05206477 0.1257368 -0.9906972 0.06802612 0.1178631 -0.9906973 0.08282768 0.1079751 -0.9906974 0.09622538 0.09622538 -0.9906948 0.1079748 0.08285796 -0.9906972 0.1178631 0.06802612 -0.9906966 0.1257368 0.05206477 -0.9906933 0.131478 0.03521949 -0.9903845 -0.1380391 0.009155809 -0.9870103 -0.160285 -0.01092571 -0.98697 -0.1592202 0.0232253 -0.9870246 -0.1601653 0.01138365 -0.9865896 -0.1570816 -0.04434418 -0.9869563 -0.1594011 -0.02255356 -0.9858418 -0.1531775 -0.06821113 -0.98461 -0.1454849 -0.09683734 -0.9828342 -0.1352908 -0.1254331 -0.9786331 -0.1071534 -0.1754862 -0.9810231 -0.1163103 -0.1551313 -0.9694608 -0.1520142 -0.1924517 -0.975041 -0.142278 -0.1704468 -0.9655054 -0.1317514 -0.2245908 -0.9636509 -0.1090154 -0.2439112 -0.9636539 -0.07577997 -0.2561808 -0.9636525 -0.04120129 -0.2639629 -0.9636494 -0.00589019 -0.2671056 -0.9636545 0.02948182 -0.26552 -0.9636515 0.0643655 -0.2592933 -0.9636523 0.09812009 -0.2484895 -0.9636615 0.1301321 -0.2332857 -0.9636539 0.1598867 -0.2140266 -0.9636595 0.1868051 -0.1909557 -0.9636605 0.2104269 -0.1645572 -0.9636604 0.2303556 -0.1352591 -0.9636617 0.2462257 -0.1035808 -0.9636642 0.2577624 -0.07007133 -0.9636687 0.2647525 -0.03534102 -0.9635136 0.2670713 -0.01773148 -0.9635341 0.2670159 0.01745718 -0.9194195 0.3898209 -0.05203509 -0.9190761 0.3932052 -0.02624619 -0.9637101 0.2646945 0.03463947 -0.9192348 0.3929331 0.02472043 -0.8772169 -0.4797943 0.01696872 -0.9580782 -0.1727672 -0.2285556 -0.9484505 -0.1403891 -0.2841353 -0.9223316 -0.1517127 -0.3553698 -0.9385048 -0.07303309 -0.337454 -0.933336 -0.1553424 -0.3236553 -0.9197699 -0.1122512 -0.3760628 -0.9197571 -0.06140458 -0.3876549 -0.9197261 -0.009491443 -0.3924462 -0.9197139 0.04257369 -0.3902742 -0.9196899 0.09393745 -0.3812432 -0.9196673 0.1436846 -0.3654681 -0.9196447 0.190869 -0.343253 -0.9196249 0.2347205 -0.3149546 -0.9196011 0.2744276 -0.2811113 -0.9195606 0.3093381 -0.2423189 -0.9195431 0.3387629 -0.1991987 -0.9195062 0.3622602 -0.1525643 -0.9194747 0.3793504 -0.1032456 -0.8588618 0.5075591 -0.06885051 -0.8583407 0.5119221 -0.03445565 -0.9195793 0.3898545 0.0488615 -0.8586038 0.5117197 0.03070253 -0.8994517 -0.1668466 -0.403917 -0.8604663 -0.1572974 -0.4846189 -0.8746832 -0.05658274 -0.4813809 -0.8679129 -0.1726182 -0.4657577 -0.8592286 -0.0941202 -0.5028596 -0.8592101 -0.02554464 -0.5109848 -0.859201 0.04345899 -0.5097892 -0.8591664 0.1117295 -0.4993492 -0.8591454 0.1779573 -0.479792 -0.8591139 0.2409791 -0.4515002 -0.8590888 0.2996083 -0.4149714 -0.8590597 0.3528041 -0.3708716 -0.8590205 0.3995863 -0.3200231 -0.8589828 0.4391048 -0.2633164 -0.8589392 0.4706404 -0.2017945 -0.8588885 0.4936098 -0.1366018 -0.7828807 0.6167643 -0.08185267 -0.7822293 0.621639 -0.04101735 -0.8590562 0.5082983 0.06045866 -0.7818346 0.6221594 0.0406512 -0.8110727 -0.1475288 -0.5660357 -0.7838499 -0.1677324 -0.5978671 -0.7912462 -0.1957514 -0.5793194 -0.7827607 -0.0909782 -0.6156367 -0.7827595 -0.009064197 -0.6222584 -0.7827521 0.07297098 -0.6180409 -0.7827595 0.1537563 -0.6030312 -0.7827613 0.2318558 -0.5775185 -0.7827624 0.3059267 -0.5419335 -0.7827698 0.3746601 -0.4968916 -0.7827788 0.4368472 -0.4431952 -0.7827895 0.4914218 -0.3817659 -0.7828143 0.5374104 -0.313675 -0.7828371 0.5740277 -0.2401217 -0.782862 0.6006286 -0.1623955 -0.6929344 0.7148471 -0.09399855 -0.6922042 0.7201598 -0.04715204 -0.7823859 0.6174 0.08179098 -0.6922324 0.7201268 0.04724341 -0.7267262 -0.1809491 -0.6626662 -0.6934282 -0.183085 -0.6968768 -0.6998541 -0.219063 -0.6798644 -0.6924842 -0.0935418 -0.7153431 -0.6925082 5.49343e-4 -0.7214097 -0.6925482 0.09467142 -0.7151325 -0.6925812 0.1871461 -0.6966403 -0.6926231 0.2764388 -0.6662244 -0.6926658 0.3609821 -0.6244246 -0.6927049 0.4393306 -0.5719691 -0.6927292 0.5101927 -0.5097349 -0.6927614 0.572301 -0.4388089 -0.6928185 0.6246079 -0.3603718 -0.6928486 0.6662663 -0.2757722 -0.6929016 0.6965028 -0.1864706 -0.5907327 0.800004 -0.1050171 -0.589841 0.8057936 -0.05276733 -0.6959007 0.7126253 0.08881109 -0.5916129 0.804911 0.04596173 -0.6283879 -0.2106121 -0.7488467 -0.5911265 -0.2055468 -0.7799488 -0.589058 -0.2395175 -0.7717786 -0.5911012 -0.1024233 -0.800068 -0.5910639 0.00262463 -0.8066205 -0.5910385 0.1076724 -0.7994249 -0.5910083 0.2108891 -0.7786111 -0.5909983 0.3105297 -0.7445083 -0.5909753 0.4048687 -0.6977317 -0.590937 0.4923304 -0.6390652 -0.5909113 0.5714095 -0.5694868 -0.5908854 0.6407235 -0.4902325 -0.5908426 0.6991536 -0.4026031 -0.5908147 0.7456675 -0.308088 -0.5907697 0.779473 -0.2083579 -0.4779342 0.8708719 -0.1147225 -0.4770743 0.876966 -0.0577116 -0.5917118 0.8015028 0.08643114 -0.4756647 0.8778402 0.05603235 -0.4774395 -0.2284043 -0.8484593 -0.5409625 -0.2478203 -0.8037069 -0.4785948 -0.1178634 -0.8700892 -0.4785377 -0.002990841 -0.8780619 -0.4785098 0.1118832 -0.8709251 -0.4784515 0.2248664 -0.8488341 -0.4784181 0.333971 -0.812145 -0.4783632 0.4373754 -0.7614929 -0.4783293 0.5332641 -0.6977326 -0.4782673 0.6199681 -0.6220129 -0.4782118 0.6960303 -0.5355888 -0.4781492 0.7601495 -0.4399388 -0.4780859 0.8112049 -0.3367202 -0.478022 0.8483114 -0.2277342 -0.3566129 0.9261253 -0.1229605 -0.3558532 0.932482 -0.06201487 -0.4754518 0.8723179 0.1140486 -0.3559406 0.932471 0.06167846 -0.4664908 -0.2809932 -0.8387069 -0.3560363 -0.2580088 -0.8981479 -0.4229702 -0.2826719 -0.8609256 -0.3572019 -0.1394748 -0.9235548 -0.3571698 -0.01632791 -0.9338968 -0.3571593 0.1070592 -0.9278877 -0.3571332 0.2285872 -0.905651 -0.3570751 0.3461492 -0.8675704 -0.35705 0.4576429 -0.8142962 -0.3570149 0.561128 -0.746777 -0.356954 0.6547922 -0.6662064 -0.3569245 0.7370133 -0.5739481 -0.3568569 0.8063385 -0.4716688 -0.3567992 0.8615552 -0.3611329 -0.3567357 0.9017122 -0.244243 -0.2289533 0.9647656 -0.1296446 -0.2285601 0.9713119 -0.06567782 -0.3599476 0.9250476 0.1213457 -0.2340214 0.9709998 0.0489223 -0.3440195 -0.3147205 -0.8846478 -0.2282561 -0.2917369 -0.9288643 -0.2980501 -0.3199323 -0.8993384 -0.2294445 -0.1670019 -0.9588877 -0.2294415 -0.03726363 -0.9726089 -0.2294134 0.09311431 -0.968865 -0.2294123 0.2218436 -0.9477107 -0.2293844 0.3465792 -0.9095415 -0.2293516 0.4651123 -0.8550254 -0.2293217 0.5752575 -0.785169 -0.2292947 0.6750965 -0.7011908 -0.2292583 0.7627906 -0.6046414 -0.2291988 0.8368048 -0.4972181 -0.2291409 0.89578 -0.3808842 -0.2290764 0.9386763 -0.2577034 -0.09827184 0.9859538 -0.1350475 -0.1314451 0.9889972 -0.06787413 -0.2331628 0.9688463 0.08349913 -0.1101742 0.9858916 0.1260136 -0.215619 -0.351308 -0.9110935 -0.09729415 -0.3294206 -0.9391571 -0.1687399 -0.3589348 -0.917983 -0.09863889 -0.2005739 -0.9747002 -0.09881991 -0.06622582 -0.9928992 -0.0989741 0.06933987 -0.9926712 -0.09906572 0.2036249 -0.9740241 -0.09915804 0.3341587 -0.9372864 -0.09918713 0.4585193 -0.8831319 -0.09918653 0.5743666 -0.8125671 -0.09915697 0.6795721 -0.7268769 -0.09909743 0.7721481 -0.6276679 -0.09894168 0.8504042 -0.516743 -0.09875929 0.9128521 -0.3961664 -0.09848451 0.9583246 -0.2681697 -0.06543356 0.9955728 -0.06747835 -0.08188331 0.9935868 0.07797682 -0.0840494 -0.3902775 -0.9168529 0.03671443 -0.3777346 -0.9251857 -0.03903353 -0.3996438 -0.9158391 0.03573805 -0.2553852 -0.9661787 0.03589075 -0.1271132 -0.9912388 0.03601241 0.003296017 -0.9993459 0.03610378 0.1336726 -0.9903677 0.03619551 0.2617311 -0.9644619 0.03628724 0.3853045 -0.9220758 0.03631788 0.5022857 -0.8639388 0.0363484 0.6106595 -0.7910587 0.03637856 0.7085588 -0.7047134 0.03634792 0.7943447 -0.606379 0.03628748 0.8665668 -0.4977403 0.03622597 0.9239916 -0.3806933 0.03607368 0.9656887 -0.2571853 0.03613454 0.9909537 -0.1292482 0.001434326 0.997842 -0.06564587 -0.08893358 0.9890428 0.1178355 0.0187999 0.9930994 0.1157599 0.06894338 0.9954523 -0.06573885 0.05212658 0.9951971 0.08285933 0.04934942 -0.4330053 -0.9000395 0.1695061 -0.420805 -0.8911739 0.09058231 -0.4382927 -0.8942564 0.1686487 -0.2992095 -0.9391652 0.1686477 -0.1709061 -0.9707466 0.1686486 -0.03955274 -0.9848824 0.168651 0.09250473 -0.9813255 0.1686488 0.2229424 -0.9601325 0.1686468 0.3494096 -0.9216676 0.168649 0.4695986 -0.8666226 0.1686497 0.5813624 -0.7959743 0.1686503 0.6826888 -0.7109803 0.1686171 0.7717323 -0.6131864 0.1686183 0.8469066 -0.5042986 0.1686177 0.9068126 -0.3863407 0.1685888 0.9504026 -0.2613676 0.1683717 0.976904 -0.1315661 0.1345904 0.9886447 -0.06683743 0.0372945 0.9903193 0.1337049 0.1506413 0.9818847 0.1149342 0.200388 0.9775251 -0.06549388 0.1839722 0.9794661 0.08246397 0.1686466 -0.4795107 -0.8611782 0.2168071 -0.488457 -0.8452246 0.299883 -0.471249 -0.8294544 0.2845601 -0.5224565 -0.8037816 0.2983521 -0.3621975 -0.8830623 0.2983259 -0.2438795 -0.9227808 0.2982627 -0.1214047 -0.9467314 0.2982336 0.003112912 -0.9544879 0.2982021 0.1275698 -0.9459394 0.2982023 0.24986 -0.9212196 0.2981727 0.367848 -0.8807843 0.2981457 0.479554 -0.8253103 0.2981456 0.5830457 -0.7557559 0.2981479 0.6765629 -0.6733279 0.2981706 0.7585191 -0.5794336 0.2981721 0.827527 -0.4757021 0.2982 0.8824232 -0.3638767 0.2982298 0.9222782 -0.24589 0.298536 0.9463609 -0.1236016 0.2649653 0.9621703 -0.06341832 0.1631872 0.9781165 0.1290665 0.2801626 0.9531938 0.113713 0.3296411 0.9420453 -0.06235128 0.3084262 0.9489614 0.06592124 0.3907056 0.9183809 -0.06265568 0.2953637 0.9518905 0.08163857 0.408042 0.9047729 0.1220158 0.4359363 0.8967764 0.07584023 0.5929211 0.7950477 0.1278436 0.2586225 0.9544374 0.1488743 0.5370857 0.8147234 0.2185515 0.5925395 0.7848135 0.1815615 0.2635601 0.9499272 0.1678532 0.2575802 0.9405034 0.2215983 0.5938447 0.76576 0.2469012 0.2592908 0.9409666 0.2176015 0.2562988 0.9209117 0.2936541 0.5369899 0.7789787 0.323781 0.5949677 0.7446632 0.3024737 0.2571842 0.9038223 0.3419967 0.2517549 0.896417 0.3647684 0.2582254 0.9226958 0.2862728 0.594031 0.719405 0.3599772 0.252027 0.8870694 0.3867691 0.2524869 0.864187 0.435237 0.5378413 0.728892 0.4236076 0.5924394 0.6880256 0.4190901 0.2510492 0.8553556 0.4531459 0.2657039 0.8225651 0.5027804 0.2486093 0.8799294 0.4048676 0.2582832 0.867109 0.4259247 0.5380172 0.6677835 0.5143956 0.5911274 0.6596126 0.4641978 0.2628349 0.8592492 0.438872 0.2641472 0.7882606 0.5557622 0.2609067 0.8387224 0.4779881 0.2469295 0.8514811 0.4626076 0.2550515 0.844078 0.471679 0.5936276 0.6156013 0.5183063 0.2618584 0.7810584 0.5669021 0.2669495 0.7358431 0.6223126 0.5376959 0.5945236 0.5978503 0.5945203 0.5763001 0.5607352 0.264051 0.6931493 0.6706872 0.5940492 0.5297459 0.6053717 0.2621924 0.6829335 0.6818042 0.2664619 0.6312867 0.7283374 0.5387615 0.5095238 0.6709111 0.591831 0.4788483 0.6484138 0.2638122 0.5813391 0.7697066 0.5388128 0.418568 0.7310824 0.589411 0.4370302 0.6794111 0.2624991 0.5679088 0.7801115 0.2659763 0.5116268 0.8170036 0.5933537 0.3739514 0.7128057 0.2635949 0.4555917 0.8502669 0.5382904 0.3189824 0.7800602 0.5937557 0.3231093 0.7369224 0.2627706 0.4391108 0.859147 0.2655469 0.3796884 0.8861837 0.5939875 0.2613631 0.7608339 0.2633807 0.3189256 0.9104488 0.5396078 0.212077 0.8147679 0.5911033 0.1984993 0.7817896 0.2630147 0.2996684 0.9170726 0.2651838 0.2386319 0.9342015 0.5395135 0.1053208 0.8353639 0.5873809 0.1493936 0.7954027 0.2631974 0.1746002 0.9488108 0.5929853 0.07669436 0.8015525 0.263259 0.1528708 0.9525362 0.2648134 0.0918622 0.9599142 0.5387741 -0.005310177 0.8424335 0.5926868 0.02200448 0.8051324 0.2630433 0.02609372 0.9644312 0.5938667 -0.0458393 0.8032566 0.2635325 0.00225836 0.9646479 0.2644153 -0.05710071 0.9627171 0.5385113 -0.1161255 0.834578 0.5949985 -0.105138 0.7968206 0.2628604 -0.1230527 0.9569548 0.5940239 -0.1669395 0.7869352 0.2638404 -0.1485381 0.9530608 0.2640237 -0.204755 0.9425321 0.5391494 -0.2253526 0.8115013 0.5925073 -0.2320709 0.7714132 0.2626828 -0.2692751 0.9265466 0.5391818 -0.3286912 0.7753999 0.5913185 -0.2830088 0.7551481 0.2641438 -0.2959448 0.9179568 0.263566 -0.3475251 0.8998663 0.5936548 -0.3463291 0.7263817 0.2624664 -0.4091119 0.8739216 0.5387241 -0.4279701 0.7256845 0.594582 -0.3974562 0.6989284 0.2623705 -0.4206107 0.8684748 0.2570912 -0.479574 0.8389952 0.5940485 -0.4522276 0.6652793 0.2608178 -0.5033547 0.8237767 0.2570632 -0.5429976 0.7994199 0.5419299 -0.5158054 0.6635185 0.5920698 -0.5064943 0.6268309 0.2608509 -0.5667793 0.7814846 0.2570309 -0.6032382 0.7550091 0.5813531 -0.5450052 0.6041507 0.590056 -0.5471462 0.5936878 0.2609103 -0.6266853 0.7342966 0.2570037 -0.6597985 0.7061269 0.610422 -0.5774303 0.5421802 0.2609397 -0.6827771 0.6824413 0.2570049 -0.7124782 0.6529346 0.6110334 -0.5361688 0.5823755 0.621589 -0.5975397 0.5065308 0.260967 -0.7344676 0.6264612 0.2561797 -0.7612756 0.5956774 0.7579689 -0.08752834 0.6463916 0.8017459 -0.08585119 0.5914669 0.7401229 -0.08609485 0.6669377 0.2641151 -0.7899039 0.5534393 0.2566379 -0.817707 0.5152595 0.8485808 -0.08856612 0.5216003 0.8590729 -0.0793488 0.5056656 0.8059229 -0.08713257 0.5855736 0.7047153 -0.0877422 0.7040438 0.6855401 -0.0873748 0.7227728 0.5357011 -0.5601164 0.6318972 0.6399269 -0.08749854 0.7634381 0.4246493 -0.5013145 0.7538945 0.4791214 -0.5414721 0.6908333 0.4484778 -0.5437279 0.7093854 0.4228089 -0.3987905 0.8137561 0.4228474 -0.2855402 0.8600389 0.4229022 -0.1670917 0.8906369 0.4229702 -0.04559618 0.9049957 0.4230579 0.07669484 0.902851 0.4231545 0.1976145 0.8842449 0.4232767 0.3149015 0.8495139 0.4233942 0.4264461 0.7993003 0.4235429 0.5302069 0.7345013 0.4237267 0.6242675 0.6563125 0.4239161 0.7069541 0.5661371 0.424221 0.7765991 0.465758 0.4318811 0.8279325 0.3577799 0.4381638 0.8656765 0.2421086 0.646952 -0.08670586 0.7575852 0.580141 -0.08725458 0.8098291 0.5865222 -0.08664458 0.8052854 0.5233153 -0.08740741 0.8476445 0.3896088 -0.5515134 0.7375893 0.5211733 -0.08755904 0.8489476 0.4485383 -0.08649092 0.8895689 0.2998548 -0.467041 0.8318414 0.3431243 -0.5268483 0.7776224 0.2985385 -0.3528015 0.8867954 0.2985656 -0.2291963 0.9264597 0.2985692 -0.1013237 0.9489942 0.2985684 0.02838271 0.9539661 0.2986006 0.1576015 0.9412754 0.2985989 0.2838887 0.9111783 0.2986011 0.4049304 0.8642157 0.2986002 0.5184913 0.801252 0.2985958 0.6224306 0.7234783 0.2985973 0.7148757 0.6322914 0.2985689 0.7940472 0.5294767 0.3436129 0.7986199 0.4941018 0.3042472 0.8150187 0.4931313 0.3915973 0.8529016 0.3452686 0.4294041 0.6729162 0.6023254 0.3908836 0.7981252 0.4584825 0.3807907 0.8259774 0.4156439 0.3774034 0.8418179 0.3858879 0.3686102 0.9202438 0.131446 0.4239352 0.8434453 0.3299682 0.3857597 0.886637 0.2550775 0.3177919 0.9478213 0.02536106 0.3209095 0.9398084 0.1173768 0.13334 -0.7586251 0.637737 0.1736563 -0.7887781 0.5896379 0.1683766 -0.7786771 0.6044101 0.451933 -0.08560723 0.8879348 0.3272287 -0.08588153 0.9410344 0.2861211 -0.5203589 0.8045878 0.1230529 -0.7478395 0.6523758 0.1699002 -0.4206762 0.8911597 0.2172367 -0.4884621 0.8451113 0.1688919 -0.2989941 0.9391902 0.1686506 -0.1706343 0.970794 0.1683446 -0.03915625 0.9849503 0.1738698 0.08722484 0.9808982 0.1923338 0.223128 0.9556263 0.1764923 0.3586307 0.9166431 0.1655987 0.4706105 0.8666619 0.1655973 0.5823678 0.7958803 0.1655973 0.6836308 0.7107928 0.1656276 0.7725933 0.6129169 0.1649547 0.8473578 0.5047523 0.3717525 0.9283284 0.002533078 0.2234948 0.9747037 0.001709043 0.126562 0.991957 0.001892149 0.2851983 0.798708 0.5298372 0.339706 0.9405317 9.15567e-5 0.01678532 0.9998579 0.001617491 -0.01492369 0.9998887 -1.52594e-4 -0.2092976 0.9778515 9.766e-4 -0.3056513 0.9521427 0.001281797 -0.4096552 0.9122404 -5.18821e-4 -0.5813613 0.8136434 0.001861631 -0.5996187 0.8002852 -0.001007139 -0.8018892 0.5974723 9.46092e-4 -0.769493 0.6386551 -5.49354e-4 -0.8918359 0.4523575 0.001190245 -0.9460512 0.3240173 0 -0.9460631 0.3239825 0 -0.8842692 0.4669774 0 0 0 1 0.247446 0.9556031 0.1599792 0.05542278 -0.7298657 0.6813402 0.07315415 -0.7303822 0.6791101 0.168954 -0.4795473 0.8610976 0.02636861 -0.720895 0.6925426 0.03735566 -0.3803321 0.9240953 0.09085494 -0.4385882 0.8940838 0.04962426 -0.4341059 0.8994941 0.03631812 -0.2612158 0.964597 0.03656125 -0.1362961 0.9899932 0.0368362 -0.009277701 0.9992783 0.1351077 0.112249 0.9844523 0.06024545 0.03164869 0.9976817 0.0950663 0.04623609 0.9943967 0.1610177 0.2486374 0.9551193 0.297138 -0.001464903 0.9548335 0.1626979 0.1736543 0.9712743 0.04059058 0.4768637 0.8780397 0.2160118 0.2662152 0.939398 0.149575 0.311663 0.9383462 0.119176 0.3582912 0.9259722 0.1034891 0.436357 0.8938024 0.08264708 0.4195532 0.9039605 0.03958326 0.5885307 0.8075054 0.03955352 0.6913937 0.7213946 0.03940063 0.7818173 0.6222615 0.03912568 0.8581718 0.5118695 0.2099403 0.8835868 0.4185684 0.1565033 0.9080429 0.3885421 0.03869867 0.9190632 0.3922057 0.2007237 0.8783074 0.4339197 0.2229107 0.8620396 0.4551908 0.2474477 0.8401259 0.4826573 0.2129341 0.9238234 0.3181346 0.1581526 0.9523948 0.2606374 0.03811824 0.9633948 0.2653631 0.2156787 0.9101113 0.3538084 0.2204371 0.8972519 0.3825528 0.2246546 0.9419562 0.2494975 0.9460603 -0.3239909 -1.39745e-6 0.9460577 -0.3239985 0 0.990049 -0.1406943 0.002868771 0.9809883 -0.1940674 0 0.9995799 0.02896225 -0.00112915 0.9986611 0.05169856 0.001831114 0.9623469 0.2717997 0.003692746 0.8854268 0.4647789 3.35713e-4 0.9088973 0.4170166 0.001739561 0.7709435 0.6369035 -2.44153e-4 0.6894004 0.7243756 0.002685666 0.6313014 0.7755377 2.74678e-4 0.48205 0.8761438 -6.10383e-5 -0.03940063 -0.7052748 0.7078384 -0.02911543 -0.7031352 0.7104599 -0.0778225 -0.6936885 0.7160587 -0.03912496 -0.4001309 0.9156225 -0.140694 -0.6799703 0.7196149 -0.1336444 -0.6760963 0.7245916 -0.09668552 -0.3373617 0.9363969 -0.08350014 -0.3933907 0.9155718 -0.09793525 -0.2173253 0.9711738 -0.09790503 -0.09180122 0.9909527 -0.1012926 0.02908462 0.9944314 -0.2833349 0.9590172 0.002746641 -0.3343346 0.9424545 2.7467e-4 -0.4930132 0.8700214 -8.54548e-4 0.1027591 -0.1429839 0.984376 -0.2019112 0.9794039 6.10373e-5 -0.5438585 0.8391659 0.004303216 -0.6860139 0.7275812 -0.003265559 -0.75919 0.6508477 0.005279779 -0.8454402 0.5340538 -0.004181087 -0.9117668 0.4106689 0.005707085 -0.953213 0.3022643 -0.004608392 -0.9903889 0.1381924 0.005737662 -0.9990206 0.04397839 -0.00488305 -0.9893711 -0.1453018 0.005676567 -0.9748126 -0.222973 -0.004852533 -0.9088566 -0.417073 0.005462884 -0.8795747 -0.4757394 -0.004516899 -0.7553188 -0.6553381 0.005066156 -0.7200878 -0.6938722 -0.003875851 -0.5399482 -0.8416931 0.002960324 -0.514397 -0.8575522 3.35709e-4 -0.3427637 -0.9394186 0.002411007 0.04049849 0.4154836 0.9086987 -0.2820572 -0.9593974 7.32458e-4 -0.2047827 -0.9788067 0.001312315 -0.09817928 0.533867 0.8398494 -0.1037943 0.4301011 0.8967942 -0.002533078 0.4215905 0.9067828 -0.09796571 0.6350073 0.7662692 -0.0977236 0.7261215 0.6805863 -0.09738683 0.8057686 0.5841685 -0.09302318 0.8707495 0.4828477 -0.07410109 0.9278811 0.3654392 -0.07455825 0.9661139 0.2471134 -0.1833879 -0.665342 0.7236636 -0.1695649 -0.3604018 0.9172559 -0.2315812 -0.6532373 0.7208684 -0.2378356 -0.6486538 0.7229679 -0.2286464 -0.2964286 0.9272815 -0.2154961 -0.3534429 0.9102964 -0.2298409 -0.1765236 0.9570854 -0.2297771 -0.05157697 0.9718757 -0.1449967 0.09601336 0.9847627 -0.1613836 0.1098983 0.9807537 -0.2300209 0.07385575 0.9703792 -0.08948284 0.08554583 0.9923078 -0.04022443 0.05554509 0.9976456 0.02160763 -0.01660245 0.9996287 0.755378 0.6552753 0.004303157 0.7945647 0.6071774 0.001678526 0.67912 0.7340246 -0.001983761 -0.1731979 0.1395959 0.9749439 0.9087347 0.4173477 0.004699885 0.8792455 0.4763673 0.00125122 0.5408375 0.8411197 0.003570735 0.4898934 0.8717796 -0.002197325 0.2813529 0.9596031 0.001617491 0.2500109 0.968243 3.05189e-4 0.1299182 0.9915226 0.002075254 -0.1421902 0.989838 0.001678526 -0.1308942 0.9913964 0 0.1426774 0.9897693 0 -0.2868812 -0.635625 0.7167148 -0.2981424 -0.3211234 0.8988831 -0.2931718 -0.6340153 0.7155942 -0.3394649 -0.6213095 0.7062139 -0.3565828 -0.2581288 0.8978965 -0.3439203 -0.3151408 0.8845366 -0.3579871 -0.1396241 0.9232282 -0.3582061 -0.01651096 0.9334966 -0.2350862 0.1985247 0.9514843 -0.358385 0.1068166 0.9274429 -0.1754857 0.3466377 0.9214375 -0.2287435 0.3200579 0.9193691 -0.3585671 0.2282817 0.9051614 -0.2998824 0.4086531 0.862017 -0.2235519 0.3127896 0.9231399 -0.1851012 0.2429662 0.9522106 -0.1747222 0.1863805 0.9668167 -0.2288054 0.4360334 0.8703579 -0.3587526 0.3457209 0.8670489 -0.2289537 0.5447036 0.8067704 -0.3589093 0.457121 0.8137719 -0.2291076 0.6442604 0.7296837 -0.3590915 0.5604891 0.7462608 -0.2292318 0.733017 0.6404209 -0.359211 0.654057 0.6657153 -0.229354 0.8094993 0.5404699 -0.3593598 0.7361459 0.5735414 -0.2453156 0.8623892 0.4428377 -0.3594834 0.8053661 0.4713355 -0.2922803 0.8889874 0.3525248 -0.2488256 0.9184849 0.3073621 -0.3596077 0.8604889 0.3608896 -0.4256259 0.8380674 0.3413003 -0.3010129 0.8761817 0.3764263 -0.249155 0.8840975 0.3953398 -0.2244089 0.8841766 0.4097225 -0.2099431 0.8810043 0.4239758 -0.1958101 0.873333 0.4460358 -0.1100518 0.7882472 0.6054378 -0.1399301 0.8702524 0.4723138 -0.7002316 0.6885428 0.1886389 -0.3081191 0.9280805 0.2091156 -0.3596747 0.9005755 0.2441271 0.9799497 0.1992454 0 -0.2661253 0.961561 0.06766051 0.979949 0.1992487 -1.07902e-5 0.9799506 0.1992409 0 0.931718 0.3631774 0.001953184 0.9442763 0.3291538 0 0.8469676 0.5316436 -0.001037597 0.8556352 0.5175744 0.002288937 0.6996824 0.7144536 -7.62979e-4 0.6324784 0.7745755 0.002014219 0.5253022 0.8509152 9.46106e-4 0.342238 0.9396133 -3.66226e-4 0.3371438 0.9414515 0.001800596 0.1517109 0.988425 -1.52596e-4 -0.002594113 0.9999943 0.002197384 -0.02868783 0.9995885 0 -0.1948658 0.9808299 -1.22077e-4 -0.3476117 0.9376361 0.002166807 -0.3562822 0.9343785 0 0.1092898 0.7388433 0.6649559 -0.5191916 0.8546579 2.74672e-4 -0.08707153 0.8902782 0.447016 -0.6513158 0.7588054 0.00149542 -0.6790428 0.7340987 -1.83113e-4 -0.1136848 0.9064874 0.4066405 -0.8134017 0.5816988 0.002044796 -0.1243646 0.9168192 0.3794419 -0.8732692 0.487235 0.001831114 -0.922508 0.385978 -5.18829e-4 -0.1092265 0.9347884 0.3379948 -0.9882551 0.1528069 0.001434326 -0.9873313 0.1586701 -7.93503e-4 -0.0606113 0.9419778 0.3301576 -0.9983872 -0.05670362 0.002807676 -0.9799547 -0.1992206 0 -0.1276299 0.9589943 0.2530624 -0.9799504 -0.1992418 0 -0.9997367 -0.02295017 0 -0.1475578 0.9792529 0.1388905 -0.211067 0.9770242 0.02957254 -0.2298067 0.9679349 0.1014446 -0.1397751 0.3681762 0.9191894 -0.03982782 0.4103335 0.9110655 -0.08731633 0.3811583 0.9203772 0.7592273 -0.6507924 0.006592154 0.7958863 -0.605445 0.001220762 0.8783657 -0.4779877 -0.001220703 0.6857643 -0.7278197 -0.002441525 0.9118304 -0.4105175 0.006378531 0.9640837 -0.265551 -0.005035698 0.9904085 -0.1380382 0.006042778 0.999983 -0.003204464 -0.004882991 0.9893492 0.1454557 0.005554497 0.9652296 0.2613661 -0.004425227 -0.3430949 -0.6208791 0.7048369 -0.3875938 -0.6086139 0.6923585 -0.4223515 -0.2832767 0.8610306 -0.3948559 -0.6072383 0.6894567 -0.4366092 -0.5951874 0.6746292 -0.4774127 -0.2284366 0.8484657 -0.4661165 -0.281202 0.8388449 -0.4784846 -0.1179273 0.8701412 -0.478358 -0.003082394 0.8781595 -0.4782394 0.1117926 0.8710854 -0.4781124 0.2248038 0.8490418 -0.4779868 0.3339377 0.8124127 -0.4778454 0.437407 0.7617999 -0.4777206 0.533327 0.6981014 -0.477595 0.6201197 0.6223782 -0.4774402 0.696262 0.5359758 -0.4712177 0.761975 0.4442387 -0.4671877 0.81709 0.3377863 -0.4716486 0.8519522 0.2274314 -0.4445497 -0.5941267 0.6703649 -0.4827521 -0.5828549 0.6536289 -0.5403178 -0.248551 0.8039149 -0.4940142 -0.5811769 0.6466711 -0.527857 -0.570492 0.6292106 -0.5887485 -0.2018854 0.7826989 -0.5803868 -0.2506861 0.7747952 -0.5911317 -0.1005616 0.8002817 -0.591106 0.005493521 0.8065752 -0.5910887 0.1115158 0.7988608 -0.5910769 0.2155613 0.7772782 -0.5910626 0.3159028 0.742193 -0.5910464 0.4107354 0.6942338 -0.5910353 0.4984399 0.63422 -0.591013 0.5775232 0.563179 -0.5919751 0.6440098 0.484579 -0.5073819 0.7416473 0.4387747 -0.5515252 0.6813874 0.4811769 -0.1331541 -0.2096346 0.968671 -0.5185256 0.6986209 0.4930113 -0.5274911 0.8111656 0.2525146 -0.4153985 0.7694533 0.4851658 -0.471646 0.7730551 0.4241884 -0.4971303 0.7753146 0.3895495 -0.5131848 0.7797723 0.3586037 -0.5223452 0.7927501 0.3141701 -0.5728202 0.8158164 0.07950323 -0.5975589 0.795382 0.1014446 -0.5420745 -0.5684122 0.6189208 -0.5708075 -0.559027 0.6013882 -0.6404457 -0.2360966 0.7308132 -0.5883604 -0.5561925 0.5869259 -0.6113647 -0.5480065 0.570896 -0.6926042 -0.09360253 0.7152189 -0.6948304 -0.1818333 0.695807 -0.6926951 4.57788e-4 0.7212305 -0.6927909 0.09451866 0.7149175 -0.6928973 0.1869577 0.6963765 -0.6929929 0.2761656 0.6659532 -0.6930906 0.3606452 0.6241478 -0.6931883 0.4389308 0.5716904 -0.6933001 0.5096673 0.5094842 -0.6933985 0.5717181 0.4385623 -0.6223876 0.6562339 0.4266039 -0.6384086 0.64613 0.4182708 -0.6961484 0.620094 0.3617469 -0.5995204 0.6692264 0.4389891 -0.01919662 0.9998139 0.001922667 0.04400801 0.9990313 0 -0.1275984 0.9918255 8.85041e-4 -0.6422241 0.6480534 0.4093595 0.2949346 0.9555161 0.001617491 0.1481686 0.9889604 0.001861631 -0.3113894 0.9502824 -2.13636e-4 -0.3673875 0.9300659 0.002014219 -0.4779878 0.8783659 0.00100708 -0.6157855 0.7879136 6.40903e-4 -0.6817006 0.7316295 0.001617491 -0.7391095 0.6735852 4.57785e-4 -0.8473089 0.5310978 0.001617491 -0.9006714 0.4344964 0.002014219 -0.9365935 0.3504176 -4.57783e-4 -0.9970037 0.07730531 0.002746701 -0.9889256 0.1484121 0 -0.9974685 -0.07111036 0 -0.9560896 -0.293071 0.001495361 -0.9520546 -0.3059271 -7.62987e-4 -0.8650876 -0.501608 0.003601193 -0.782182 -0.62305 -1.76526e-5 -0.7821798 -0.6230528 0 -0.8850586 -0.4654798 0 -0.6163682 0.7844075 0.06924831 -0.6994328 -0.2190648 0.6802974 -0.6327512 -0.5442765 0.5508076 -0.6503615 -0.537685 0.5365864 -0.7838239 -0.1677333 0.5979011 -0.7262775 -0.1803714 0.6633153 -0.6748707 -0.5328649 0.5104944 -0.6862866 -0.5280442 0.5001801 -0.782763 -0.09094792 0.6156384 -0.7827597 -0.009033679 0.6222586 -0.7827769 0.07300096 0.6180058 -0.782782 0.1537852 0.6029946 -0.7828008 0.2318584 0.577464 -0.7828119 0.3059223 0.5418645 -0.7828381 0.3746184 0.4968158 -0.7744046 0.4385973 0.4559935 -0.7685402 0.5068361 0.3904656 -0.7758944 0.546175 0.315723 -0.6575443 0.6811054 0.3220731 -0.7024101 0.6569052 0.2740361 -0.7802209 0.5778183 0.2395445 -0.6530282 0.6679828 0.3568658 -0.6456115 0.6583687 0.3869579 -0.6615558 0.7058079 0.2533364 -0.7057827 0.6840837 0.1841211 -0.782229 0.6014047 0.1625739 -0.6523523 0.7441242 0.1439295 0.7821695 0.6230658 0 0.7821699 0.6230652 0 0.6808794 0.7323954 7.01937e-4 0.6907777 0.7230673 0 0.5099421 0.8602086 -4.88304e-4 0.563878 0.8258573 0.001159727 0.2975623 0.954702 -9.15576e-4 -0.7911424 -0.1955653 0.5795241 -0.7141545 -0.5219737 0.4663978 -0.7199487 -0.5198341 0.4598332 -0.860619 -0.1569312 0.4844663 -0.8105592 -0.1465836 0.567016 -0.749004 -0.5120829 0.4204335 -0.8593845 -0.09366279 0.5026785 -0.8578106 -0.02661293 0.5132764 -0.8578435 0.04605394 0.5118434 -0.8590221 0.1126766 0.4993846 -0.8588783 0.1791492 0.4798268 -0.8587763 0.242352 0.4514077 -0.8586919 0.3011648 0.4146662 -0.8651295 0.3381839 0.3703818 -0.7896842 0.4357836 0.4318466 -0.3195718 -0.4506234 0.8335542 -0.1602259 -0.5729375 0.803785 -0.7971305 0.3960474 0.4557735 -0.8076868 0.4971248 0.3170319 -0.6963785 0.48647 0.5276399 -0.7706679 0.4679185 0.4325774 -0.7886503 0.4650843 0.4021534 -0.7982023 0.469143 0.3778597 -0.8010188 0.4852014 0.3506402 -0.8177061 0.5156556 0.2558441 -0.821708 0.5405315 0.1806146 -0.8216072 0.5294165 0.2113759 -0.8590198 0.4976131 0.1202756 -0.8679325 -0.171792 0.4660266 -0.7486687 -0.5139449 0.4187552 -0.7755643 -0.5043365 0.379664 -0.9224017 -0.1551883 0.3536829 -0.8726019 -0.03500539 0.4871762 -0.7800135 -0.5034778 0.3716036 -0.7934397 -0.499936 0.3471565 -0.5175781 -0.4382582 0.734876 -0.7617412 -0.5040023 0.4071022 -0.7676223 -0.5044846 0.3952865 -0.7731457 -0.5044232 0.3844518 -0.9193817 -0.120275 0.3745279 -0.9018464 -0.06711202 0.4268129 -0.9163424 -0.08234107 0.3918374 -0.8837105 -0.07397824 0.4621504 -0.8818886 -0.1476223 0.4477501 -0.916669 0.08307272 0.390918 -0.8623346 -0.073794 0.5009328 -0.8805445 -0.005188286 0.4739351 -0.8871846 0.033113 0.4602251 -0.8905867 0.06918746 0.4495203 -0.8912692 0.1169783 0.438127 -0.9030936 0.06756949 0.4240948 -0.9196547 0.1225331 0.3731233 -0.9197198 0.16819 0.354722 -0.9197558 0.2111926 0.3308277 -0.9197838 0.2508973 0.3017421 -0.8756768 0.3559411 0.3263378 -0.8894561 0.343648 0.3012871 -0.9198013 0.28661 0.267993 -0.8587437 0.371752 0.352647 -0.8471469 0.3703177 0.3810604 -0.8408795 0.3550971 0.4084455 -0.833352 0.3166041 0.4530852 0.4539869 0.8910084 0 -0.9215039 0.3127632 0.2302386 -0.8972421 0.355735 0.2615519 0.4539911 0.8910062 5.65593e-6 0.3454477 0.9384374 -0.001098692 0.3264638 0.9452099 0 0.1015974 0.9948253 -8.24011e-4 -0.03634786 0.999338 0.001525938 -0.139135 0.9902729 0.001068115 0.2340527 0.9722239 -1.52597e-4 -0.3460815 0.9382044 -5.18817e-4 -0.3737094 0.927544 0.001892149 -0.5349019 0.8449113 0.002197325 -0.6849486 0.7285914 2.74675e-4 -0.6921805 0.7217233 0.001281797 -0.805212 0.5929833 0.00213629 -0.8908579 0.4542796 0.001525938 -0.9107796 0.4128921 9.4609e-4 -0.9545495 0.2980507 0.001098632 -0.9922747 0.1240305 0.002746701 -0.9989303 0.04620635 0.001770079 -0.9969671 -0.07782363 -2.44153e-4 -0.9443805 -0.3288424 0.002838253 -0.9592366 -0.2826042 -2.13632e-4 -0.8759922 -0.4823252 3.6623e-4 -0.7533109 -0.657663 0.001525938 -0.737244 -0.6756264 -7.01934e-4 -0.5794886 -0.8149707 0.003967404 -0.4540067 -0.8909983 0 -0.4541832 -0.8909084 1.02562e-4 -0.452395 -0.8918175 -5.86336e-4 -0.4539973 -0.8910031 0 -0.6153384 -0.7882631 0 -0.8405455 0.5202519 0.1510674 -0.9197123 0.3803854 0.09714108 -0.8976382 -0.159281 0.4109444 -0.7910594 -0.4983491 0.3547865 -0.8129274 -0.4954105 0.3061333 -0.9346052 -0.1553708 0.3199582 -0.8146623 -0.4942055 0.3034574 -0.8262416 -0.4957511 0.2674993 -0.7998337 -0.4950625 0.3393808 -0.9637731 -0.1381919 0.2281327 -0.9678853 -0.1508257 0.2011213 -0.921043 0.1429831 0.3622645 -0.8346465 -0.4915466 0.2484895 -0.9638005 -0.1058716 0.244704 -0.9637882 -0.07159739 0.2568779 -0.9247837 -0.05276715 0.3768168 -0.9612902 -0.08261513 0.2628609 -0.9430144 -0.141182 0.3013166 -0.9341716 -0.07068318 0.3497535 -0.3874036 0.9219069 0.002533018 -0.5671361 0.8236185 0.003082394 -0.7262061 0.6874772 -9.15578e-5 -0.7118817 0.7022988 0.00100708 -0.8580375 0.5135713 0.004028439 -0.9403077 0.3403236 0.001068174 -0.9260387 0.3774287 1.83114e-4 -0.9869393 0.1610513 0.003662288 -0.9999948 -0.001709043 0.002746701 -0.9999944 -0.003051877 0.001403868 -0.9854298 -0.1700826 0 -0.9231789 -0.3843603 0.002838253 -0.9385982 -0.3450123 -3.05186e-5 -0.8533535 -0.5213328 3.05194e-5 -0.7076988 -0.7065086 0.002868711 -0.7270512 -0.6865832 -3.66227e-4 -0.9246661 0.05328625 0.3770323 -0.5638641 -0.8258673 7.93487e-4 -0.9619041 0.07733565 0.2622209 -0.9549551 0.06729549 0.2890196 -0.9433261 0.1382837 0.3016849 -0.9341319 0.07046884 0.3499027 -0.9638891 0.1027582 0.2456799 -0.9638741 0.1338858 0.2302641 -0.9638584 0.162759 0.2109184 -0.9638487 0.1888511 0.187966 -0.9638302 0.2117735 0.1618133 -0.9249165 0.332202 0.1848551 -0.9638121 0.2310878 0.1329091 -0.9021406 0.4123112 0.1270504 -0.9232698 0.3595173 0.135353 -0.9637895 0.2465018 0.1017197 -0.9029036 0.3707138 0.2175697 -0.9637564 0.2577626 0.0687896 -0.8844418 0.466453 -0.01358097 0.453998 0.8910027 1.41603e-5 0.453975 0.8910145 -1.0872e-5 -0.9500567 -0.03863704 0.3096764 -0.8366599 -0.4899896 0.2447659 -0.847597 -0.4855226 0.2141194 -0.9574235 -0.1687417 0.2342362 -0.8578867 -0.4839995 0.1725539 -0.8577056 -0.4828103 0.1767354 -0.9753176 -0.1409965 0.1699283 -0.8631764 -0.482418 0.1489951 -0.9791796 -0.09079474 0.181559 -0.8661325 -0.481378 0.1344977 0 1 0 -0.2644155 -0.9640607 0.02591049 -0.1957218 0.980654 0.003296077 -0.1346201 0.9908973 0 -0.35219 0.935928 -0.001098632 -0.9807662 -0.1128601 0.1592494 -0.8667746 -0.4821721 0.1273259 -0.8695433 -0.4798175 0.1169177 -0.9826585 -0.133369 0.1288217 -0.8719447 -0.4801342 0.09583151 -0.9845244 -0.144204 0.09958469 -0.874526 -0.4790894 0.07535171 -0.9858025 -0.1525047 0.07025527 -0.8768424 -0.4778365 0.05310308 -0.9865806 -0.1567444 0.04571712 -0.8774432 -0.4784417 0.03445559 -0.9879521 -1.52594e-4 0.1547604 -0.9878539 -0.0177623 0.1543674 -0.9878225 0.01791489 0.1545504 -0.9784133 0.136329 0.1553119 -0.9712004 0.05630719 0.2315157 0 1 -2.9223e-6 -0.3835398 -0.9235231 0.001525938 -0.3517922 -0.936078 -6.40898e-4 -0.1486583 -0.9888787 0.004455745 -0.1966971 -0.9804644 0 -0.1319934 -0.9912477 0.002410948 0.1414849 -0.989937 0.002624571 0.1285145 -0.9917076 0 0.258652 -0.96597 -0.001098692 -0.1426774 -0.9897693 0 0.2832134 -0.9590497 0.003753781 0.4993247 -0.8664097 -0.003021359 0.5439339 -0.8391103 0.005462825 0.2610598 -0.9452356 0.1959016 0.2527612 -0.9498535 0.1840927 0.9837459 -0.0877723 0.1566534 0.9819105 -0.08536094 0.1690129 0.9766315 -0.08764994 0.1962357 0.2690249 -0.9370552 0.2226055 0.2703105 -0.9133547 0.3044922 0.2688408 -0.9058309 0.3274065 -0.5000086 -0.8660205 -6.55002e-6 0.2685093 -0.8586315 0.4366404 0.2773255 -0.8870633 0.3690654 -0.5000159 -0.8660162 0 0.2653617 -0.8790659 0.396013 -0.3825297 -0.9239432 -3.05194e-5 -0.3820633 -0.9241362 0 -0.1816214 -0.9833685 3.05195e-5 0.2620955 -0.8750047 0.4070293 -0.2588022 -0.9659304 0 0.01968479 -0.9998063 0 0.2591412 -0.869867 0.4197348 0.02755862 -0.9996195 0.00125122 0.177103 -0.9841837 0.004150569 0.2523332 -0.8568586 0.4495791 0.3581401 -0.9336668 0.001403868 0.9072033 -0.01873856 0.420275 0.909443 -0.008911609 0.4157332 0.3659309 -0.9306364 0.003235042 0.6027746 -0.7979111 -0.00100708 0.864378 -0.08795768 0.49509 0.8973189 -0.05496466 0.4379473 0.8901291 -0.07165956 0.4500392 0.8847388 -0.08026432 0.4591242 0.8806394 -0.08603435 0.4659103 0.8878693 -0.08661395 0.4518697 0.8810244 -0.0865826 0.46508 0.8764893 -0.08691948 0.4735099 0.8738045 -0.08704167 0.4784241 0.2686303 0.919911 0.2856601 0.2647207 0.9173973 0.2971622 0.2607231 0.945354 0.1957788 0.2795535 0.9328728 0.2271525 0.2698483 0.8646315 0.4237858 0.32558 0.8390368 0.4359073 0.294268 0.8692841 0.3971795 0.270707 0.8944622 0.3558865 0.2594105 0.8527281 0.4533885 0.2589246 0.8573141 0.444939 1 -1.11851e-5 0 1 -2.4651e-6 0 1 2.88769e-6 0 1 2.8451e-6 0 1 2.79798e-6 0 1 1.28393e-6 0 1 -2.7476e-6 0 1 1.62998e-7 0 1 -1.26269e-6 0 1 1.37625e-6 0 1 1.25322e-6 0 1 -2.73983e-6 0 1 -2.49834e-6 0 1 2.75795e-6 0 1 2.49389e-6 0 1 -2.77139e-6 0 1 1.73608e-6 0 1 -1.46442e-6 0 1 -5.67748e-6 0 -0.9659261 0.2588183 0 -0.965924 0.2588257 0 0.9659257 -0.2588197 1.47075e-6 0.965927 -0.258815 0 0.9967777 -0.08014261 0.003357052 0.9925621 -0.1217394 0 0.9940187 0.1091986 -0.001648008 0.9944634 0.1050161 0.003784358 0.9358462 0.3524073 -0.001037657 0.890544 0.4548855 0.0032655 0.8261151 0.5635002 0.001159667 0.6839725 0.7295076 -5.18832e-4 0.6688916 0.7433588 0.001342833 0.5171516 0.8558866 0.003540217 0.3545383 0.9350386 0.002349913 0.3599702 0.9329623 0.001709043 0.1813744 0.9834141 -2.44152e-4 0.008972585 0.9999569 0.002441465 -0.00665307 0.999978 -1.52594e-4 -0.2095436 0.977799 7.93495e-4 -0.3219162 0.9467656 0.00225836 -0.42278 0.9062318 -0.001068115 -0.6087654 0.7933451 0.002899289 -0.6242066 0.7812577 -0.001617491 -0.8314668 0.5555726 0.001464903 -0.7993804 0.6008247 -8.85047e-4 -0.9166021 0.3997964 0.001861631 -0.9104752 0.4135638 0 0.4999901 0.8660311 0 0.9712988 -0.08722335 0.2212935 0.9684058 -0.08755964 0.2335026 0.9666157 -0.08707231 0.2409825 0.4998713 0.8660997 -6.84799e-5 0.9453617 -0.08624714 0.3144085 0.6134618 0.7897088 0.004974544 0.6528751 0.7574657 0 0.7819623 0.6233236 0.001648008 0.8829782 0.4694141 4.27267e-4 0.9559612 0.2934752 0.003265559 0.752329 0.6587876 -4.27269e-4 0.9966446 0.08185076 -3.05186e-4 0.9970922 -0.07617586 0.00213629 0.9618607 0.2735399 -1.83113e-4 0.9949901 -0.09995067 0.002197384 0.9014356 -0.43291 0.001709043 0.8877065 -0.4604098 -3.35709e-4 0.6815554 -0.7317595 0.003234982 0.9617351 -0.2739662 0.002838194 0.770557 -0.6373698 0.001281797 0.9470419 -0.08743757 0.3089765 0.9471654 -0.08749872 0.3085803 0.9688355 -0.08723163 0.231837 0.9653716 -0.08749747 0.2457681 0.9689716 -0.08722835 0.2312693 0.9246181 -0.08719414 0.3707811 0.920152 -0.08942103 0.3812145 0.8963751 -0.08966493 0.4341335 0.8870891 -0.09057968 0.4526239 0.9062415 -0.09106969 0.4128352 0.8728051 -0.08954191 0.4797849 0.8793503 -0.08795636 0.4679817 0.8866994 -0.08713179 0.4540619 0 -1 -5.32651e-7 0 -1 1.34993e-6 0 -1 -2.1061e-6 0 -1 1.96617e-6 0 -1 -4.48956e-7 0 -1 -1.79267e-6 0.3837449 -0.08548349 0.9194741 0.308125 -0.08603447 0.9474477 0 -1 -1.80369e-6 0.185004 -0.08554375 0.9790076 0.2353917 -0.08600205 0.968088 0 -1 -3.11534e-6 0.1567767 -0.08643013 0.9838451 0 -1 -3.2954e-6 0.03927761 -0.08526945 0.9955835 0.08118128 -0.0864306 0.9929448 0 -1 3.13845e-6 0.001525938 -0.08676517 0.9962277 0 -1 -3.57465e-6 -0.1066344 -0.08502674 0.9906562 -0.07513761 -0.08676528 0.9933912 0 -1 1.74101e-6 -0.1539385 -0.08701002 0.984242 -0.2320974 -0.08594161 0.9688885 -0.2298714 -0.0870105 0.9693237 0 -1 1.74374e-6 -0.3057408 -0.08758991 0.9480774 -0.3181331 -0.08691895 0.9440532 -0.3794138 -0.0873152 0.9210978 0 -1 -1.74613e-6 -0.4518325 -0.08725357 0.8878256 -0.4505913 -0.08725547 0.888456 0 -1 3.29909e-6 -0.3862257 -0.0871945 0.918274 -0.5151708 -0.08704185 0.8526564 -0.5192281 -0.08743834 0.850151 0 -1 -1.74744e-6 -0.5758686 -0.08688843 0.8129119 -0.5846946 -0.08759123 0.8065111 -0.633553 -0.08679729 0.7688153 -0.646527 -0.0877133 0.7578319 0 -1 1.74737e-6 -0.6878334 -0.08670395 0.7206717 -0.704452 -0.08780467 0.7042995 -0.7384666 -0.08664321 0.6687003 -0.7578218 -0.08786469 0.6465184 -0.7851963 -0.08661329 0.6131599 -0.8061583 -0.08786404 0.58514 0 -1 -1.49157e-6 -0.8278441 -0.08658409 0.5542359 -0.8496909 -0.08810949 0.5198676 0 -1 -1.06197e-6 -0.8828518 -0.0928691 0.4603782 -0.8870289 -0.08948111 0.45296 0 -1 -1.16548e-6 -0.8660898 -0.08609318 0.492419 -0.8645433 -0.08810842 0.4947746 -0.8765332 -0.09570723 0.4717305 -0.8714262 -0.09204709 0.4818129 0 -1 6.76612e-7 -0.9071751 -0.08923733 0.4111815 -0.9208555 -0.0895738 0.3794756 -0.8963526 -0.08838397 0.4344426 0 -1 1.72795e-6 -0.9468868 -0.08728474 0.3094946 -0.9474069 -0.08768159 0.3077859 -0.9246701 -0.08743745 0.3705944 -0.965447 -0.08725458 0.2455582 -0.9687395 -0.08792573 0.2319762 -0.9717353 -0.08682745 0.2195255 -0.9839301 -0.08749771 0.1556465 -0.9728074 -0.08725506 0.2145517 -0.9689489 -0.08722275 0.2313664 -0.9687546 -0.08703929 0.2322472 -0.9663448 -0.0875582 0.2418913 -0.9688315 -0.08723658 0.2318521 -0.9721481 -0.08728396 0.217508 -0.985306 -0.08694863 0.14701 -0.8559495 -0.4843747 0.1809195 -0.853114 -0.482362 0.1988046 -0.8596729 -0.4850767 0.1601968 -0.954176 -0.08707064 0.2862986 -0.952955 -0.08649075 0.2905101 -0.8404035 -0.48272 0.2463804 -0.9358717 -0.08740699 0.3413269 -0.9288498 -0.08636909 0.3602478 -0.8296678 -0.488889 0.2695161 -0.8151836 -0.4899038 0.3089824 -0.9014673 -0.08542239 0.4243348 -0.9002048 -0.0862177 0.4268465 -0.799394 -0.5007314 0.3320203 -0.7790634 -0.508175 0.3671764 -0.9093673 -0.08325511 0.4075779 -0.920802 -0.08643102 0.3803333 -0.8800171 -0.08664357 0.4669721 -0.7695784 -0.5109261 0.383019 -0.8893347 -0.08633929 0.4490316 -0.8940154 -0.08688676 0.4395306 -0.7869369 -0.5032612 0.3570133 -0.8731159 -0.08694839 0.4796965 -0.7630955 -0.5147934 0.3907339 -0.7604821 -0.5119017 0.3995293 -0.7580908 -0.5109179 0.4052917 -0.7437899 -0.5081796 0.4342005 0.8974561 -0.08719414 0.4324001 0.8897982 -0.087408 0.4479053 0.8929086 -0.08722466 0.4417085 0.8980182 -0.08719241 0.4312319 0.9089749 -0.08728402 0.4076104 0.9054104 -0.08719307 0.4154871 0.9199129 -0.08661377 0.3824374 0.9257157 -0.08731609 0.3680034 0.9479997 -0.0871334 0.3061115 0.08736592 -0.9961764 -6.85883e-5 0.08715736 -0.9961946 0 -0.9534345 -0.08642894 0.288951 -0.9478502 -0.08856528 0.3061637 -0.08716464 0.996194 4.46253e-6 -0.08717268 0.9961933 0 -0.2732035 0.9619498 0.003540158 -0.2288964 0.9734508 0 -0.4488481 0.8936066 -0.001617491 -0.453267 0.8913661 0.003936886 -0.6597632 0.7514733 -7.3246e-4 -0.7533785 0.6575772 0.00363183 -0.8183391 0.5747356 6.40901e-4 -0.9237804 0.3829222 -6.40899e-4 -0.943946 0.3300911 0.002441465 -0.9831513 0.1827805 0.002197384 -0.9999987 -0.001190245 0.001129209 -0.999033 -0.04394704 0.001312255 -0.9831354 -0.1828691 0.001953184 -0.875802 -0.08639913 0.4748747 -0.9336729 -0.3581119 0.003296017 -0.8807224 -0.08685755 0.4656006 -0.9117566 -0.4107254 0.002197325 -0.8400929 -0.5424424 -3.96745e-4 -0.8839316 -0.08707165 0.4594381 -0.8878613 -0.08719301 0.4517741 -0.6926605 -0.7212568 0.003173947 -0.7000216 -0.7141216 -4.88309e-4 -0.8936867 -0.08716213 0.4401444 -0.8972592 -0.08728438 0.4327902 -0.5190971 -0.8547142 0.001464903 -0.8896886 -0.08716213 0.4481709 -0.8889956 -0.08715337 0.4495455 -0.9002528 -0.08710151 0.4265657 -0.9089 -0.08731615 0.4077705 -0.3746219 -0.9271702 0.003723323 -0.2845857 -0.9586494 -0.001556396 -0.9201842 -0.08710175 0.381673 -0.92544 -0.08804845 0.3685218 -0.08298218 -0.996549 0.002014219 -0.0480681 -0.9988407 -0.002594113 -0.9091377 -0.08713245 0.4072793 -0.9349796 -0.08667391 0.3439489 0.04333657 -0.9990605 -3.05187e-4 0.06491464 -0.9978908 0 0.08723795 0.9961876 3.50721e-5 0.08716458 0.996194 0 -0.08715736 -0.9961946 -8.78254e-6 -0.08718186 -0.9961925 0 -0.05923688 -0.998208 -0.008484184 0.05380499 -0.9985516 0 0.281482 -0.9595657 -0.00125128 0.3747483 -0.9271198 0.003570735 0.5154414 -0.8569225 0.002014219 0.08118128 -0.996699 -8.24021e-4 -0.0444054 -0.9989845 -0.007629752 0.6949179 -0.7190889 -4.27266e-4 0.6926299 -0.7212873 0.002960324 0.8356992 -0.5491877 -2.7467e-4 0.9114218 -0.4114582 0.00350964 0.9295985 -0.3685739 1.22075e-4 0.9819062 -0.189368 -1.22074e-4 0.99905 -0.04345947 0.003265559 0.9999582 -0.00915569 1.52595e-4 0.9842798 0.1766155 4.5779e-4 0.9436016 0.3310754 0.002319455 0.9267089 0.3757802 -3.0519e-5 0.8242284 0.5662508 0.002746701 0.7537202 0.6571896 0.002807676 0.6634596 0.7482118 -8.54541e-4 0.4521376 0.8919456 0.002197325 0.4517123 0.892163 -0.001098632 0.2418655 0.9703002 0.004333734 0.2754345 0.9613198 0 0.08717745 -0.9961928 0 0.08715879 -0.9961945 0 -0.08716565 0.9961939 -2.96169e-6 -0.08714985 0.9961952 0 -0.2729975 0.9620071 0.003845453 -0.2271813 0.9738525 0 -0.4468955 0.8945846 -0.001739561 -0.4533031 0.8913466 0.004181087 -0.6571097 0.7537947 -5.79866e-4 -0.7533629 0.6575941 0.003814876 -0.8153839 0.5789204 4.88309e-4 -0.9217776 0.3877185 -7.32466e-4 -0.9439455 0.330091 0.002655088 -0.9823536 0.1870219 0.002075254 -0.9999954 0.002899289 9.76618e-4 -0.9990315 -0.04397749 0.001434326 -0.9839872 -0.1782298 0.001861631 -0.9352068 -0.3540864 0.003326594 -0.9117678 -0.4106999 0.002258419 -0.8413261 -0.5405277 -4.2727e-4 -0.6926603 -0.7212566 0.0032655 -0.7004838 -0.7136682 -5.49351e-4 -0.5200092 -0.8541592 0.001648008 -0.3747109 -0.9271333 0.003936886 -0.2852609 -0.9584487 -0.001586973 -0.08285838 -0.9965592 0.00213629 -0.04599165 -0.9989379 -0.002807676 0.04339748 -0.9990579 -3.35705e-4 0.06503617 -0.997883 0 -0.9964963 0.02569669 -0.0795927 -0.9965943 0 -0.08246201 -0.9838114 0.01400822 -0.1786584 -0.9838114 -0.01400822 0.1786584 -0.9455084 -0.3224024 0.04550379 -0.9964963 -0.02569669 0.0795927 -0.9965943 0 0.08246201 -0.9822971 8.85062e-4 -0.187328 -0.9469853 3.05194e-5 -0.3212773 -0.9455084 0.3224024 -0.04550379 -0.9442763 -9.15588e-5 -0.3291538 -0.8810096 1.22074e-4 -0.4730986 -0.8774181 -6.10378e-5 -0.4797264 -0.8023449 -5.18823e-4 -0.5968604 -0.7987114 -0.01367247 -0.6015591 -0.7265132 -0.1573578 -0.6688926 -0.6771942 -0.02545315 -0.7353641 -0.6768198 0 -0.7361487 -0.6063224 -0.1578446 -0.7793961 -0.5343004 -0.01455765 -0.8451694 -0.5266065 -0.001190185 -0.8501085 -0.4079839 4.27272e-4 -0.912989 -0.3946154 0 -0.9188465 -0.2544662 8.54528e-4 -0.9670814 -0.2358227 -5.79867e-4 -0.971796 -0.09317421 0.001098632 -0.9956493 -0.07168942 -0.00100708 -0.9974265 0.07168942 0.00100708 -0.9974265 0.09317421 -0.001098632 -0.9956493 0.2358227 5.79867e-4 -0.971796 0.2544662 -8.54528e-4 -0.9670814 0.3946154 0 -0.9188465 0.4079839 -4.27272e-4 -0.912989 0.5266065 0.001190185 -0.8501085 0.5343222 0.01455742 -0.8451555 0.6063561 0.1578454 -0.7793697 0.6771942 0.02545315 -0.7353641 0.7265424 0.1573575 -0.6688609 0.7987114 0.01367247 -0.6015591 0.6768198 0 -0.7361487 0.8023449 5.18823e-4 -0.5968604 0.877431 6.10387e-5 -0.479703 0.8810223 -1.22076e-4 -0.4730749 0.9442763 9.15588e-5 -0.3291538 0.9469853 -3.05194e-5 -0.3212773 0.9822971 -8.85062e-4 -0.187328 0.9838114 -0.01400822 -0.1786584 0.9455084 -0.3224024 -0.04550379 0.9964963 -0.02569669 -0.0795927 0.9964963 0.02569669 0.0795927 0.9965943 0 0.08246201 0.9838114 0.01400822 0.1786584 0.9965943 0 -0.08246201 0.9822971 8.85062e-4 0.187328 0.9469853 3.05194e-5 0.3212773 0.9455084 0.3224024 0.04550379 0.9442763 -9.15588e-5 0.3291538 0.8810096 1.22074e-4 0.4730986 0.8774181 -6.10378e-5 0.4797264 0.8023449 -5.18823e-4 0.5968604 0.7987114 -0.01367247 0.6015591 0.7265132 -0.1573578 0.6688926 0.6771942 -0.02545315 0.7353641 0.6768198 0 0.7361487 0.6063224 -0.1578446 0.7793961 0.5343004 -0.01455765 0.8451694 0.5266065 -0.001190185 0.8501085 0.4079839 4.27272e-4 0.912989 0.3946154 0 0.9188465 0.2544662 8.54528e-4 0.9670814 0.2358227 -5.79867e-4 0.971796 0.09317421 0.001098632 0.9956493 0.07168942 -0.00100708 0.9974265 -0.07168942 0.00100708 0.9974265 -0.09317421 -0.001098632 0.9956493 -0.2358227 5.79867e-4 0.971796 -0.2544662 -8.54528e-4 0.9670814 -0.3946154 0 0.9188465 -0.4079839 -4.27272e-4 0.912989 -0.5266065 0.001190185 0.8501085 -0.5343222 0.01455742 0.8451555 -0.6063561 0.1578454 0.7793697 -0.6771942 0.02545315 0.7353641 -0.7265424 0.1573575 0.6688609 -0.7987114 0.01367247 0.6015591 -0.6768198 0 0.7361487 -0.8023449 5.18823e-4 0.5968604 -0.877431 6.10387e-5 0.479703 -0.8810223 -1.22076e-4 0.4730749 -0.9442763 9.15588e-5 0.3291538 -0.9469853 -3.05194e-5 0.3212773 -0.9822971 -8.85062e-4 0.187328 0 1 2.03074e-6 0 1 1.4202e-6 0 1 7.36266e-7 0 1 1.58135e-6 0 1 3.43753e-6 0 1 3.43501e-6 0 1 -1.65517e-6 0 1 1.65904e-6 0 1 8.31121e-7 0 1 -8.3057e-7 0 1 -1.76531e-6 0 1 1.91521e-6 0 1 1.44231e-6 0 1 2.08891e-6 0 1 -2.03074e-6 0 1 -1.4202e-6 0 1 -7.36266e-7 0 1 -1.58135e-6 0 1 -3.43753e-6 0 1 -3.43501e-6 0 1 1.65517e-6 0 1 -1.65904e-6 0 1 -8.31121e-7 0 1 8.3057e-7 0 1 1.76531e-6 0 1 -1.91521e-6 0 1 -1.44231e-6 0 1 -2.08891e-6 -0.9818162 0.1743836 -0.07501488 -0.9818822 0.1731027 -0.07709056 -0.9726589 0.1749076 -0.152781 -0.9743276 0.1710605 0.1463704 -0.9842034 0.1621468 0.07107847 -0.9857797 0.1600698 0.05114907 -0.9821522 0.1731629 0.07342791 -0.9412464 0.1720069 -0.2906355 -0.9362847 0.176734 -0.3035395 0 1 -5.46199e-7 -0.9738705 0.1737463 -0.1462484 0 1 8.35414e-7 -0.8877468 0.1709999 -0.427393 -0.8771243 0.1778969 -0.4461004 0 1 0 -0.8149754 0.1694712 -0.5541613 -0.8057629 0.1737142 -0.5661886 -0.7515044 0.171121 -0.637149 -0.7227563 0.1668486 -0.67066 -0.6941902 0.1702057 -0.6993784 -0.6423974 0.1704799 -0.7471696 -0.614812 0.1676732 -0.7706438 -0.5748286 0.1685268 -0.8007315 -0.5174566 0.1697489 -0.8387038 -0.4948107 0.167002 -0.8528029 -0.4302601 0.1773167 -0.8851187 -0.3616492 0.1676099 -0.9171242 -0.3018096 0.1812567 -0.9359791 -0.2212352 0.1673684 -0.9607512 -0.1515277 0.1813755 -0.9716698 -0.07580953 0.1672754 -0.9829913 0.002166867 0.181315 -0.9834228 0.07141393 0.167304 -0.9833156 0.1556783 0.1811313 -0.9710591 0.2172685 0.1674606 -0.9616399 0.3052483 0.180854 -0.9349414 0.3584513 0.1677045 -0.9183616 0.4473485 0.1804897 -0.8759582 0.4918193 0.1680395 -0.8543282 0.5786451 0.1800636 -0.795454 0.6142884 0.1684959 -0.770882 0.6959559 0.1795129 -0.6952846 0.7228842 0.1690778 -0.6699635 0.7960541 0.1789016 -0.5781799 0.8148741 0.1698112 -0.554206 0.8765697 0.1781095 -0.4471049 0.8882365 0.1706644 -0.4265086 0.9358196 0.1771352 -0.3047373 0.941661 0.1716994 -0.2894718 0.9692159 0.1752694 -0.1729195 0 1 -4.2097e-7 0.9743276 0.1710605 -0.1463704 0.9842034 0.1621468 -0.07107847 0 1 -1.37394e-7 0 1 -6.64364e-7 0.9857797 0.1600698 -0.05114907 0.9818162 0.1743836 0.07501488 0.9818822 0.1731027 0.07709056 0.9726589 0.1749076 0.152781 0.9821522 0.1731629 -0.07342791 0.9412464 0.1720069 0.2906355 0.9362847 0.176734 0.3035395 0.9738705 0.1737463 0.1462484 0.8877468 0.1709999 0.427393 0.8771243 0.1778969 0.4461004 0.8149754 0.1694712 0.5541613 0.8057629 0.1737142 0.5661886 0.7515044 0.171121 0.637149 0.7227563 0.1668486 0.67066 0.6941902 0.1702057 0.6993784 0.6423974 0.1704799 0.7471696 0.614812 0.1676732 0.7706438 0.5748286 0.1685268 0.8007315 0.5174566 0.1697489 0.8387038 0.4948107 0.167002 0.8528029 0.4302601 0.1773167 0.8851187 0.3616492 0.1676099 0.9171242 0.3018096 0.1812567 0.9359791 0.2212352 0.1673684 0.9607512 0.1515277 0.1813755 0.9716698 0.07580953 0.1672754 0.9829913 -0.002166867 0.181315 0.9834228 -0.07141393 0.167304 0.9833156 -0.1556783 0.1811313 0.9710591 -0.2172685 0.1674606 0.9616399 -0.3052483 0.180854 0.9349414 -0.3584513 0.1677045 0.9183616 -0.4473485 0.1804897 0.8759582 -0.4918193 0.1680395 0.8543282 -0.5786451 0.1800636 0.795454 -0.6142884 0.1684959 0.770882 -0.6959559 0.1795129 0.6952846 -0.7228842 0.1690778 0.6699635 -0.7960541 0.1789016 0.5781799 -0.8148741 0.1698112 0.554206 -0.8765697 0.1781095 0.4471049 -0.8882365 0.1706644 0.4265086 -0.9358196 0.1771352 0.3047373 -0.941661 0.1716994 0.2894718 -0.9692159 0.1752694 0.1729195 0 -1 -1.43082e-6 0 -1 -4.40491e-7 0 -1 3.59572e-7 0 -1 0 0 -1 -1.3622e-7 0 -1 -1.0339e-6 0 -1 8.6272e-7 0 -1 -2.51831e-7 0 -1 2.97874e-7 0 -1 1.69293e-6 0 -1 -1.21032e-6 0 -1 7.24116e-7 0 -1 1.4367e-6 0 -1 -2.73011e-7 0 -1 3.69314e-7 0 -1 -3.75738e-7 0 -1 1.3622e-7 0 -1 4.40491e-7 0 -1 0 0 -1 1.43082e-6 0 -1 -3.59572e-7 0 -1 1.0339e-6 0 -1 -8.6272e-7 0 -1 2.51831e-7 0 -1 -2.97874e-7 0 -1 -1.69293e-6 0 -1 1.21032e-6 0 -1 -7.24116e-7 0 -1 -1.4367e-6 0 -1 2.73011e-7 0 -1 -3.69314e-7 0 -1 3.75738e-7 -0.998205 0.01413011 -0.0581991 -0.9957408 0 -0.09219765 -0.9829488 0.00125122 -0.1838756 -0.9829488 -0.00125122 0.1838756 -0.9961537 -0.01059019 0.08698034 -0.998205 -0.01413011 0.0581991 -0.9957408 0 0.09219765 -0.9816856 0.006988883 -0.1903797 -0.9323842 0.00137335 -0.3614664 -0.9961537 0.01059019 -0.08698034 -0.9233242 -1.22076e-4 -0.3840215 -0.8501448 2.44154e-4 -0.526549 -0.9629915 0.01046794 -0.2693288 -0.849386 -1.52597e-4 -0.5277723 -0.7542777 1.52595e-4 -0.6565557 -0.7403103 -0.004272699 -0.6722519 -0.6734725 -0.001190245 -0.7392113 -0.5997555 -0.004181027 -0.8001725 -0.5833725 9.15573e-5 -0.8122047 -0.4455525 -9.15582e-5 -0.8952558 -0.4444525 2.74674e-4 -0.8958024 -0.27406 -2.44151e-4 -0.9617127 -0.2719871 3.6623e-4 -0.9623008 -0.09335863 -3.66232e-4 -0.9956325 -0.09067332 3.96753e-4 -0.9958807 0.09067332 -3.96753e-4 -0.9958807 0.09335863 3.66232e-4 -0.9956325 0.2719871 -3.6623e-4 -0.9623008 0.27406 2.44151e-4 -0.9617127 0.4444525 -2.74674e-4 -0.8958024 0.4455525 9.15582e-5 -0.8952558 0.5833725 -9.15573e-5 -0.8122047 0.5997555 0.004181027 -0.8001725 0.6734725 0.001190245 -0.7392113 0.7403103 0.004272699 -0.6722519 0.7542777 -1.52595e-4 -0.6565557 0.849386 1.52597e-4 -0.5277723 0.8501448 -2.44154e-4 -0.526549 0.9233242 1.22076e-4 -0.3840215 0.9323842 -0.00137335 -0.3614664 0.9629915 -0.01046794 -0.2693288 0.9816856 -0.006988883 -0.1903797 0.9829488 -0.00125122 -0.1838756 0.9961537 -0.01059019 -0.08698034 0.998205 -0.01413011 -0.0581991 0.998205 0.01413011 0.0581991 0.9957408 0 0.09219765 0.9829488 0.00125122 0.1838756 0.9957408 0 -0.09219765 0.9816856 0.006988883 0.1903797 0.9323842 0.00137335 0.3614664 0.9961537 0.01059019 0.08698034 0.9233242 -1.22076e-4 0.3840215 0.8501448 2.44154e-4 0.526549 0.9629915 0.01046794 0.2693288 0.849386 -1.52597e-4 0.5277723 0.7542777 1.52595e-4 0.6565557 0.7403103 -0.004272699 0.6722519 0.6734725 -0.001190245 0.7392113 0.5997555 -0.004181027 0.8001725 0.5833725 9.15573e-5 0.8122047 0.4455525 -9.15582e-5 0.8952558 0.4444525 2.74674e-4 0.8958024 0.27406 -2.44151e-4 0.9617127 0.2719871 3.6623e-4 0.9623008 0.09335863 -3.66232e-4 0.9956325 0.09067332 3.96753e-4 0.9958807 -0.09067332 -3.96753e-4 0.9958807 -0.09335863 3.66232e-4 0.9956325 -0.2719871 -3.6623e-4 0.9623008 -0.27406 2.44151e-4 0.9617127 -0.4444525 -2.74674e-4 0.8958024 -0.4455525 9.15582e-5 0.8952558 -0.5833725 -9.15573e-5 0.8122047 -0.5997555 0.004181027 0.8001725 -0.6734725 0.001190245 0.7392113 -0.7403103 0.004272699 0.6722519 -0.7542777 -1.52595e-4 0.6565557 -0.849386 1.52597e-4 0.5277723 -0.8501448 -2.44154e-4 0.526549 -0.9233242 1.22076e-4 0.3840215 -0.9323842 -0.00137335 0.3614664 -0.9629915 -0.01046794 0.2693288 -0.9816856 -0.006988883 0.1903797 0 -1 7.90004e-7 0 -1 3.4694e-7 0 -1 -5.04964e-7 0 -1 5.14737e-7 0 -1 2.37884e-7 0 -1 0 0 -1 0 0 -1 -3.29064e-7 0 -1 0 0 -1 -1.67052e-7 0 -1 2.72506e-7 0 -1 0 0 -1 0 0 -1 -2.64488e-7 0 -1 0 0 -1 1.49889e-7 0 -1 -5.14737e-7 0 -1 5.04964e-7 0 -1 -3.4694e-7 0 -1 5.57173e-7 0.5002261 -0.8658947 -7.62366e-5 0.500003 -0.8660237 0 -0.4999883 0.8660321 1.16996e-5 -0.5000051 0.8660225 0 -0.6516939 0.7584784 0.00238043 -0.6205513 0.7841659 0 -0.789557 0.6136761 -0.001190185 -0.7824473 0.6227106 0.002807736 -0.9167075 0.3995584 -6.40905e-4 -0.9560477 0.293199 0.002716183 -0.9837111 0.1797555 6.40894e-4 -0.9995415 -0.03027522 -4.88311e-4 -0.9971393 -0.07556444 0.001861631 -0.9725455 -0.2327065 0.001739561 -0.9149681 -0.403526 5.18828e-4 -0.9012116 -0.4333775 0.001312315 -0.8342824 -0.5513356 0.00137335 -0.7344499 -0.6786604 0.001861631 -0.6810371 -0.7322484 8.54539e-4 -0.6017466 -0.7986868 6.40903e-4 -0.4437411 -0.8961495 0.003173887 -0.3672084 -0.9301372 0.001648008 -0.25062 -0.9680855 -1.83113e-4 -0.02771109 -0.9996144 0.001800596 -0.04232996 -0.9991036 -5.18825e-4 0.2590168 -0.9658728 3.66231e-4 0.1789956 -0.98385 -9.15578e-5 0.3854236 -0.9227398 1.83114e-4 0.3825558 -0.9239324 0 -0.008423268 0.04815936 -0.9988042 0 0.08246201 -0.9965943 -4.2727e-4 0.1644682 -0.9863823 4.2727e-4 -0.1644682 -0.9863823 0.005310297 -0.07995998 -0.9967839 0.008423268 -0.04815936 -0.9988042 0 -0.08246201 -0.9965943 9.15562e-5 0.1856759 -0.9826111 -1.22077e-4 0.3246021 -0.9458507 -0.005310297 0.07995998 -0.9967839 1.22075e-4 0.3258797 -0.9454113 -1.22074e-4 0.4758151 -0.8795453 9.15572e-5 0.4768602 -0.8789792 -6.10383e-5 0.5977172 -0.801707 0.002349972 0.6132943 -0.789851 3.35716e-4 0.6771689 -0.7358276 0.00463891 0.7357613 -0.6772251 0 0.735886 -0.6771055 3.35708e-4 0.7896775 -0.6135222 0.002410948 0.8379305 -0.5457718 -1.52593e-4 0.8489382 -0.5284921 1.83116e-4 0.9155188 -0.4022753 -3.05192e-4 0.9165219 -0.3999845 2.74672e-4 0.9691033 -0.2466553 -3.66227e-4 0.9699213 -0.2434187 3.66227e-4 0.9964436 -0.08426278 -3.66228e-4 0.9967514 -0.0805397 3.66228e-4 0.9967514 0.0805397 -3.66227e-4 0.9964436 0.08426278 3.66227e-4 0.9699213 0.2434187 -2.74672e-4 0.9691033 0.2466553 3.05192e-4 0.9165219 0.3999845 -1.83116e-4 0.9155188 0.4022753 1.52593e-4 0.8489382 0.5284921 -0.002410948 0.8379305 0.5457718 -3.35708e-4 0.7896775 0.6135222 -0.00463891 0.7357613 0.6772251 -3.35716e-4 0.6771689 0.7358276 -0.002349972 0.6132943 0.789851 0 0.735886 0.6771055 6.10383e-5 0.5977172 0.801707 -9.15572e-5 0.4768602 0.8789792 1.22074e-4 0.4758151 0.8795453 -1.22075e-4 0.3258797 0.9454113 1.22077e-4 0.3246021 0.9458507 -9.15562e-5 0.1856759 0.9826111 4.2727e-4 0.1644682 0.9863823 0.005310297 0.07995998 0.9967839 0.008423268 0.04815936 0.9988042 -0.008423268 -0.04815936 0.9988042 0 -0.08246201 0.9965943 -4.2727e-4 -0.1644682 0.9863823 0 0.08246201 0.9965943 9.15562e-5 -0.1856759 0.9826111 -1.22077e-4 -0.3246021 0.9458507 -0.005310297 -0.07995998 0.9967839 1.22075e-4 -0.3258797 0.9454113 -1.22074e-4 -0.4758151 0.8795453 9.15572e-5 -0.4768602 0.8789792 -6.10383e-5 -0.5977172 0.801707 0.002349972 -0.6132943 0.789851 3.35716e-4 -0.6771689 0.7358276 0.00463891 -0.7357613 0.6772251 0 -0.735886 0.6771055 3.35708e-4 -0.7896775 0.6135222 0.002410948 -0.8379305 0.5457718 -1.52593e-4 -0.8489382 0.5284921 1.83116e-4 -0.9155188 0.4022753 -3.05192e-4 -0.9165219 0.3999845 2.74672e-4 -0.9691033 0.2466553 -3.66227e-4 -0.9699213 0.2434187 3.66227e-4 -0.9964436 0.08426278 -3.66228e-4 -0.9967514 0.0805397 3.66228e-4 -0.9967514 -0.0805397 -3.66227e-4 -0.9964436 -0.08426278 3.66227e-4 -0.9699213 -0.2434187 -2.74672e-4 -0.9691033 -0.2466553 3.05192e-4 -0.9165219 -0.3999845 -1.83116e-4 -0.9155188 -0.4022753 1.52593e-4 -0.8489382 -0.5284921 -0.002410948 -0.8379305 -0.5457718 -3.35708e-4 -0.7896775 -0.6135222 -0.00463891 -0.7357613 -0.6772251 -3.35716e-4 -0.6771689 -0.7358276 -0.002349972 -0.6132943 -0.789851 0 -0.735886 -0.6771055 6.10383e-5 -0.5977172 -0.801707 -9.15572e-5 -0.4768602 -0.8789792 1.22074e-4 -0.4758151 -0.8795453 -1.22075e-4 -0.3258797 -0.9454113 1.22077e-4 -0.3246021 -0.9458507 -9.15562e-5 -0.1856759 -0.9826111 1 1.02955e-6 0 1 1.97421e-6 0 1 1.05891e-6 0 1 -1.97421e-6 0 1 -1.2949e-6 0 1 -2.58141e-6 0 1 2.25697e-6 0 1 7.45433e-7 0 1 2.66744e-6 0 1 2.03628e-6 0 1 -6.45357e-6 0 1 -4.41354e-6 0 1 -1.41469e-6 0 1 1.08918e-5 0 1 2.82806e-6 0 1 1.21768e-5 0 1 -6.14147e-6 0 1 -9.02887e-6 0 1 -1.05891e-6 0 1 1.2949e-6 0 1 2.58142e-6 0 1 -2.25697e-6 0 1 -7.45431e-7 0 1 -2.66744e-6 0 1 -2.03628e-6 0 1 6.45357e-6 0 1 4.41355e-6 0 1 1.41469e-6 0 1 -1.08918e-5 0 1 -2.82806e-6 0 1 -1.21768e-5 0 1 6.14148e-6 0 1 9.02896e-6 0 1.95298e-6 0 1 4.08918e-6 0 1 -4.08918e-6 0 1 6.16861e-6 0 1 -2.52272e-6 0 1 -0.8660254 0.5000002 0 -0.4999665 0.8660449 0 -0.5660923 0.824342 0 -0.9931306 0.1170112 0 -0.9969457 0.07809907 0 -0.8660259 0.499999 0 -1 0 0 -0.9969457 -0.07809907 0 -0.9931271 -0.1170413 0 -0.8660254 -0.5000002 0 -0.5661622 -0.8242939 0 -0.5000254 -0.8660107 0 -0.8660259 -0.499999 0 -0.4308053 -0.9024449 0 0.4308053 -0.9024449 0 0.5000254 -0.8660107 0 0.5661622 -0.8242939 0 0.8660254 -0.5000002 0 0.9931271 -0.1170413 0 0.9969457 -0.07809907 0 0.8660259 -0.499999 0 0.9969457 0.07809907 0 0.9931306 0.1170112 0 0.8660254 0.5000002 0 0.5660923 0.824342 0 0.4999665 0.8660449 0 0.8660259 0.499999 0 0.4308053 0.9024449 0 -0.4308053 0.9024449 0 -3.87765e-6 0 1 -9.70233e-6 0 1 3.99233e-6 0 1 1.1969e-5 0 1 -7.0375e-6 0 1 5.73566e-6 0 1 9.70252e-6 0 1 -9.09058e-6 0 1 4.94315e-4 0 1 4.36392e-6 0 1 -3.99208e-6 0 1 -3.98928e-6 0 1 -2.86816e-6 0 1 9.48992e-5 0 1 0.9858715 0.1595815 -0.05090492 0.9749147 0.2225787 0 0.8996222 0.4365808 -0.008789598 0.8996101 -0.4366055 0.008789479 0.9789318 -0.1965737 0.05523961 0.9858705 -0.1595863 0.05090647 0.9749147 -0.2225787 0 0.8747642 0.4845491 9.15568e-5 0.6235108 0.7818148 -2.13636e-4 0.978936 0.1965441 -0.05527037 0.6227988 0.7823821 1.52594e-4 0.2228173 0.9748602 -1.83112e-4 0.2219944 0.975048 1.52594e-4 -0.2219944 0.975048 -1.52594e-4 -0.2228173 0.9748602 1.83112e-4 -0.6227988 0.7823821 -1.52594e-4 -0.6235108 0.7818148 2.13636e-4 -0.8747642 0.4845491 -9.15568e-5 -0.8996222 0.4365808 0.008789598 -0.978936 0.1965441 0.05527037 -0.9858715 0.1595815 0.05090492 -0.9858705 -0.1595863 -0.05090647 -0.9749147 -0.2225787 0 -0.8996101 -0.4366055 -0.008789479 -0.9749147 0.2225787 0 -0.8747642 -0.4845491 9.15568e-5 -0.6235294 -0.7817999 -2.13632e-4 -0.9789318 -0.1965737 -0.05523961 -0.6227988 -0.7823821 1.52594e-4 -0.2228173 -0.9748602 -1.83112e-4 -0.2219944 -0.975048 1.52594e-4 0.2219944 -0.975048 -1.52594e-4 0.2228173 -0.9748602 1.83112e-4 0.6227988 -0.7823821 -1.52594e-4 0.6235294 -0.7817999 2.13632e-4 0.8747642 -0.4845491 -9.15568e-5 -2.56353e-5 0 1 1.31445e-5 0 1 2.56371e-5 0 1 -5.54994e-6 0 1 0.965938 0.2587737 1.52597e-4 0.9660031 0.2585306 0 0.8969641 0.4421035 0 0.8969641 -0.4421035 0 0.8729753 -0.4873939 -0.01901352 0.965938 -0.2587737 -1.52597e-4 0.9660031 -0.2585306 0 0.8729753 0.4873939 0.01901352 0.7067351 0.7074066 0.01007133 0.5005141 0.8649128 0.03756904 0.4982016 0.8670613 0 0.256973 0.9663652 0.01016294 0.0534687 0.998388 0.01904362 -0.0534687 0.998388 -0.01904362 -0.256973 0.9663652 -0.01016294 -0.5005141 0.8649128 -0.03756904 -0.7067351 0.7074066 -0.01007133 -0.8729753 0.4873939 -0.01901352 -0.4982016 0.8670613 0 -0.8969641 0.4421035 0 -0.965938 0.2587737 -1.52597e-4 -0.965938 -0.2587737 1.52597e-4 -0.9660031 -0.2585306 0 -0.8969641 -0.4421035 0 -0.9660031 0.2585306 0 -0.8729753 -0.4873939 0.01901352 -0.7067351 -0.7074066 0.01007133 -0.5005141 -0.8649128 0.03756904 -0.4982016 -0.8670613 0 -0.256973 -0.9663652 0.01016294 -0.0534687 -0.998388 0.01904362 0.0534687 -0.998388 -0.01904362 0.256973 -0.9663652 -0.01016294 0.5005141 -0.8649128 -0.03756904 0.7067351 -0.7074066 -0.01007133 0.4982016 -0.8670613 0 5.2004e-6 0 1 3.0045e-6 0 1 -1.03559e-5 0 1 5.17794e-6 0 1 -7.18928e-6 0 1 + + + + + + + + + + 0.168547 0.426867 0.141981 0.464168 0.16604 0.464168 0.143157 0.507913 0.16604 0.464168 0.141981 0.464168 0.09109896 0.433505 0.168547 0.426867 0.16604 0.464168 0.08998799 0.464168 0.09109896 0.433505 0.16604 0.464168 0.168338 0.499887 0.08998799 0.464168 0.16604 0.464168 0.168338 0.499887 0.16604 0.464168 0.143157 0.507913 0.168547 0.426867 0.142284 0.441947 0.141981 0.464168 0.143157 0.507913 0.141981 0.464168 0.142284 0.441947 0.168547 0.426867 0.143173 0.420147 0.142284 0.441947 0.143157 0.507913 0.142284 0.441947 0.143173 0.420147 0.1766549 0.388019 0.146665 0.378283 0.143173 0.420147 0.146624 0.549698 0.143173 0.420147 0.146665 0.378283 0.168547 0.426867 0.1766549 0.388019 0.143173 0.420147 0.143157 0.507913 0.143173 0.420147 0.146624 0.549698 0.190195 0.350796 0.15222 0.340457 0.146665 0.378283 0.150132 0.44292 0.146665 0.378283 0.15222 0.340457 0.1766549 0.388019 0.190195 0.350796 0.146665 0.378283 0.150106 0.484456 0.146624 0.549698 0.146665 0.378283 0.150132 0.44292 0.150106 0.484456 0.146665 0.378283 0.209464 0.315026 0.159465 0.308135 0.15222 0.340457 0.152423 0.402474 0.15222 0.340457 0.159465 0.308135 0.190195 0.350796 0.209464 0.315026 0.15222 0.340457 0.152423 0.402474 0.150132 0.44292 0.15222 0.340457 0.238286 0.267285 0.168123 0.281727 0.159465 0.308135 0.163079 0.332085 0.159465 0.308135 0.168123 0.281727 0.234534 0.281547 0.238286 0.267285 0.159465 0.308135 0.209464 0.315026 0.234534 0.281547 0.159465 0.308135 0.156827 0.365011 0.152423 0.402474 0.159465 0.308135 0.163079 0.332085 0.156827 0.365011 0.159465 0.308135 0.246377 0.244359 0.177721 0.261935 0.168123 0.281727 0.17083 0.304808 0.168123 0.281727 0.177721 0.261935 0.242249 0.254885 0.246377 0.244359 0.168123 0.281727 0.238286 0.267285 0.242249 0.254885 0.168123 0.281727 0.17083 0.304808 0.163079 0.332085 0.168123 0.281727 0.254945 0.228855 0.187831 0.2488099 0.177721 0.261935 0.179678 0.283856 0.177721 0.261935 0.187831 0.2488099 0.250623 0.235694 0.254945 0.228855 0.177721 0.261935 0.246377 0.244359 0.250623 0.235694 0.177721 0.261935 0.179678 0.283856 0.17083 0.304808 0.177721 0.261935 0.263659 0.220435 0.198088 0.242057 0.187831 0.2488099 0.189107 0.269592 0.187831 0.2488099 0.198088 0.242057 0.259302 0.22379 0.263659 0.220435 0.187831 0.2488099 0.254945 0.228855 0.259302 0.22379 0.187831 0.2488099 0.189107 0.269592 0.179678 0.283856 0.187831 0.2488099 0.272239 0.2185479 0.208182 0.241217 0.198088 0.242057 0.198875 0.261648 0.198088 0.242057 0.208182 0.241217 0.267981 0.218715 0.272239 0.2185479 0.198088 0.242057 0.263659 0.220435 0.267981 0.218715 0.198088 0.242057 0.198875 0.261648 0.189107 0.269592 0.198088 0.242057 0.280463 0.222536 0.2178609 0.245746 0.208182 0.241217 0.208608 0.259786 0.208182 0.241217 0.2178609 0.245746 0.276408 0.219851 0.280463 0.222536 0.208182 0.241217 0.272239 0.2185479 0.276408 0.219851 0.208182 0.241217 0.208608 0.259786 0.198875 0.261648 0.208182 0.241217 0.288163 0.231705 0.226929 0.25506 0.2178609 0.245746 0.2179909 0.263531 0.2178609 0.245746 0.226929 0.25506 0.284387 0.226516 0.288163 0.231705 0.2178609 0.245746 0.280463 0.222536 0.284387 0.226516 0.2178609 0.245746 0.213342 0.260991 0.2178609 0.245746 0.2179909 0.263531 0.213342 0.260991 0.208608 0.259786 0.2178609 0.245746 0.295221 0.245373 0.235242 0.268577 0.226929 0.25506 0.2347469 0.285269 0.226929 0.25506 0.235242 0.268577 0.291778 0.238018 0.295221 0.245373 0.226929 0.25506 0.288163 0.231705 0.291778 0.238018 0.226929 0.25506 0.226733 0.272218 0.2179909 0.263531 0.226929 0.25506 0.2347469 0.285269 0.226733 0.272218 0.226929 0.25506 0.301558 0.262894 0.242697 0.285734 0.235242 0.268577 0.241888 0.302042 0.235242 0.268577 0.242697 0.285734 0.298483 0.25369 0.301558 0.262894 0.235242 0.268577 0.295221 0.245373 0.298483 0.25369 0.235242 0.268577 0.241888 0.302042 0.2347469 0.285269 0.235242 0.268577 0.30444 0.272911 0.246078 0.29551 0.242697 0.285734 0.241888 0.302042 0.242697 0.285734 0.246078 0.29551 0.301558 0.262894 0.30444 0.272911 0.242697 0.285734 0.307126 0.28367 0.249221 0.30599 0.246078 0.29551 0.248057 0.321857 0.246078 0.29551 0.249221 0.30599 0.30444 0.272911 0.307126 0.28367 0.246078 0.29551 0.248057 0.321857 0.241888 0.302042 0.246078 0.29551 0.309614 0.295106 0.252119 0.317123 0.249221 0.30599 0.250798 0.33287 0.249221 0.30599 0.252119 0.317123 0.307126 0.28367 0.309614 0.295106 0.249221 0.30599 0.250798 0.33287 0.248057 0.321857 0.249221 0.30599 0.311901 0.307154 0.254769 0.328827 0.252119 0.317123 0.253291 0.344484 0.252119 0.317123 0.254769 0.328827 0.309614 0.295106 0.311901 0.307154 0.252119 0.317123 0.253291 0.344484 0.250798 0.33287 0.252119 0.317123 0.313988 0.319753 0.257165 0.341052 0.254769 0.328827 0.255519 0.356607 0.254769 0.328827 0.257165 0.341052 0.311901 0.307154 0.313988 0.319753 0.254769 0.328827 0.255519 0.356607 0.253291 0.344484 0.254769 0.328827 0.315873 0.332844 0.259304 0.353692 0.257165 0.341052 0.257485 0.369174 0.257165 0.341052 0.259304 0.353692 0.313988 0.319753 0.315873 0.332844 0.257165 0.341052 0.257485 0.369174 0.255519 0.356607 0.257165 0.341052 0.319041 0.360281 0.262794 0.379889 0.259304 0.353692 0.260625 0.39539 0.259304 0.353692 0.262794 0.379889 0.317557 0.346371 0.319041 0.360281 0.259304 0.353692 0.315873 0.332844 0.317557 0.346371 0.259304 0.353692 0.260625 0.39539 0.257485 0.369174 0.259304 0.353692 0.321409 0.389041 0.265298 0.407368 0.262794 0.379889 0.263741 0.450489 0.262794 0.379889 0.265298 0.407368 0.320324 0.374521 0.321409 0.389041 0.262794 0.379889 0.319041 0.360281 0.320324 0.374521 0.262794 0.379889 0.262708 0.422645 0.260625 0.39539 0.262794 0.379889 0.263741 0.450489 0.262708 0.422645 0.262794 0.379889 0.322984 0.418727 0.266798 0.435612 0.265298 0.407368 0.266792 0.492908 0.265298 0.407368 0.266798 0.435612 0.322295 0.403792 0.322984 0.418727 0.265298 0.407368 0.321409 0.389041 0.322295 0.403792 0.265298 0.407368 0.26528 0.521216 0.265298 0.407368 0.266792 0.492908 0.263741 0.450489 0.265298 0.407368 0.26528 0.521216 0.323868 0.464168 0.267297 0.464168 0.266798 0.435612 0.267169 0.478612 0.266798 0.435612 0.267297 0.464168 0.323769 0.448961 0.323868 0.464168 0.266798 0.435612 0.323475 0.433798 0.323769 0.448961 0.266798 0.435612 0.322984 0.418727 0.323475 0.433798 0.266798 0.435612 0.266792 0.492908 0.266798 0.435612 0.267169 0.478612 0.323769 0.479376 0.267297 0.464168 0.323868 0.464168 0.267169 0.478612 0.267297 0.464168 0.323769 0.479376 0.353653 0.464168 0.323868 0.464168 0.323769 0.448961 0.3534 0.492191 0.323868 0.464168 0.353653 0.464168 0.3534 0.492191 0.323769 0.479376 0.323868 0.464168 0.3534 0.436146 0.323769 0.448961 0.323475 0.433798 0.3534 0.436146 0.353653 0.464168 0.323769 0.448961 0.3534 0.436146 0.323475 0.433798 0.322984 0.418727 0.352639 0.408346 0.322984 0.418727 0.322295 0.403792 0.352639 0.408346 0.3534 0.436146 0.322984 0.418727 0.352639 0.408346 0.322295 0.403792 0.321409 0.389041 0.351366 0.380996 0.321409 0.389041 0.320324 0.374521 0.351366 0.380996 0.352639 0.408346 0.321409 0.389041 0.349578 0.35433 0.320324 0.374521 0.319041 0.360281 0.349578 0.35433 0.351366 0.380996 0.320324 0.374521 0.349578 0.35433 0.319041 0.360281 0.317557 0.346371 0.347267 0.328593 0.317557 0.346371 0.315873 0.332844 0.347267 0.328593 0.349578 0.35433 0.317557 0.346371 0.347267 0.328593 0.315873 0.332844 0.313988 0.319753 0.344426 0.30405 0.313988 0.319753 0.311901 0.307154 0.344426 0.30405 0.347267 0.328593 0.313988 0.319753 0.341048 0.280981 0.311901 0.307154 0.309614 0.295106 0.341048 0.280981 0.344426 0.30405 0.311901 0.307154 0.341048 0.280981 0.309614 0.295106 0.307126 0.28367 0.33713 0.259696 0.307126 0.28367 0.30444 0.272911 0.33713 0.259696 0.341048 0.280981 0.307126 0.28367 0.33713 0.259696 0.30444 0.272911 0.301558 0.262894 0.332673 0.24053 0.301558 0.262894 0.298483 0.25369 0.332673 0.24053 0.33713 0.259696 0.301558 0.262894 0.327684 0.223854 0.298483 0.25369 0.295221 0.245373 0.327684 0.223854 0.332673 0.24053 0.298483 0.25369 0.327684 0.223854 0.295221 0.245373 0.291778 0.238018 0.322182 0.210075 0.291778 0.238018 0.288163 0.231705 0.322182 0.210075 0.327684 0.223854 0.291778 0.238018 0.322182 0.210075 0.288163 0.231705 0.284387 0.226516 0.316201 0.1996369 0.284387 0.226516 0.280463 0.222536 0.316201 0.1996369 0.322182 0.210075 0.284387 0.226516 0.316201 0.1996369 0.280463 0.222536 0.276408 0.219851 0.309791 0.1930209 0.276408 0.219851 0.272239 0.2185479 0.309791 0.1930209 0.316201 0.1996369 0.276408 0.219851 0.303031 0.190735 0.272239 0.2185479 0.267981 0.218715 0.303031 0.190735 0.309791 0.1930209 0.272239 0.2185479 0.303031 0.190735 0.267981 0.218715 0.263659 0.220435 0.296025 0.193304 0.263659 0.220435 0.259302 0.22379 0.296025 0.193304 0.303031 0.190735 0.263659 0.220435 0.296025 0.193304 0.259302 0.22379 0.254945 0.228855 0.28891 0.201242 0.254945 0.228855 0.250623 0.235694 0.28891 0.201242 0.296025 0.193304 0.254945 0.228855 0.281856 0.215011 0.250623 0.235694 0.246377 0.244359 0.281856 0.215011 0.28891 0.201242 0.250623 0.235694 0.281856 0.215011 0.246377 0.244359 0.242249 0.254885 0.274962 0.234896 0.242249 0.254885 0.238286 0.267285 0.281856 0.215011 0.242249 0.254885 0.274962 0.234896 0.255748 0.254707 0.238286 0.267285 0.234534 0.281547 0.274962 0.234896 0.238286 0.267285 0.255748 0.254707 0.16039 0.232811 0.234534 0.281547 0.209464 0.315026 0.179038 0.207861 0.255748 0.254707 0.234534 0.281547 0.16039 0.232811 0.179038 0.207861 0.234534 0.281547 0.129774 0.285984 0.209464 0.315026 0.190195 0.350796 0.144001 0.25885 0.16039 0.232811 0.209464 0.315026 0.129774 0.285984 0.144001 0.25885 0.209464 0.315026 0.107684 0.343274 0.190195 0.350796 0.1766549 0.388019 0.117648 0.314212 0.129774 0.285984 0.190195 0.350796 0.107684 0.343274 0.117648 0.314212 0.190195 0.350796 0.09994399 0.372982 0.1766549 0.388019 0.168547 0.426867 0.09994399 0.372982 0.107684 0.343274 0.1766549 0.388019 0.09440398 0.403153 0.09994399 0.372982 0.168547 0.426867 0.09109896 0.433505 0.09440398 0.403153 0.168547 0.426867 0.199791 0.184312 0.274962 0.234896 0.255748 0.254707 0.179038 0.207861 0.199791 0.184312 0.255748 0.254707 0.222553 0.162441 0.28051 0.229799 0.274962 0.234896 0.281856 0.215011 0.274962 0.234896 0.28051 0.229799 0.199791 0.184312 0.222553 0.162441 0.274962 0.234896 0.247205 0.142373 0.308761 0.207342 0.28051 0.229799 0.281856 0.215011 0.28051 0.229799 0.308761 0.207342 0.222553 0.162441 0.247205 0.142373 0.28051 0.229799 0.273624 0.124296 0.320742 0.1993319 0.308761 0.207342 0.281856 0.215011 0.308761 0.207342 0.320742 0.1993319 0.247205 0.142373 0.273624 0.124296 0.308761 0.207342 0.273624 0.124296 0.340349 0.187869 0.320742 0.1993319 0.371386 0.169657 0.320742 0.1993319 0.340349 0.187869 0.327189 0.181913 0.281856 0.215011 0.320742 0.1993319 0.327189 0.181913 0.320742 0.1993319 0.371386 0.169657 0.331122 0.09460496 0.383976 0.169753 0.340349 0.187869 0.371386 0.169657 0.340349 0.187869 0.383976 0.169753 0.301652 0.108325 0.331122 0.09460496 0.340349 0.187869 0.273624 0.124296 0.301652 0.108325 0.340349 0.187869 0.393544 0.07431197 0.430021 0.158322 0.383976 0.169753 0.38208 0.164475 0.383976 0.169753 0.430021 0.158322 0.361826 0.08322995 0.393544 0.07431197 0.383976 0.169753 0.331122 0.09460496 0.361826 0.08322995 0.383976 0.169753 0.371386 0.169657 0.383976 0.169753 0.38208 0.164475 0.45903 0.06407898 0.477354 0.153809 0.430021 0.158322 0.424481 0.148683 0.430021 0.158322 0.477354 0.153809 0.426031 0.067905 0.45903 0.06407898 0.430021 0.158322 0.393544 0.07431197 0.426031 0.067905 0.430021 0.158322 0.38208 0.164475 0.430021 0.158322 0.424481 0.148683 0.525488 0.06422799 0.524559 0.15625 0.477354 0.153809 0.472402 0.1389 0.477354 0.153809 0.524559 0.15625 0.492274 0.06284499 0.525488 0.06422799 0.477354 0.153809 0.45903 0.06407898 0.492274 0.06284499 0.477354 0.153809 0.426501 0.148106 0.477354 0.153809 0.472402 0.1389 0.424481 0.148683 0.477354 0.153809 0.426501 0.148106 0.590749 0.07471299 0.570424 0.165427 0.524559 0.15625 0.518568 0.136789 0.524559 0.15625 0.570424 0.165427 0.558403 0.06819099 0.590749 0.07471299 0.524559 0.15625 0.525488 0.06422799 0.558403 0.06819099 0.524559 0.15625 0.477273 0.138346 0.524559 0.15625 0.518568 0.136789 0.472402 0.1389 0.524559 0.15625 0.477273 0.138346 0.622282 0.08371496 0.59253 0.172433 0.570424 0.165427 0.563848 0.141517 0.570424 0.165427 0.59253 0.172433 0.590749 0.07471299 0.622282 0.08371496 0.570424 0.165427 0.528728 0.13726 0.570424 0.165427 0.563848 0.141517 0.518568 0.136789 0.570424 0.165427 0.528728 0.13726 0.652761 0.09513098 0.613912 0.1809689 0.59253 0.172433 0.577795 0.14437 0.59253 0.172433 0.613912 0.1809689 0.622282 0.08371496 0.652761 0.09513098 0.59253 0.172433 0.563848 0.141517 0.59253 0.172433 0.577795 0.14437 0.681987 0.10885 0.634432 0.190953 0.613912 0.1809689 0.607211 0.152675 0.613912 0.1809689 0.634432 0.190953 0.652761 0.09513098 0.681987 0.10885 0.613912 0.1809689 0.577795 0.14437 0.613912 0.1809689 0.607211 0.152675 0.681987 0.10885 0.654051 0.20234 0.634432 0.190953 0.647786 0.169735 0.634432 0.190953 0.654051 0.20234 0.623571 0.158724 0.634432 0.190953 0.647786 0.169735 0.607211 0.152675 0.634432 0.190953 0.623571 0.158724 0.709765 0.124773 0.672737 0.215101 0.654051 0.20234 0.665365 0.1794289 0.654051 0.20234 0.672737 0.215101 0.681987 0.10885 0.709765 0.124773 0.654051 0.20234 0.647786 0.169735 0.654051 0.20234 0.665365 0.1794289 0.735943 0.142765 0.690353 0.229134 0.672737 0.215101 0.684882 0.192094 0.672737 0.215101 0.690353 0.229134 0.709765 0.124773 0.735943 0.142765 0.672737 0.215101 0.665365 0.1794289 0.672737 0.215101 0.684882 0.192094 0.76038 0.162712 0.7068 0.244336 0.690353 0.229134 0.702696 0.2056609 0.690353 0.229134 0.7068 0.244336 0.735943 0.142765 0.76038 0.162712 0.690353 0.229134 0.684882 0.192094 0.690353 0.229134 0.702696 0.2056609 0.782957 0.184441 0.72202 0.260627 0.7068 0.244336 0.717974 0.21909 0.7068 0.244336 0.72202 0.260627 0.76038 0.162712 0.782957 0.184441 0.7068 0.244336 0.702696 0.2056609 0.7068 0.244336 0.717974 0.21909 0.80357 0.207837 0.735953 0.27791 0.72202 0.260627 0.735249 0.236679 0.72202 0.260627 0.735953 0.27791 0.782957 0.184441 0.80357 0.207837 0.72202 0.260627 0.717974 0.21909 0.72202 0.260627 0.735249 0.236679 0.822117 0.232637 0.748563 0.296111 0.735953 0.27791 0.746736 0.250095 0.735953 0.27791 0.748563 0.296111 0.80357 0.207837 0.822117 0.232637 0.735953 0.27791 0.735249 0.236679 0.735953 0.27791 0.746736 0.250095 0.838448 0.258543 0.759815 0.315158 0.748563 0.296111 0.763075 0.272215 0.748563 0.296111 0.759815 0.315158 0.822117 0.232637 0.838448 0.258543 0.748563 0.296111 0.746736 0.250095 0.748563 0.296111 0.763075 0.272215 0.852653 0.285569 0.769663 0.33495 0.759815 0.315158 0.770367 0.283545 0.759815 0.315158 0.769663 0.33495 0.838448 0.258543 0.852653 0.285569 0.759815 0.315158 0.763075 0.272215 0.759815 0.315158 0.770367 0.283545 0.86479 0.313725 0.778064 0.355382 0.769663 0.33495 0.785566 0.311212 0.769663 0.33495 0.778064 0.355382 0.852653 0.285569 0.86479 0.313725 0.769663 0.33495 0.770367 0.283545 0.769663 0.33495 0.785566 0.311212 0.874786 0.34276 0.784998 0.376378 0.778064 0.355382 0.797678 0.339191 0.778064 0.355382 0.784998 0.376378 0.86479 0.313725 0.874786 0.34276 0.778064 0.355382 0.787026 0.314241 0.778064 0.355382 0.797678 0.339191 0.785566 0.311212 0.778064 0.355382 0.787026 0.314241 0.882575 0.372499 0.790438 0.397867 0.784998 0.376378 0.804683 0.359535 0.784998 0.376378 0.790438 0.397867 0.874786 0.34276 0.882575 0.372499 0.784998 0.376378 0.803039 0.354371 0.784998 0.376378 0.804683 0.359535 0.797678 0.339191 0.784998 0.376378 0.803039 0.354371 0.888164 0.402762 0.794351 0.419734 0.790438 0.397867 0.813228 0.392925 0.790438 0.397867 0.794351 0.419734 0.882575 0.372499 0.888164 0.402762 0.790438 0.397867 0.80958 0.376955 0.790438 0.397867 0.813228 0.392925 0.804683 0.359535 0.790438 0.397867 0.80958 0.376955 0.891503 0.433276 0.796711 0.441871 0.794351 0.419734 0.817225 0.416602 0.794351 0.419734 0.796711 0.441871 0.888164 0.402762 0.891503 0.433276 0.794351 0.419734 0.816053 0.408564 0.794351 0.419734 0.817225 0.416602 0.815379 0.404445 0.794351 0.419734 0.816053 0.408564 0.813228 0.392925 0.794351 0.419734 0.815379 0.404445 0.892637 0.464168 0.797503 0.464168 0.796711 0.441871 0.819791 0.443343 0.796711 0.441871 0.797503 0.464168 0.891503 0.433276 0.892637 0.464168 0.796711 0.441871 0.819112 0.433842 0.796711 0.441871 0.819791 0.443343 0.818248 0.424978 0.796711 0.441871 0.819112 0.433842 0.817225 0.416602 0.796711 0.441871 0.818248 0.424978 0.891526 0.494831 0.797503 0.464168 0.892637 0.464168 0.820325 0.456998 0.797503 0.464168 0.820396 0.464168 0.796711 0.486472 0.820396 0.464168 0.797503 0.464168 0.820119 0.450055 0.797503 0.464168 0.820325 0.456998 0.819791 0.443343 0.797503 0.464168 0.820119 0.450055 0.796711 0.486472 0.797503 0.464168 0.891526 0.494831 0.891526 0.494831 0.892637 0.464168 0.891503 0.433276 0.888221 0.525184 0.891503 0.433276 0.888164 0.402762 0.891526 0.494831 0.891503 0.433276 0.888221 0.525184 0.882682 0.555355 0.888164 0.402762 0.882575 0.372499 0.888221 0.525184 0.888164 0.402762 0.882682 0.555355 0.874941 0.585063 0.882575 0.372499 0.874786 0.34276 0.882682 0.555355 0.882575 0.372499 0.874941 0.585063 0.864978 0.614125 0.874786 0.34276 0.86479 0.313725 0.874941 0.585063 0.874786 0.34276 0.864978 0.614125 0.852851 0.642353 0.86479 0.313725 0.852653 0.285569 0.864978 0.614125 0.86479 0.313725 0.852851 0.642353 0.848447 0.464168 0.852653 0.285569 0.838448 0.258543 0.848447 0.464168 0.852851 0.642353 0.852653 0.285569 0.830588 0.350424 0.838448 0.258543 0.822117 0.232637 0.843984 0.406672 0.848447 0.464168 0.838448 0.258543 0.830588 0.350424 0.843984 0.406672 0.838448 0.258543 0.808396 0.296993 0.822117 0.232637 0.80357 0.207837 0.808396 0.296993 0.830588 0.350424 0.822117 0.232637 0.808396 0.296993 0.80357 0.207837 0.782957 0.184441 0.777812 0.2479439 0.782957 0.184441 0.76038 0.162712 0.777812 0.2479439 0.808396 0.296993 0.782957 0.184441 0.759273 0.225193 0.76038 0.162712 0.735943 0.142765 0.759273 0.225193 0.777812 0.2479439 0.76038 0.162712 0.716342 0.184466 0.735943 0.142765 0.709765 0.124773 0.738737 0.203938 0.759273 0.225193 0.735943 0.142765 0.716342 0.184466 0.738737 0.203938 0.735943 0.142765 0.692223 0.166882 0.709765 0.124773 0.681987 0.10885 0.692223 0.166882 0.716342 0.184466 0.709765 0.124773 0.692223 0.166882 0.681987 0.10885 0.652761 0.09513098 0.63943 0.137993 0.652761 0.09513098 0.622282 0.08371496 0.63943 0.137993 0.692223 0.166882 0.652761 0.09513098 0.63943 0.137993 0.622282 0.08371496 0.590749 0.07471299 0.581861 0.118227 0.590749 0.07471299 0.558403 0.06819099 0.581861 0.118227 0.63943 0.137993 0.590749 0.07471299 0.581861 0.118227 0.558403 0.06819099 0.525488 0.06422799 0.521334 0.108245 0.525488 0.06422799 0.492274 0.06284499 0.521334 0.108245 0.581861 0.118227 0.525488 0.06422799 0.459869 0.108362 0.492274 0.06284499 0.45903 0.06407898 0.459869 0.108362 0.521334 0.108245 0.492274 0.06284499 0.459869 0.108362 0.45903 0.06407898 0.426031 0.067905 0.399545 0.118536 0.426031 0.067905 0.393544 0.07431197 0.399545 0.118536 0.459869 0.108362 0.426031 0.067905 0.399545 0.118536 0.393544 0.07431197 0.361826 0.08322995 0.342342 0.13837 0.361826 0.08322995 0.331122 0.09460496 0.342342 0.13837 0.399545 0.118536 0.361826 0.08322995 0.342342 0.13837 0.331122 0.09460496 0.301652 0.108325 0.289973 0.167168 0.301652 0.108325 0.273624 0.124296 0.289973 0.167168 0.342342 0.13837 0.301652 0.108325 0.289973 0.167168 0.273624 0.124296 0.247205 0.142373 0.24382 0.204003 0.247205 0.142373 0.222553 0.162441 0.24382 0.204003 0.289973 0.167168 0.247205 0.142373 0.204963 0.247744 0.222553 0.162441 0.199791 0.184312 0.204963 0.247744 0.24382 0.204003 0.222553 0.162441 0.204963 0.247744 0.199791 0.184312 0.179038 0.207861 0.174439 0.296587 0.179038 0.207861 0.16039 0.232811 0.174439 0.296587 0.204963 0.247744 0.179038 0.207861 0.152193 0.349945 0.16039 0.232811 0.144001 0.25885 0.152193 0.349945 0.174439 0.296587 0.16039 0.232811 0.138697 0.406317 0.144001 0.25885 0.129774 0.285984 0.138697 0.406317 0.152193 0.349945 0.144001 0.25885 0.117835 0.614612 0.129774 0.285984 0.117648 0.314212 0.129972 0.642768 0.129774 0.285984 0.117835 0.614612 0.1341789 0.464168 0.129774 0.285984 0.129972 0.642768 0.135325 0.435047 0.138697 0.406317 0.129774 0.285984 0.1341789 0.464168 0.135325 0.435047 0.129774 0.285984 0.107839 0.585576 0.117648 0.314212 0.107684 0.343274 0.117835 0.614612 0.117648 0.314212 0.107839 0.585576 0.10005 0.555838 0.107684 0.343274 0.09994399 0.372982 0.107839 0.585576 0.107684 0.343274 0.10005 0.555838 0.09446197 0.525575 0.09994399 0.372982 0.09440398 0.403153 0.10005 0.555838 0.09994399 0.372982 0.09446197 0.525575 0.09112298 0.495061 0.09440398 0.403153 0.09109896 0.433505 0.09446197 0.525575 0.09440398 0.403153 0.09112298 0.495061 0.09112298 0.495061 0.09109896 0.433505 0.08998799 0.464168 0.09112298 0.495061 0.08998799 0.464168 0.168338 0.499887 0.354115 0.464168 0.353653 0.464168 0.3534 0.436146 0.384726 0.494784 0.353653 0.464168 0.354115 0.464168 0.384726 0.494784 0.3534 0.492191 0.353653 0.464168 0.384726 0.433553 0.3534 0.436146 0.352639 0.408346 0.384946 0.464168 0.3534 0.436146 0.384726 0.433553 0.354115 0.464168 0.3534 0.436146 0.384946 0.464168 0.384065 0.403177 0.352639 0.408346 0.351366 0.380996 0.384726 0.433553 0.352639 0.408346 0.384065 0.403177 0.382958 0.373286 0.351366 0.380996 0.349578 0.35433 0.384065 0.403177 0.351366 0.380996 0.382958 0.373286 0.381399 0.344133 0.349578 0.35433 0.347267 0.328593 0.382958 0.373286 0.349578 0.35433 0.381399 0.344133 0.37938 0.315987 0.347267 0.328593 0.344426 0.30405 0.381399 0.344133 0.347267 0.328593 0.37938 0.315987 0.376891 0.289138 0.344426 0.30405 0.341048 0.280981 0.37938 0.315987 0.344426 0.30405 0.376891 0.289138 0.373921 0.263903 0.341048 0.280981 0.33713 0.259696 0.376891 0.289138 0.341048 0.280981 0.373921 0.263903 0.370464 0.240629 0.33713 0.259696 0.332673 0.24053 0.373921 0.263903 0.33713 0.259696 0.370464 0.240629 0.366515 0.219705 0.332673 0.24053 0.327684 0.223854 0.370464 0.240629 0.332673 0.24053 0.366515 0.219705 0.362077 0.201562 0.327684 0.223854 0.322182 0.210075 0.366515 0.219705 0.327684 0.223854 0.362077 0.201562 0.357161 0.186686 0.322182 0.210075 0.316201 0.1996369 0.362077 0.201562 0.322182 0.210075 0.357161 0.186686 0.351795 0.175616 0.316201 0.1996369 0.309791 0.1930209 0.357161 0.186686 0.316201 0.1996369 0.351795 0.175616 0.346026 0.168946 0.309791 0.1930209 0.303031 0.190735 0.351795 0.175616 0.309791 0.1930209 0.346026 0.168946 0.339928 0.1673229 0.303031 0.190735 0.296025 0.193304 0.346026 0.168946 0.303031 0.190735 0.339928 0.1673229 0.333602 0.17142 0.296025 0.193304 0.28891 0.201242 0.339928 0.1673229 0.296025 0.193304 0.333602 0.17142 0.327189 0.181913 0.28891 0.201242 0.281856 0.215011 0.333602 0.17142 0.28891 0.201242 0.327189 0.181913 0.817463 0.464168 0.814787 0.464168 0.806829 0.464168 0.817345 0.469794 0.806829 0.464168 0.814787 0.464168 0.817345 0.458542 0.817463 0.464168 0.806829 0.464168 0.816993 0.453025 0.817345 0.458542 0.806829 0.464168 0.816415 0.447721 0.816993 0.453025 0.806829 0.464168 0.815623 0.44273 0.816415 0.447721 0.806829 0.464168 0.814633 0.438146 0.815623 0.44273 0.806829 0.464168 0.813465 0.434049 0.814633 0.438146 0.806829 0.464168 0.812144 0.430512 0.813465 0.434049 0.806829 0.464168 0.810694 0.427592 0.812144 0.430512 0.806829 0.464168 0.809145 0.425334 0.810694 0.427592 0.806829 0.464168 0.807525 0.423768 0.809145 0.425334 0.806829 0.464168 0.805864 0.422912 0.807525 0.423768 0.806829 0.464168 0.804192 0.42277 0.805864 0.422912 0.806829 0.464168 0.802536 0.423334 0.804192 0.42277 0.806829 0.464168 0.800925 0.424583 0.802536 0.423334 0.806829 0.464168 0.799385 0.426486 0.800925 0.424583 0.806829 0.464168 0.79794 0.429004 0.799385 0.426486 0.806829 0.464168 0.796612 0.432088 0.79794 0.429004 0.806829 0.464168 0.795421 0.435682 0.796612 0.432088 0.806829 0.464168 0.794384 0.439723 0.795421 0.435682 0.806829 0.464168 0.793515 0.444145 0.794384 0.439723 0.806829 0.464168 0.792827 0.448876 0.793515 0.444145 0.806829 0.464168 0.792329 0.453842 0.792827 0.448876 0.806829 0.464168 0.792027 0.458965 0.792329 0.453842 0.806829 0.464168 0.791926 0.464168 0.792027 0.458965 0.806829 0.464168 0.792027 0.469371 0.791926 0.464168 0.806829 0.464168 0.816993 0.475312 0.806829 0.464168 0.817345 0.469794 0.816415 0.480616 0.806829 0.464168 0.816993 0.475312 0.815623 0.485606 0.806829 0.464168 0.816415 0.480616 0.814633 0.490191 0.806829 0.464168 0.815623 0.485606 0.813465 0.494287 0.806829 0.464168 0.814633 0.490191 0.812144 0.497824 0.806829 0.464168 0.813465 0.494287 0.810694 0.500745 0.806829 0.464168 0.812144 0.497824 0.809145 0.503003 0.806829 0.464168 0.810694 0.500745 0.807525 0.504569 0.806829 0.464168 0.809145 0.503003 0.805864 0.505425 0.806829 0.464168 0.807525 0.504569 0.804192 0.505566 0.806829 0.464168 0.805864 0.505425 0.802536 0.505003 0.806829 0.464168 0.804192 0.505566 0.800925 0.503754 0.806829 0.464168 0.802536 0.505003 0.799385 0.50185 0.806829 0.464168 0.800925 0.503754 0.79794 0.499332 0.806829 0.464168 0.799385 0.50185 0.796612 0.496249 0.806829 0.464168 0.79794 0.499332 0.795421 0.492655 0.806829 0.464168 0.796612 0.496249 0.794384 0.488614 0.806829 0.464168 0.795421 0.492655 0.793515 0.484192 0.806829 0.464168 0.794384 0.488614 0.792827 0.479461 0.806829 0.464168 0.793515 0.484192 0.792329 0.474495 0.806829 0.464168 0.792827 0.479461 0.792027 0.469371 0.806829 0.464168 0.792329 0.474495 0.817345 0.469794 0.814787 0.464168 0.817463 0.464168 0.820396 0.464168 0.817463 0.464168 0.817345 0.458542 0.82032 0.47156 0.817463 0.464168 0.820396 0.464168 0.817345 0.469794 0.817463 0.464168 0.82032 0.47156 0.820119 0.450055 0.817345 0.458542 0.816993 0.453025 0.820325 0.456998 0.820396 0.464168 0.817345 0.458542 0.820119 0.450055 0.820325 0.456998 0.817345 0.458542 0.819791 0.443343 0.816993 0.453025 0.816415 0.447721 0.819791 0.443343 0.820119 0.450055 0.816993 0.453025 0.819112 0.433842 0.816415 0.447721 0.815623 0.44273 0.819112 0.433842 0.819791 0.443343 0.816415 0.447721 0.818248 0.424978 0.815623 0.44273 0.814633 0.438146 0.818248 0.424978 0.819112 0.433842 0.815623 0.44273 0.816053 0.408564 0.814633 0.438146 0.813465 0.434049 0.817225 0.416602 0.818248 0.424978 0.814633 0.438146 0.816053 0.408564 0.817225 0.416602 0.814633 0.438146 0.812768 0.397212 0.813465 0.434049 0.812144 0.430512 0.815379 0.404445 0.816053 0.408564 0.813465 0.434049 0.812768 0.397212 0.815379 0.404445 0.813465 0.434049 0.809837 0.391217 0.812144 0.430512 0.810694 0.427592 0.809837 0.391217 0.812768 0.397212 0.812144 0.430512 0.806713 0.386657 0.810694 0.427592 0.809145 0.425334 0.806713 0.386657 0.809837 0.391217 0.810694 0.427592 0.803463 0.383577 0.809145 0.425334 0.807525 0.423768 0.803463 0.383577 0.806713 0.386657 0.809145 0.425334 0.80015 0.381991 0.807525 0.423768 0.805864 0.422912 0.80015 0.381991 0.803463 0.383577 0.807525 0.423768 0.796837 0.38188 0.805864 0.422912 0.804192 0.42277 0.796837 0.38188 0.80015 0.381991 0.805864 0.422912 0.793582 0.383202 0.804192 0.42277 0.802536 0.423334 0.793582 0.383202 0.796837 0.38188 0.804192 0.42277 0.790441 0.38589 0.802536 0.423334 0.800925 0.424583 0.790441 0.38589 0.793582 0.383202 0.802536 0.423334 0.787461 0.389861 0.800925 0.424583 0.799385 0.426486 0.787461 0.389861 0.790441 0.38589 0.800925 0.424583 0.784687 0.395016 0.799385 0.426486 0.79794 0.429004 0.784687 0.395016 0.787461 0.389861 0.799385 0.426486 0.782155 0.401245 0.79794 0.429004 0.796612 0.432088 0.782155 0.401245 0.784687 0.395016 0.79794 0.429004 0.7799 0.408427 0.796612 0.432088 0.795421 0.435682 0.7799 0.408427 0.782155 0.401245 0.796612 0.432088 0.777947 0.416436 0.795421 0.435682 0.794384 0.439723 0.777947 0.416436 0.7799 0.408427 0.795421 0.435682 0.776321 0.425141 0.794384 0.439723 0.793515 0.444145 0.776321 0.425141 0.777947 0.416436 0.794384 0.439723 0.775038 0.434405 0.793515 0.444145 0.792827 0.448876 0.775038 0.434405 0.776321 0.425141 0.793515 0.444145 0.774112 0.444091 0.792827 0.448876 0.792329 0.453842 0.774112 0.444091 0.775038 0.434405 0.792827 0.448876 0.773553 0.454059 0.792329 0.453842 0.792027 0.458965 0.773553 0.454059 0.774112 0.444091 0.792329 0.453842 0.773553 0.454059 0.792027 0.458965 0.791926 0.464168 0.773553 0.454059 0.791926 0.464168 0.773366 0.464168 0.792027 0.469371 0.773366 0.464168 0.791926 0.464168 0.751967 0.449664 0.773553 0.454059 0.773366 0.464168 0.751967 0.449664 0.773366 0.464168 0.751718 0.464168 0.773547 0.474108 0.751718 0.464168 0.773366 0.464168 0.773547 0.474108 0.773366 0.464168 0.792027 0.469371 0.796711 0.486472 0.82032 0.47156 0.820396 0.464168 0.813228 0.392925 0.815379 0.404445 0.812768 0.397212 0.80958 0.376955 0.812768 0.397212 0.809837 0.391217 0.80958 0.376955 0.813228 0.392925 0.812768 0.397212 0.798351 0.347673 0.809837 0.391217 0.806713 0.386657 0.804683 0.359535 0.80958 0.376955 0.809837 0.391217 0.803039 0.354371 0.804683 0.359535 0.809837 0.391217 0.798351 0.347673 0.803039 0.354371 0.809837 0.391217 0.793595 0.343623 0.806713 0.386657 0.803463 0.383577 0.793595 0.343623 0.798351 0.347673 0.806713 0.386657 0.788795 0.341846 0.803463 0.383577 0.80015 0.381991 0.788795 0.341846 0.793595 0.343623 0.803463 0.383577 0.784044 0.34227 0.80015 0.381991 0.796837 0.38188 0.784044 0.34227 0.788795 0.341846 0.80015 0.381991 0.779423 0.344787 0.796837 0.38188 0.793582 0.383202 0.779423 0.344787 0.784044 0.34227 0.796837 0.38188 0.775005 0.349263 0.793582 0.383202 0.790441 0.38589 0.775005 0.349263 0.779423 0.344787 0.793582 0.383202 0.770854 0.355546 0.790441 0.38589 0.787461 0.389861 0.770854 0.355546 0.775005 0.349263 0.790441 0.38589 0.767022 0.363468 0.787461 0.389861 0.784687 0.395016 0.767022 0.363468 0.770854 0.355546 0.787461 0.389861 0.763554 0.372854 0.784687 0.395016 0.782155 0.401245 0.763554 0.372854 0.767022 0.363468 0.784687 0.395016 0.760487 0.383522 0.782155 0.401245 0.7799 0.408427 0.760487 0.383522 0.763554 0.372854 0.782155 0.401245 0.757848 0.395289 0.7799 0.408427 0.777947 0.416436 0.757848 0.395289 0.760487 0.383522 0.7799 0.408427 0.755662 0.407971 0.777947 0.416436 0.776321 0.425141 0.755662 0.407971 0.757848 0.395289 0.777947 0.416436 0.753946 0.421383 0.776321 0.425141 0.775038 0.434405 0.753946 0.421383 0.755662 0.407971 0.776321 0.425141 0.752711 0.435342 0.775038 0.434405 0.774112 0.444091 0.752711 0.435342 0.753946 0.421383 0.775038 0.434405 0.751967 0.449664 0.774112 0.444091 0.773553 0.454059 0.751967 0.449664 0.752711 0.435342 0.774112 0.444091 0.727766 0.445456 0.751967 0.449664 0.751718 0.464168 0.727766 0.445456 0.751718 0.464168 0.72747 0.464168 0.751939 0.477845 0.72747 0.464168 0.751718 0.464168 0.773547 0.474108 0.751939 0.477845 0.751718 0.464168 0.797678 0.339191 0.803039 0.354371 0.798351 0.347673 0.779327 0.30554 0.798351 0.347673 0.793595 0.343623 0.787026 0.314241 0.797678 0.339191 0.798351 0.347673 0.785566 0.311212 0.787026 0.314241 0.798351 0.347673 0.779327 0.30554 0.785566 0.311212 0.798351 0.347673 0.773201 0.303344 0.793595 0.343623 0.788795 0.341846 0.773201 0.303344 0.779327 0.30554 0.793595 0.343623 0.767176 0.304146 0.788795 0.341846 0.784044 0.34227 0.767176 0.304146 0.773201 0.303344 0.788795 0.341846 0.761359 0.30775 0.784044 0.34227 0.779423 0.344787 0.761359 0.30775 0.767176 0.304146 0.784044 0.34227 0.755839 0.313934 0.779423 0.344787 0.775005 0.349263 0.755839 0.313934 0.761359 0.30775 0.779423 0.344787 0.75069 0.322457 0.775005 0.349263 0.770854 0.355546 0.75069 0.322457 0.755839 0.313934 0.775005 0.349263 0.745973 0.333071 0.770854 0.355546 0.767022 0.363468 0.745973 0.333071 0.75069 0.322457 0.770854 0.355546 0.741732 0.345528 0.767022 0.363468 0.763554 0.372854 0.741732 0.345528 0.745973 0.333071 0.767022 0.363468 0.738004 0.359579 0.763554 0.372854 0.760487 0.383522 0.738004 0.359579 0.741732 0.345528 0.763554 0.372854 0.734815 0.374982 0.760487 0.383522 0.757848 0.395289 0.734815 0.374982 0.738004 0.359579 0.760487 0.383522 0.732185 0.391501 0.757848 0.395289 0.755662 0.407971 0.732185 0.391501 0.734815 0.374982 0.757848 0.395289 0.730128 0.408902 0.755662 0.407971 0.753946 0.421383 0.730128 0.408902 0.732185 0.391501 0.755662 0.407971 0.728653 0.426961 0.753946 0.421383 0.752711 0.435342 0.728653 0.426961 0.730128 0.408902 0.753946 0.421383 0.727766 0.445456 0.752711 0.435342 0.751967 0.449664 0.727766 0.445456 0.728653 0.426961 0.752711 0.435342 0.701346 0.442439 0.727766 0.445456 0.72747 0.464168 0.701346 0.442439 0.72747 0.464168 0.701047 0.464168 0.727701 0.480709 0.701047 0.464168 0.72747 0.464168 0.751939 0.477845 0.727701 0.480709 0.72747 0.464168 0.770367 0.283545 0.785566 0.311212 0.779327 0.30554 0.756043 0.2677 0.779327 0.30554 0.773201 0.303344 0.763075 0.272215 0.770367 0.283545 0.779327 0.30554 0.756043 0.2677 0.763075 0.272215 0.779327 0.30554 0.749229 0.267105 0.773201 0.303344 0.767176 0.304146 0.749229 0.267105 0.756043 0.2677 0.773201 0.303344 0.742624 0.269905 0.767176 0.304146 0.761359 0.30775 0.742624 0.269905 0.749229 0.267105 0.767176 0.304146 0.736331 0.275813 0.761359 0.30775 0.755839 0.313934 0.736331 0.275813 0.742624 0.269905 0.761359 0.30775 0.73043 0.284529 0.755839 0.313934 0.75069 0.322457 0.73043 0.284529 0.736331 0.275813 0.755839 0.313934 0.724984 0.295751 0.75069 0.322457 0.745973 0.333071 0.724984 0.295751 0.73043 0.284529 0.75069 0.322457 0.720041 0.309182 0.745973 0.333071 0.741732 0.345528 0.720041 0.309182 0.724984 0.295751 0.745973 0.333071 0.715633 0.324536 0.741732 0.345528 0.738004 0.359579 0.715633 0.324536 0.720041 0.309182 0.741732 0.345528 0.711786 0.341537 0.738004 0.359579 0.734815 0.374982 0.711786 0.341537 0.715633 0.324536 0.738004 0.359579 0.708515 0.359923 0.734815 0.374982 0.732185 0.391501 0.708515 0.359923 0.711786 0.341537 0.734815 0.374982 0.705831 0.379442 0.732185 0.391501 0.730128 0.408902 0.705831 0.379442 0.708515 0.359923 0.732185 0.391501 0.70374 0.399854 0.730128 0.408902 0.728653 0.426961 0.70374 0.399854 0.705831 0.379442 0.730128 0.408902 0.702244 0.420928 0.728653 0.426961 0.727766 0.445456 0.702244 0.420928 0.70374 0.399854 0.728653 0.426961 0.701346 0.442439 0.702244 0.420928 0.727766 0.445456 0.673116 0.439724 0.701346 0.442439 0.701047 0.464168 0.673116 0.439724 0.701047 0.464168 0.672827 0.464168 0.701346 0.485896 0.672827 0.464168 0.701047 0.464168 0.727701 0.480709 0.701346 0.485896 0.701047 0.464168 0.746736 0.250095 0.763075 0.272215 0.756043 0.2677 0.72806 0.233491 0.756043 0.2677 0.749229 0.267105 0.735249 0.236679 0.746736 0.250095 0.756043 0.2677 0.72806 0.233491 0.735249 0.236679 0.756043 0.2677 0.720963 0.234363 0.749229 0.267105 0.742624 0.269905 0.720963 0.234363 0.72806 0.233491 0.749229 0.267105 0.714159 0.238992 0.742624 0.269905 0.736331 0.275813 0.714159 0.238992 0.720963 0.234363 0.742624 0.269905 0.707742 0.247001 0.736331 0.275813 0.73043 0.284529 0.707742 0.247001 0.714159 0.238992 0.736331 0.275813 0.70178 0.258019 0.73043 0.284529 0.724984 0.295751 0.70178 0.258019 0.707742 0.247001 0.73043 0.284529 0.696323 0.271688 0.724984 0.295751 0.720041 0.309182 0.696323 0.271688 0.70178 0.258019 0.724984 0.295751 0.691407 0.287667 0.720041 0.309182 0.715633 0.324536 0.691407 0.287667 0.696323 0.271688 0.720041 0.309182 0.687052 0.305636 0.715633 0.324536 0.711786 0.341537 0.687052 0.305636 0.691407 0.287667 0.715633 0.324536 0.683273 0.325296 0.711786 0.341537 0.708515 0.359923 0.683273 0.325296 0.687052 0.305636 0.711786 0.341537 0.680075 0.346368 0.708515 0.359923 0.705831 0.379442 0.680075 0.346368 0.683273 0.325296 0.708515 0.359923 0.677462 0.368589 0.705831 0.379442 0.70374 0.399854 0.677462 0.368589 0.680075 0.346368 0.705831 0.379442 0.675432 0.391711 0.70374 0.399854 0.702244 0.420928 0.675432 0.391711 0.677462 0.368589 0.70374 0.399854 0.673984 0.415498 0.702244 0.420928 0.701346 0.442439 0.673984 0.415498 0.675432 0.391711 0.702244 0.420928 0.673116 0.439724 0.673984 0.415498 0.701346 0.442439 0.643408 0.437308 0.673116 0.439724 0.672827 0.464168 0.643408 0.437308 0.672827 0.464168 0.643142 0.464168 0.673116 0.488612 0.643142 0.464168 0.672827 0.464168 0.701346 0.485896 0.673116 0.488612 0.672827 0.464168 0.717974 0.21909 0.735249 0.236679 0.72806 0.233491 0.695598 0.203266 0.72806 0.233491 0.720963 0.234363 0.702696 0.2056609 0.717974 0.21909 0.72806 0.233491 0.695598 0.203266 0.702696 0.2056609 0.72806 0.233491 0.688661 0.205383 0.720963 0.234363 0.714159 0.238992 0.688661 0.205383 0.695598 0.203266 0.720963 0.234363 0.682067 0.211596 0.714159 0.238992 0.707742 0.247001 0.682067 0.211596 0.688661 0.205383 0.714159 0.238992 0.675898 0.221446 0.707742 0.247001 0.70178 0.258019 0.675898 0.221446 0.682067 0.211596 0.707742 0.247001 0.670208 0.23449 0.70178 0.258019 0.696323 0.271688 0.670208 0.23449 0.675898 0.221446 0.70178 0.258019 0.665037 0.250319 0.696323 0.271688 0.691407 0.287667 0.665037 0.250319 0.670208 0.23449 0.696323 0.271688 0.660405 0.268551 0.691407 0.287667 0.687052 0.305636 0.660405 0.268551 0.665037 0.250319 0.691407 0.287667 0.656326 0.288837 0.687052 0.305636 0.683273 0.325296 0.656326 0.288837 0.660405 0.268551 0.687052 0.305636 0.652802 0.310855 0.683273 0.325296 0.680075 0.346368 0.652802 0.310855 0.656326 0.288837 0.683273 0.325296 0.649833 0.334312 0.680075 0.346368 0.677462 0.368589 0.649833 0.334312 0.652802 0.310855 0.680075 0.346368 0.647414 0.358933 0.677462 0.368589 0.675432 0.391711 0.647414 0.358933 0.649833 0.334312 0.677462 0.368589 0.64554 0.384464 0.675432 0.391711 0.673984 0.415498 0.64554 0.384464 0.647414 0.358933 0.675432 0.391711 0.644206 0.410665 0.673984 0.415498 0.673116 0.439724 0.644206 0.410665 0.64554 0.384464 0.673984 0.415498 0.643408 0.437308 0.644206 0.410665 0.673116 0.439724 0.612524 0.435197 0.643408 0.437308 0.643142 0.464168 0.612524 0.435197 0.643142 0.464168 0.612294 0.464168 0.643332 0.486877 0.612294 0.464168 0.643142 0.464168 0.673116 0.488612 0.643332 0.486877 0.643142 0.464168 0.658881 0.177524 0.702696 0.2056609 0.695598 0.203266 0.658881 0.177524 0.684882 0.192094 0.702696 0.2056609 0.652578 0.1805689 0.695598 0.203266 0.688661 0.205383 0.652578 0.1805689 0.658881 0.177524 0.695598 0.203266 0.646627 0.188045 0.688661 0.205383 0.682067 0.211596 0.646627 0.188045 0.652578 0.1805689 0.688661 0.205383 0.641093 0.199406 0.682067 0.211596 0.675898 0.221446 0.641093 0.199406 0.646627 0.188045 0.682067 0.211596 0.636021 0.214147 0.675898 0.221446 0.670208 0.23449 0.636021 0.214147 0.641093 0.199406 0.675898 0.221446 0.631436 0.231804 0.670208 0.23449 0.665037 0.250319 0.631436 0.231804 0.636021 0.214147 0.670208 0.23449 0.62735 0.251959 0.665037 0.250319 0.660405 0.268551 0.62735 0.251959 0.631436 0.231804 0.665037 0.250319 0.623768 0.274234 0.660405 0.268551 0.656326 0.288837 0.623768 0.274234 0.62735 0.251959 0.660405 0.268551 0.620685 0.298287 0.656326 0.288837 0.652802 0.310855 0.620685 0.298287 0.623768 0.274234 0.656326 0.288837 0.618097 0.323808 0.652802 0.310855 0.649833 0.334312 0.618097 0.323808 0.620685 0.298287 0.652802 0.310855 0.615994 0.350513 0.649833 0.334312 0.647414 0.358933 0.615994 0.350513 0.618097 0.323808 0.649833 0.334312 0.614369 0.378141 0.647414 0.358933 0.64554 0.384464 0.614369 0.378141 0.615994 0.350513 0.647414 0.358933 0.613214 0.406447 0.64554 0.384464 0.644206 0.410665 0.613214 0.406447 0.614369 0.378141 0.64554 0.384464 0.612524 0.435197 0.644206 0.410665 0.643408 0.437308 0.612524 0.435197 0.613214 0.406447 0.644206 0.410665 0.580738 0.433401 0.612524 0.435197 0.612294 0.464168 0.580738 0.433401 0.612294 0.464168 0.580556 0.464168 0.612524 0.493139 0.580556 0.464168 0.612294 0.464168 0.643332 0.486877 0.612524 0.493139 0.612294 0.464168 0.658881 0.177524 0.665365 0.1794289 0.684882 0.192094 0.618231 0.156866 0.665365 0.1794289 0.658881 0.177524 0.618231 0.156866 0.647786 0.169735 0.665365 0.1794289 0.613046 0.160407 0.658881 0.177524 0.652578 0.1805689 0.613046 0.160407 0.618231 0.156866 0.658881 0.177524 0.608173 0.168722 0.652578 0.1805689 0.646627 0.188045 0.608173 0.168722 0.613046 0.160407 0.652578 0.1805689 0.603664 0.1811839 0.646627 0.188045 0.641093 0.199406 0.603664 0.1811839 0.608173 0.168722 0.646627 0.188045 0.599549 0.1972219 0.641093 0.199406 0.636021 0.214147 0.599549 0.1972219 0.603664 0.1811839 0.641093 0.199406 0.595845 0.216321 0.636021 0.214147 0.631436 0.231804 0.595845 0.216321 0.599549 0.1972219 0.636021 0.214147 0.592558 0.238026 0.631436 0.231804 0.62735 0.251959 0.592558 0.238026 0.595845 0.216321 0.631436 0.231804 0.589686 0.261928 0.62735 0.251959 0.623768 0.274234 0.589686 0.261928 0.592558 0.238026 0.62735 0.251959 0.587224 0.287665 0.623768 0.274234 0.620685 0.298287 0.587224 0.287665 0.589686 0.261928 0.623768 0.274234 0.585161 0.31491 0.620685 0.298287 0.618097 0.323808 0.585161 0.31491 0.587224 0.287665 0.620685 0.298287 0.583489 0.343368 0.618097 0.323808 0.615994 0.350513 0.583489 0.343368 0.585161 0.31491 0.618097 0.323808 0.5822 0.372768 0.615994 0.350513 0.614369 0.378141 0.5822 0.372768 0.583489 0.343368 0.615994 0.350513 0.581284 0.402858 0.614369 0.378141 0.613214 0.406447 0.581284 0.402858 0.5822 0.372768 0.614369 0.378141 0.580738 0.433401 0.613214 0.406447 0.612524 0.435197 0.580738 0.433401 0.581284 0.402858 0.613214 0.406447 0.548305 0.431924 0.580738 0.433401 0.580556 0.464168 0.548305 0.431924 0.580556 0.464168 0.548182 0.464168 0.580738 0.494935 0.548182 0.464168 0.580556 0.464168 0.612524 0.493139 0.580738 0.494935 0.580556 0.464168 0.618231 0.156866 0.623571 0.158724 0.647786 0.169735 0.574102 0.141959 0.623571 0.158724 0.618231 0.156866 0.574102 0.141959 0.607211 0.152675 0.623571 0.158724 0.570496 0.145425 0.618231 0.156866 0.613046 0.160407 0.570496 0.145425 0.574102 0.141959 0.618231 0.156866 0.567115 0.154041 0.613046 0.160407 0.608173 0.168722 0.567115 0.154041 0.570496 0.145425 0.613046 0.160407 0.563995 0.167097 0.608173 0.168722 0.603664 0.1811839 0.563995 0.167097 0.567115 0.154041 0.608173 0.168722 0.561157 0.183955 0.603664 0.1811839 0.599549 0.1972219 0.561157 0.183955 0.563995 0.167097 0.603664 0.1811839 0.55861 0.204049 0.599549 0.1972219 0.595845 0.216321 0.55861 0.204049 0.561157 0.183955 0.599549 0.1972219 0.556356 0.226881 0.595845 0.216321 0.592558 0.238026 0.556356 0.226881 0.55861 0.204049 0.595845 0.216321 0.554392 0.252012 0.592558 0.238026 0.589686 0.261928 0.554392 0.252012 0.556356 0.226881 0.592558 0.238026 0.552711 0.279054 0.589686 0.261928 0.587224 0.287665 0.552711 0.279054 0.554392 0.252012 0.589686 0.261928 0.551307 0.307662 0.587224 0.287665 0.585161 0.31491 0.551307 0.307662 0.552711 0.279054 0.587224 0.287665 0.550171 0.337525 0.585161 0.31491 0.583489 0.343368 0.550171 0.337525 0.551307 0.307662 0.585161 0.31491 0.549295 0.368361 0.583489 0.343368 0.5822 0.372768 0.549295 0.368361 0.550171 0.337525 0.583489 0.343368 0.548675 0.399909 0.5822 0.372768 0.581284 0.402858 0.548675 0.399909 0.549295 0.368361 0.5822 0.372768 0.548305 0.431924 0.581284 0.402858 0.580738 0.433401 0.548305 0.431924 0.548675 0.399909 0.581284 0.402858 0.515465 0.430767 0.548305 0.431924 0.548182 0.464168 0.515465 0.430767 0.548182 0.464168 0.515739 0.464168 0.548238 0.486101 0.515739 0.464168 0.548182 0.464168 0.580738 0.494935 0.548238 0.486101 0.548182 0.464168 0.574102 0.141959 0.577795 0.14437 0.607211 0.152675 0.527099 0.133518 0.577795 0.14437 0.574102 0.141959 0.527099 0.133518 0.563848 0.141517 0.577795 0.14437 0.525466 0.136185 0.574102 0.141959 0.570496 0.145425 0.525466 0.136185 0.527099 0.133518 0.574102 0.141959 0.523936 0.144434 0.570496 0.145425 0.567115 0.154041 0.523936 0.144434 0.525466 0.136185 0.570496 0.145425 0.522524 0.157471 0.567115 0.154041 0.563995 0.167097 0.522524 0.157471 0.523936 0.144434 0.567115 0.154041 0.521241 0.174588 0.563995 0.167097 0.561157 0.183955 0.521241 0.174588 0.522524 0.157471 0.563995 0.167097 0.520092 0.195161 0.561157 0.183955 0.55861 0.204049 0.520092 0.195161 0.521241 0.174588 0.561157 0.183955 0.519077 0.218647 0.55861 0.204049 0.556356 0.226881 0.519077 0.218647 0.520092 0.195161 0.55861 0.204049 0.518193 0.244569 0.556356 0.226881 0.554392 0.252012 0.518193 0.244569 0.519077 0.218647 0.556356 0.226881 0.517439 0.272509 0.554392 0.252012 0.552711 0.279054 0.517439 0.272509 0.518193 0.244569 0.554392 0.252012 0.516809 0.302098 0.552711 0.279054 0.551307 0.307662 0.516809 0.302098 0.517439 0.272509 0.552711 0.279054 0.5163 0.333005 0.551307 0.307662 0.550171 0.337525 0.5163 0.333005 0.516809 0.302098 0.551307 0.307662 0.515908 0.364933 0.550171 0.337525 0.549295 0.368361 0.515908 0.364933 0.5163 0.333005 0.550171 0.337525 0.515631 0.397606 0.549295 0.368361 0.548675 0.399909 0.515631 0.397606 0.515908 0.364933 0.549295 0.368361 0.515465 0.430767 0.548675 0.399909 0.548305 0.431924 0.515465 0.430767 0.515631 0.397606 0.548675 0.399909 0.51541 0.464168 0.515465 0.430767 0.515739 0.464168 0.548238 0.486101 0.51541 0.464168 0.515739 0.464168 0.527099 0.133518 0.528728 0.13726 0.563848 0.141517 0.477934 0.132473 0.528728 0.13726 0.527099 0.133518 0.477934 0.132473 0.518568 0.136789 0.528728 0.13726 0.478524 0.132818 0.527099 0.133518 0.525466 0.136185 0.478524 0.132818 0.477934 0.132473 0.527099 0.133518 0.479081 0.138617 0.525466 0.136185 0.523936 0.144434 0.479081 0.138617 0.478524 0.132818 0.525466 0.136185 0.479601 0.149137 0.523936 0.144434 0.522524 0.157471 0.479601 0.149137 0.479081 0.138617 0.523936 0.144434 0.480078 0.163715 0.522524 0.157471 0.521241 0.174588 0.480078 0.163715 0.479601 0.149137 0.522524 0.157471 0.48051 0.1817629 0.521241 0.174588 0.520092 0.195161 0.48051 0.1817629 0.480078 0.163715 0.521241 0.174588 0.480897 0.202763 0.520092 0.195161 0.519077 0.218647 0.480897 0.202763 0.48051 0.1817629 0.520092 0.195161 0.481238 0.226261 0.519077 0.218647 0.518193 0.244569 0.481238 0.226261 0.480897 0.202763 0.519077 0.218647 0.481536 0.251858 0.518193 0.244569 0.517439 0.272509 0.481536 0.251858 0.481238 0.226261 0.518193 0.244569 0.48179 0.279201 0.517439 0.272509 0.516809 0.302098 0.48179 0.279201 0.481536 0.251858 0.517439 0.272509 0.482002 0.307974 0.516809 0.302098 0.5163 0.333005 0.482002 0.307974 0.48179 0.279201 0.516809 0.302098 0.482173 0.337896 0.5163 0.333005 0.515908 0.364933 0.482173 0.337896 0.482002 0.307974 0.5163 0.333005 0.482305 0.368709 0.515908 0.364933 0.515631 0.397606 0.482305 0.368709 0.482173 0.337896 0.515908 0.364933 0.482399 0.400174 0.515631 0.397606 0.515465 0.430767 0.482399 0.400174 0.482305 0.368709 0.515631 0.397606 0.482455 0.432065 0.515465 0.430767 0.51541 0.464168 0.482455 0.432065 0.482399 0.400174 0.515465 0.430767 0.482455 0.432065 0.51541 0.464168 0.482835 0.464168 0.515457 0.494898 0.482835 0.464168 0.51541 0.464168 0.515457 0.494898 0.51541 0.464168 0.548238 0.486101 0.482473 0.464168 0.482455 0.432065 0.482835 0.464168 0.515457 0.494898 0.482473 0.464168 0.482835 0.464168 0.477934 0.132473 0.477273 0.138346 0.518568 0.136789 0.427423 0.139556 0.477273 0.138346 0.477934 0.132473 0.427423 0.139556 0.472402 0.1389 0.477273 0.138346 0.430258 0.13725 0.477934 0.132473 0.478524 0.132818 0.430258 0.13725 0.427423 0.139556 0.477934 0.132473 0.43296 0.140941 0.478524 0.132818 0.479081 0.138617 0.43296 0.140941 0.430258 0.13725 0.478524 0.132818 0.43549 0.149835 0.479081 0.138617 0.479601 0.149137 0.43549 0.149835 0.43296 0.140941 0.479081 0.138617 0.437822 0.163203 0.479601 0.149137 0.480078 0.163715 0.437822 0.163203 0.43549 0.149835 0.479601 0.149137 0.439941 0.1803939 0.480078 0.163715 0.48051 0.1817629 0.439941 0.1803939 0.437822 0.163203 0.480078 0.163715 0.441841 0.200836 0.48051 0.1817629 0.480897 0.202763 0.441841 0.200836 0.439941 0.1803939 0.48051 0.1817629 0.44352 0.224022 0.480897 0.202763 0.481238 0.226261 0.44352 0.224022 0.441841 0.200836 0.480897 0.202763 0.444982 0.249512 0.481238 0.226261 0.481536 0.251858 0.444982 0.249512 0.44352 0.224022 0.481238 0.226261 0.446232 0.276914 0.481536 0.251858 0.48179 0.279201 0.446232 0.276914 0.444982 0.249512 0.481536 0.251858 0.447276 0.305881 0.48179 0.279201 0.482002 0.307974 0.447276 0.305881 0.446232 0.276914 0.48179 0.279201 0.44812 0.336103 0.482002 0.307974 0.482173 0.337896 0.44812 0.336103 0.447276 0.305881 0.482002 0.307974 0.44877 0.367296 0.482173 0.337896 0.482305 0.368709 0.44877 0.367296 0.44812 0.336103 0.482173 0.337896 0.449231 0.3992 0.482305 0.368709 0.482399 0.400174 0.449231 0.3992 0.44877 0.367296 0.482305 0.368709 0.449505 0.431569 0.482399 0.400174 0.482455 0.432065 0.449505 0.431569 0.449231 0.3992 0.482399 0.400174 0.449505 0.431569 0.482455 0.432065 0.482473 0.464168 0.449505 0.431569 0.482473 0.464168 0.44999 0.464168 0.482454 0.497193 0.44999 0.464168 0.482473 0.464168 0.515457 0.494898 0.482454 0.497193 0.482473 0.464168 0.449597 0.464168 0.449505 0.431569 0.44999 0.464168 0.482454 0.497193 0.449597 0.464168 0.44999 0.464168 0.427423 0.139556 0.426501 0.148106 0.472402 0.1389 0.427423 0.139556 0.424481 0.148683 0.426501 0.148106 0.376309 0.1565819 0.424481 0.148683 0.427423 0.139556 0.376309 0.1565819 0.38208 0.164475 0.424481 0.148683 0.381036 0.150104 0.427423 0.139556 0.430258 0.13725 0.381036 0.150104 0.376309 0.1565819 0.427423 0.139556 0.385621 0.149607 0.430258 0.13725 0.43296 0.140941 0.385621 0.149607 0.381036 0.150104 0.430258 0.13725 0.389985 0.1543869 0.43296 0.140941 0.43549 0.149835 0.389985 0.1543869 0.385621 0.149607 0.43296 0.140941 0.394069 0.163775 0.43549 0.149835 0.437822 0.163203 0.394069 0.163775 0.389985 0.1543869 0.43549 0.149835 0.397837 0.177153 0.437822 0.163203 0.439941 0.1803939 0.397837 0.177153 0.394069 0.163775 0.437822 0.163203 0.401265 0.193964 0.439941 0.1803939 0.441841 0.200836 0.401265 0.193964 0.397837 0.177153 0.439941 0.1803939 0.404345 0.213711 0.441841 0.200836 0.44352 0.224022 0.404345 0.213711 0.401265 0.193964 0.441841 0.200836 0.407074 0.2359549 0.44352 0.224022 0.444982 0.249512 0.407074 0.2359549 0.404345 0.213711 0.44352 0.224022 0.409455 0.260303 0.444982 0.249512 0.446232 0.276914 0.409455 0.260303 0.407074 0.2359549 0.444982 0.249512 0.411495 0.286408 0.446232 0.276914 0.447276 0.305881 0.411495 0.286408 0.409455 0.260303 0.446232 0.276914 0.413202 0.313956 0.447276 0.305881 0.44812 0.336103 0.413202 0.313956 0.411495 0.286408 0.447276 0.305881 0.414585 0.342665 0.44812 0.336103 0.44877 0.367296 0.414585 0.342665 0.413202 0.313956 0.44812 0.336103 0.415651 0.372275 0.44877 0.367296 0.449231 0.3992 0.415651 0.372275 0.414585 0.342665 0.44877 0.367296 0.416408 0.402546 0.449231 0.3992 0.449505 0.431569 0.416408 0.402546 0.415651 0.372275 0.449231 0.3992 0.416859 0.43325 0.449505 0.431569 0.449597 0.464168 0.416859 0.43325 0.416408 0.402546 0.449505 0.431569 0.416859 0.43325 0.449597 0.464168 0.41743 0.464168 0.449505 0.496767 0.41743 0.464168 0.449597 0.464168 0.482454 0.497193 0.449505 0.496767 0.449597 0.464168 0.41701 0.464168 0.416859 0.43325 0.41743 0.464168 0.449505 0.496767 0.41701 0.464168 0.41743 0.464168 0.376309 0.1565819 0.371386 0.169657 0.38208 0.164475 0.327189 0.181913 0.371386 0.169657 0.376309 0.1565819 0.333602 0.17142 0.376309 0.1565819 0.381036 0.150104 0.333602 0.17142 0.327189 0.181913 0.376309 0.1565819 0.339928 0.1673229 0.381036 0.150104 0.385621 0.149607 0.339928 0.1673229 0.333602 0.17142 0.381036 0.150104 0.346026 0.168946 0.385621 0.149607 0.389985 0.1543869 0.346026 0.168946 0.339928 0.1673229 0.385621 0.149607 0.351795 0.175616 0.389985 0.1543869 0.394069 0.163775 0.351795 0.175616 0.346026 0.168946 0.389985 0.1543869 0.357161 0.186686 0.394069 0.163775 0.397837 0.177153 0.357161 0.186686 0.351795 0.175616 0.394069 0.163775 0.362077 0.201562 0.397837 0.177153 0.401265 0.193964 0.362077 0.201562 0.357161 0.186686 0.397837 0.177153 0.366515 0.219705 0.401265 0.193964 0.404345 0.213711 0.366515 0.219705 0.362077 0.201562 0.401265 0.193964 0.370464 0.240629 0.404345 0.213711 0.407074 0.2359549 0.370464 0.240629 0.366515 0.219705 0.404345 0.213711 0.373921 0.263903 0.407074 0.2359549 0.409455 0.260303 0.373921 0.263903 0.370464 0.240629 0.407074 0.2359549 0.376891 0.289138 0.409455 0.260303 0.411495 0.286408 0.376891 0.289138 0.373921 0.263903 0.409455 0.260303 0.37938 0.315987 0.411495 0.286408 0.413202 0.313956 0.37938 0.315987 0.376891 0.289138 0.411495 0.286408 0.381399 0.344133 0.413202 0.313956 0.414585 0.342665 0.381399 0.344133 0.37938 0.315987 0.413202 0.313956 0.382958 0.373286 0.414585 0.342665 0.415651 0.372275 0.382958 0.373286 0.381399 0.344133 0.414585 0.342665 0.384065 0.403177 0.415651 0.372275 0.416408 0.402546 0.384065 0.403177 0.382958 0.373286 0.415651 0.372275 0.384726 0.433553 0.416408 0.402546 0.416859 0.43325 0.384726 0.433553 0.384065 0.403177 0.416408 0.402546 0.384726 0.433553 0.416859 0.43325 0.41701 0.464168 0.384726 0.433553 0.41701 0.464168 0.38539 0.464168 0.416933 0.486187 0.38539 0.464168 0.41701 0.464168 0.449505 0.496767 0.416933 0.486187 0.41701 0.464168 0.384946 0.464168 0.384726 0.433553 0.38539 0.464168 0.416933 0.486187 0.384946 0.464168 0.38539 0.464168 0.384726 0.494784 0.354115 0.464168 0.384946 0.464168 0.416933 0.486187 0.384726 0.494784 0.384946 0.464168 0.3534 0.492191 0.323475 0.494538 0.323769 0.479376 0.267169 0.478612 0.323769 0.479376 0.323475 0.494538 0.352639 0.51999 0.322984 0.50961 0.323475 0.494538 0.266792 0.492908 0.323475 0.494538 0.322984 0.50961 0.3534 0.492191 0.352639 0.51999 0.323475 0.494538 0.266792 0.492908 0.267169 0.478612 0.323475 0.494538 0.352639 0.51999 0.322295 0.524544 0.322984 0.50961 0.311088 0.509904 0.322984 0.50961 0.322295 0.524544 0.311088 0.509904 0.266792 0.492908 0.322984 0.50961 0.351366 0.54734 0.321409 0.539296 0.322295 0.524544 0.311712 0.5355 0.322295 0.524544 0.321409 0.539296 0.352639 0.51999 0.351366 0.54734 0.322295 0.524544 0.311365 0.522763 0.311088 0.509904 0.322295 0.524544 0.311712 0.5355 0.311365 0.522763 0.322295 0.524544 0.351366 0.54734 0.320324 0.553816 0.321409 0.539296 0.311564 0.542102 0.321409 0.539296 0.320324 0.553816 0.311564 0.542102 0.311712 0.5355 0.321409 0.539296 0.349578 0.574007 0.319041 0.568056 0.320324 0.553816 0.307949 0.554083 0.320324 0.553816 0.319041 0.568056 0.351366 0.54734 0.349578 0.574007 0.320324 0.553816 0.310799 0.547288 0.311564 0.542102 0.320324 0.553816 0.309559 0.55124 0.310799 0.547288 0.320324 0.553816 0.307949 0.554083 0.309559 0.55124 0.320324 0.553816 0.347267 0.599743 0.317557 0.581966 0.319041 0.568056 0.26277 0.54866 0.319041 0.568056 0.317557 0.581966 0.349578 0.574007 0.347267 0.599743 0.319041 0.568056 0.302306 0.556529 0.319041 0.568056 0.26277 0.54866 0.306085 0.555861 0.307949 0.554083 0.319041 0.568056 0.304192 0.556612 0.306085 0.555861 0.319041 0.568056 0.302306 0.556529 0.304192 0.556612 0.319041 0.568056 0.347267 0.599743 0.315873 0.595493 0.317557 0.581966 0.259287 0.574749 0.317557 0.581966 0.315873 0.595493 0.259287 0.574749 0.26277 0.54866 0.317557 0.581966 0.344426 0.624287 0.313988 0.608584 0.315873 0.595493 0.259287 0.574749 0.315873 0.595493 0.313988 0.608584 0.347267 0.599743 0.344426 0.624287 0.315873 0.595493 0.344426 0.624287 0.311901 0.621183 0.313988 0.608584 0.254779 0.599464 0.313988 0.608584 0.311901 0.621183 0.254779 0.599464 0.259287 0.574749 0.313988 0.608584 0.341048 0.647356 0.309614 0.63323 0.311901 0.621183 0.254779 0.599464 0.311901 0.621183 0.309614 0.63323 0.344426 0.624287 0.341048 0.647356 0.311901 0.621183 0.33713 0.668641 0.307126 0.644666 0.309614 0.63323 0.249276 0.622149 0.309614 0.63323 0.307126 0.644666 0.341048 0.647356 0.33713 0.668641 0.309614 0.63323 0.249276 0.622149 0.254779 0.599464 0.309614 0.63323 0.33713 0.668641 0.30444 0.655426 0.307126 0.644666 0.249276 0.622149 0.307126 0.644666 0.30444 0.655426 0.332673 0.687807 0.301558 0.665443 0.30444 0.655426 0.242811 0.642293 0.30444 0.655426 0.301558 0.665443 0.33713 0.668641 0.332673 0.687807 0.30444 0.655426 0.242811 0.642293 0.249276 0.622149 0.30444 0.655426 0.332673 0.687807 0.298483 0.674646 0.301558 0.665443 0.242811 0.642293 0.301558 0.665443 0.298483 0.674646 0.327684 0.704482 0.295221 0.682964 0.298483 0.674646 0.235419 0.659412 0.298483 0.674646 0.295221 0.682964 0.332673 0.687807 0.327684 0.704482 0.298483 0.674646 0.235419 0.659412 0.242811 0.642293 0.298483 0.674646 0.322182 0.718261 0.291778 0.690319 0.295221 0.682964 0.235419 0.659412 0.295221 0.682964 0.291778 0.690319 0.327684 0.704482 0.322182 0.718261 0.295221 0.682964 0.322182 0.718261 0.288163 0.696632 0.291778 0.690319 0.227158 0.672973 0.291778 0.690319 0.288163 0.696632 0.227158 0.672973 0.235419 0.659412 0.291778 0.690319 0.316201 0.728699 0.284387 0.701821 0.288163 0.696632 0.227158 0.672973 0.288163 0.696632 0.284387 0.701821 0.322182 0.718261 0.316201 0.728699 0.288163 0.696632 0.316201 0.728699 0.280463 0.705801 0.284387 0.701821 0.21812 0.682395 0.284387 0.701821 0.280463 0.705801 0.21812 0.682395 0.227158 0.672973 0.284387 0.701821 0.309791 0.735316 0.276408 0.708486 0.280463 0.705801 0.21812 0.682395 0.280463 0.705801 0.276408 0.708486 0.316201 0.728699 0.309791 0.735316 0.280463 0.705801 0.309791 0.735316 0.272239 0.709789 0.276408 0.708486 0.208443 0.687066 0.276408 0.708486 0.272239 0.709789 0.208443 0.687066 0.21812 0.682395 0.276408 0.708486 0.303031 0.737602 0.267981 0.709622 0.272239 0.709789 0.208443 0.687066 0.272239 0.709789 0.267981 0.709622 0.309791 0.735316 0.303031 0.737602 0.272239 0.709789 0.296025 0.735032 0.263659 0.707902 0.267981 0.709622 0.198319 0.686362 0.267981 0.709622 0.263659 0.707902 0.303031 0.737602 0.296025 0.735032 0.267981 0.709622 0.198319 0.686362 0.208443 0.687066 0.267981 0.709622 0.296025 0.735032 0.259302 0.704546 0.263659 0.707902 0.198319 0.686362 0.263659 0.707902 0.259302 0.704546 0.28891 0.727094 0.254945 0.699482 0.259302 0.704546 0.188 0.679689 0.259302 0.704546 0.254945 0.699482 0.296025 0.735032 0.28891 0.727094 0.259302 0.704546 0.188 0.679689 0.198319 0.686362 0.259302 0.704546 0.28891 0.727094 0.250623 0.692643 0.254945 0.699482 0.182867 0.673949 0.254945 0.699482 0.250623 0.692643 0.182867 0.673949 0.188 0.679689 0.254945 0.699482 0.281856 0.713326 0.246377 0.683978 0.250623 0.692643 0.177812 0.666552 0.250623 0.692643 0.246377 0.683978 0.28891 0.727094 0.281856 0.713326 0.250623 0.692643 0.177812 0.666552 0.182867 0.673949 0.250623 0.692643 0.274962 0.69344 0.242249 0.673452 0.246377 0.683978 0.172885 0.657449 0.246377 0.683978 0.242249 0.673452 0.281856 0.713326 0.274962 0.69344 0.246377 0.683978 0.172885 0.657449 0.177812 0.666552 0.246377 0.683978 0.274962 0.69344 0.238286 0.661051 0.242249 0.673452 0.1681399 0.646654 0.242249 0.673452 0.238286 0.661051 0.1681399 0.646654 0.172885 0.657449 0.242249 0.673452 0.255748 0.67363 0.234534 0.646789 0.238286 0.661051 0.163637 0.634163 0.238286 0.661051 0.234534 0.646789 0.274962 0.69344 0.255748 0.67363 0.238286 0.661051 0.163637 0.634163 0.1681399 0.646654 0.238286 0.661051 0.179056 0.720499 0.234534 0.646789 0.255748 0.67363 0.1594319 0.62008 0.234534 0.646789 0.212484 0.617942 0.144178 0.669793 0.212484 0.617942 0.234534 0.646789 0.1594319 0.62008 0.163637 0.634163 0.234534 0.646789 0.160509 0.6957 0.144178 0.669793 0.234534 0.646789 0.179056 0.720499 0.160509 0.6957 0.234534 0.646789 0.199668 0.743895 0.255748 0.67363 0.274962 0.69344 0.199668 0.743895 0.179056 0.720499 0.255748 0.67363 0.28051 0.698537 0.274962 0.69344 0.281856 0.713326 0.199668 0.743895 0.274962 0.69344 0.28051 0.698537 0.327189 0.746424 0.281856 0.713326 0.28891 0.727094 0.308761 0.720995 0.28051 0.698537 0.281856 0.713326 0.320742 0.729004 0.308761 0.720995 0.281856 0.713326 0.327189 0.746424 0.320742 0.729004 0.281856 0.713326 0.333602 0.756916 0.28891 0.727094 0.296025 0.735032 0.333602 0.756916 0.327189 0.746424 0.28891 0.727094 0.339928 0.761014 0.296025 0.735032 0.303031 0.737602 0.339928 0.761014 0.333602 0.756916 0.296025 0.735032 0.346026 0.75939 0.303031 0.737602 0.309791 0.735316 0.346026 0.75939 0.339928 0.761014 0.303031 0.737602 0.351795 0.752721 0.309791 0.735316 0.316201 0.728699 0.351795 0.752721 0.346026 0.75939 0.309791 0.735316 0.357161 0.741651 0.316201 0.728699 0.322182 0.718261 0.357161 0.741651 0.351795 0.752721 0.316201 0.728699 0.362077 0.726775 0.322182 0.718261 0.327684 0.704482 0.362077 0.726775 0.357161 0.741651 0.322182 0.718261 0.366515 0.708632 0.327684 0.704482 0.332673 0.687807 0.366515 0.708632 0.362077 0.726775 0.327684 0.704482 0.370464 0.687707 0.332673 0.687807 0.33713 0.668641 0.370464 0.687707 0.366515 0.708632 0.332673 0.687807 0.373921 0.664434 0.33713 0.668641 0.341048 0.647356 0.373921 0.664434 0.370464 0.687707 0.33713 0.668641 0.376891 0.639198 0.341048 0.647356 0.344426 0.624287 0.376891 0.639198 0.373921 0.664434 0.341048 0.647356 0.37938 0.61235 0.344426 0.624287 0.347267 0.599743 0.37938 0.61235 0.376891 0.639198 0.344426 0.624287 0.381399 0.584204 0.347267 0.599743 0.349578 0.574007 0.381399 0.584204 0.37938 0.61235 0.347267 0.599743 0.382958 0.555051 0.349578 0.574007 0.351366 0.54734 0.382958 0.555051 0.381399 0.584204 0.349578 0.574007 0.384065 0.525159 0.351366 0.54734 0.352639 0.51999 0.384065 0.525159 0.382958 0.555051 0.351366 0.54734 0.384726 0.494784 0.352639 0.51999 0.3534 0.492191 0.384726 0.494784 0.384065 0.525159 0.352639 0.51999 0.222245 0.765625 0.28051 0.698537 0.308761 0.720995 0.222245 0.765625 0.199668 0.743895 0.28051 0.698537 0.246682 0.785572 0.308761 0.720995 0.320742 0.729004 0.246682 0.785572 0.222245 0.765625 0.308761 0.720995 0.340349 0.740468 0.320742 0.729004 0.327189 0.746424 0.272861 0.803563 0.320742 0.729004 0.340349 0.740468 0.272861 0.803563 0.246682 0.785572 0.320742 0.729004 0.37651 0.772157 0.327189 0.746424 0.333602 0.756916 0.371388 0.758681 0.340349 0.740468 0.327189 0.746424 0.37651 0.772157 0.371388 0.758681 0.327189 0.746424 0.381429 0.778496 0.333602 0.756916 0.339928 0.761014 0.381429 0.778496 0.37651 0.772157 0.333602 0.756916 0.386186 0.778403 0.339928 0.761014 0.346026 0.75939 0.386186 0.778403 0.381429 0.778496 0.339928 0.761014 0.390693 0.772674 0.346026 0.75939 0.351795 0.752721 0.390693 0.772674 0.386186 0.778403 0.346026 0.75939 0.394889 0.762059 0.351795 0.752721 0.357161 0.741651 0.394889 0.762059 0.390693 0.772674 0.351795 0.752721 0.398735 0.747244 0.357161 0.741651 0.362077 0.726775 0.398735 0.747244 0.394889 0.762059 0.357161 0.741651 0.402209 0.728842 0.362077 0.726775 0.366515 0.708632 0.402209 0.728842 0.398735 0.747244 0.362077 0.726775 0.405303 0.707397 0.366515 0.708632 0.370464 0.687707 0.405303 0.707397 0.402209 0.728842 0.366515 0.708632 0.408016 0.683391 0.370464 0.687707 0.373921 0.664434 0.408016 0.683391 0.405303 0.707397 0.370464 0.687707 0.410354 0.657247 0.373921 0.664434 0.376891 0.639198 0.410354 0.657247 0.408016 0.683391 0.373921 0.664434 0.412326 0.629343 0.376891 0.639198 0.37938 0.61235 0.412326 0.629343 0.410354 0.657247 0.376891 0.639198 0.41394 0.600017 0.37938 0.61235 0.381399 0.584204 0.41394 0.600017 0.412326 0.629343 0.37938 0.61235 0.414748 0.569488 0.381399 0.584204 0.382958 0.555051 0.415223 0.569655 0.41394 0.600017 0.381399 0.584204 0.414748 0.569488 0.415223 0.569655 0.381399 0.584204 0.406425 0.553508 0.382958 0.555051 0.384065 0.525159 0.412891 0.568276 0.414748 0.569488 0.382958 0.555051 0.411038 0.566117 0.412891 0.568276 0.382958 0.555051 0.409297 0.563008 0.411038 0.566117 0.382958 0.555051 0.407729 0.558856 0.409297 0.563008 0.382958 0.555051 0.406425 0.553508 0.407729 0.558856 0.382958 0.555051 0.403137 0.508277 0.384065 0.525159 0.384726 0.494784 0.405529 0.546743 0.406425 0.553508 0.384065 0.525159 0.404148 0.527588 0.405529 0.546743 0.384065 0.525159 0.403137 0.508277 0.404148 0.527588 0.384065 0.525159 0.411651 0.508175 0.403137 0.508277 0.384726 0.494784 0.416704 0.508121 0.411651 0.508175 0.384726 0.494784 0.416933 0.486187 0.416704 0.508121 0.384726 0.494784 0.384061 0.758612 0.340349 0.740468 0.371388 0.758681 0.300639 0.819487 0.272861 0.803563 0.340349 0.740468 0.384061 0.758612 0.300639 0.819487 0.340349 0.740468 0.382023 0.763835 0.371388 0.758681 0.37651 0.772157 0.384061 0.758612 0.371388 0.758681 0.382023 0.763835 0.427423 0.788781 0.37651 0.772157 0.381429 0.778496 0.424483 0.779655 0.382023 0.763835 0.37651 0.772157 0.427423 0.788781 0.424483 0.779655 0.37651 0.772157 0.430258 0.791087 0.381429 0.778496 0.386186 0.778403 0.430258 0.791087 0.427423 0.788781 0.381429 0.778496 0.43296 0.787395 0.386186 0.778403 0.390693 0.772674 0.43296 0.787395 0.430258 0.791087 0.386186 0.778403 0.43549 0.778501 0.390693 0.772674 0.394889 0.762059 0.43549 0.778501 0.43296 0.787395 0.390693 0.772674 0.437822 0.765133 0.394889 0.762059 0.398735 0.747244 0.437822 0.765133 0.43549 0.778501 0.394889 0.762059 0.439941 0.747941 0.398735 0.747244 0.402209 0.728842 0.439941 0.747941 0.437822 0.765133 0.398735 0.747244 0.441841 0.7275 0.402209 0.728842 0.405303 0.707397 0.441841 0.7275 0.439941 0.747941 0.402209 0.728842 0.44352 0.704313 0.405303 0.707397 0.408016 0.683391 0.44352 0.704313 0.441841 0.7275 0.405303 0.707397 0.444982 0.678823 0.408016 0.683391 0.410354 0.657247 0.444982 0.678823 0.44352 0.704313 0.408016 0.683391 0.446232 0.651422 0.410354 0.657247 0.412326 0.629343 0.446232 0.651422 0.444982 0.678823 0.410354 0.657247 0.447276 0.622455 0.412326 0.629343 0.41394 0.600017 0.447276 0.622455 0.446232 0.651422 0.412326 0.629343 0.44812 0.592233 0.41394 0.600017 0.415223 0.569655 0.44812 0.592233 0.447276 0.622455 0.41394 0.600017 0.416842 0.508986 0.415223 0.569655 0.414748 0.569488 0.416456 0.56981 0.44812 0.592233 0.415223 0.569655 0.416842 0.508986 0.416456 0.56981 0.415223 0.569655 0.413467 0.509004 0.414748 0.569488 0.412891 0.568276 0.416842 0.508986 0.414748 0.569488 0.413467 0.509004 0.413467 0.509004 0.412891 0.568276 0.411038 0.566117 0.410758 0.508975 0.411038 0.566117 0.409297 0.563008 0.413467 0.509004 0.411038 0.566117 0.410758 0.508975 0.408407 0.50891 0.409297 0.563008 0.407729 0.558856 0.410758 0.508975 0.409297 0.563008 0.408407 0.50891 0.40661 0.508818 0.407729 0.558856 0.406425 0.553508 0.408407 0.50891 0.407729 0.558856 0.40661 0.508818 0.40661 0.508818 0.406425 0.553508 0.405529 0.546743 0.403137 0.508277 0.405529 0.546743 0.404148 0.527588 0.405529 0.508704 0.405529 0.546743 0.403137 0.508277 0.40661 0.508818 0.405529 0.546743 0.405529 0.508704 0.422751 0.508506 0.403137 0.508277 0.411651 0.508175 0.422989 0.508655 0.405529 0.508704 0.403137 0.508277 0.422751 0.508506 0.422989 0.508655 0.403137 0.508277 0.422751 0.508506 0.411651 0.508175 0.416704 0.508121 0.420205 0.508085 0.416704 0.508121 0.416933 0.486187 0.422751 0.508506 0.416704 0.508121 0.420205 0.508085 0.420205 0.508085 0.416933 0.486187 0.449505 0.496767 0.430046 0.770019 0.382023 0.763835 0.424483 0.779655 0.384061 0.758612 0.382023 0.763835 0.430046 0.770019 0.426383 0.780198 0.424483 0.779655 0.427423 0.788781 0.430046 0.770019 0.424483 0.779655 0.426383 0.780198 0.47792 0.795799 0.427423 0.788781 0.430258 0.791087 0.472223 0.789415 0.426383 0.780198 0.427423 0.788781 0.477271 0.78999 0.472223 0.789415 0.427423 0.788781 0.47792 0.795799 0.477271 0.78999 0.427423 0.788781 0.478496 0.795665 0.430258 0.791087 0.43296 0.787395 0.478496 0.795665 0.47792 0.795799 0.430258 0.791087 0.479043 0.790299 0.43296 0.787395 0.43549 0.778501 0.479043 0.790299 0.478496 0.795665 0.43296 0.787395 0.479553 0.780388 0.43549 0.778501 0.437822 0.765133 0.479553 0.780388 0.479043 0.790299 0.43549 0.778501 0.464601 0.761951 0.437822 0.765133 0.439941 0.747941 0.479948 0.766601 0.479553 0.780388 0.437822 0.765133 0.472116 0.764864 0.479948 0.766601 0.437822 0.765133 0.464601 0.761951 0.472116 0.764864 0.437822 0.765133 0.45386 0.748783 0.439941 0.747941 0.441841 0.7275 0.458722 0.758108 0.464601 0.761951 0.439941 0.747941 0.45507 0.753662 0.458722 0.758108 0.439941 0.747941 0.45386 0.748783 0.45507 0.753662 0.439941 0.747941 0.481164 0.707682 0.441841 0.7275 0.44352 0.704313 0.455311 0.743883 0.45386 0.748783 0.441841 0.7275 0.459283 0.739384 0.455311 0.743883 0.441841 0.7275 0.465401 0.735601 0.459283 0.739384 0.441841 0.7275 0.473177 0.732758 0.465401 0.735601 0.441841 0.7275 0.480751 0.731186 0.473177 0.732758 0.441841 0.7275 0.481164 0.707682 0.480751 0.731186 0.441841 0.7275 0.481479 0.681784 0.44352 0.704313 0.444982 0.678823 0.481479 0.681784 0.481164 0.707682 0.44352 0.704313 0.481749 0.653965 0.444982 0.678823 0.446232 0.651422 0.481749 0.653965 0.481479 0.681784 0.444982 0.678823 0.481974 0.624578 0.446232 0.651422 0.447276 0.622455 0.481974 0.624578 0.481749 0.653965 0.446232 0.651422 0.482155 0.593933 0.447276 0.622455 0.44812 0.592233 0.482155 0.593933 0.481974 0.624578 0.447276 0.622455 0.422053 0.562599 0.44877 0.56104 0.44812 0.592233 0.482295 0.562315 0.44812 0.592233 0.44877 0.56104 0.420984 0.56577 0.422053 0.562599 0.44812 0.592233 0.419629 0.568016 0.420984 0.56577 0.44812 0.592233 0.418079 0.569347 0.419629 0.568016 0.44812 0.592233 0.416456 0.56981 0.418079 0.569347 0.44812 0.592233 0.482295 0.562315 0.482155 0.593933 0.44812 0.592233 0.422751 0.546378 0.449231 0.529136 0.44877 0.56104 0.482394 0.529987 0.44877 0.56104 0.449231 0.529136 0.423052 0.553079 0.422751 0.546378 0.44877 0.56104 0.422773 0.558418 0.423052 0.553079 0.44877 0.56104 0.422053 0.562599 0.422773 0.558418 0.44877 0.56104 0.482394 0.529987 0.482295 0.562315 0.44877 0.56104 0.420205 0.508085 0.449505 0.496767 0.449231 0.529136 0.482454 0.497193 0.449231 0.529136 0.449505 0.496767 0.421281 0.527312 0.420205 0.508085 0.449231 0.529136 0.422751 0.546378 0.421281 0.527312 0.449231 0.529136 0.482454 0.497193 0.482394 0.529987 0.449231 0.529136 0.422751 0.508506 0.420205 0.508085 0.421281 0.527312 0.422751 0.508506 0.421281 0.527312 0.422751 0.546378 0.422751 0.508506 0.422751 0.546378 0.423052 0.553079 0.422989 0.508655 0.423052 0.553079 0.422773 0.558418 0.422751 0.508506 0.423052 0.553079 0.422989 0.508655 0.422989 0.508655 0.422773 0.558418 0.422053 0.562599 0.421962 0.508798 0.422053 0.562599 0.420984 0.56577 0.422989 0.508655 0.422053 0.562599 0.421962 0.508798 0.419813 0.508914 0.420984 0.56577 0.419629 0.568016 0.421962 0.508798 0.420984 0.56577 0.419813 0.508914 0.419813 0.508914 0.419629 0.568016 0.418079 0.569347 0.416842 0.508986 0.418079 0.569347 0.416456 0.56981 0.419813 0.508914 0.418079 0.569347 0.416842 0.508986 0.477244 0.774525 0.426383 0.780198 0.472223 0.789415 0.430046 0.770019 0.426383 0.780198 0.477244 0.774525 0.477244 0.774525 0.472223 0.789415 0.477271 0.78999 0.518333 0.791554 0.477271 0.78999 0.47792 0.795799 0.524176 0.772134 0.477271 0.78999 0.518333 0.791554 0.477244 0.774525 0.477271 0.78999 0.524176 0.772134 0.527205 0.794779 0.47792 0.795799 0.478496 0.795665 0.528724 0.791077 0.518333 0.791554 0.47792 0.795799 0.527205 0.794779 0.528724 0.791077 0.47792 0.795799 0.525669 0.792817 0.478496 0.795665 0.479043 0.790299 0.525669 0.792817 0.527205 0.794779 0.478496 0.795665 0.524219 0.785867 0.479043 0.790299 0.479553 0.780388 0.524219 0.785867 0.525669 0.792817 0.479043 0.790299 0.522871 0.774591 0.479553 0.780388 0.479948 0.766601 0.522871 0.774591 0.524219 0.785867 0.479553 0.780388 0.480303 0.703615 0.479948 0.766601 0.472116 0.764864 0.481228 0.76679 0.522871 0.774591 0.479948 0.766601 0.480303 0.703615 0.481228 0.76679 0.479948 0.766601 0.470261 0.702505 0.472116 0.764864 0.464601 0.761951 0.470261 0.702505 0.480303 0.703615 0.472116 0.764864 0.462164 0.7008 0.464601 0.761951 0.458722 0.758108 0.462164 0.7008 0.470261 0.702505 0.464601 0.761951 0.456649 0.698681 0.458722 0.758108 0.45507 0.753662 0.456649 0.698681 0.462164 0.7008 0.458722 0.758108 0.45405 0.696341 0.45507 0.753662 0.45386 0.748783 0.45405 0.696341 0.456649 0.698681 0.45507 0.753662 0.45448 0.693983 0.45386 0.748783 0.455311 0.743883 0.45448 0.693983 0.45405 0.696341 0.45386 0.748783 0.457819 0.691782 0.455311 0.743883 0.459283 0.739384 0.457819 0.691782 0.45448 0.693983 0.455311 0.743883 0.463706 0.689908 0.459283 0.739384 0.465401 0.735601 0.463706 0.689908 0.457819 0.691782 0.459283 0.739384 0.471662 0.688479 0.465401 0.735601 0.473177 0.732758 0.471662 0.688479 0.463706 0.689908 0.465401 0.735601 0.471662 0.688479 0.473177 0.732758 0.480751 0.731186 0.481981 0.731017 0.480751 0.731186 0.481164 0.707682 0.481107 0.68758 0.480751 0.731186 0.481981 0.731017 0.481107 0.68758 0.471662 0.688479 0.480751 0.731186 0.518495 0.69332 0.481164 0.707682 0.481479 0.681784 0.519346 0.716496 0.481164 0.707682 0.518495 0.69332 0.491313 0.73043 0.481164 0.707682 0.519346 0.716496 0.491313 0.73043 0.481981 0.731017 0.481164 0.707682 0.517754 0.668314 0.481479 0.681784 0.481749 0.653965 0.518495 0.69332 0.481479 0.681784 0.517754 0.668314 0.51712 0.641782 0.481749 0.653965 0.481974 0.624578 0.517754 0.668314 0.481749 0.653965 0.51712 0.641782 0.516591 0.613992 0.481974 0.624578 0.482155 0.593933 0.51712 0.641782 0.481974 0.624578 0.516591 0.613992 0.516162 0.585192 0.482155 0.593933 0.482295 0.562315 0.516591 0.613992 0.482155 0.593933 0.516162 0.585192 0.515831 0.555604 0.482295 0.562315 0.482394 0.529987 0.516162 0.585192 0.482295 0.562315 0.515831 0.555604 0.515597 0.52544 0.482394 0.529987 0.482454 0.497193 0.515831 0.555604 0.482394 0.529987 0.515597 0.52544 0.515597 0.52544 0.482454 0.497193 0.515457 0.494898 0.524176 0.772134 0.518333 0.791554 0.528724 0.791077 0.563564 0.78687 0.528724 0.791077 0.527205 0.794779 0.569996 0.763027 0.528724 0.791077 0.563564 0.78687 0.524176 0.772134 0.528724 0.791077 0.569996 0.763027 0.574234 0.786396 0.527205 0.794779 0.525669 0.792817 0.57779 0.783968 0.563564 0.78687 0.527205 0.794779 0.574234 0.786396 0.57779 0.783968 0.527205 0.794779 0.570745 0.783337 0.525669 0.792817 0.524219 0.785867 0.570745 0.783337 0.574234 0.786396 0.525669 0.792817 0.567463 0.775436 0.524219 0.785867 0.522871 0.774591 0.567463 0.775436 0.570745 0.783337 0.524219 0.785867 0.518594 0.76166 0.521928 0.759642 0.522871 0.774591 0.564421 0.763339 0.522871 0.774591 0.521928 0.759642 0.510578 0.764842 0.518594 0.76166 0.522871 0.774591 0.501216 0.766814 0.510578 0.764842 0.522871 0.774591 0.491313 0.767471 0.501216 0.766814 0.522871 0.774591 0.481228 0.76679 0.491313 0.767471 0.522871 0.774591 0.564421 0.763339 0.567463 0.775436 0.522871 0.774591 0.520307 0.700844 0.521928 0.759642 0.518594 0.76166 0.524516 0.757552 0.564421 0.763339 0.521928 0.759642 0.525869 0.69874 0.524516 0.757552 0.521928 0.759642 0.520307 0.700844 0.525869 0.69874 0.521928 0.759642 0.512241 0.702525 0.518594 0.76166 0.510578 0.764842 0.512241 0.702525 0.520307 0.700844 0.518594 0.76166 0.502279 0.703618 0.510578 0.764842 0.501216 0.766814 0.502279 0.703618 0.512241 0.702525 0.510578 0.764842 0.502279 0.703618 0.501216 0.766814 0.491313 0.767471 0.491313 0.703997 0.491313 0.767471 0.481228 0.76679 0.491313 0.703997 0.502279 0.703618 0.491313 0.767471 0.480303 0.703615 0.491313 0.703997 0.481228 0.76679 0.569996 0.763027 0.563564 0.78687 0.57779 0.783968 0.606891 0.775769 0.57779 0.783968 0.574234 0.786396 0.592108 0.756055 0.57779 0.783968 0.606891 0.775769 0.569996 0.763027 0.57779 0.783968 0.592108 0.756055 0.618231 0.77147 0.574234 0.786396 0.570745 0.783337 0.623566 0.769615 0.606891 0.775769 0.574234 0.786396 0.618231 0.77147 0.623566 0.769615 0.574234 0.786396 0.613046 0.76793 0.570745 0.783337 0.567463 0.775436 0.613046 0.76793 0.618231 0.77147 0.570745 0.783337 0.608173 0.759614 0.567463 0.775436 0.564421 0.763339 0.608173 0.759614 0.613046 0.76793 0.567463 0.775436 0.524516 0.757552 0.561639 0.747624 0.564421 0.763339 0.603664 0.747152 0.564421 0.763339 0.561639 0.747624 0.603664 0.747152 0.608173 0.759614 0.564421 0.763339 0.52053 0.737394 0.559127 0.728811 0.561639 0.747624 0.599549 0.731115 0.561639 0.747624 0.559127 0.728811 0.522683 0.738864 0.52053 0.737394 0.561639 0.747624 0.526821 0.743099 0.522683 0.738864 0.561639 0.747624 0.528699 0.74787 0.526821 0.743099 0.561639 0.747624 0.527952 0.752834 0.528699 0.74787 0.561639 0.747624 0.524516 0.757552 0.527952 0.752834 0.561639 0.747624 0.599549 0.731115 0.603664 0.747152 0.561639 0.747624 0.519346 0.716496 0.556888 0.707357 0.559127 0.728811 0.595845 0.712015 0.559127 0.728811 0.556888 0.707357 0.52053 0.737394 0.519346 0.716496 0.559127 0.728811 0.595845 0.712015 0.599549 0.731115 0.559127 0.728811 0.518495 0.69332 0.55492 0.683668 0.556888 0.707357 0.592558 0.690311 0.556888 0.707357 0.55492 0.683668 0.519346 0.716496 0.518495 0.69332 0.556888 0.707357 0.592558 0.690311 0.595845 0.712015 0.556888 0.707357 0.517754 0.668314 0.553217 0.658104 0.55492 0.683668 0.589686 0.666409 0.55492 0.683668 0.553217 0.658104 0.518495 0.69332 0.517754 0.668314 0.55492 0.683668 0.589686 0.666409 0.592558 0.690311 0.55492 0.683668 0.51712 0.641782 0.551774 0.630984 0.553217 0.658104 0.587224 0.640672 0.553217 0.658104 0.551774 0.630984 0.517754 0.668314 0.51712 0.641782 0.553217 0.658104 0.587224 0.640672 0.589686 0.666409 0.553217 0.658104 0.516591 0.613992 0.550583 0.602597 0.551774 0.630984 0.585161 0.613427 0.551774 0.630984 0.550583 0.602597 0.51712 0.641782 0.516591 0.613992 0.551774 0.630984 0.585161 0.613427 0.587224 0.640672 0.551774 0.630984 0.516162 0.585192 0.549637 0.573205 0.550583 0.602597 0.583489 0.584969 0.550583 0.602597 0.549637 0.573205 0.516591 0.613992 0.516162 0.585192 0.550583 0.602597 0.583489 0.584969 0.585161 0.613427 0.550583 0.602597 0.547207 0.545699 0.54893 0.54305 0.549637 0.573205 0.5822 0.555569 0.549637 0.573205 0.54893 0.54305 0.54655 0.552422 0.547207 0.545699 0.549637 0.573205 0.545444 0.557749 0.54655 0.552422 0.549637 0.573205 0.544037 0.561892 0.545444 0.557749 0.549637 0.573205 0.542423 0.565005 0.544037 0.561892 0.549637 0.573205 0.540667 0.56718 0.542423 0.565005 0.549637 0.573205 0.538868 0.568433 0.540667 0.56718 0.549637 0.573205 0.537146 0.568819 0.538868 0.568433 0.549637 0.573205 0.535473 0.568419 0.537146 0.568819 0.549637 0.573205 0.516162 0.585192 0.535473 0.568419 0.549637 0.573205 0.5822 0.555569 0.583489 0.584969 0.549637 0.573205 0.548011 0.526904 0.548484 0.512361 0.54893 0.54305 0.581284 0.525478 0.54893 0.54305 0.548484 0.512361 0.547207 0.545699 0.548011 0.526904 0.54893 0.54305 0.581284 0.525478 0.5822 0.555569 0.54893 0.54305 0.547207 0.508384 0.548484 0.512361 0.548011 0.526904 0.548601 0.507962 0.581284 0.525478 0.548484 0.512361 0.547207 0.508384 0.548601 0.507962 0.548484 0.512361 0.547207 0.508384 0.548011 0.526904 0.547207 0.545699 0.547207 0.508384 0.547207 0.545699 0.54655 0.552422 0.546258 0.508512 0.54655 0.552422 0.545444 0.557749 0.547207 0.508384 0.54655 0.552422 0.546258 0.508512 0.54441 0.508617 0.545444 0.557749 0.544037 0.561892 0.546258 0.508512 0.545444 0.557749 0.54441 0.508617 0.54441 0.508617 0.544037 0.561892 0.542423 0.565005 0.541865 0.508689 0.542423 0.565005 0.540667 0.56718 0.54441 0.508617 0.542423 0.565005 0.541865 0.508689 0.538883 0.508719 0.540667 0.56718 0.538868 0.568433 0.541865 0.508689 0.540667 0.56718 0.538883 0.508719 0.538883 0.508719 0.538868 0.568433 0.537146 0.568819 0.535762 0.5087 0.537146 0.568819 0.535473 0.568419 0.538883 0.508719 0.537146 0.568819 0.535762 0.5087 0.515831 0.555604 0.533805 0.567123 0.535473 0.568419 0.535762 0.5087 0.535473 0.568419 0.533805 0.567123 0.516162 0.585192 0.515831 0.555604 0.535473 0.568419 0.515831 0.555604 0.532307 0.564888 0.533805 0.567123 0.532995 0.508635 0.533805 0.567123 0.532307 0.564888 0.535762 0.5087 0.533805 0.567123 0.532995 0.508635 0.515831 0.555604 0.531075 0.561722 0.532307 0.564888 0.532995 0.508635 0.532307 0.564888 0.531075 0.561722 0.515831 0.555604 0.530168 0.557538 0.531075 0.561722 0.53092 0.508531 0.531075 0.561722 0.530168 0.557538 0.532995 0.508635 0.531075 0.561722 0.53092 0.508531 0.515831 0.555604 0.529676 0.552191 0.530168 0.557538 0.529789 0.508403 0.530168 0.557538 0.529676 0.552191 0.53092 0.508531 0.530168 0.557538 0.529789 0.508403 0.515597 0.52544 0.529741 0.54548 0.529676 0.552191 0.529789 0.508403 0.529676 0.552191 0.529741 0.54548 0.515831 0.555604 0.515597 0.52544 0.529676 0.552191 0.531298 0.507846 0.529741 0.54548 0.530638 0.526738 0.515597 0.52544 0.530638 0.526738 0.529741 0.54548 0.529741 0.508265 0.529741 0.54548 0.531298 0.507846 0.529789 0.508403 0.529741 0.54548 0.529741 0.508265 0.515597 0.52544 0.531298 0.507846 0.530638 0.526738 0.548409 0.50796 0.531298 0.507846 0.539962 0.507898 0.515457 0.494898 0.539962 0.507898 0.531298 0.507846 0.548601 0.507962 0.531298 0.507846 0.548409 0.50796 0.515597 0.52544 0.515457 0.494898 0.531298 0.507846 0.529741 0.508265 0.531298 0.507846 0.548601 0.507962 0.515457 0.494898 0.548409 0.50796 0.539962 0.507898 0.515457 0.494898 0.548238 0.486101 0.548409 0.50796 0.580738 0.494935 0.548409 0.50796 0.548238 0.486101 0.548601 0.507962 0.548409 0.50796 0.580738 0.494935 0.516694 0.735353 0.519346 0.716496 0.52053 0.737394 0.500525 0.731002 0.491313 0.73043 0.519346 0.716496 0.50915 0.732677 0.500525 0.731002 0.519346 0.716496 0.516694 0.735353 0.50915 0.732677 0.519346 0.716496 0.519076 0.689946 0.52053 0.737394 0.522683 0.738864 0.519076 0.689946 0.516694 0.735353 0.52053 0.737394 0.524927 0.691836 0.522683 0.738864 0.526821 0.743099 0.524927 0.691836 0.519076 0.689946 0.522683 0.738864 0.528193 0.694041 0.526821 0.743099 0.528699 0.74787 0.528193 0.694041 0.524927 0.691836 0.526821 0.743099 0.528548 0.6964 0.528699 0.74787 0.527952 0.752834 0.528548 0.6964 0.528193 0.694041 0.528699 0.74787 0.525869 0.69874 0.527952 0.752834 0.524516 0.757552 0.525869 0.69874 0.528548 0.6964 0.527952 0.752834 0.613496 0.747551 0.606891 0.775769 0.623566 0.769615 0.592108 0.756055 0.606891 0.775769 0.613496 0.747551 0.647436 0.758779 0.623566 0.769615 0.618231 0.77147 0.634006 0.73761 0.623566 0.769615 0.647436 0.758779 0.613496 0.747551 0.623566 0.769615 0.634006 0.73761 0.658881 0.750813 0.618231 0.77147 0.613046 0.76793 0.665359 0.748911 0.647436 0.758779 0.618231 0.77147 0.658881 0.750813 0.665359 0.748911 0.618231 0.77147 0.652578 0.747767 0.613046 0.76793 0.608173 0.759614 0.652578 0.747767 0.658881 0.750813 0.613046 0.76793 0.646627 0.740292 0.608173 0.759614 0.603664 0.747152 0.646627 0.740292 0.652578 0.747767 0.608173 0.759614 0.641093 0.72893 0.603664 0.747152 0.599549 0.731115 0.641093 0.72893 0.646627 0.740292 0.603664 0.747152 0.636021 0.71419 0.599549 0.731115 0.595845 0.712015 0.636021 0.71419 0.641093 0.72893 0.599549 0.731115 0.631436 0.696533 0.595845 0.712015 0.592558 0.690311 0.631436 0.696533 0.636021 0.71419 0.595845 0.712015 0.62735 0.676378 0.592558 0.690311 0.589686 0.666409 0.62735 0.676378 0.631436 0.696533 0.592558 0.690311 0.623768 0.654103 0.589686 0.666409 0.587224 0.640672 0.623768 0.654103 0.62735 0.676378 0.589686 0.666409 0.620685 0.63005 0.587224 0.640672 0.585161 0.613427 0.620685 0.63005 0.623768 0.654103 0.587224 0.640672 0.618097 0.604529 0.585161 0.613427 0.583489 0.584969 0.618097 0.604529 0.620685 0.63005 0.585161 0.613427 0.615994 0.577823 0.583489 0.584969 0.5822 0.555569 0.615994 0.577823 0.618097 0.604529 0.583489 0.584969 0.614369 0.550195 0.5822 0.555569 0.581284 0.525478 0.614369 0.550195 0.615994 0.577823 0.5822 0.555569 0.548601 0.507962 0.580738 0.494935 0.581284 0.525478 0.613214 0.52189 0.581284 0.525478 0.580738 0.494935 0.613214 0.52189 0.614369 0.550195 0.581284 0.525478 0.612524 0.493139 0.613214 0.52189 0.580738 0.494935 0.547207 0.508384 0.529741 0.508265 0.548601 0.507962 0.653612 0.726273 0.647436 0.758779 0.665359 0.748911 0.634006 0.73761 0.647436 0.758779 0.653612 0.726273 0.684541 0.736483 0.665359 0.748911 0.658881 0.750813 0.67229 0.713565 0.665359 0.748911 0.684541 0.736483 0.653612 0.726273 0.665359 0.748911 0.67229 0.713565 0.695533 0.725071 0.658881 0.750813 0.652578 0.747767 0.702701 0.722671 0.684541 0.736483 0.658881 0.750813 0.695533 0.725071 0.702701 0.722671 0.658881 0.750813 0.688537 0.722875 0.652578 0.747767 0.646627 0.740292 0.688537 0.722875 0.695533 0.725071 0.652578 0.747767 0.681892 0.716517 0.646627 0.740292 0.641093 0.72893 0.681892 0.716517 0.688537 0.722875 0.646627 0.740292 0.675681 0.706468 0.641093 0.72893 0.636021 0.71419 0.675681 0.706468 0.681892 0.716517 0.641093 0.72893 0.669961 0.693182 0.636021 0.71419 0.631436 0.696533 0.669961 0.693182 0.675681 0.706468 0.636021 0.71419 0.664769 0.677079 0.631436 0.696533 0.62735 0.676378 0.664769 0.677079 0.669961 0.693182 0.631436 0.696533 0.660128 0.658549 0.62735 0.676378 0.623768 0.654103 0.660128 0.658549 0.664769 0.677079 0.62735 0.676378 0.65605 0.637949 0.623768 0.654103 0.620685 0.63005 0.65605 0.637949 0.660128 0.658549 0.623768 0.654103 0.652538 0.615608 0.620685 0.63005 0.618097 0.604529 0.652538 0.615608 0.65605 0.637949 0.620685 0.63005 0.64959 0.591826 0.618097 0.604529 0.615994 0.577823 0.64959 0.591826 0.652538 0.615608 0.618097 0.604529 0.637531 0.571221 0.615994 0.577823 0.614369 0.550195 0.641932 0.5727 0.64959 0.591826 0.615994 0.577823 0.640307 0.573046 0.641932 0.5727 0.615994 0.577823 0.63885 0.572593 0.640307 0.573046 0.615994 0.577823 0.637531 0.571221 0.63885 0.572593 0.615994 0.577823 0.639828 0.529174 0.614369 0.550195 0.613214 0.52189 0.636505 0.568879 0.637531 0.571221 0.614369 0.550195 0.635856 0.565577 0.636505 0.568879 0.614369 0.550195 0.63564 0.561228 0.635856 0.565577 0.614369 0.550195 0.63594 0.555692 0.63564 0.561228 0.614369 0.550195 0.636884 0.548758 0.63594 0.555692 0.614369 0.550195 0.639828 0.529174 0.636884 0.548758 0.614369 0.550195 0.641987 0.509397 0.613214 0.52189 0.612524 0.493139 0.641987 0.509397 0.639828 0.529174 0.613214 0.52189 0.643903 0.509443 0.641987 0.509397 0.612524 0.493139 0.643332 0.486877 0.643903 0.509443 0.612524 0.493139 0.689902 0.699589 0.684541 0.736483 0.702701 0.722671 0.67229 0.713565 0.684541 0.736483 0.689902 0.699589 0.717583 0.709613 0.702701 0.722671 0.695533 0.725071 0.706344 0.684452 0.702701 0.722671 0.717583 0.709613 0.689902 0.699589 0.702701 0.722671 0.706344 0.684452 0.720963 0.693973 0.695533 0.725071 0.688537 0.722875 0.72806 0.694845 0.717583 0.709613 0.695533 0.725071 0.720963 0.693973 0.72806 0.694845 0.695533 0.725071 0.71416 0.689345 0.688537 0.722875 0.681892 0.716517 0.71416 0.689345 0.720963 0.693973 0.688537 0.722875 0.707742 0.681336 0.681892 0.716517 0.675681 0.706468 0.707742 0.681336 0.71416 0.689345 0.681892 0.716517 0.70178 0.670318 0.675681 0.706468 0.669961 0.693182 0.70178 0.670318 0.707742 0.681336 0.675681 0.706468 0.696323 0.656649 0.669961 0.693182 0.664769 0.677079 0.696323 0.656649 0.70178 0.670318 0.669961 0.693182 0.691407 0.640671 0.664769 0.677079 0.660128 0.658549 0.691407 0.640671 0.696323 0.656649 0.664769 0.677079 0.687052 0.622701 0.660128 0.658549 0.65605 0.637949 0.687052 0.622701 0.691407 0.640671 0.660128 0.658549 0.683273 0.603041 0.65605 0.637949 0.652538 0.615608 0.683273 0.603041 0.687052 0.622701 0.65605 0.637949 0.680075 0.581969 0.652538 0.615608 0.64959 0.591826 0.680075 0.581969 0.683273 0.603041 0.652538 0.615608 0.645697 0.569309 0.647203 0.566972 0.64959 0.591826 0.677462 0.559748 0.64959 0.591826 0.647203 0.566972 0.643762 0.571476 0.645697 0.569309 0.64959 0.591826 0.641932 0.5727 0.643762 0.571476 0.64959 0.591826 0.677462 0.559748 0.680075 0.581969 0.64959 0.591826 0.646228 0.510424 0.647203 0.566972 0.645697 0.569309 0.64764 0.566175 0.677462 0.559748 0.647203 0.566972 0.64886 0.510386 0.64764 0.566175 0.647203 0.566972 0.64886 0.510386 0.647203 0.566972 0.646228 0.510424 0.646228 0.510424 0.645697 0.569309 0.643762 0.571476 0.642763 0.510419 0.643762 0.571476 0.641932 0.5727 0.646228 0.510424 0.643762 0.571476 0.642763 0.510419 0.642763 0.510419 0.641932 0.5727 0.640307 0.573046 0.63962 0.510355 0.640307 0.573046 0.63885 0.572593 0.642763 0.510419 0.640307 0.573046 0.63962 0.510355 0.63962 0.510355 0.63885 0.572593 0.637531 0.571221 0.637217 0.510243 0.637531 0.571221 0.636505 0.568879 0.63962 0.510355 0.637531 0.571221 0.637217 0.510243 0.635865 0.5101 0.636505 0.568879 0.635856 0.565577 0.637217 0.510243 0.636505 0.568879 0.635865 0.5101 0.635865 0.5101 0.635856 0.565577 0.63564 0.561228 0.635744 0.509944 0.63564 0.561228 0.63594 0.555692 0.635865 0.5101 0.63564 0.561228 0.635744 0.509944 0.635744 0.509944 0.63594 0.555692 0.636884 0.548758 0.641987 0.509397 0.636884 0.548758 0.639828 0.529174 0.636884 0.509797 0.636884 0.548758 0.641987 0.509397 0.635744 0.509944 0.636884 0.548758 0.636884 0.509797 0.636884 0.509797 0.641987 0.509397 0.643903 0.509443 0.673116 0.488612 0.643903 0.509443 0.643332 0.486877 0.649949 0.509594 0.643903 0.509443 0.673116 0.488612 0.636884 0.509797 0.643903 0.509443 0.649949 0.509594 0.72806 0.694845 0.735213 0.691697 0.717583 0.709613 0.721573 0.668223 0.717583 0.709613 0.735213 0.691697 0.706344 0.684452 0.717583 0.709613 0.721573 0.668223 0.75604 0.660637 0.735213 0.691697 0.72806 0.694845 0.75604 0.660637 0.74655 0.678472 0.735213 0.691697 0.735533 0.650987 0.735213 0.691697 0.74655 0.678472 0.721573 0.668223 0.735213 0.691697 0.735533 0.650987 0.749226 0.661231 0.72806 0.694845 0.720963 0.693973 0.749226 0.661231 0.75604 0.660637 0.72806 0.694845 0.742622 0.65843 0.720963 0.693973 0.71416 0.689345 0.742622 0.65843 0.749226 0.661231 0.720963 0.693973 0.736329 0.652521 0.71416 0.689345 0.707742 0.681336 0.736329 0.652521 0.742622 0.65843 0.71416 0.689345 0.730428 0.643805 0.707742 0.681336 0.70178 0.670318 0.730428 0.643805 0.736329 0.652521 0.707742 0.681336 0.724983 0.632582 0.70178 0.670318 0.696323 0.656649 0.724983 0.632582 0.730428 0.643805 0.70178 0.670318 0.720039 0.61915 0.696323 0.656649 0.691407 0.640671 0.720039 0.61915 0.724983 0.632582 0.696323 0.656649 0.715632 0.603797 0.691407 0.640671 0.687052 0.622701 0.715632 0.603797 0.720039 0.61915 0.691407 0.640671 0.711785 0.586796 0.687052 0.622701 0.683273 0.603041 0.711785 0.586796 0.715632 0.603797 0.687052 0.622701 0.708515 0.568411 0.683273 0.603041 0.680075 0.581969 0.708515 0.568411 0.711785 0.586796 0.683273 0.603041 0.705831 0.548892 0.680075 0.581969 0.677462 0.559748 0.705831 0.548892 0.708515 0.568411 0.680075 0.581969 0.652814 0.549528 0.675432 0.536626 0.677462 0.559748 0.70374 0.52848 0.677462 0.559748 0.675432 0.536626 0.651309 0.556499 0.652814 0.549528 0.677462 0.559748 0.649539 0.561964 0.651309 0.556499 0.677462 0.559748 0.64764 0.566175 0.649539 0.561964 0.677462 0.559748 0.70374 0.52848 0.705831 0.548892 0.677462 0.559748 0.655704 0.529756 0.673984 0.512839 0.675432 0.536626 0.702244 0.507407 0.675432 0.536626 0.673984 0.512839 0.652814 0.549528 0.655704 0.529756 0.675432 0.536626 0.702244 0.507407 0.70374 0.52848 0.675432 0.536626 0.657821 0.509802 0.673116 0.488612 0.673984 0.512839 0.701346 0.485896 0.673984 0.512839 0.673116 0.488612 0.655704 0.529756 0.657821 0.509802 0.673984 0.512839 0.701346 0.485896 0.702244 0.507407 0.673984 0.512839 0.657821 0.509802 0.649949 0.509594 0.673116 0.488612 0.636884 0.509797 0.649949 0.509594 0.657821 0.509802 0.652814 0.510213 0.657821 0.509802 0.655704 0.529756 0.635744 0.509944 0.636884 0.509797 0.657821 0.509802 0.635865 0.5101 0.635744 0.509944 0.657821 0.509802 0.652814 0.510213 0.635865 0.5101 0.657821 0.509802 0.652814 0.510213 0.655704 0.529756 0.652814 0.549528 0.652814 0.510213 0.652814 0.549528 0.651309 0.556499 0.651124 0.510313 0.651309 0.556499 0.649539 0.561964 0.652814 0.510213 0.651309 0.556499 0.651124 0.510313 0.64886 0.510386 0.649539 0.561964 0.64764 0.566175 0.651124 0.510313 0.649539 0.561964 0.64886 0.510386 0.75604 0.660637 0.76312 0.656056 0.74655 0.678472 0.748194 0.632799 0.74655 0.678472 0.76312 0.656056 0.735533 0.650987 0.74655 0.678472 0.748194 0.632799 0.779297 0.622814 0.76312 0.656056 0.75604 0.660637 0.779297 0.622814 0.770096 0.645231 0.76312 0.656056 0.748194 0.632799 0.76312 0.656056 0.770096 0.645231 0.773158 0.624997 0.75604 0.660637 0.749226 0.661231 0.773158 0.624997 0.779297 0.622814 0.75604 0.660637 0.76712 0.62417 0.749226 0.661231 0.742622 0.65843 0.76712 0.62417 0.773158 0.624997 0.749226 0.661231 0.761293 0.620529 0.742622 0.65843 0.736329 0.652521 0.761293 0.620529 0.76712 0.62417 0.742622 0.65843 0.755765 0.6143 0.736329 0.652521 0.730428 0.643805 0.755765 0.6143 0.761293 0.620529 0.736329 0.652521 0.750611 0.605724 0.730428 0.643805 0.724983 0.632582 0.750611 0.605724 0.755765 0.6143 0.730428 0.643805 0.74589 0.595052 0.724983 0.632582 0.720039 0.61915 0.74589 0.595052 0.750611 0.605724 0.724983 0.632582 0.741649 0.582534 0.720039 0.61915 0.715632 0.603797 0.741649 0.582534 0.74589 0.595052 0.720039 0.61915 0.737925 0.568418 0.715632 0.603797 0.711785 0.586796 0.737925 0.568418 0.741649 0.582534 0.715632 0.603797 0.7191 0.579932 0.711785 0.586796 0.708515 0.568411 0.723207 0.5791 0.737925 0.568418 0.711785 0.586796 0.72153 0.580274 0.723207 0.5791 0.711785 0.586796 0.720177 0.580525 0.72153 0.580274 0.711785 0.586796 0.7191 0.579932 0.720177 0.580525 0.711785 0.586796 0.721356 0.554478 0.708515 0.568411 0.705831 0.548892 0.718299 0.578363 0.7191 0.579932 0.708515 0.568411 0.717904 0.575795 0.718299 0.578363 0.708515 0.568411 0.717958 0.572243 0.717904 0.575795 0.708515 0.568411 0.718502 0.567616 0.717958 0.572243 0.708515 0.568411 0.719603 0.561765 0.718502 0.567616 0.708515 0.568411 0.721356 0.554478 0.719603 0.561765 0.708515 0.568411 0.726171 0.533478 0.705831 0.548892 0.70374 0.52848 0.726171 0.533478 0.721356 0.554478 0.705831 0.548892 0.729561 0.513195 0.70374 0.52848 0.702244 0.507407 0.728073 0.523001 0.726171 0.533478 0.70374 0.52848 0.729561 0.513195 0.728073 0.523001 0.70374 0.52848 0.728394 0.4971 0.702244 0.507407 0.701346 0.485896 0.728394 0.4971 0.729561 0.513195 0.702244 0.507407 0.727701 0.480709 0.728394 0.4971 0.701346 0.485896 0.779297 0.622814 0.785517 0.617226 0.770096 0.645231 0.759537 0.61369 0.770096 0.645231 0.785517 0.617226 0.748194 0.632799 0.770096 0.645231 0.759537 0.61369 0.798712 0.580257 0.785517 0.617226 0.779297 0.622814 0.798712 0.580257 0.786559 0.615073 0.785517 0.617226 0.774305 0.604159 0.785517 0.617226 0.786559 0.615073 0.767754 0.614538 0.759537 0.61369 0.785517 0.617226 0.768708 0.613713 0.767754 0.614538 0.785517 0.617226 0.770153 0.611737 0.768708 0.613713 0.785517 0.617226 0.772045 0.608548 0.770153 0.611737 0.785517 0.617226 0.774305 0.604159 0.772045 0.608548 0.785517 0.617226 0.794352 0.584226 0.779297 0.622814 0.773158 0.624997 0.794352 0.584226 0.798712 0.580257 0.779297 0.622814 0.785549 0.586453 0.773158 0.624997 0.76712 0.62417 0.789942 0.586269 0.794352 0.584226 0.773158 0.624997 0.785549 0.586453 0.789942 0.586269 0.773158 0.624997 0.781752 0.592544 0.76712 0.62417 0.761293 0.620529 0.457819 0.691782 0.456649 0.698681 0.45448 0.693983 0.783441 0.590142 0.785549 0.586453 0.76712 0.62417 0.781752 0.592544 0.783441 0.590142 0.76712 0.62417 0.776612 0.580949 0.761293 0.620529 0.755765 0.6143 0.780487 0.593793 0.781752 0.592544 0.761293 0.620529 0.77969 0.593982 0.780487 0.593793 0.761293 0.620529 0.779292 0.593234 0.77969 0.593982 0.761293 0.620529 0.779319 0.591453 0.779292 0.593234 0.761293 0.620529 0.779824 0.588595 0.779319 0.591453 0.761293 0.620529 0.780818 0.584661 0.779824 0.588595 0.761293 0.620529 0.463706 0.689908 0.462164 0.7008 0.457819 0.691782 0.776612 0.580949 0.780818 0.584661 0.761293 0.620529 0.772592 0.575686 0.755765 0.6143 0.750611 0.605724 0.772592 0.575686 0.776612 0.580949 0.755765 0.6143 0.768836 0.568902 0.750611 0.605724 0.74589 0.595052 0.768836 0.568902 0.772592 0.575686 0.750611 0.605724 0.765386 0.56074 0.74589 0.595052 0.741649 0.582534 0.765386 0.56074 0.768836 0.568902 0.74589 0.595052 0.762275 0.55135 0.741649 0.582534 0.737925 0.568418 0.762275 0.55135 0.765386 0.56074 0.741649 0.582534 0.73413 0.55583 0.734852 0.552992 0.737925 0.568418 0.759531 0.540886 0.737925 0.568418 0.734852 0.552992 0.73183 0.563414 0.73413 0.55583 0.737925 0.568418 0.7295 0.569256 0.73183 0.563414 0.737925 0.568418 0.727252 0.57368 0.7295 0.569256 0.737925 0.568418 0.725141 0.576917 0.727252 0.57368 0.737925 0.568418 0.723207 0.5791 0.725141 0.576917 0.737925 0.568418 0.759531 0.540886 0.762275 0.55135 0.737925 0.568418 0.73413 0.513625 0.734852 0.552992 0.73413 0.55583 0.757175 0.529502 0.759531 0.540886 0.734852 0.552992 0.738979 0.534433 0.757175 0.529502 0.734852 0.552992 0.73413 0.513625 0.738979 0.534433 0.734852 0.552992 0.73413 0.513625 0.73413 0.55583 0.73183 0.563414 0.730019 0.51373 0.73183 0.563414 0.7295 0.569256 0.732202 0.513689 0.73413 0.513625 0.73183 0.563414 0.730019 0.51373 0.732202 0.513689 0.73183 0.563414 0.730019 0.51373 0.7295 0.569256 0.727252 0.57368 0.726247 0.513738 0.727252 0.57368 0.725141 0.576917 0.726247 0.513738 0.730019 0.51373 0.727252 0.57368 0.726247 0.513738 0.725141 0.576917 0.723207 0.5791 0.722704 0.513676 0.723207 0.5791 0.72153 0.580274 0.722704 0.513676 0.726247 0.513738 0.723207 0.5791 0.722704 0.513676 0.72153 0.580274 0.720177 0.580525 0.719902 0.513553 0.720177 0.580525 0.7191 0.579932 0.719902 0.513553 0.722704 0.513676 0.720177 0.580525 0.719902 0.513553 0.7191 0.579932 0.718299 0.578363 0.718235 0.513389 0.718299 0.578363 0.717904 0.575795 0.718235 0.513389 0.719902 0.513553 0.718299 0.578363 0.717929 0.513207 0.717904 0.575795 0.717958 0.572243 0.717929 0.513207 0.718235 0.513389 0.717904 0.575795 0.717929 0.513207 0.717958 0.572243 0.718502 0.567616 0.719021 0.513034 0.718502 0.567616 0.719603 0.561765 0.719021 0.513034 0.717929 0.513207 0.718502 0.567616 0.719021 0.513034 0.719603 0.561765 0.721356 0.554478 0.728073 0.523001 0.721356 0.554478 0.726171 0.533478 0.729561 0.513195 0.721356 0.554478 0.728073 0.523001 0.729648 0.51255 0.721356 0.554478 0.729561 0.513195 0.721356 0.512893 0.721356 0.554478 0.729648 0.51255 0.721356 0.512893 0.719021 0.513034 0.721356 0.554478 0.729648 0.51255 0.729561 0.513195 0.728394 0.4971 0.751939 0.477845 0.728394 0.4971 0.727701 0.480709 0.751939 0.477845 0.752601 0.491369 0.728394 0.4971 0.729648 0.51255 0.728394 0.4971 0.752601 0.491369 0.798712 0.580257 0.797165 0.590487 0.786559 0.615073 0.776909 0.598459 0.786559 0.615073 0.797165 0.590487 0.776909 0.598459 0.774305 0.604159 0.786559 0.615073 0.798712 0.580257 0.803002 0.57408 0.797165 0.590487 0.783064 0.582238 0.797165 0.590487 0.803002 0.57408 0.779839 0.591251 0.776909 0.598459 0.797165 0.590487 0.783064 0.582238 0.779839 0.591251 0.797165 0.590487 0.809641 0.537457 0.803002 0.57408 0.798712 0.580257 0.812666 0.531366 0.804195 0.570366 0.803002 0.57408 0.783064 0.582238 0.803002 0.57408 0.804195 0.570366 0.809641 0.537457 0.812666 0.531366 0.803002 0.57408 0.806417 0.542027 0.798712 0.580257 0.794352 0.584226 0.806417 0.542027 0.809641 0.537457 0.798712 0.580257 0.803065 0.545029 0.794352 0.584226 0.789942 0.586269 0.803065 0.545029 0.806417 0.542027 0.794352 0.584226 0.787879 0.581686 0.789942 0.586269 0.785549 0.586453 0.799663 0.546316 0.803065 0.545029 0.789942 0.586269 0.793534 0.567118 0.799663 0.546316 0.789942 0.586269 0.790579 0.5753 0.793534 0.567118 0.789942 0.586269 0.787879 0.581686 0.790579 0.5753 0.789942 0.586269 0.45448 0.693983 0.456649 0.698681 0.45405 0.696341 0.789162 0.519769 0.787879 0.581686 0.785549 0.586453 0.784984 0.519698 0.785549 0.586453 0.783441 0.590142 0.784984 0.519698 0.789162 0.519769 0.785549 0.586453 0.784984 0.519698 0.783441 0.590142 0.781752 0.592544 0.781678 0.519545 0.781752 0.592544 0.780487 0.593793 0.781678 0.519545 0.784984 0.519698 0.781752 0.592544 0.781678 0.519545 0.780487 0.593793 0.77969 0.593982 0.779689 0.519335 0.77969 0.593982 0.779292 0.593234 0.779689 0.519335 0.781678 0.519545 0.77969 0.593982 0.779311 0.5191 0.779292 0.593234 0.779319 0.591453 0.779311 0.5191 0.779689 0.519335 0.779292 0.593234 0.779311 0.5191 0.779319 0.591453 0.779824 0.588595 0.780567 0.518879 0.779824 0.588595 0.780818 0.584661 0.780567 0.518879 0.779311 0.5191 0.779824 0.588595 0.457819 0.691782 0.462164 0.7008 0.456649 0.698681 0.782324 0.579548 0.780818 0.584661 0.776612 0.580949 0.780567 0.518879 0.780818 0.584661 0.782324 0.579548 0.789928 0.541867 0.776612 0.580949 0.772592 0.575686 0.793062 0.544619 0.776612 0.580949 0.789928 0.541867 0.787048 0.564988 0.776612 0.580949 0.793062 0.544619 0.784382 0.573077 0.782324 0.579548 0.776612 0.580949 0.787048 0.564988 0.784382 0.573077 0.776612 0.580949 0.787027 0.537769 0.772592 0.575686 0.768836 0.568902 0.789928 0.541867 0.772592 0.575686 0.787027 0.537769 0.784331 0.532543 0.768836 0.568902 0.765386 0.56074 0.787027 0.537769 0.768836 0.568902 0.784331 0.532543 0.781875 0.526294 0.765386 0.56074 0.762275 0.55135 0.784331 0.532543 0.765386 0.56074 0.781875 0.526294 0.779689 0.519138 0.762275 0.55135 0.759531 0.540886 0.781875 0.526294 0.762275 0.55135 0.779689 0.519138 0.777798 0.511194 0.759531 0.540886 0.757175 0.529502 0.779689 0.519138 0.759531 0.540886 0.777798 0.511194 0.738979 0.534433 0.755227 0.517351 0.757175 0.529502 0.776224 0.502589 0.757175 0.529502 0.755227 0.517351 0.777798 0.511194 0.757175 0.529502 0.776224 0.502589 0.742454 0.513267 0.753699 0.504589 0.755227 0.517351 0.774983 0.493452 0.755227 0.517351 0.753699 0.504589 0.740883 0.523817 0.742454 0.513267 0.755227 0.517351 0.738979 0.534433 0.740883 0.523817 0.755227 0.517351 0.776224 0.502589 0.755227 0.517351 0.774983 0.493452 0.729648 0.51255 0.752601 0.491369 0.753699 0.504589 0.774087 0.483914 0.753699 0.504589 0.752601 0.491369 0.736136 0.512901 0.729648 0.51255 0.753699 0.504589 0.742454 0.513267 0.736136 0.512901 0.753699 0.504589 0.774983 0.493452 0.753699 0.504589 0.774087 0.483914 0.773547 0.474108 0.752601 0.491369 0.751939 0.477845 0.774087 0.483914 0.752601 0.491369 0.773547 0.474108 0.73413 0.513625 0.729648 0.51255 0.736136 0.512901 0.732202 0.513689 0.729648 0.51255 0.73413 0.513625 0.730019 0.51373 0.729648 0.51255 0.732202 0.513689 0.726247 0.513738 0.729648 0.51255 0.730019 0.51373 0.721356 0.512893 0.729648 0.51255 0.726247 0.513738 0.73413 0.513625 0.736136 0.512901 0.742454 0.513267 0.73413 0.513625 0.742454 0.513267 0.740883 0.523817 0.73413 0.513625 0.740883 0.523817 0.738979 0.534433 0.812666 0.531366 0.809172 0.552976 0.804195 0.570366 0.790909 0.555589 0.804195 0.570366 0.809172 0.552976 0.790909 0.555589 0.783064 0.582238 0.804195 0.570366 0.812666 0.531366 0.812924 0.536888 0.809172 0.552976 0.796832 0.528168 0.809172 0.552976 0.812924 0.536888 0.790909 0.555589 0.809172 0.552976 0.796832 0.528168 0.812666 0.531366 0.815372 0.523936 0.812924 0.536888 0.796832 0.528168 0.812924 0.536888 0.815372 0.523936 0.813465 0.494287 0.815372 0.523936 0.812666 0.531366 0.814633 0.490191 0.815851 0.521042 0.815372 0.523936 0.796832 0.528168 0.815372 0.523936 0.815851 0.521042 0.813465 0.494287 0.814633 0.490191 0.815372 0.523936 0.812144 0.497824 0.812666 0.531366 0.809641 0.537457 0.812144 0.497824 0.813465 0.494287 0.812666 0.531366 0.810694 0.500745 0.809641 0.537457 0.806417 0.542027 0.810694 0.500745 0.812144 0.497824 0.809641 0.537457 0.809145 0.503003 0.806417 0.542027 0.803065 0.545029 0.809145 0.503003 0.810694 0.500745 0.806417 0.542027 0.807525 0.504569 0.803065 0.545029 0.799663 0.546316 0.807525 0.504569 0.809145 0.503003 0.803065 0.545029 0.793534 0.519745 0.799663 0.546316 0.793534 0.567118 0.805394 0.519536 0.807525 0.504569 0.799663 0.546316 0.800621 0.542506 0.805394 0.519536 0.799663 0.546316 0.793534 0.519745 0.800621 0.542506 0.799663 0.546316 0.793534 0.519745 0.793534 0.567118 0.790579 0.5753 0.789162 0.519769 0.790579 0.5753 0.787879 0.581686 0.789162 0.519769 0.793534 0.519745 0.790579 0.5753 0.814633 0.490191 0.81707 0.512872 0.815851 0.521042 0.794343 0.508661 0.815851 0.521042 0.81707 0.512872 0.796832 0.528168 0.815851 0.521042 0.794343 0.508661 0.814633 0.490191 0.818137 0.504347 0.81707 0.512872 0.794343 0.508661 0.81707 0.512872 0.818137 0.504347 0.815623 0.485606 0.819042 0.495302 0.818137 0.504347 0.794343 0.508661 0.818137 0.504347 0.819042 0.495302 0.814633 0.490191 0.815623 0.485606 0.818137 0.504347 0.816415 0.480616 0.819757 0.485581 0.819042 0.495302 0.796711 0.486472 0.819042 0.495302 0.819757 0.485581 0.815623 0.485606 0.816415 0.480616 0.819042 0.495302 0.794343 0.508661 0.819042 0.495302 0.796711 0.486472 0.816993 0.475312 0.820102 0.478699 0.819757 0.485581 0.796711 0.486472 0.819757 0.485581 0.820102 0.478699 0.816415 0.480616 0.816993 0.475312 0.819757 0.485581 0.817345 0.469794 0.82032 0.47156 0.820102 0.478699 0.796711 0.486472 0.820102 0.478699 0.82032 0.47156 0.816993 0.475312 0.817345 0.469794 0.820102 0.478699 0.805394 0.519536 0.805864 0.505425 0.807525 0.504569 0.802193 0.518956 0.804192 0.505566 0.805864 0.505425 0.803832 0.519244 0.802193 0.518956 0.805864 0.505425 0.805394 0.519536 0.803832 0.519244 0.805864 0.505425 0.800477 0.518673 0.802536 0.505003 0.804192 0.505566 0.802193 0.518956 0.800477 0.518673 0.804192 0.505566 0.798687 0.518394 0.800925 0.503754 0.802536 0.505003 0.800477 0.518673 0.798687 0.518394 0.802536 0.505003 0.789928 0.541867 0.799385 0.50185 0.800925 0.503754 0.798687 0.518394 0.789928 0.541867 0.800925 0.503754 0.787027 0.537769 0.79794 0.499332 0.799385 0.50185 0.789928 0.541867 0.787027 0.537769 0.799385 0.50185 0.784331 0.532543 0.796612 0.496249 0.79794 0.499332 0.787027 0.537769 0.784331 0.532543 0.79794 0.499332 0.781875 0.526294 0.795421 0.492655 0.796612 0.496249 0.784331 0.532543 0.781875 0.526294 0.796612 0.496249 0.779689 0.519138 0.794384 0.488614 0.795421 0.492655 0.781875 0.526294 0.779689 0.519138 0.795421 0.492655 0.777798 0.511194 0.793515 0.484192 0.794384 0.488614 0.779689 0.519138 0.777798 0.511194 0.794384 0.488614 0.776224 0.502589 0.792827 0.479461 0.793515 0.484192 0.777798 0.511194 0.776224 0.502589 0.793515 0.484192 0.774983 0.493452 0.792329 0.474495 0.792827 0.479461 0.776224 0.502589 0.774983 0.493452 0.792827 0.479461 0.774087 0.483914 0.792027 0.469371 0.792329 0.474495 0.774983 0.493452 0.774087 0.483914 0.792329 0.474495 0.774087 0.483914 0.773547 0.474108 0.792027 0.469371 0.794002 0.540888 0.793062 0.544619 0.789928 0.541867 0.798687 0.518394 0.794002 0.540888 0.789928 0.541867 0.798687 0.518394 0.793062 0.544619 0.794002 0.540888 0.787048 0.564988 0.793062 0.544619 0.798687 0.518394 0.805394 0.519536 0.798687 0.518394 0.800477 0.518673 0.793534 0.519745 0.798687 0.518394 0.805394 0.519536 0.787048 0.51859 0.787048 0.564988 0.798687 0.518394 0.787048 0.51859 0.798687 0.518394 0.793534 0.519745 0.803832 0.519244 0.800477 0.518673 0.802193 0.518956 0.805394 0.519536 0.800477 0.518673 0.803832 0.519244 0.793534 0.519745 0.805394 0.519536 0.800621 0.542506 0.783272 0.5187 0.782324 0.579548 0.784382 0.573077 0.783272 0.5187 0.780567 0.518879 0.782324 0.579548 0.783272 0.5187 0.784382 0.573077 0.787048 0.564988 0.787048 0.51859 0.783272 0.5187 0.787048 0.564988 0.481107 0.68758 0.481981 0.731017 0.491313 0.73043 0.491313 0.687273 0.491313 0.73043 0.500525 0.731002 0.481107 0.68758 0.491313 0.73043 0.491313 0.687273 0.501559 0.687582 0.500525 0.731002 0.50915 0.732677 0.501559 0.687582 0.491313 0.687273 0.500525 0.731002 0.511083 0.688495 0.50915 0.732677 0.516694 0.735353 0.511083 0.688495 0.501559 0.687582 0.50915 0.732677 0.519076 0.689946 0.511083 0.688495 0.516694 0.735353 0.143157 0.507913 0.169953 0.535003 0.175265 0.535253 0.183606 0.534474 0.175265 0.535253 0.169953 0.535003 0.168338 0.499887 0.143157 0.507913 0.175265 0.535253 0.09446197 0.525575 0.168338 0.499887 0.175265 0.535253 0.172843 0.535998 0.175265 0.535253 0.183606 0.534474 0.09446197 0.525575 0.175265 0.535253 0.172843 0.535998 0.143157 0.507913 0.164679 0.534752 0.169953 0.535003 0.183606 0.534474 0.169953 0.535003 0.164679 0.534752 0.146624 0.549698 0.172929 0.555827 0.164679 0.534752 0.183606 0.534474 0.164679 0.534752 0.172929 0.555827 0.143157 0.507913 0.146624 0.549698 0.164679 0.534752 0.152169 0.587601 0.183606 0.577051 0.172929 0.555827 0.183606 0.534474 0.172929 0.555827 0.183606 0.577051 0.146624 0.549698 0.152169 0.587601 0.172929 0.555827 0.152169 0.587601 0.187285 0.582512 0.183606 0.577051 0.183606 0.534474 0.183606 0.577051 0.187285 0.582512 0.152169 0.587601 0.190891 0.58596 0.187285 0.582512 0.187268 0.534452 0.187285 0.582512 0.190891 0.58596 0.183606 0.534474 0.187285 0.582512 0.187268 0.534452 0.152169 0.587601 0.193005 0.587105 0.190891 0.58596 0.190891 0.534495 0.190891 0.58596 0.193005 0.587105 0.187268 0.534452 0.190891 0.58596 0.190891 0.534495 0.152169 0.587601 0.194876 0.587472 0.193005 0.587105 0.190891 0.534495 0.193005 0.587105 0.194876 0.587472 0.152169 0.587601 0.212484 0.617942 0.194876 0.587472 0.197492 0.594609 0.194876 0.587472 0.212484 0.617942 0.190891 0.534495 0.194876 0.587472 0.195545 0.534668 0.197492 0.594609 0.195545 0.534668 0.194876 0.587472 0.152169 0.587601 0.1594319 0.62008 0.212484 0.617942 0.154431 0.642667 0.212484 0.617942 0.144178 0.669793 0.1993809 0.60009 0.197492 0.594609 0.212484 0.617942 0.200536 0.604047 0.1993809 0.60009 0.212484 0.617942 0.200944 0.606496 0.200536 0.604047 0.212484 0.617942 0.200684 0.607519 0.200944 0.606496 0.212484 0.617942 0.152966 0.630988 0.200684 0.607519 0.212484 0.617942 0.154631 0.63634 0.152966 0.630988 0.212484 0.617942 0.155381 0.640009 0.154631 0.63634 0.212484 0.617942 0.155277 0.64205 0.155381 0.640009 0.212484 0.617942 0.154431 0.642667 0.155277 0.64205 0.212484 0.617942 0.293037 0.522375 0.26528 0.521216 0.266792 0.492908 0.301963 0.50994 0.292825 0.509971 0.266792 0.492908 0.293037 0.522375 0.266792 0.492908 0.292825 0.509971 0.311088 0.509904 0.301963 0.50994 0.266792 0.492908 0.296527 0.550762 0.26277 0.54866 0.26528 0.521216 0.263729 0.478497 0.26528 0.521216 0.26277 0.54866 0.294983 0.546724 0.296527 0.550762 0.26528 0.521216 0.29385 0.541437 0.294983 0.546724 0.26528 0.521216 0.293302 0.534696 0.29385 0.541437 0.26528 0.521216 0.293037 0.522375 0.293302 0.534696 0.26528 0.521216 0.263729 0.478497 0.263741 0.450489 0.26528 0.521216 0.262676 0.506259 0.26277 0.54866 0.259287 0.574749 0.300336 0.555603 0.302306 0.556529 0.26277 0.54866 0.298349 0.553694 0.300336 0.555603 0.26277 0.54866 0.296527 0.550762 0.298349 0.553694 0.26277 0.54866 0.262676 0.506259 0.263729 0.478497 0.26277 0.54866 0.257453 0.559382 0.259287 0.574749 0.254779 0.599464 0.260584 0.53336 0.262676 0.506259 0.259287 0.574749 0.257453 0.559382 0.260584 0.53336 0.259287 0.574749 0.253283 0.58389 0.254779 0.599464 0.249276 0.622149 0.253283 0.58389 0.257453 0.559382 0.254779 0.599464 0.248082 0.606388 0.249276 0.622149 0.242811 0.642293 0.248082 0.606388 0.253283 0.58389 0.249276 0.622149 0.241941 0.626149 0.242811 0.642293 0.235419 0.659412 0.241941 0.626149 0.248082 0.606388 0.242811 0.642293 0.234813 0.642937 0.235419 0.659412 0.227158 0.672973 0.234813 0.642937 0.241941 0.626149 0.235419 0.659412 0.226785 0.656051 0.227158 0.672973 0.21812 0.682395 0.226785 0.656051 0.234813 0.642937 0.227158 0.672973 0.2179909 0.664805 0.21812 0.682395 0.208443 0.687066 0.22249 0.660994 0.226785 0.656051 0.21812 0.682395 0.2179909 0.664805 0.22249 0.660994 0.21812 0.682395 0.19896 0.66673 0.208443 0.687066 0.198319 0.686362 0.208667 0.668544 0.2179909 0.664805 0.208443 0.687066 0.19896 0.66673 0.208667 0.668544 0.208443 0.687066 0.1891829 0.658832 0.198319 0.686362 0.188 0.679689 0.1891829 0.658832 0.19896 0.66673 0.198319 0.686362 0.1891829 0.658832 0.188 0.679689 0.182867 0.673949 0.179717 0.644556 0.182867 0.673949 0.177812 0.666552 0.179717 0.644556 0.1891829 0.658832 0.182867 0.673949 0.1751649 0.634856 0.177812 0.666552 0.172885 0.657449 0.1751649 0.634856 0.179717 0.644556 0.177812 0.666552 0.170817 0.623489 0.172885 0.657449 0.1681399 0.646654 0.170817 0.623489 0.1751649 0.634856 0.172885 0.657449 0.166754 0.610507 0.1681399 0.646654 0.163637 0.634163 0.166754 0.610507 0.170817 0.623489 0.1681399 0.646654 0.163018 0.595989 0.163637 0.634163 0.1594319 0.62008 0.163018 0.595989 0.166754 0.610507 0.163637 0.634163 0.156744 0.562777 0.1594319 0.62008 0.152169 0.587601 0.156744 0.562777 0.163018 0.595989 0.1594319 0.62008 0.150106 0.484456 0.152169 0.587601 0.146624 0.549698 0.152353 0.525052 0.156744 0.562777 0.152169 0.587601 0.150106 0.484456 0.152353 0.525052 0.152169 0.587601 0.09446197 0.525575 0.09112298 0.495061 0.168338 0.499887 0.293302 0.510315 0.292825 0.509971 0.301963 0.50994 0.293037 0.522375 0.292825 0.509971 0.293302 0.534696 0.293302 0.510315 0.293302 0.534696 0.292825 0.509971 0.300765 0.510708 0.301963 0.50994 0.311088 0.509904 0.293989 0.510452 0.293302 0.510315 0.301963 0.50994 0.295577 0.51057 0.293989 0.510452 0.301963 0.50994 0.297907 0.510658 0.295577 0.51057 0.301963 0.50994 0.300765 0.510708 0.297907 0.510658 0.301963 0.50994 0.311712 0.510253 0.311088 0.509904 0.311365 0.522763 0.304166 0.510708 0.300765 0.510708 0.311088 0.509904 0.307332 0.510652 0.304166 0.510708 0.311088 0.509904 0.309843 0.510547 0.307332 0.510652 0.311088 0.509904 0.311712 0.510253 0.309843 0.510547 0.311088 0.509904 0.311712 0.510253 0.311365 0.522763 0.311712 0.5355 0.311712 0.510253 0.311712 0.5355 0.311564 0.542102 0.31137 0.510408 0.311564 0.542102 0.310799 0.547288 0.311712 0.510253 0.311564 0.542102 0.31137 0.510408 0.309843 0.510547 0.310799 0.547288 0.309559 0.55124 0.31137 0.510408 0.310799 0.547288 0.309843 0.510547 0.309843 0.510547 0.309559 0.55124 0.307949 0.554083 0.307332 0.510652 0.307949 0.554083 0.306085 0.555861 0.309843 0.510547 0.307949 0.554083 0.307332 0.510652 0.307332 0.510652 0.306085 0.555861 0.304192 0.556612 0.304166 0.510708 0.304192 0.556612 0.302306 0.556529 0.307332 0.510652 0.304192 0.556612 0.304166 0.510708 0.300765 0.510708 0.302306 0.556529 0.300336 0.555603 0.304166 0.510708 0.302306 0.556529 0.300765 0.510708 0.300765 0.510708 0.300336 0.555603 0.298349 0.553694 0.297907 0.510658 0.298349 0.553694 0.296527 0.550762 0.300765 0.510708 0.298349 0.553694 0.297907 0.510658 0.295577 0.51057 0.296527 0.550762 0.294983 0.546724 0.297907 0.510658 0.296527 0.550762 0.295577 0.51057 0.293989 0.510452 0.294983 0.546724 0.29385 0.541437 0.295577 0.51057 0.294983 0.546724 0.293989 0.510452 0.293989 0.510452 0.29385 0.541437 0.293302 0.534696 0.293989 0.510452 0.293302 0.534696 0.293302 0.510315 0.195545 0.534668 0.189811 0.536455 0.170369 0.536757 0.189811 0.591181 0.170369 0.536757 0.189811 0.536455 0.190891 0.534495 0.195545 0.534668 0.170369 0.536757 0.187268 0.534452 0.190891 0.534495 0.170369 0.536757 0.183606 0.534474 0.187268 0.534452 0.170369 0.536757 0.172843 0.535998 0.183606 0.534474 0.170369 0.536757 0.09446197 0.525575 0.172843 0.535998 0.170369 0.536757 0.10005 0.555838 0.09446197 0.525575 0.170369 0.536757 0.125784 0.550361 0.10005 0.555838 0.170369 0.536757 0.178806 0.564607 0.170369 0.536757 0.189811 0.591181 0.125784 0.550361 0.170369 0.536757 0.178806 0.564607 0.198991 0.534948 0.194756 0.536299 0.189811 0.536455 0.189811 0.591181 0.189811 0.536455 0.194756 0.536299 0.195545 0.534668 0.198991 0.534948 0.189811 0.536455 0.200765 0.535299 0.198525 0.536025 0.194756 0.536299 0.196044 0.60265 0.194756 0.536299 0.198525 0.536025 0.198991 0.534948 0.200765 0.535299 0.194756 0.536299 0.1932 0.59785 0.194756 0.536299 0.196044 0.60265 0.189811 0.591181 0.194756 0.536299 0.1932 0.59785 0.200765 0.535299 0.200613 0.535675 0.198525 0.536025 0.199825 0.60733 0.198525 0.536025 0.200613 0.535675 0.19828 0.605776 0.198525 0.536025 0.199825 0.60733 0.196044 0.60265 0.198525 0.536025 0.19828 0.605776 0.200684 0.607519 0.200613 0.535675 0.200765 0.535299 0.199825 0.60733 0.200613 0.535675 0.200684 0.607519 0.200536 0.604047 0.200765 0.535299 0.198991 0.534948 0.200944 0.606496 0.200765 0.535299 0.200536 0.604047 0.200684 0.607519 0.200765 0.535299 0.200944 0.606496 0.197492 0.594609 0.198991 0.534948 0.195545 0.534668 0.1993809 0.60009 0.198991 0.534948 0.197492 0.594609 0.200536 0.604047 0.198991 0.534948 0.1993809 0.60009 0.12354 0.580789 0.107839 0.585576 0.10005 0.555838 0.121 0.55181 0.116051 0.553306 0.10005 0.555838 0.12354 0.580789 0.10005 0.555838 0.116051 0.553306 0.125784 0.550361 0.121 0.55181 0.10005 0.555838 0.133051 0.60763 0.117835 0.614612 0.107839 0.585576 0.12354 0.580789 0.133051 0.60763 0.107839 0.585576 0.142886 0.628368 0.129972 0.642768 0.117835 0.614612 0.1382 0.619408 0.142886 0.628368 0.117835 0.614612 0.133051 0.60763 0.1382 0.619408 0.117835 0.614612 0.154431 0.642667 0.144178 0.669793 0.129972 0.642768 0.1341789 0.464168 0.129972 0.642768 0.144178 0.669793 0.152804 0.641868 0.154431 0.642667 0.129972 0.642768 0.150288 0.639355 0.152804 0.641868 0.129972 0.642768 0.1469489 0.634918 0.150288 0.639355 0.129972 0.642768 0.142886 0.628368 0.1469489 0.634918 0.129972 0.642768 0.152038 0.577913 0.144178 0.669793 0.160509 0.6957 0.1386409 0.521665 0.1341789 0.464168 0.144178 0.669793 0.152038 0.577913 0.1386409 0.521665 0.144178 0.669793 0.174229 0.631343 0.160509 0.6957 0.179056 0.720499 0.174229 0.631343 0.152038 0.577913 0.160509 0.6957 0.174229 0.631343 0.179056 0.720499 0.199668 0.743895 0.204814 0.680393 0.199668 0.743895 0.222245 0.765625 0.204814 0.680393 0.174229 0.631343 0.199668 0.743895 0.223352 0.703144 0.222245 0.765625 0.246682 0.785572 0.223352 0.703144 0.204814 0.680393 0.222245 0.765625 0.266283 0.74387 0.246682 0.785572 0.272861 0.803563 0.243889 0.724398 0.223352 0.703144 0.246682 0.785572 0.266283 0.74387 0.243889 0.724398 0.246682 0.785572 0.290403 0.761454 0.272861 0.803563 0.300639 0.819487 0.290403 0.761454 0.266283 0.74387 0.272861 0.803563 0.384061 0.758612 0.329864 0.833205 0.300639 0.819487 0.290403 0.761454 0.300639 0.819487 0.329864 0.833205 0.384061 0.758612 0.360344 0.844622 0.329864 0.833205 0.343195 0.790344 0.329864 0.833205 0.360344 0.844622 0.343195 0.790344 0.290403 0.761454 0.329864 0.833205 0.430046 0.770019 0.391877 0.853624 0.360344 0.844622 0.343195 0.790344 0.360344 0.844622 0.391877 0.853624 0.384061 0.758612 0.430046 0.770019 0.360344 0.844622 0.430046 0.770019 0.424223 0.860146 0.391877 0.853624 0.400765 0.81011 0.391877 0.853624 0.424223 0.860146 0.400765 0.81011 0.343195 0.790344 0.391877 0.853624 0.477244 0.774525 0.457137 0.864109 0.424223 0.860146 0.400765 0.81011 0.424223 0.860146 0.457137 0.864109 0.430046 0.770019 0.477244 0.774525 0.424223 0.860146 0.477244 0.774525 0.490351 0.865492 0.457137 0.864109 0.461291 0.820092 0.457137 0.864109 0.490351 0.865492 0.461291 0.820092 0.400765 0.81011 0.457137 0.864109 0.524176 0.772134 0.523595 0.864258 0.490351 0.865492 0.522757 0.819974 0.490351 0.865492 0.523595 0.864258 0.477244 0.774525 0.524176 0.772134 0.490351 0.865492 0.522757 0.819974 0.461291 0.820092 0.490351 0.865492 0.524176 0.772134 0.556595 0.860432 0.523595 0.864258 0.522757 0.819974 0.523595 0.864258 0.556595 0.860432 0.569996 0.763027 0.589081 0.854025 0.556595 0.860432 0.58308 0.8098 0.556595 0.860432 0.589081 0.854025 0.524176 0.772134 0.569996 0.763027 0.556595 0.860432 0.58308 0.8098 0.522757 0.819974 0.556595 0.860432 0.569996 0.763027 0.620799 0.845107 0.589081 0.854025 0.58308 0.8098 0.589081 0.854025 0.620799 0.845107 0.592108 0.756055 0.651503 0.833731 0.620799 0.845107 0.640283 0.789966 0.620799 0.845107 0.651503 0.833731 0.569996 0.763027 0.592108 0.756055 0.620799 0.845107 0.640283 0.789966 0.58308 0.8098 0.620799 0.845107 0.634006 0.73761 0.680974 0.820012 0.651503 0.833731 0.640283 0.789966 0.651503 0.833731 0.680974 0.820012 0.613496 0.747551 0.634006 0.73761 0.651503 0.833731 0.592108 0.756055 0.613496 0.747551 0.651503 0.833731 0.653612 0.726273 0.709001 0.80404 0.680974 0.820012 0.692652 0.761168 0.680974 0.820012 0.709001 0.80404 0.634006 0.73761 0.653612 0.726273 0.680974 0.820012 0.692652 0.761168 0.640283 0.789966 0.680974 0.820012 0.67229 0.713565 0.73542 0.785963 0.709001 0.80404 0.692652 0.761168 0.709001 0.80404 0.73542 0.785963 0.653612 0.726273 0.67229 0.713565 0.709001 0.80404 0.689902 0.699589 0.760073 0.765896 0.73542 0.785963 0.738805 0.724333 0.73542 0.785963 0.760073 0.765896 0.67229 0.713565 0.689902 0.699589 0.73542 0.785963 0.738805 0.724333 0.692652 0.761168 0.73542 0.785963 0.706344 0.684452 0.782834 0.744025 0.760073 0.765896 0.777662 0.680593 0.760073 0.765896 0.782834 0.744025 0.689902 0.699589 0.706344 0.684452 0.760073 0.765896 0.777662 0.680593 0.738805 0.724333 0.760073 0.765896 0.721573 0.668223 0.803588 0.720475 0.782834 0.744025 0.777662 0.680593 0.782834 0.744025 0.803588 0.720475 0.706344 0.684452 0.721573 0.668223 0.782834 0.744025 0.735533 0.650987 0.822236 0.695526 0.803588 0.720475 0.808187 0.631749 0.803588 0.720475 0.822236 0.695526 0.721573 0.668223 0.735533 0.650987 0.803588 0.720475 0.808187 0.631749 0.777662 0.680593 0.803588 0.720475 0.748194 0.632799 0.838624 0.669486 0.822236 0.695526 0.830432 0.578392 0.822236 0.695526 0.838624 0.669486 0.735533 0.650987 0.748194 0.632799 0.822236 0.695526 0.830432 0.578392 0.808187 0.631749 0.822236 0.695526 0.835777 0.63477 0.852851 0.642353 0.838624 0.669486 0.843928 0.52202 0.838624 0.669486 0.852851 0.642353 0.748194 0.632799 0.759537 0.61369 0.838624 0.669486 0.828243 0.642663 0.838624 0.669486 0.759537 0.61369 0.832442 0.639232 0.835777 0.63477 0.838624 0.669486 0.829907 0.641801 0.832442 0.639232 0.838624 0.669486 0.828243 0.642663 0.829907 0.641801 0.838624 0.669486 0.843928 0.52202 0.830432 0.578392 0.838624 0.669486 0.844471 0.619314 0.864978 0.614125 0.852851 0.642353 0.83982 0.628228 0.844471 0.619314 0.852851 0.642353 0.835777 0.63477 0.83982 0.628228 0.852851 0.642353 0.8473 0.49329 0.852851 0.642353 0.848447 0.464168 0.8473 0.49329 0.843928 0.52202 0.852851 0.642353 0.859086 0.580789 0.874941 0.585063 0.864978 0.614125 0.849575 0.60763 0.859086 0.580789 0.864978 0.614125 0.844471 0.619314 0.849575 0.60763 0.864978 0.614125 0.866575 0.553306 0.882682 0.555355 0.874941 0.585063 0.859086 0.580789 0.866575 0.553306 0.874941 0.585063 0.7904 0.530643 0.888221 0.525184 0.882682 0.555355 0.814226 0.537362 0.7904 0.530643 0.882682 0.555355 0.861626 0.55181 0.856841 0.550361 0.882682 0.555355 0.821207 0.539502 0.882682 0.555355 0.856841 0.550361 0.866575 0.553306 0.861626 0.55181 0.882682 0.555355 0.817666 0.538417 0.814226 0.537362 0.882682 0.555355 0.821207 0.539502 0.817666 0.538417 0.882682 0.555355 0.794343 0.508661 0.891526 0.494831 0.888221 0.525184 0.7904 0.530643 0.794343 0.508661 0.888221 0.525184 0.794343 0.508661 0.796711 0.486472 0.891526 0.494831 0.791391 0.529809 0.794343 0.508661 0.7904 0.530643 0.794154 0.528978 0.796832 0.528168 0.794343 0.508661 0.791391 0.529809 0.794154 0.528978 0.794343 0.508661 0.808935 0.557873 0.784912 0.552254 0.7904 0.530643 0.791391 0.529809 0.7904 0.530643 0.784912 0.552254 0.808935 0.557873 0.7904 0.530643 0.814226 0.537362 0.802337 0.578001 0.777929 0.573319 0.784912 0.552254 0.78522 0.55665 0.784912 0.552254 0.777929 0.573319 0.808935 0.557873 0.802337 0.578001 0.784912 0.552254 0.78522 0.55665 0.791391 0.529809 0.784912 0.552254 0.793065 0.603295 0.769471 0.593808 0.777929 0.573319 0.777042 0.582974 0.777929 0.573319 0.769471 0.593808 0.795367 0.596838 0.793065 0.603295 0.777929 0.573319 0.798456 0.588514 0.795367 0.596838 0.777929 0.573319 0.802337 0.578001 0.798456 0.588514 0.777929 0.573319 0.777042 0.582974 0.78522 0.55665 0.777929 0.573319 0.790818 0.613015 0.759537 0.61369 0.769471 0.593808 0.770856 0.600493 0.769471 0.593808 0.759537 0.61369 0.790808 0.611324 0.790818 0.613015 0.769471 0.593808 0.791544 0.608096 0.790808 0.611324 0.769471 0.593808 0.793065 0.603295 0.791544 0.608096 0.769471 0.593808 0.773516 0.592922 0.777042 0.582974 0.769471 0.593808 0.770856 0.600493 0.773516 0.592922 0.769471 0.593808 0.82737 0.642103 0.828243 0.642663 0.759537 0.61369 0.790818 0.613015 0.82737 0.642103 0.759537 0.61369 0.76897 0.606153 0.770856 0.600493 0.759537 0.61369 0.767775 0.610231 0.76897 0.606153 0.759537 0.61369 0.76721 0.612933 0.767775 0.610231 0.759537 0.61369 0.767236 0.61433 0.76721 0.612933 0.759537 0.61369 0.767754 0.614538 0.767236 0.61433 0.759537 0.61369 0.150377 0.623876 0.199825 0.60733 0.200684 0.607519 0.152966 0.630988 0.150377 0.623876 0.200684 0.607519 0.150377 0.623876 0.19828 0.605776 0.199825 0.60733 0.150377 0.623876 0.196044 0.60265 0.19828 0.605776 0.146845 0.614807 0.1932 0.59785 0.196044 0.60265 0.150377 0.623876 0.146845 0.614807 0.196044 0.60265 0.146845 0.614807 0.189811 0.591181 0.1932 0.59785 0.142346 0.603473 0.178806 0.564607 0.189811 0.591181 0.146845 0.614807 0.142346 0.603473 0.189811 0.591181 0.133073 0.577225 0.125784 0.550361 0.178806 0.564607 0.142346 0.603473 0.133073 0.577225 0.178806 0.564607 0.829088 0.551542 0.856841 0.550361 0.861626 0.55181 0.849553 0.577225 0.856841 0.550361 0.84028 0.603473 0.84028 0.550755 0.84028 0.603473 0.856841 0.550361 0.815794 0.560378 0.856841 0.550361 0.849553 0.577225 0.815794 0.560378 0.821207 0.539502 0.856841 0.550361 0.833136 0.551086 0.84028 0.550755 0.856841 0.550361 0.829088 0.551542 0.833136 0.551086 0.856841 0.550361 0.831085 0.553211 0.861626 0.55181 0.866575 0.553306 0.827264 0.5521 0.829088 0.551542 0.861626 0.55181 0.827948 0.552685 0.827264 0.5521 0.861626 0.55181 0.831085 0.553211 0.827948 0.552685 0.861626 0.55181 0.849575 0.55374 0.866575 0.553306 0.859086 0.580789 0.836263 0.553599 0.831085 0.553211 0.866575 0.553306 0.842747 0.553786 0.836263 0.553599 0.866575 0.553306 0.849575 0.55374 0.842747 0.553786 0.866575 0.553306 0.849575 0.55374 0.859086 0.580789 0.849575 0.60763 0.849575 0.55374 0.849575 0.60763 0.844471 0.619314 0.842747 0.553786 0.844471 0.619314 0.83982 0.628228 0.849575 0.55374 0.844471 0.619314 0.842747 0.553786 0.836263 0.553599 0.83982 0.628228 0.835777 0.63477 0.842747 0.553786 0.83982 0.628228 0.836263 0.553599 0.836263 0.553599 0.835777 0.63477 0.832442 0.639232 0.831085 0.553211 0.832442 0.639232 0.829907 0.641801 0.836263 0.553599 0.832442 0.639232 0.831085 0.553211 0.831085 0.553211 0.829907 0.641801 0.828243 0.642663 0.827948 0.552685 0.828243 0.642663 0.82737 0.642103 0.831085 0.553211 0.828243 0.642663 0.827948 0.552685 0.790818 0.613015 0.827232 0.640132 0.82737 0.642103 0.827948 0.552685 0.82737 0.642103 0.827232 0.640132 0.790818 0.613015 0.827949 0.636508 0.827232 0.640132 0.827264 0.5521 0.827232 0.640132 0.827949 0.636508 0.827948 0.552685 0.827232 0.640132 0.827264 0.5521 0.791469 0.613387 0.829599 0.631164 0.827949 0.636508 0.829088 0.551542 0.827949 0.636508 0.829599 0.631164 0.790818 0.613015 0.791469 0.613387 0.827949 0.636508 0.827264 0.5521 0.827949 0.636508 0.829088 0.551542 0.794864 0.609934 0.832191 0.624028 0.829599 0.631164 0.829088 0.551542 0.829599 0.631164 0.832191 0.624028 0.792797 0.612441 0.794864 0.609934 0.829599 0.631164 0.791469 0.613387 0.792797 0.612441 0.829599 0.631164 0.797596 0.605743 0.835743 0.614903 0.832191 0.624028 0.833136 0.551086 0.832191 0.624028 0.835743 0.614903 0.794864 0.609934 0.797596 0.605743 0.832191 0.624028 0.829088 0.551542 0.832191 0.624028 0.833136 0.551086 0.804789 0.591531 0.84028 0.603473 0.835743 0.614903 0.838835 0.550794 0.835743 0.614903 0.84028 0.603473 0.800928 0.599701 0.804789 0.591531 0.835743 0.614903 0.797596 0.605743 0.800928 0.599701 0.835743 0.614903 0.833136 0.551086 0.835743 0.614903 0.838835 0.550794 0.809056 0.580858 0.849553 0.577225 0.84028 0.603473 0.804789 0.591531 0.809056 0.580858 0.84028 0.603473 0.839553 0.550773 0.84028 0.603473 0.84028 0.550755 0.838835 0.550794 0.84028 0.603473 0.839553 0.550773 0.809056 0.580858 0.815794 0.560378 0.849553 0.577225 0.133051 0.55374 0.116051 0.553306 0.121 0.55181 0.12354 0.580789 0.116051 0.553306 0.133051 0.60763 0.133051 0.55374 0.133051 0.60763 0.116051 0.553306 0.154677 0.552685 0.121 0.55181 0.125784 0.550361 0.139878 0.553786 0.133051 0.55374 0.121 0.55181 0.146362 0.553599 0.139878 0.553786 0.121 0.55181 0.151539 0.553211 0.146362 0.553599 0.121 0.55181 0.154677 0.552685 0.151539 0.553211 0.121 0.55181 0.142346 0.550755 0.125784 0.550361 0.133073 0.577225 0.155362 0.552101 0.154677 0.552685 0.125784 0.550361 0.153538 0.551542 0.155362 0.552101 0.125784 0.550361 0.1494899 0.551087 0.153538 0.551542 0.125784 0.550361 0.142346 0.550755 0.1494899 0.551087 0.125784 0.550361 0.142346 0.550755 0.133073 0.577225 0.142346 0.603473 0.142346 0.550755 0.142346 0.603473 0.146845 0.614807 0.1494899 0.551087 0.146845 0.614807 0.150377 0.623876 0.143791 0.550794 0.146845 0.614807 0.1494899 0.551087 0.143073 0.550773 0.146845 0.614807 0.143791 0.550794 0.142346 0.550755 0.146845 0.614807 0.143073 0.550773 0.1494899 0.551087 0.150377 0.623876 0.152966 0.630988 0.153538 0.551542 0.152966 0.630988 0.154631 0.63634 0.1494899 0.551087 0.152966 0.630988 0.153538 0.551542 0.155362 0.552101 0.154631 0.63634 0.155381 0.640009 0.153538 0.551542 0.154631 0.63634 0.155362 0.552101 0.155362 0.552101 0.155381 0.640009 0.155277 0.64205 0.154677 0.552685 0.155277 0.64205 0.154431 0.642667 0.155362 0.552101 0.155277 0.64205 0.154677 0.552685 0.154677 0.552685 0.154431 0.642667 0.152804 0.641868 0.151539 0.553211 0.152804 0.641868 0.150288 0.639355 0.154677 0.552685 0.152804 0.641868 0.151539 0.553211 0.151539 0.553211 0.150288 0.639355 0.1469489 0.634918 0.146362 0.553599 0.1469489 0.634918 0.142886 0.628368 0.151539 0.553211 0.1469489 0.634918 0.146362 0.553599 0.139878 0.553786 0.142886 0.628368 0.1382 0.619408 0.146362 0.553599 0.142886 0.628368 0.139878 0.553786 0.139878 0.553786 0.1382 0.619408 0.133051 0.60763 0.139878 0.553786 0.133051 0.60763 0.133051 0.55374 0.792586 0.538104 0.814226 0.537362 0.817666 0.538417 0.808935 0.557873 0.814226 0.537362 0.802337 0.578001 0.802337 0.537565 0.802337 0.578001 0.814226 0.537362 0.796171 0.537787 0.802337 0.537565 0.814226 0.537362 0.792586 0.538104 0.796171 0.537787 0.814226 0.537362 0.793677 0.5393 0.817666 0.538417 0.821207 0.539502 0.790848 0.538499 0.792586 0.538104 0.817666 0.538417 0.791219 0.538918 0.790848 0.538499 0.817666 0.538417 0.793677 0.5393 0.791219 0.538918 0.817666 0.538417 0.809056 0.539722 0.821207 0.539502 0.815794 0.560378 0.797899 0.539589 0.793677 0.5393 0.821207 0.539502 0.803289 0.539738 0.797899 0.539589 0.821207 0.539502 0.809056 0.539722 0.803289 0.539738 0.821207 0.539502 0.809056 0.539722 0.815794 0.560378 0.809056 0.580858 0.809056 0.539722 0.809056 0.580858 0.804789 0.591531 0.803289 0.539738 0.804789 0.591531 0.800928 0.599701 0.809056 0.539722 0.804789 0.591531 0.803289 0.539738 0.797899 0.539589 0.800928 0.599701 0.797596 0.605743 0.803289 0.539738 0.800928 0.599701 0.797899 0.539589 0.797899 0.539589 0.797596 0.605743 0.794864 0.609934 0.793677 0.5393 0.794864 0.609934 0.792797 0.612441 0.797899 0.539589 0.794864 0.609934 0.793677 0.5393 0.793677 0.5393 0.792797 0.612441 0.791469 0.613387 0.791219 0.538918 0.791469 0.613387 0.790818 0.613015 0.793677 0.5393 0.791469 0.613387 0.791219 0.538918 0.791219 0.538918 0.790818 0.613015 0.790808 0.611324 0.790848 0.538499 0.790808 0.611324 0.791544 0.608096 0.791219 0.538918 0.790808 0.611324 0.790848 0.538499 0.792586 0.538104 0.791544 0.608096 0.793065 0.603295 0.790848 0.538499 0.791544 0.608096 0.792586 0.538104 0.792586 0.538104 0.793065 0.603295 0.795367 0.596838 0.796171 0.537787 0.795367 0.596838 0.798456 0.588514 0.792586 0.538104 0.795367 0.596838 0.796171 0.537787 0.8011 0.53759 0.798456 0.588514 0.802337 0.578001 0.796171 0.537787 0.798456 0.588514 0.8011 0.53759 0.801715 0.537576 0.802337 0.578001 0.802337 0.537565 0.8011 0.53759 0.802337 0.578001 0.801715 0.537576 0.850682 0.464168 0.848447 0.464168 0.843984 0.406672 0.846196 0.52201 0.8473 0.49329 0.848447 0.464168 0.846196 0.52201 0.848447 0.464168 0.850682 0.464168 0.84614 0.40597 0.843984 0.406672 0.830588 0.350424 0.84953 0.434872 0.850682 0.464168 0.843984 0.406672 0.84614 0.40597 0.84953 0.434872 0.843984 0.406672 0.832573 0.349258 0.830588 0.350424 0.808396 0.296993 0.832573 0.349258 0.84614 0.40597 0.830588 0.350424 0.810208 0.295574 0.808396 0.296993 0.777812 0.2479439 0.810208 0.295574 0.832573 0.349258 0.808396 0.296993 0.779512 0.2464269 0.777812 0.2479439 0.759273 0.225193 0.779512 0.2464269 0.810208 0.295574 0.777812 0.2479439 0.740427 0.202409 0.759273 0.225193 0.738737 0.203938 0.740427 0.202409 0.779512 0.2464269 0.759273 0.225193 0.740427 0.202409 0.738737 0.203938 0.716342 0.184466 0.69399 0.1653349 0.716342 0.184466 0.692223 0.166882 0.69399 0.1653349 0.740427 0.202409 0.716342 0.184466 0.641285 0.1363469 0.692223 0.166882 0.63943 0.137993 0.641285 0.1363469 0.69399 0.1653349 0.692223 0.166882 0.583703 0.116379 0.63943 0.137993 0.581861 0.118227 0.583703 0.116379 0.641285 0.1363469 0.63943 0.137993 0.522971 0.106136 0.581861 0.118227 0.521334 0.108245 0.522971 0.106136 0.583703 0.116379 0.581861 0.118227 0.461086 0.106018 0.521334 0.108245 0.459869 0.108362 0.461086 0.106018 0.522971 0.106136 0.521334 0.108245 0.40015 0.116068 0.459869 0.108362 0.399545 0.118536 0.40015 0.116068 0.461086 0.106018 0.459869 0.108362 0.342198 0.135967 0.399545 0.118536 0.342342 0.13837 0.342198 0.135967 0.40015 0.116068 0.399545 0.118536 0.289067 0.165047 0.342342 0.13837 0.289973 0.167168 0.289067 0.165047 0.342198 0.135967 0.342342 0.13837 0.264798 0.1827459 0.289973 0.167168 0.24382 0.204003 0.264798 0.1827459 0.289067 0.165047 0.289973 0.167168 0.2216089 0.223734 0.24382 0.204003 0.204963 0.247744 0.242267 0.202343 0.264798 0.1827459 0.24382 0.204003 0.2216089 0.223734 0.242267 0.202343 0.24382 0.204003 0.2029629 0.246628 0.204963 0.247744 0.174439 0.296587 0.2029629 0.246628 0.2216089 0.223734 0.204963 0.247744 0.1722069 0.295983 0.174439 0.296587 0.152193 0.349945 0.1722069 0.295983 0.2029629 0.246628 0.174439 0.296587 0.149896 0.34974 0.152193 0.349945 0.138697 0.406317 0.149896 0.34974 0.1722069 0.295983 0.152193 0.349945 0.136429 0.406327 0.138697 0.406317 0.135325 0.435047 0.136429 0.406327 0.149896 0.34974 0.138697 0.406317 0.136429 0.406327 0.135325 0.435047 0.1341789 0.464168 0.131943 0.464168 0.1341789 0.464168 0.1386409 0.521665 0.131943 0.464168 0.136429 0.406327 0.1341789 0.464168 0.136485 0.522367 0.1386409 0.521665 0.152038 0.577913 0.133096 0.493464 0.131943 0.464168 0.1386409 0.521665 0.136485 0.522367 0.133096 0.493464 0.1386409 0.521665 0.150052 0.579079 0.152038 0.577913 0.174229 0.631343 0.150052 0.579079 0.136485 0.522367 0.152038 0.577913 0.172417 0.632763 0.174229 0.631343 0.204814 0.680393 0.172417 0.632763 0.150052 0.579079 0.174229 0.631343 0.203113 0.68191 0.204814 0.680393 0.223352 0.703144 0.203113 0.68191 0.172417 0.632763 0.204814 0.680393 0.242198 0.725928 0.223352 0.703144 0.243889 0.724398 0.242198 0.725928 0.203113 0.68191 0.223352 0.703144 0.242198 0.725928 0.243889 0.724398 0.266283 0.74387 0.288635 0.763002 0.266283 0.74387 0.290403 0.761454 0.288635 0.763002 0.242198 0.725928 0.266283 0.74387 0.34134 0.79199 0.290403 0.761454 0.343195 0.790344 0.34134 0.79199 0.288635 0.763002 0.290403 0.761454 0.398922 0.811957 0.343195 0.790344 0.400765 0.81011 0.398922 0.811957 0.34134 0.79199 0.343195 0.790344 0.459654 0.8222 0.400765 0.81011 0.461291 0.820092 0.459654 0.8222 0.398922 0.811957 0.400765 0.81011 0.521539 0.822319 0.461291 0.820092 0.522757 0.819974 0.521539 0.822319 0.459654 0.8222 0.461291 0.820092 0.582476 0.812269 0.522757 0.819974 0.58308 0.8098 0.582476 0.812269 0.521539 0.822319 0.522757 0.819974 0.640427 0.79237 0.58308 0.8098 0.640283 0.789966 0.640427 0.79237 0.582476 0.812269 0.58308 0.8098 0.693558 0.763289 0.640283 0.789966 0.692652 0.761168 0.693558 0.763289 0.640427 0.79237 0.640283 0.789966 0.717828 0.745591 0.692652 0.761168 0.738805 0.724333 0.717828 0.745591 0.693558 0.763289 0.692652 0.761168 0.761016 0.704603 0.738805 0.724333 0.777662 0.680593 0.740358 0.725993 0.717828 0.745591 0.738805 0.724333 0.761016 0.704603 0.740358 0.725993 0.738805 0.724333 0.779662 0.681709 0.777662 0.680593 0.808187 0.631749 0.779662 0.681709 0.761016 0.704603 0.777662 0.680593 0.810418 0.632354 0.808187 0.631749 0.830432 0.578392 0.810418 0.632354 0.779662 0.681709 0.808187 0.631749 0.83273 0.578597 0.830432 0.578392 0.843928 0.52202 0.83273 0.578597 0.810418 0.632354 0.830432 0.578392 0.846196 0.52201 0.843928 0.52202 0.8473 0.49329 0.846196 0.52201 0.83273 0.578597 0.843928 0.52202 0.855793 0.284627 0.850682 0.464168 0.84953 0.434872 0.855595 0.644127 0.846196 0.52201 0.850682 0.464168 0.855595 0.644127 0.850682 0.464168 0.855793 0.284627 0.855793 0.284627 0.84953 0.434872 0.84614 0.40597 0.855793 0.284627 0.84614 0.40597 0.832573 0.349258 0.824969 0.231036 0.832573 0.349258 0.810208 0.295574 0.824969 0.231036 0.855793 0.284627 0.832573 0.349258 0.806188 0.205886 0.810208 0.295574 0.779512 0.2464269 0.806188 0.205886 0.824969 0.231036 0.810208 0.295574 0.762348 0.160094 0.779512 0.2464269 0.740427 0.202409 0.785281 0.1821449 0.806188 0.205886 0.779512 0.2464269 0.762348 0.160094 0.785281 0.1821449 0.779512 0.2464269 0.737505 0.13986 0.740427 0.202409 0.69399 0.1653349 0.737505 0.13986 0.762348 0.160094 0.740427 0.202409 0.682619 0.105523 0.69399 0.1653349 0.641285 0.1363469 0.710876 0.121631 0.737505 0.13986 0.69399 0.1653349 0.682619 0.105523 0.710876 0.121631 0.69399 0.1653349 0.621937 0.08021098 0.641285 0.1363469 0.583703 0.116379 0.621937 0.08021098 0.682619 0.105523 0.641285 0.1363469 0.557172 0.06475198 0.583703 0.116379 0.522971 0.106136 0.557172 0.06475198 0.621937 0.08021098 0.583703 0.116379 0.490341 0.05964791 0.522971 0.106136 0.461086 0.106018 0.490341 0.05964791 0.557172 0.06475198 0.522971 0.106136 0.423626 0.06504195 0.461086 0.106018 0.40015 0.116068 0.423626 0.06504195 0.490341 0.05964791 0.461086 0.106018 0.35919 0.080702 0.40015 0.116068 0.342198 0.135967 0.35919 0.080702 0.423626 0.06504195 0.40015 0.116068 0.298982 0.106055 0.342198 0.135967 0.289067 0.165047 0.298982 0.106055 0.35919 0.080702 0.342198 0.135967 0.298982 0.106055 0.289067 0.165047 0.264798 0.1827459 0.2445909 0.140257 0.264798 0.1827459 0.242267 0.202343 0.2445909 0.140257 0.298982 0.106055 0.264798 0.1827459 0.2445909 0.140257 0.242267 0.202343 0.2216089 0.223734 0.2445909 0.140257 0.2216089 0.223734 0.2029629 0.246628 0.197218 0.182278 0.2029629 0.246628 0.1722069 0.295983 0.197218 0.182278 0.2445909 0.140257 0.2029629 0.246628 0.1577759 0.230862 0.1722069 0.295983 0.149896 0.34974 0.1577759 0.230862 0.197218 0.182278 0.1722069 0.295983 0.1577759 0.230862 0.149896 0.34974 0.136429 0.406327 0.127031 0.28421 0.136429 0.406327 0.131943 0.464168 0.127031 0.28421 0.1577759 0.230862 0.136429 0.406327 0.126832 0.643709 0.131943 0.464168 0.133096 0.493464 0.126832 0.643709 0.127031 0.28421 0.131943 0.464168 0.126832 0.643709 0.133096 0.493464 0.136485 0.522367 0.126832 0.643709 0.136485 0.522367 0.150052 0.579079 0.157657 0.697301 0.150052 0.579079 0.172417 0.632763 0.157657 0.697301 0.126832 0.643709 0.150052 0.579079 0.176438 0.72245 0.172417 0.632763 0.203113 0.68191 0.176438 0.72245 0.157657 0.697301 0.172417 0.632763 0.220277 0.768242 0.203113 0.68191 0.242198 0.725928 0.197344 0.746191 0.176438 0.72245 0.203113 0.68191 0.220277 0.768242 0.197344 0.746191 0.203113 0.68191 0.245121 0.788476 0.242198 0.725928 0.288635 0.763002 0.245121 0.788476 0.220277 0.768242 0.242198 0.725928 0.300006 0.822813 0.288635 0.763002 0.34134 0.79199 0.27175 0.806706 0.245121 0.788476 0.288635 0.763002 0.300006 0.822813 0.27175 0.806706 0.288635 0.763002 0.360689 0.848125 0.34134 0.79199 0.398922 0.811957 0.360689 0.848125 0.300006 0.822813 0.34134 0.79199 0.425454 0.863585 0.398922 0.811957 0.459654 0.8222 0.425454 0.863585 0.360689 0.848125 0.398922 0.811957 0.492285 0.868689 0.459654 0.8222 0.521539 0.822319 0.492285 0.868689 0.425454 0.863585 0.459654 0.8222 0.559 0.863295 0.521539 0.822319 0.582476 0.812269 0.559 0.863295 0.492285 0.868689 0.521539 0.822319 0.623436 0.847635 0.582476 0.812269 0.640427 0.79237 0.623436 0.847635 0.559 0.863295 0.582476 0.812269 0.683644 0.822282 0.640427 0.79237 0.693558 0.763289 0.683644 0.822282 0.623436 0.847635 0.640427 0.79237 0.683644 0.822282 0.693558 0.763289 0.717828 0.745591 0.738035 0.788079 0.717828 0.745591 0.740358 0.725993 0.738035 0.788079 0.683644 0.822282 0.717828 0.745591 0.738035 0.788079 0.740358 0.725993 0.761016 0.704603 0.738035 0.788079 0.761016 0.704603 0.779662 0.681709 0.785408 0.746059 0.779662 0.681709 0.810418 0.632354 0.785408 0.746059 0.738035 0.788079 0.779662 0.681709 0.82485 0.697474 0.810418 0.632354 0.83273 0.578597 0.82485 0.697474 0.785408 0.746059 0.810418 0.632354 0.82485 0.697474 0.83273 0.578597 0.846196 0.52201 0.855595 0.644127 0.82485 0.697474 0.846196 0.52201 0.894693 0.495293 0.891391 0.402693 0.895835 0.464168 0.956799 0.464168 0.895835 0.464168 0.891391 0.402693 0.952327 0.53099 0.894693 0.495293 0.895835 0.464168 0.952327 0.53099 0.895835 0.464168 0.956799 0.464168 0.891333 0.526038 0.878027 0.342358 0.891391 0.402693 0.938683 0.330994 0.891391 0.402693 0.878027 0.342358 0.894693 0.495293 0.891333 0.526038 0.891391 0.402693 0.952267 0.396909 0.956799 0.464168 0.891391 0.402693 0.938683 0.330994 0.952267 0.396909 0.891391 0.402693 0.877871 0.586495 0.855793 0.284627 0.878027 0.342358 0.916107 0.267757 0.878027 0.342358 0.855793 0.284627 0.891333 0.526038 0.877871 0.586495 0.878027 0.342358 0.916107 0.267757 0.938683 0.330994 0.878027 0.342358 0.884775 0.208649 0.855793 0.284627 0.824969 0.231036 0.877871 0.586495 0.855595 0.644127 0.855793 0.284627 0.884775 0.208649 0.916107 0.267757 0.855793 0.284627 0.884775 0.208649 0.824969 0.231036 0.806188 0.205886 0.844246 0.154072 0.806188 0.205886 0.785281 0.1821449 0.844246 0.154072 0.884775 0.208649 0.806188 0.205886 0.844246 0.154072 0.785281 0.1821449 0.762348 0.160094 0.79499 0.105755 0.762348 0.160094 0.737505 0.13986 0.79499 0.105755 0.844246 0.154072 0.762348 0.160094 0.79499 0.105755 0.737505 0.13986 0.710876 0.121631 0.737711 0.06512999 0.710876 0.121631 0.682619 0.105523 0.737711 0.06512999 0.79499 0.105755 0.710876 0.121631 0.673398 0.03335493 0.682619 0.105523 0.621937 0.08021098 0.673398 0.03335493 0.737711 0.06512999 0.682619 0.105523 0.603499 0.01144397 0.621937 0.08021098 0.557172 0.06475198 0.603499 0.01144397 0.673398 0.03335493 0.621937 0.08021098 0.529944 1.76e-4 0.557172 0.06475198 0.490341 0.05964791 0.529944 1.76e-4 0.603499 0.01144397 0.557172 0.06475198 0.455036 0 0.490341 0.05964791 0.423626 0.06504195 0.455036 0 0.529944 1.76e-4 0.490341 0.05964791 0.381227 0.01096296 0.423626 0.06504195 0.35919 0.080702 0.381227 0.01096296 0.455036 0 0.423626 0.06504195 0.310866 0.03270393 0.35919 0.080702 0.298982 0.106055 0.310866 0.03270393 0.381227 0.01096296 0.35919 0.080702 0.245983 0.06449598 0.298982 0.106055 0.2445909 0.140257 0.245983 0.06449598 0.310866 0.03270393 0.298982 0.106055 0.188159 0.105318 0.2445909 0.140257 0.197218 0.182278 0.188159 0.105318 0.245983 0.06449598 0.2445909 0.140257 0.138484 0.153952 0.197218 0.182278 0.1577759 0.230862 0.138484 0.153952 0.188159 0.105318 0.197218 0.182278 0.09771096 0.208869 0.1577759 0.230862 0.127031 0.28421 0.09771096 0.208869 0.138484 0.153952 0.1577759 0.230862 0.126832 0.643709 0.104754 0.341841 0.127031 0.28421 0.06630599 0.268239 0.127031 0.28421 0.104754 0.341841 0.06630599 0.268239 0.09771096 0.208869 0.127031 0.28421 0.104598 0.585978 0.09129196 0.402299 0.104754 0.341841 0.04377889 0.331575 0.104754 0.341841 0.09129196 0.402299 0.126832 0.643709 0.104598 0.585978 0.104754 0.341841 0.04377889 0.331575 0.06630599 0.268239 0.104754 0.341841 0.09123396 0.525644 0.08793199 0.433043 0.09129196 0.402299 0.03029888 0.397347 0.09129196 0.402299 0.08793199 0.433043 0.104598 0.585978 0.09123396 0.525644 0.09129196 0.402299 0.03029888 0.397347 0.04377889 0.331575 0.09129196 0.402299 0.09123396 0.525644 0.08679097 0.464168 0.08793199 0.433043 0.03029888 0.397347 0.08793199 0.433043 0.08679097 0.464168 0.02582591 0.464168 0.08679097 0.464168 0.09123396 0.525644 0.02582591 0.464168 0.03029888 0.397347 0.08679097 0.464168 0.04394197 0.597343 0.09123396 0.525644 0.104598 0.585978 0.03035897 0.531427 0.02582591 0.464168 0.09123396 0.525644 0.04394197 0.597343 0.03035897 0.531427 0.09123396 0.525644 0.066518 0.660579 0.104598 0.585978 0.126832 0.643709 0.066518 0.660579 0.04394197 0.597343 0.104598 0.585978 0.09785097 0.719687 0.126832 0.643709 0.157657 0.697301 0.09785097 0.719687 0.066518 0.660579 0.126832 0.643709 0.09785097 0.719687 0.157657 0.697301 0.176438 0.72245 0.138379 0.774265 0.176438 0.72245 0.197344 0.746191 0.138379 0.774265 0.09785097 0.719687 0.176438 0.72245 0.138379 0.774265 0.197344 0.746191 0.220277 0.768242 0.187635 0.822581 0.220277 0.768242 0.245121 0.788476 0.187635 0.822581 0.138379 0.774265 0.220277 0.768242 0.187635 0.822581 0.245121 0.788476 0.27175 0.806706 0.244915 0.863206 0.27175 0.806706 0.300006 0.822813 0.244915 0.863206 0.187635 0.822581 0.27175 0.806706 0.309227 0.894981 0.300006 0.822813 0.360689 0.848125 0.309227 0.894981 0.244915 0.863206 0.300006 0.822813 0.379126 0.916893 0.360689 0.848125 0.425454 0.863585 0.379126 0.916893 0.309227 0.894981 0.360689 0.848125 0.452681 0.928161 0.425454 0.863585 0.492285 0.868689 0.452681 0.928161 0.379126 0.916893 0.425454 0.863585 0.52759 0.928337 0.492285 0.868689 0.559 0.863295 0.52759 0.928337 0.452681 0.928161 0.492285 0.868689 0.601399 0.917374 0.559 0.863295 0.623436 0.847635 0.601399 0.917374 0.52759 0.928337 0.559 0.863295 0.67176 0.895632 0.623436 0.847635 0.683644 0.822282 0.67176 0.895632 0.601399 0.917374 0.623436 0.847635 0.736642 0.86384 0.683644 0.822282 0.738035 0.788079 0.736642 0.86384 0.67176 0.895632 0.683644 0.822282 0.794466 0.823018 0.738035 0.788079 0.785408 0.746059 0.794466 0.823018 0.736642 0.86384 0.738035 0.788079 0.844142 0.774385 0.785408 0.746059 0.82485 0.697474 0.844142 0.774385 0.794466 0.823018 0.785408 0.746059 0.884914 0.719467 0.82485 0.697474 0.855595 0.644127 0.884914 0.719467 0.844142 0.774385 0.82485 0.697474 0.91632 0.660098 0.855595 0.644127 0.877871 0.586495 0.91632 0.660098 0.884914 0.719467 0.855595 0.644127 0.938847 0.596762 0.877871 0.586495 0.891333 0.526038 0.938847 0.596762 0.91632 0.660098 0.877871 0.586495 0.952327 0.53099 0.891333 0.526038 0.894693 0.495293 0.952327 0.53099 0.938847 0.596762 0.891333 0.526038 0.952327 0.53099 0.956799 0.464168 0.952267 0.396909 0.938847 0.596762 0.952267 0.396909 0.938683 0.330994 0.952327 0.53099 0.952267 0.396909 0.938847 0.596762 0.91632 0.660098 0.938683 0.330994 0.916107 0.267757 0.938847 0.596762 0.938683 0.330994 0.91632 0.660098 0.884914 0.719467 0.916107 0.267757 0.884775 0.208649 0.91632 0.660098 0.916107 0.267757 0.884914 0.719467 0.884914 0.719467 0.884775 0.208649 0.844246 0.154072 0.823608 0.464168 0.844246 0.154072 0.79499 0.105755 0.884914 0.719467 0.844246 0.154072 0.844142 0.774385 0.823608 0.464168 0.844142 0.774385 0.844246 0.154072 0.776678 0.291529 0.79499 0.105755 0.737711 0.06512999 0.818356 0.404238 0.823608 0.464168 0.79499 0.105755 0.802618 0.346002 0.818356 0.404238 0.79499 0.105755 0.776678 0.291529 0.802618 0.346002 0.79499 0.105755 0.719617 0.2205899 0.737711 0.06512999 0.673398 0.03335493 0.741071 0.242671 0.776678 0.291529 0.737711 0.06512999 0.719617 0.2205899 0.741071 0.242671 0.737711 0.06512999 0.643456 0.1676 0.673398 0.03335493 0.603499 0.01144397 0.696129 0.200643 0.719617 0.2205899 0.673398 0.03335493 0.643456 0.1676 0.696129 0.200643 0.673398 0.03335493 0.584858 0.144848 0.603499 0.01144397 0.529944 1.76e-4 0.584858 0.144848 0.643456 0.1676 0.603499 0.01144397 0.522575 0.133298 0.529944 1.76e-4 0.455036 0 0.522575 0.133298 0.584858 0.144848 0.529944 1.76e-4 0.397034 0.145057 0.455036 0 0.381227 0.01096296 0.459108 0.133385 0.522575 0.133298 0.455036 0 0.397034 0.145057 0.459108 0.133385 0.455036 0 0.33879 0.167789 0.381227 0.01096296 0.310866 0.03270393 0.33879 0.167789 0.397034 0.145057 0.381227 0.01096296 0.286474 0.200658 0.310866 0.03270393 0.245983 0.06449598 0.286474 0.200658 0.33879 0.167789 0.310866 0.03270393 0.241758 0.242437 0.245983 0.06449598 0.188159 0.105318 0.241758 0.242437 0.286474 0.200658 0.245983 0.06449598 0.180187 0.345515 0.188159 0.105318 0.138484 0.153952 0.206203 0.291099 0.241758 0.242437 0.188159 0.105318 0.180187 0.345515 0.206203 0.291099 0.188159 0.105318 0.138379 0.774265 0.138484 0.153952 0.09771096 0.208869 0.159017 0.464168 0.138484 0.153952 0.138379 0.774265 0.170974 0.374304 0.180187 0.345515 0.138484 0.153952 0.164331 0.40389 0.170974 0.374304 0.138484 0.153952 0.160364 0.433795 0.164331 0.40389 0.138484 0.153952 0.159017 0.464168 0.160364 0.433795 0.138484 0.153952 0.066518 0.660579 0.09771096 0.208869 0.06630599 0.268239 0.09785097 0.719687 0.09771096 0.208869 0.066518 0.660579 0.138379 0.774265 0.09771096 0.208869 0.09785097 0.719687 0.04394197 0.597343 0.06630599 0.268239 0.04377889 0.331575 0.066518 0.660579 0.06630599 0.268239 0.04394197 0.597343 0.03035897 0.531427 0.04377889 0.331575 0.03029888 0.397347 0.04394197 0.597343 0.04377889 0.331575 0.03035897 0.531427 0.03035897 0.531427 0.03029888 0.397347 0.02582591 0.464168 0.159017 0.464168 0.138379 0.774265 0.187635 0.822581 0.2059479 0.636807 0.187635 0.822581 0.244915 0.863206 0.16427 0.524099 0.159017 0.464168 0.187635 0.822581 0.1800079 0.582334 0.16427 0.524099 0.187635 0.822581 0.2059479 0.636807 0.1800079 0.582334 0.187635 0.822581 0.263008 0.707747 0.244915 0.863206 0.309227 0.894981 0.241554 0.685665 0.2059479 0.636807 0.244915 0.863206 0.263008 0.707747 0.241554 0.685665 0.244915 0.863206 0.339169 0.760737 0.309227 0.894981 0.379126 0.916893 0.286496 0.727694 0.263008 0.707747 0.309227 0.894981 0.339169 0.760737 0.286496 0.727694 0.309227 0.894981 0.397767 0.783489 0.379126 0.916893 0.452681 0.928161 0.397767 0.783489 0.339169 0.760737 0.379126 0.916893 0.46005 0.795038 0.452681 0.928161 0.52759 0.928337 0.46005 0.795038 0.397767 0.783489 0.452681 0.928161 0.585591 0.78328 0.52759 0.928337 0.601399 0.917374 0.523517 0.794951 0.46005 0.795038 0.52759 0.928337 0.585591 0.78328 0.523517 0.794951 0.52759 0.928337 0.643835 0.760547 0.601399 0.917374 0.67176 0.895632 0.643835 0.760547 0.585591 0.78328 0.601399 0.917374 0.696151 0.727678 0.67176 0.895632 0.736642 0.86384 0.696151 0.727678 0.643835 0.760547 0.67176 0.895632 0.740867 0.685899 0.736642 0.86384 0.794466 0.823018 0.740867 0.685899 0.696151 0.727678 0.736642 0.86384 0.802439 0.582822 0.794466 0.823018 0.844142 0.774385 0.776423 0.637238 0.740867 0.685899 0.794466 0.823018 0.802439 0.582822 0.776423 0.637238 0.794466 0.823018 0.822262 0.494541 0.844142 0.774385 0.823608 0.464168 0.811651 0.554033 0.802439 0.582822 0.844142 0.774385 0.818295 0.524447 0.811651 0.554033 0.844142 0.774385 0.822262 0.494541 0.818295 0.524447 0.844142 0.774385 0.878361 0.464168 0.823608 0.464168 0.818356 0.404238 0.872403 0.533527 0.822262 0.494541 0.823608 0.464168 0.872403 0.533527 0.823608 0.464168 0.878361 0.464168 0.872334 0.394407 0.818356 0.404238 0.802618 0.346002 0.876834 0.429022 0.878361 0.464168 0.818356 0.404238 0.872334 0.394407 0.876834 0.429022 0.818356 0.404238 0.854307 0.326767 0.802618 0.346002 0.776678 0.291529 0.864789 0.36014 0.872334 0.394407 0.802618 0.346002 0.854307 0.326767 0.864789 0.36014 0.802618 0.346002 0.824591 0.263568 0.776678 0.291529 0.741071 0.242671 0.824591 0.263568 0.854307 0.326767 0.776678 0.291529 0.783722 0.206875 0.741071 0.242671 0.719617 0.2205899 0.783722 0.206875 0.824591 0.263568 0.741071 0.242671 0.731947 0.158022 0.719617 0.2205899 0.696129 0.200643 0.731947 0.158022 0.783722 0.206875 0.719617 0.2205899 0.67092 0.119445 0.696129 0.200643 0.643456 0.1676 0.67092 0.119445 0.731947 0.158022 0.696129 0.200643 0.60254 0.09267801 0.643456 0.1676 0.584858 0.144848 0.60254 0.09267801 0.67092 0.119445 0.643456 0.1676 0.529346 0.07890599 0.584858 0.144848 0.522575 0.133298 0.529346 0.07890599 0.60254 0.09267801 0.584858 0.144848 0.454391 0.078803 0.522575 0.133298 0.459108 0.133385 0.454391 0.078803 0.529346 0.07890599 0.522575 0.133298 0.380947 0.09243196 0.459108 0.133385 0.397034 0.145057 0.380947 0.09243196 0.454391 0.078803 0.459108 0.133385 0.312149 0.119222 0.397034 0.145057 0.33879 0.167789 0.312149 0.119222 0.380947 0.09243196 0.397034 0.145057 0.250704 0.158004 0.33879 0.167789 0.286474 0.200658 0.250704 0.158004 0.312149 0.119222 0.33879 0.167789 0.223459 0.181351 0.286474 0.200658 0.241758 0.242437 0.223459 0.181351 0.250704 0.158004 0.286474 0.200658 0.198667 0.207147 0.241758 0.242437 0.206203 0.291099 0.198667 0.207147 0.223459 0.181351 0.241758 0.242437 0.157742 0.264069 0.206203 0.291099 0.180187 0.345515 0.157742 0.264069 0.198667 0.207147 0.206203 0.291099 0.1281149 0.327332 0.180187 0.345515 0.170974 0.374304 0.1281149 0.327332 0.157742 0.264069 0.180187 0.345515 0.1281149 0.327332 0.170974 0.374304 0.164331 0.40389 0.110222 0.39481 0.164331 0.40389 0.160364 0.433795 0.110222 0.39481 0.1281149 0.327332 0.164331 0.40389 0.110222 0.39481 0.160364 0.433795 0.159017 0.464168 0.104264 0.464168 0.159017 0.464168 0.16427 0.524099 0.104264 0.464168 0.110222 0.39481 0.159017 0.464168 0.110291 0.53393 0.16427 0.524099 0.1800079 0.582334 0.105791 0.499314 0.104264 0.464168 0.16427 0.524099 0.110291 0.53393 0.105791 0.499314 0.16427 0.524099 0.128319 0.60157 0.1800079 0.582334 0.2059479 0.636807 0.117837 0.568197 0.110291 0.53393 0.1800079 0.582334 0.128319 0.60157 0.117837 0.568197 0.1800079 0.582334 0.158034 0.664769 0.2059479 0.636807 0.241554 0.685665 0.158034 0.664769 0.128319 0.60157 0.2059479 0.636807 0.198903 0.721462 0.241554 0.685665 0.263008 0.707747 0.198903 0.721462 0.158034 0.664769 0.241554 0.685665 0.250679 0.770315 0.263008 0.707747 0.286496 0.727694 0.250679 0.770315 0.198903 0.721462 0.263008 0.707747 0.311705 0.808892 0.286496 0.727694 0.339169 0.760737 0.311705 0.808892 0.250679 0.770315 0.286496 0.727694 0.380085 0.835658 0.339169 0.760737 0.397767 0.783489 0.380085 0.835658 0.311705 0.808892 0.339169 0.760737 0.453279 0.84943 0.397767 0.783489 0.46005 0.795038 0.453279 0.84943 0.380085 0.835658 0.397767 0.783489 0.528234 0.849533 0.46005 0.795038 0.523517 0.794951 0.528234 0.849533 0.453279 0.84943 0.46005 0.795038 0.601678 0.835904 0.523517 0.794951 0.585591 0.78328 0.601678 0.835904 0.528234 0.849533 0.523517 0.794951 0.670476 0.809115 0.585591 0.78328 0.643835 0.760547 0.670476 0.809115 0.601678 0.835904 0.585591 0.78328 0.731921 0.770333 0.643835 0.760547 0.696151 0.727678 0.731921 0.770333 0.670476 0.809115 0.643835 0.760547 0.759167 0.746986 0.696151 0.727678 0.740867 0.685899 0.759167 0.746986 0.731921 0.770333 0.696151 0.727678 0.783958 0.721189 0.740867 0.685899 0.776423 0.637238 0.783958 0.721189 0.759167 0.746986 0.740867 0.685899 0.824883 0.664268 0.776423 0.637238 0.802439 0.582822 0.824883 0.664268 0.783958 0.721189 0.776423 0.637238 0.854511 0.601005 0.802439 0.582822 0.811651 0.554033 0.854511 0.601005 0.824883 0.664268 0.802439 0.582822 0.854511 0.601005 0.811651 0.554033 0.818295 0.524447 0.872403 0.533527 0.818295 0.524447 0.822262 0.494541 0.872403 0.533527 0.854511 0.601005 0.818295 0.524447 0.872403 0.533527 0.878361 0.464168 0.876834 0.429022 0.872403 0.533527 0.876834 0.429022 0.872334 0.394407 0.872403 0.533527 0.872334 0.394407 0.864789 0.36014 0.854511 0.601005 0.864789 0.36014 0.854307 0.326767 0.872403 0.533527 0.864789 0.36014 0.854511 0.601005 0.824883 0.664268 0.854307 0.326767 0.824591 0.263568 0.854511 0.601005 0.854307 0.326767 0.824883 0.664268 0.783958 0.721189 0.824591 0.263568 0.783722 0.206875 0.824883 0.664268 0.824591 0.263568 0.783958 0.721189 0.759167 0.746986 0.783722 0.206875 0.731947 0.158022 0.783958 0.721189 0.783722 0.206875 0.759167 0.746986 0.731921 0.770333 0.731947 0.158022 0.67092 0.119445 0.759167 0.746986 0.731947 0.158022 0.731921 0.770333 0.670476 0.809115 0.67092 0.119445 0.60254 0.09267801 0.731921 0.770333 0.67092 0.119445 0.670476 0.809115 0.601678 0.835904 0.60254 0.09267801 0.529346 0.07890599 0.670476 0.809115 0.60254 0.09267801 0.601678 0.835904 0.528234 0.849533 0.529346 0.07890599 0.454391 0.078803 0.601678 0.835904 0.529346 0.07890599 0.528234 0.849533 0.453279 0.84943 0.454391 0.078803 0.380947 0.09243196 0.528234 0.849533 0.454391 0.078803 0.453279 0.84943 0.380085 0.835658 0.380947 0.09243196 0.312149 0.119222 0.453279 0.84943 0.380947 0.09243196 0.380085 0.835658 0.311705 0.808892 0.312149 0.119222 0.250704 0.158004 0.380085 0.835658 0.312149 0.119222 0.311705 0.808892 0.250679 0.770315 0.250704 0.158004 0.223459 0.181351 0.311705 0.808892 0.250704 0.158004 0.250679 0.770315 0.198903 0.721462 0.223459 0.181351 0.198667 0.207147 0.250679 0.770315 0.223459 0.181351 0.198903 0.721462 0.158034 0.664769 0.198667 0.207147 0.157742 0.264069 0.198903 0.721462 0.198667 0.207147 0.158034 0.664769 0.128319 0.60157 0.157742 0.264069 0.1281149 0.327332 0.158034 0.664769 0.157742 0.264069 0.128319 0.60157 0.117837 0.568197 0.1281149 0.327332 0.110222 0.39481 0.128319 0.60157 0.1281149 0.327332 0.117837 0.568197 0.105791 0.499314 0.110222 0.39481 0.104264 0.464168 0.110291 0.53393 0.110222 0.39481 0.105791 0.499314 0.117837 0.568197 0.110222 0.39481 0.110291 0.53393 0.783064 0.527967 0.796832 0.528168 0.794154 0.528978 0.790909 0.555589 0.796832 0.528168 0.783064 0.582238 0.783064 0.527967 0.783064 0.582238 0.796832 0.528168 0.783064 0.527967 0.794154 0.528978 0.791391 0.529809 0.777042 0.529588 0.791391 0.529809 0.78522 0.55665 0.779746 0.527945 0.783064 0.527967 0.791391 0.529809 0.777042 0.529588 0.779746 0.527945 0.791391 0.529809 0.777042 0.529588 0.78522 0.55665 0.777042 0.582974 0.777042 0.529588 0.777042 0.582974 0.773516 0.592922 0.772599 0.529456 0.773516 0.592922 0.770856 0.600493 0.777042 0.529588 0.773516 0.592922 0.772599 0.529456 0.769241 0.529229 0.770856 0.600493 0.76897 0.606153 0.772599 0.529456 0.770856 0.600493 0.769241 0.529229 0.769241 0.529229 0.76897 0.606153 0.767775 0.610231 0.767416 0.52894 0.767775 0.610231 0.76721 0.612933 0.769241 0.529229 0.767775 0.610231 0.767416 0.52894 0.767416 0.52894 0.76721 0.612933 0.767236 0.61433 0.767347 0.528631 0.767236 0.61433 0.767754 0.614538 0.767416 0.52894 0.767236 0.61433 0.767347 0.528631 0.767347 0.528631 0.767754 0.614538 0.768708 0.613713 0.76902 0.528344 0.768708 0.613713 0.770153 0.611737 0.767347 0.528631 0.768708 0.613713 0.76902 0.528344 0.76902 0.528344 0.770153 0.611737 0.772045 0.608548 0.772197 0.528116 0.772045 0.608548 0.774305 0.604159 0.76902 0.528344 0.772045 0.608548 0.772197 0.528116 0.776451 0.527978 0.774305 0.604159 0.776909 0.598459 0.772197 0.528116 0.774305 0.604159 0.776451 0.527978 0.779746 0.527945 0.776909 0.598459 0.779839 0.591251 0.776451 0.527978 0.776909 0.598459 0.779746 0.527945 0.779746 0.527945 0.779839 0.591251 0.783064 0.582238 0.779746 0.527945 0.783064 0.582238 0.783064 0.527967 0.777042 0.529588 0.776451 0.527978 0.779746 0.527945 0.777042 0.529588 0.772197 0.528116 0.776451 0.527978 0.777042 0.529588 0.76902 0.528344 0.772197 0.528116 0.772599 0.529456 0.767347 0.528631 0.76902 0.528344 0.777042 0.529588 0.772599 0.529456 0.76902 0.528344 0.769241 0.529229 0.767416 0.52894 0.767347 0.528631 0.772599 0.529456 0.769241 0.529229 0.767347 0.528631 0.838835 0.550794 0.839553 0.550773 0.84028 0.550755 0.833136 0.551086 0.838835 0.550794 0.84028 0.550755 0.143073 0.550773 0.143791 0.550794 0.1494899 0.551087 0.142346 0.550755 0.143073 0.550773 0.1494899 0.551087 0.8011 0.53759 0.801715 0.537576 0.802337 0.537565 0.796171 0.537787 0.8011 0.53759 0.802337 0.537565 0.091623 0.272003 0.2179909 0.263531 0.226733 0.272218 0.07880097 0.268957 0.213342 0.260991 0.2179909 0.263531 0.07880097 0.268957 0.2179909 0.263531 0.091623 0.272003 0.103784 0.279933 0.226733 0.272218 0.2347469 0.285269 0.09783697 0.275413 0.091623 0.272003 0.226733 0.272218 0.103784 0.279933 0.09783697 0.275413 0.226733 0.272218 0.11494 0.292152 0.2347469 0.285269 0.241888 0.302042 0.11494 0.292152 0.103784 0.279933 0.2347469 0.285269 0.124889 0.308016 0.241888 0.302042 0.248057 0.321857 0.124889 0.308016 0.11494 0.292152 0.241888 0.302042 0.133493 0.326853 0.248057 0.321857 0.250798 0.33287 0.133493 0.326853 0.124889 0.308016 0.248057 0.321857 0.1408039 0.348427 0.250798 0.33287 0.253291 0.344484 0.1408039 0.348427 0.133493 0.326853 0.250798 0.33287 0.1408039 0.348427 0.253291 0.344484 0.255519 0.356607 0.1466799 0.372027 0.255519 0.356607 0.257485 0.369174 0.1466799 0.372027 0.1408039 0.348427 0.255519 0.356607 0.151099 0.397161 0.257485 0.369174 0.260625 0.39539 0.151099 0.397161 0.1466799 0.372027 0.257485 0.369174 0.154057 0.423386 0.260625 0.39539 0.262708 0.422645 0.154057 0.423386 0.151099 0.397161 0.260625 0.39539 0.155547 0.450281 0.262708 0.422645 0.263741 0.450489 0.155547 0.450281 0.154057 0.423386 0.262708 0.422645 0.155564 0.477426 0.263741 0.450489 0.263729 0.478497 0.155564 0.477426 0.155547 0.450281 0.263741 0.450489 0.154102 0.504401 0.263729 0.478497 0.262676 0.506259 0.154102 0.504401 0.155564 0.477426 0.263729 0.478497 0.151156 0.530777 0.262676 0.506259 0.260584 0.53336 0.151156 0.530777 0.154102 0.504401 0.262676 0.506259 0.146724 0.556097 0.260584 0.53336 0.257453 0.559382 0.146724 0.556097 0.151156 0.530777 0.260584 0.53336 0.1439509 0.568209 0.257453 0.559382 0.253283 0.58389 0.1439509 0.568209 0.146724 0.556097 0.257453 0.559382 0.137308 0.591024 0.253283 0.58389 0.248082 0.606388 0.140814 0.579873 0.1439509 0.568209 0.253283 0.58389 0.137308 0.591024 0.140814 0.579873 0.253283 0.58389 0.133459 0.601571 0.248082 0.606388 0.241941 0.626149 0.133459 0.601571 0.137308 0.591024 0.248082 0.606388 0.124816 0.620459 0.241941 0.626149 0.234813 0.642937 0.124816 0.620459 0.133459 0.601571 0.241941 0.626149 0.114848 0.636307 0.234813 0.642937 0.226785 0.656051 0.114848 0.636307 0.124816 0.620459 0.234813 0.642937 0.103712 0.648466 0.226785 0.656051 0.22249 0.660994 0.103712 0.648466 0.114848 0.636307 0.226785 0.656051 0.103712 0.648466 0.22249 0.660994 0.2179909 0.664805 0.091623 0.656334 0.2179909 0.664805 0.208667 0.668544 0.091623 0.656334 0.103712 0.648466 0.2179909 0.664805 0.07871896 0.659382 0.208667 0.668544 0.19896 0.66673 0.085222 0.658504 0.091623 0.656334 0.208667 0.668544 0.07871896 0.659382 0.085222 0.658504 0.208667 0.668544 0.06541299 0.657024 0.19896 0.66673 0.1891829 0.658832 0.06541299 0.657024 0.07871896 0.659382 0.19896 0.66673 0.05214196 0.648874 0.1891829 0.658832 0.179717 0.644556 0.05214196 0.648874 0.06541299 0.657024 0.1891829 0.658832 0.03941088 0.634785 0.179717 0.644556 0.1751649 0.634856 0.03941088 0.634785 0.05214196 0.648874 0.179717 0.644556 0.02753597 0.614483 0.1751649 0.634856 0.170817 0.623489 0.02753597 0.614483 0.03941088 0.634785 0.1751649 0.634856 0.02753597 0.614483 0.170817 0.623489 0.166754 0.610507 0.017192 0.588394 0.166754 0.610507 0.163018 0.595989 0.017192 0.588394 0.02753597 0.614483 0.166754 0.610507 0.008887946 0.5572 0.163018 0.595989 0.156744 0.562777 0.008887946 0.5572 0.017192 0.588394 0.163018 0.595989 0.00305891 0.521949 0.156744 0.562777 0.152353 0.525052 0.00305891 0.521949 0.008887946 0.5572 0.156744 0.562777 3.5e-5 0.48405 0.152353 0.525052 0.150106 0.484456 3.5e-5 0.48405 0.00305891 0.521949 0.152353 0.525052 0 0.445186 0.150106 0.484456 0.150132 0.44292 0 0.445186 3.5e-5 0.48405 0.150106 0.484456 0.002967894 0.407148 0.150132 0.44292 0.152423 0.402474 0.002967894 0.407148 0 0.445186 0.150132 0.44292 0.008777976 0.371655 0.152423 0.402474 0.156827 0.365011 0.008777976 0.371655 0.002967894 0.407148 0.152423 0.402474 0.017111 0.340193 0.156827 0.365011 0.163079 0.332085 0.017111 0.340193 0.008777976 0.371655 0.156827 0.365011 0.022089 0.326344 0.163079 0.332085 0.17083 0.304808 0.022089 0.326344 0.017111 0.340193 0.163079 0.332085 0.03334498 0.302916 0.17083 0.304808 0.179678 0.283856 0.02751797 0.313891 0.022089 0.326344 0.17083 0.304808 0.03334498 0.302916 0.02751797 0.313891 0.17083 0.304808 0.03946393 0.293478 0.179678 0.283856 0.189107 0.269592 0.03946393 0.293478 0.03334498 0.302916 0.179678 0.283856 0.05224597 0.279374 0.189107 0.269592 0.198875 0.261648 0.05224597 0.279374 0.03946393 0.293478 0.189107 0.269592 0.06553 0.271267 0.198875 0.261648 0.208608 0.259786 0.06553 0.271267 0.05224597 0.279374 0.198875 0.261648 0.07880097 0.268957 0.208608 0.259786 0.213342 0.260991 0.07880097 0.268957 0.06553 0.271267 0.208608 0.259786 0.091623 0.656334 0.091623 0.272003 0.09783697 0.275413 0.085222 0.658504 0.091623 0.272003 0.091623 0.656334 0.07880097 0.268957 0.091623 0.272003 0.085222 0.658504 0.103712 0.648466 0.09783697 0.275413 0.103784 0.279933 0.091623 0.656334 0.09783697 0.275413 0.103712 0.648466 0.114848 0.636307 0.103784 0.279933 0.11494 0.292152 0.103712 0.648466 0.103784 0.279933 0.114848 0.636307 0.124816 0.620459 0.11494 0.292152 0.124889 0.308016 0.114848 0.636307 0.11494 0.292152 0.124816 0.620459 0.133459 0.601571 0.124889 0.308016 0.133493 0.326853 0.124816 0.620459 0.124889 0.308016 0.133459 0.601571 0.137308 0.591024 0.133493 0.326853 0.1408039 0.348427 0.133459 0.601571 0.133493 0.326853 0.137308 0.591024 0.140814 0.579873 0.1408039 0.348427 0.1466799 0.372027 0.137308 0.591024 0.1408039 0.348427 0.140814 0.579873 0.146724 0.556097 0.1466799 0.372027 0.151099 0.397161 0.1439509 0.568209 0.1466799 0.372027 0.146724 0.556097 0.140814 0.579873 0.1466799 0.372027 0.1439509 0.568209 0.151156 0.530777 0.151099 0.397161 0.154057 0.423386 0.146724 0.556097 0.151099 0.397161 0.151156 0.530777 0.154102 0.504401 0.154057 0.423386 0.155547 0.450281 0.151156 0.530777 0.154057 0.423386 0.154102 0.504401 0.154102 0.504401 0.155547 0.450281 0.155564 0.477426 0.07880097 0.268957 0.085222 0.658504 0.07871896 0.659382 0.06553 0.271267 0.07871896 0.659382 0.06541299 0.657024 0.07880097 0.268957 0.07871896 0.659382 0.06553 0.271267 0.05224597 0.279374 0.06541299 0.657024 0.05214196 0.648874 0.06553 0.271267 0.06541299 0.657024 0.05224597 0.279374 0.03946393 0.293478 0.05214196 0.648874 0.03941088 0.634785 0.05224597 0.279374 0.05214196 0.648874 0.03946393 0.293478 0.03334498 0.302916 0.03941088 0.634785 0.02753597 0.614483 0.03946393 0.293478 0.03941088 0.634785 0.03334498 0.302916 0.02751797 0.313891 0.02753597 0.614483 0.017192 0.588394 0.03334498 0.302916 0.02753597 0.614483 0.02751797 0.313891 0.017111 0.340193 0.017192 0.588394 0.008887946 0.5572 0.022089 0.326344 0.017192 0.588394 0.017111 0.340193 0.02751797 0.313891 0.017192 0.588394 0.022089 0.326344 0.008777976 0.371655 0.008887946 0.5572 0.00305891 0.521949 0.017111 0.340193 0.008887946 0.5572 0.008777976 0.371655 0.002967894 0.407148 0.00305891 0.521949 3.5e-5 0.48405 0.008777976 0.371655 0.00305891 0.521949 0.002967894 0.407148 0.002967894 0.407148 3.5e-5 0.48405 0 0.445186 0.311712 0.510253 0.31137 0.510408 0.309843 0.510547 0.421962 0.508798 0.40661 0.508818 0.405529 0.508704 0.422989 0.508655 0.421962 0.508798 0.405529 0.508704 0.419813 0.508914 0.408407 0.50891 0.40661 0.508818 0.421962 0.508798 0.419813 0.508914 0.40661 0.508818 0.416842 0.508986 0.410758 0.508975 0.408407 0.50891 0.419813 0.508914 0.416842 0.508986 0.408407 0.50891 0.416842 0.508986 0.413467 0.509004 0.410758 0.508975 0.547207 0.508384 0.529789 0.508403 0.529741 0.508265 0.547207 0.508384 0.53092 0.508531 0.529789 0.508403 0.546258 0.508512 0.532995 0.508635 0.53092 0.508531 0.547207 0.508384 0.546258 0.508512 0.53092 0.508531 0.54441 0.508617 0.535762 0.5087 0.532995 0.508635 0.546258 0.508512 0.54441 0.508617 0.532995 0.508635 0.541865 0.508689 0.538883 0.508719 0.535762 0.5087 0.54441 0.508617 0.541865 0.508689 0.535762 0.5087 0.787048 0.51859 0.793534 0.519745 0.789162 0.519769 0.780567 0.518879 0.789162 0.519769 0.784984 0.519698 0.783272 0.5187 0.789162 0.519769 0.780567 0.518879 0.787048 0.51859 0.789162 0.519769 0.783272 0.5187 0.779311 0.5191 0.784984 0.519698 0.781678 0.519545 0.780567 0.518879 0.784984 0.519698 0.779311 0.5191 0.779311 0.5191 0.781678 0.519545 0.779689 0.519335 0.721356 0.512893 0.726247 0.513738 0.722704 0.513676 0.719021 0.513034 0.722704 0.513676 0.719902 0.513553 0.721356 0.512893 0.722704 0.513676 0.719021 0.513034 0.717929 0.513207 0.719902 0.513553 0.718235 0.513389 0.719021 0.513034 0.719902 0.513553 0.717929 0.513207 0.652814 0.510213 0.637217 0.510243 0.635865 0.5101 0.652814 0.510213 0.63962 0.510355 0.637217 0.510243 0.651124 0.510313 0.642763 0.510419 0.63962 0.510355 0.652814 0.510213 0.651124 0.510313 0.63962 0.510355 0.64886 0.510386 0.646228 0.510424 0.642763 0.510419 0.651124 0.510313 0.64886 0.510386 0.642763 0.510419 0.491313 0.703997 0.491313 0.687273 0.501559 0.687582 0.480303 0.703615 0.491313 0.687273 0.491313 0.703997 0.481107 0.68758 0.491313 0.687273 0.480303 0.703615 0.512241 0.702525 0.501559 0.687582 0.511083 0.688495 0.502279 0.703618 0.501559 0.687582 0.512241 0.702525 0.491313 0.703997 0.501559 0.687582 0.502279 0.703618 0.520307 0.700844 0.511083 0.688495 0.519076 0.689946 0.512241 0.702525 0.511083 0.688495 0.520307 0.700844 0.525869 0.69874 0.519076 0.689946 0.524927 0.691836 0.520307 0.700844 0.519076 0.689946 0.525869 0.69874 0.528548 0.6964 0.524927 0.691836 0.528193 0.694041 0.525869 0.69874 0.524927 0.691836 0.528548 0.6964 0.471662 0.688479 0.480303 0.703615 0.470261 0.702505 0.481107 0.68758 0.480303 0.703615 0.471662 0.688479 0.463706 0.689908 0.470261 0.702505 0.462164 0.7008 0.471662 0.688479 0.470261 0.702505 0.463706 0.689908 0.053267 0.006302893 0.053047 0.00444597 0.04321491 8.7e-4 0.04321491 0.01459091 0.04321491 8.7e-4 0.053047 0.00444597 0.04391497 0.01014691 0.053267 0.006302893 0.04321491 8.7e-4 0.03981095 3.75e-4 0.04391497 0.01014691 0.04321491 8.7e-4 0.03981095 0.01406788 0.03981095 3.75e-4 0.04321491 8.7e-4 0.03981095 0.01406788 0.04321491 8.7e-4 0.04321491 0.01459091 0.05345588 0.00583595 0.05334496 0.004904985 0.053047 0.00444597 0.053047 0.01836699 0.053047 0.00444597 0.05334496 0.004904985 0.053267 0.006302893 0.05345588 0.00583595 0.053047 0.00444597 0.053047 0.01836699 0.04321491 0.01459091 0.053047 0.00444597 0.05345588 0.00583595 0.05348193 0.005368888 0.05334496 0.004904985 0.05334496 0.01885098 0.05334496 0.004904985 0.05348193 0.005368888 0.05334496 0.01885098 0.053047 0.01836699 0.05334496 0.004904985 0.05348193 0.01934099 0.05348193 0.005368888 0.05345588 0.00583595 0.05334496 0.01885098 0.05348193 0.005368888 0.05348193 0.01934099 0.05345588 0.01983398 0.05345588 0.00583595 0.053267 0.006302893 0.05345588 0.01983398 0.05348193 0.01934099 0.05345588 0.00583595 0.053267 0.02032589 0.053267 0.006302893 0.04391497 0.01014691 0.05345588 0.01983398 0.053267 0.006302893 0.053267 0.02032589 0.03981095 3.75e-4 0.04043096 0.01070892 0.04391497 0.01014691 0.04391497 0.02438396 0.04391497 0.01014691 0.04043096 0.01070892 0.053267 0.02032589 0.04391497 0.01014691 0.04391497 0.02438396 0.03610998 0 0.0365889 0.01113992 0.04043096 0.01070892 0.04043096 0.0249769 0.04043096 0.01070892 0.0365889 0.01113992 0.03981095 3.75e-4 0.03610998 0 0.04043096 0.01070892 0.04043096 0.0249769 0.04391497 0.02438396 0.04043096 0.01070892 0.01737296 0 0.01689291 0.01113992 0.0365889 0.01113992 0.0365889 0.02543199 0.0365889 0.01113992 0.01689291 0.01113992 0.03610998 0 0.01737296 0 0.0365889 0.01113992 0.04043096 0.0249769 0.0365889 0.01113992 0.0365889 0.02543199 0.01367098 3.75e-4 0.01305097 0.01070892 0.01689291 0.01113992 0.01689291 0.02543199 0.01689291 0.01113992 0.01305097 0.01070892 0.01737296 0 0.01367098 3.75e-4 0.01689291 0.01113992 0.0365889 0.02543199 0.01689291 0.01113992 0.01689291 0.02543199 0.0102669 8.7e-4 0.009566962 0.01014691 0.01305097 0.01070892 0.01305097 0.0249769 0.01305097 0.01070892 0.009566962 0.01014691 0.01367098 3.75e-4 0.0102669 8.7e-4 0.01305097 0.01070892 0.01305097 0.0249769 0.01689291 0.02543199 0.01305097 0.01070892 4.36e-4 0.00444597 2.16e-4 0.006302893 0.009566962 0.01014691 0.009566962 0.02438396 0.009566962 0.01014691 2.16e-4 0.006302893 0.0102669 8.7e-4 4.36e-4 0.00444597 0.009566962 0.01014691 0.01305097 0.0249769 0.009566962 0.01014691 0.009566962 0.02438396 1.37e-4 0.004904985 2.6e-5 0.00583595 2.16e-4 0.006302893 2.16e-4 0.02032589 2.16e-4 0.006302893 2.6e-5 0.00583595 4.36e-4 0.00444597 1.37e-4 0.004904985 2.16e-4 0.006302893 0.009566962 0.02438396 2.16e-4 0.006302893 2.16e-4 0.02032589 1.37e-4 0.004904985 0 0.005368888 2.6e-5 0.00583595 2.6e-5 0.01983398 2.6e-5 0.00583595 0 0.005368888 2.6e-5 0.01983398 2.16e-4 0.02032589 2.6e-5 0.00583595 0 0.01934099 0 0.005368888 1.37e-4 0.004904985 0 0.01934099 2.6e-5 0.01983398 0 0.005368888 1.37e-4 0.01885098 1.37e-4 0.004904985 4.36e-4 0.00444597 1.37e-4 0.01885098 0 0.01934099 1.37e-4 0.004904985 4.36e-4 0.01836699 4.36e-4 0.00444597 0.0102669 8.7e-4 1.37e-4 0.01885098 4.36e-4 0.00444597 4.36e-4 0.01836699 0.0102669 0.01459091 0.0102669 8.7e-4 0.01367098 3.75e-4 4.36e-4 0.01836699 0.0102669 8.7e-4 0.0102669 0.01459091 0.01367098 0.01406788 0.01367098 3.75e-4 0.01737296 0 0.01367098 0.01406788 0.0102669 0.01459091 0.01367098 3.75e-4 0.01737296 0.01367199 0.01737296 0 0.03610998 0 0.01367098 0.01406788 0.01737296 0 0.01737296 0.01367199 0.03610998 0.01367199 0.03610998 0 0.03981095 3.75e-4 0.01737296 0.01367199 0.03610998 0 0.03610998 0.01367199 0.03981095 0.01406788 0.03610998 0.01367199 0.03981095 3.75e-4 0.04582893 0.01720988 0.04321491 0.01459091 0.053047 0.01836699 0.03984797 0.01552498 0.03981095 0.01406788 0.04321491 0.01459091 0.04582893 0.01720988 0.03984797 0.01552498 0.04321491 0.01459091 0.053267 0.02032589 0.04391497 0.02438396 0.053047 0.01836699 0.04813593 0.01937097 0.053047 0.01836699 0.04391497 0.02438396 0.05334496 0.01885098 0.053267 0.02032589 0.053047 0.01836699 0.04749697 0.01825499 0.04582893 0.01720988 0.053047 0.01836699 0.04813593 0.01937097 0.04749697 0.01825499 0.053047 0.01836699 0.03984797 0.01552498 0.03610998 0.01367199 0.03981095 0.01406788 0.02206999 0.01460593 0.01737296 0.01367199 0.03610998 0.01367199 0.03139698 0.01460492 0.02206999 0.01460593 0.03610998 0.01367199 0.03984797 0.01552498 0.03139698 0.01460492 0.03610998 0.01367199 0.01361989 0.01552695 0.01367098 0.01406788 0.01737296 0.01367199 0.02206999 0.01460593 0.01361989 0.01552695 0.01737296 0.01367199 0.007642984 0.01721495 0.0102669 0.01459091 0.01367098 0.01406788 2.16e-4 0.02032589 4.36e-4 0.01836699 0.0102669 0.01459091 0.005346 0.01937097 2.16e-4 0.02032589 0.0102669 0.01459091 0.007642984 0.01721495 0.005346 0.01937097 0.0102669 0.01459091 0.01361989 0.01552695 0.007642984 0.01721495 0.01367098 0.01406788 2.6e-5 0.01983398 4.36e-4 0.01836699 2.16e-4 0.02032589 1.37e-4 0.01885098 4.36e-4 0.01836699 2.6e-5 0.01983398 0.007294893 0.02159088 0.009566962 0.02438396 2.16e-4 0.02032589 0.005785942 0.02050197 2.16e-4 0.02032589 0.005346 0.01937097 0.005785942 0.02050197 0.007294893 0.02159088 2.16e-4 0.02032589 1.37e-4 0.01885098 2.6e-5 0.01983398 0 0.01934099 0.013188 0.02340698 0.01305097 0.0249769 0.009566962 0.02438396 0.007294893 0.02159088 0.013188 0.02340698 0.009566962 0.02438396 0.013188 0.02340698 0.01689291 0.02543199 0.01305097 0.0249769 0.0316109 0.02443099 0.0365889 0.02543199 0.01689291 0.02543199 0.021887 0.024432 0.0316109 0.02443099 0.01689291 0.02543199 0.013188 0.02340698 0.021887 0.024432 0.01689291 0.02543199 0.04030895 0.02340495 0.04043096 0.0249769 0.0365889 0.02543199 0.0316109 0.02443099 0.04030895 0.02340495 0.0365889 0.02543199 0.04619693 0.021586 0.04391497 0.02438396 0.04043096 0.0249769 0.04619693 0.021586 0.04813593 0.01937097 0.04391497 0.02438396 0.04030895 0.02340495 0.04619693 0.021586 0.04043096 0.0249769 0.05334496 0.01885098 0.05345588 0.01983398 0.053267 0.02032589 0.05334496 0.01885098 0.05348193 0.01934099 0.05345588 0.01983398 0.005346 0.03057998 0.005346 0.01937097 0.007642984 0.01721495 0.007284939 0.03288698 0.005785942 0.02050197 0.005346 0.01937097 0.007284939 0.03288698 0.005346 0.01937097 0.005346 0.03057998 0.007653951 0.02832895 0.007642984 0.01721495 0.01361989 0.01552695 0.005984902 0.02941799 0.005346 0.03057998 0.007642984 0.01721495 0.007653951 0.02832895 0.005984902 0.02941799 0.007642984 0.01721495 0.0136339 0.026573 0.01361989 0.01552695 0.02206999 0.01460593 0.0136339 0.026573 0.007653951 0.02832895 0.01361989 0.01552695 0.02208596 0.02561396 0.02206999 0.01460593 0.03139698 0.01460492 0.02208596 0.02561396 0.0136339 0.026573 0.02206999 0.01460593 0.031412 0.02561491 0.03139698 0.01460492 0.03984797 0.01552498 0.031412 0.02561491 0.02208596 0.02561396 0.03139698 0.01460492 0.03986191 0.0265749 0.03984797 0.01552498 0.04582893 0.01720988 0.03986191 0.0265749 0.031412 0.02561491 0.03984797 0.01552498 0.04583895 0.02833396 0.04582893 0.01720988 0.04749697 0.01825499 0.04583895 0.02833396 0.03986191 0.0265749 0.04582893 0.01720988 0.04583895 0.02833396 0.04749697 0.01825499 0.04813593 0.01937097 0.04813593 0.03057998 0.04813593 0.01937097 0.04619693 0.021586 0.04813593 0.03057998 0.04583895 0.02833396 0.04813593 0.01937097 0.04618698 0.032893 0.04619693 0.021586 0.04030895 0.02340495 0.04769599 0.03175896 0.04813593 0.03057998 0.04619693 0.021586 0.04618698 0.032893 0.04769599 0.03175896 0.04619693 0.021586 0.040295 0.03478497 0.04030895 0.02340495 0.0316109 0.02443099 0.040295 0.03478497 0.04618698 0.032893 0.04030895 0.02340495 0.03159499 0.03585195 0.0316109 0.02443099 0.021887 0.024432 0.03159499 0.03585195 0.040295 0.03478497 0.0316109 0.02443099 0.02187097 0.035851 0.021887 0.024432 0.013188 0.02340698 0.02187097 0.035851 0.03159499 0.03585195 0.021887 0.024432 0.01317298 0.03478199 0.013188 0.02340698 0.007294893 0.02159088 0.01317298 0.03478199 0.02187097 0.035851 0.013188 0.02340698 0.007284939 0.03288698 0.007294893 0.02159088 0.005785942 0.02050197 0.007284939 0.03288698 0.01317298 0.03478199 0.007294893 0.02159088 0.007284939 0.03288698 0.005346 0.03057998 0.005984902 0.02941799 0.007284939 0.03288698 0.005984902 0.02941799 0.007653951 0.02832895 0.009445965 0.03059995 0.007653951 0.02832895 0.0136339 0.026573 0.009445965 0.03059995 0.007284939 0.03288698 0.007653951 0.02832895 0.01466298 0.02765196 0.0136339 0.026573 0.02208596 0.02561396 0.01188695 0.02850699 0.009445965 0.03059995 0.0136339 0.026573 0.01466298 0.02765196 0.01188695 0.02850699 0.0136339 0.026573 0.02237999 0.02659696 0.02208596 0.02561396 0.031412 0.02561491 0.01824992 0.02699995 0.01466298 0.02765196 0.02208596 0.02561396 0.02237999 0.02659696 0.01824992 0.02699995 0.02208596 0.02561396 0.03527593 0.02700597 0.031412 0.02561491 0.03986191 0.0265749 0.02678495 0.026461 0.02237999 0.02659696 0.031412 0.02561491 0.03527593 0.02700597 0.02678495 0.026461 0.031412 0.02561491 0.04158896 0.02850395 0.03986191 0.0265749 0.04583895 0.02833396 0.04158896 0.02850395 0.03527593 0.02700597 0.03986191 0.0265749 0.04769599 0.03175896 0.04583895 0.02833396 0.04813593 0.03057998 0.04618698 0.032893 0.04583895 0.02833396 0.04769599 0.03175896 0.04403597 0.03059995 0.04583895 0.02833396 0.04618698 0.032893 0.04403597 0.03059995 0.04158896 0.02850395 0.04583895 0.02833396 0.04403597 0.03059995 0.04618698 0.032893 0.040295 0.03478497 0.03911799 0.03365296 0.040295 0.03478497 0.03159499 0.03585195 0.04185491 0.032745 0.04403597 0.03059995 0.040295 0.03478497 0.03911799 0.03365296 0.04185491 0.032745 0.040295 0.03478497 0.03125 0.03479999 0.03159499 0.03585195 0.02187097 0.035851 0.03549093 0.03435695 0.03911799 0.03365296 0.03159499 0.03585195 0.03125 0.03479999 0.03549093 0.03435695 0.03159499 0.03585195 0.01794689 0.03435099 0.02187097 0.035851 0.01317298 0.03478199 0.0266959 0.03494799 0.03125 0.03479999 0.02187097 0.035851 0.01794689 0.03435099 0.0266959 0.03494799 0.02187097 0.035851 0.01163399 0.03274798 0.01317298 0.03478199 0.007284939 0.03288698 0.01163399 0.03274798 0.01794689 0.03435099 0.01317298 0.03478199 0.01163399 0.03274798 0.007284939 0.03288698 0.009445965 0.03059995 0.009445965 0.04224199 0.009445965 0.03059995 0.01188695 0.02850699 0.01162797 0.04447489 0.01163399 0.03274798 0.009445965 0.03059995 0.01162797 0.04447489 0.009445965 0.03059995 0.009445965 0.04224199 0.01189297 0.04005998 0.01188695 0.02850699 0.01466298 0.02765196 0.01189297 0.04005998 0.009445965 0.04224199 0.01188695 0.02850699 0.018206 0.03849995 0.01466298 0.02765196 0.01824992 0.02699995 0.018206 0.03849995 0.01189297 0.04005998 0.01466298 0.02765196 0.018206 0.03849995 0.01824992 0.02699995 0.02237999 0.02659696 0.02669799 0.03793299 0.02237999 0.02659696 0.02678495 0.026461 0.02669799 0.03793299 0.018206 0.03849995 0.02237999 0.02659696 0.031102 0.03807389 0.02678495 0.026461 0.03527593 0.02700597 0.031102 0.03807389 0.02669799 0.03793299 0.02678495 0.026461 0.03881895 0.03917199 0.03527593 0.02700597 0.04158896 0.02850395 0.03523188 0.03849399 0.031102 0.03807389 0.03527593 0.02700597 0.03881895 0.03917199 0.03523188 0.03849399 0.03527593 0.02700597 0.04159599 0.04006296 0.04158896 0.02850395 0.04403597 0.03059995 0.04159599 0.04006296 0.03881895 0.03917199 0.04158896 0.02850395 0.04403597 0.04224199 0.04403597 0.03059995 0.04185491 0.032745 0.04403597 0.04224199 0.04159599 0.04006296 0.04403597 0.03059995 0.041848 0.04447793 0.04185491 0.032745 0.03911799 0.03365296 0.041848 0.04447793 0.04403597 0.04224199 0.04185491 0.032745 0.03553491 0.04614692 0.03911799 0.03365296 0.03549093 0.03435695 0.03553491 0.04614692 0.041848 0.04447793 0.03911799 0.03365296 0.03553491 0.04614692 0.03549093 0.03435695 0.03125 0.03479999 0.02678591 0.04676896 0.03125 0.03479999 0.0266959 0.03494799 0.02678591 0.04676896 0.03553491 0.04614692 0.03125 0.03479999 0.02223199 0.04661399 0.0266959 0.03494799 0.01794689 0.03435099 0.02223199 0.04661399 0.02678591 0.04676896 0.0266959 0.03494799 0.014364 0.04541999 0.01794689 0.03435099 0.01163399 0.03274798 0.017991 0.04615288 0.02223199 0.04661399 0.01794689 0.03435099 0.014364 0.04541999 0.017991 0.04615288 0.01794689 0.03435099 0.01162797 0.04447489 0.014364 0.04541999 0.01163399 0.03274798 0.01162797 0.04447489 0.009445965 0.04224199 0.01189297 0.04005998 0.014364 0.04541999 0.01189297 0.04005998 0.018206 0.03849995 0.01162797 0.04447489 0.01189297 0.04005998 0.014364 0.04541999 0.017991 0.04615288 0.018206 0.03849995 0.02669799 0.03793299 0.014364 0.04541999 0.018206 0.03849995 0.017991 0.04615288 0.02678591 0.04676896 0.02669799 0.03793299 0.031102 0.03807389 0.02223199 0.04661399 0.02669799 0.03793299 0.02678591 0.04676896 0.017991 0.04615288 0.02669799 0.03793299 0.02223199 0.04661399 0.02678591 0.04676896 0.031102 0.03807389 0.03523188 0.03849399 0.03553491 0.04614692 0.03523188 0.03849399 0.03881895 0.03917199 0.02678591 0.04676896 0.03523188 0.03849399 0.03553491 0.04614692 0.041848 0.04447793 0.03881895 0.03917199 0.04159599 0.04006296 0.03553491 0.04614692 0.03881895 0.03917199 0.041848 0.04447793 0.041848 0.04447793 0.04159599 0.04006296 0.04403597 0.04224199 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 7 7 7 8 8 8 9 9 9 6 6 10 8 8 11 10 10 12 11 11 13 12 12 14 13 13 15 4 4 16 3 3 17 0 0 18 14 14 19 1 1 20 15 15 21 16 15 22 17 15 23 0 0 24 18 16 25 14 14 26 15 17 27 17 17 28 19 17 29 20 18 30 21 19 31 18 16 32 22 20 33 19 20 34 23 20 35 0 0 36 20 18 37 18 16 38 15 21 39 19 21 40 22 21 41 24 22 42 25 23 43 21 19 44 26 24 45 23 24 46 27 24 47 20 18 48 24 22 49 21 19 50 28 24 51 22 24 52 23 24 53 26 24 54 28 24 55 23 24 56 29 25 57 30 26 58 25 23 59 31 24 60 27 24 61 32 24 62 24 22 63 29 25 64 25 23 65 31 27 66 26 27 67 27 27 68 33 28 69 34 29 70 30 26 71 35 30 72 32 30 73 36 30 74 37 31 75 33 28 76 30 26 77 29 25 78 37 31 79 30 26 80 38 24 81 31 24 82 32 24 83 35 32 84 38 32 85 32 32 86 39 33 87 40 34 88 34 29 89 41 24 90 36 24 91 42 24 92 43 35 93 39 33 94 34 29 95 33 28 96 43 35 97 34 29 98 41 36 99 35 36 100 36 36 101 44 37 102 45 38 103 40 34 104 46 24 105 42 24 106 47 24 107 48 39 108 44 37 109 40 34 110 39 33 111 48 39 112 40 34 113 46 24 114 41 24 115 42 24 116 49 40 117 50 41 118 45 38 119 51 24 120 47 24 121 52 24 122 53 42 123 49 40 124 45 38 125 44 37 126 53 42 127 45 38 128 51 43 129 46 43 130 47 43 131 54 44 132 55 45 133 50 41 134 56 46 135 52 46 136 57 46 137 58 47 138 54 44 139 50 41 140 49 40 141 58 47 142 50 41 143 56 48 144 51 48 145 52 48 146 59 49 147 60 50 148 55 45 149 61 24 150 57 24 151 62 24 152 63 51 153 59 49 154 55 45 155 54 44 156 63 51 157 55 45 158 61 24 159 56 24 160 57 24 161 64 52 162 65 53 163 60 50 164 66 54 165 62 54 166 67 54 167 68 55 168 64 52 169 60 50 170 59 49 171 68 55 172 60 50 173 69 24 174 62 24 175 66 24 176 69 24 177 61 24 178 62 24 179 70 56 180 71 57 181 65 53 182 72 24 183 67 24 184 73 24 185 74 58 186 70 56 187 65 53 188 64 52 189 74 58 190 65 53 191 75 24 192 66 24 193 67 24 194 72 24 195 75 24 196 67 24 197 76 59 198 77 60 199 71 57 200 78 61 201 73 61 202 79 61 203 80 62 204 76 59 205 71 57 206 70 56 207 80 62 208 71 57 209 78 63 210 72 63 211 73 63 212 81 64 213 82 65 214 77 60 215 78 24 216 79 24 217 83 24 218 76 59 219 81 64 220 77 60 221 84 66 222 85 67 223 82 65 224 86 24 225 83 24 226 87 24 227 81 64 228 84 66 229 82 65 230 86 24 231 78 24 232 83 24 233 88 68 234 89 69 235 85 67 236 90 24 237 87 24 238 91 24 239 84 66 240 88 68 241 85 67 242 90 24 243 86 24 244 87 24 245 92 70 246 93 71 247 89 69 248 94 72 249 91 72 250 95 72 251 88 68 252 92 70 253 89 69 254 94 73 255 90 73 256 91 73 257 96 74 258 97 75 259 93 71 260 98 76 261 95 76 262 99 76 263 92 70 264 96 74 265 93 71 266 98 77 267 94 77 268 95 77 269 100 78 270 101 79 271 97 75 272 102 80 273 99 80 274 103 80 275 96 74 276 100 78 277 97 75 278 102 81 279 98 81 280 99 81 281 104 82 282 105 83 283 101 79 284 106 24 285 103 24 286 107 24 287 108 84 288 104 82 289 101 79 290 100 78 291 108 84 292 101 79 293 106 24 294 102 24 295 103 24 296 109 85 297 110 86 298 105 83 299 111 87 300 107 87 301 112 87 302 113 88 303 109 85 304 105 83 305 104 82 306 113 88 307 105 83 308 114 89 309 106 89 310 107 89 311 111 90 312 114 90 313 107 90 314 115 91 315 116 92 316 110 86 317 117 93 318 112 93 319 118 93 320 119 94 321 115 91 322 110 86 323 109 85 324 119 94 325 110 86 326 120 95 327 112 95 328 117 95 329 111 24 330 112 24 331 120 24 332 121 96 333 122 97 334 116 92 335 123 98 336 118 98 337 124 98 338 125 99 339 121 96 340 116 92 341 126 100 342 125 99 343 116 92 344 115 91 345 126 100 346 116 92 347 117 24 348 118 24 349 123 24 350 127 101 351 128 102 352 129 103 353 130 104 354 128 102 355 127 101 356 131 105 357 132 106 358 133 107 359 134 108 360 135 109 361 136 110 362 134 108 363 137 111 364 135 109 365 138 112 366 133 107 367 139 113 368 138 112 369 131 105 370 133 107 371 138 112 372 139 113 373 140 114 374 141 115 375 140 114 376 142 116 377 141 115 378 138 112 379 140 114 380 141 115 381 142 116 382 143 117 383 144 118 384 143 117 385 145 119 386 144 118 387 141 115 388 143 117 389 146 120 390 145 119 391 147 121 392 146 120 393 144 118 394 145 119 395 146 120 396 147 121 397 148 122 398 149 123 399 148 122 400 150 124 401 149 123 402 146 120 403 148 122 404 149 123 405 150 124 406 151 125 407 152 126 408 151 125 409 153 127 410 152 126 411 149 123 412 151 125 413 154 128 414 153 127 415 155 129 416 154 128 417 152 126 418 153 127 419 154 128 420 155 129 421 156 130 422 157 131 423 156 130 424 158 132 425 157 131 426 154 128 427 156 130 428 157 131 429 158 132 430 159 133 431 160 134 432 159 133 433 161 135 434 160 134 435 157 131 436 159 133 437 162 136 438 161 135 439 163 137 440 162 136 441 160 134 442 161 135 443 162 136 444 163 137 445 164 138 446 165 139 447 164 138 448 166 140 449 165 139 450 162 136 451 164 138 452 165 139 453 166 140 454 167 141 455 168 142 456 167 141 457 169 143 458 168 142 459 165 139 460 167 141 461 168 142 462 169 143 463 170 144 464 171 145 465 170 144 466 172 146 467 171 145 468 168 142 469 170 144 470 173 147 471 172 146 472 174 148 473 173 147 474 171 145 475 172 146 476 173 147 477 174 148 478 175 149 479 176 150 480 175 149 481 177 151 482 176 150 483 173 147 484 175 149 485 176 150 486 177 151 487 178 152 488 179 153 489 178 152 490 180 154 491 179 153 492 176 150 493 178 152 494 181 155 495 180 154 496 182 156 497 181 155 498 179 153 499 180 154 500 181 155 501 182 156 502 183 157 503 184 158 504 183 157 505 185 159 506 181 155 507 183 157 508 184 158 509 186 160 510 185 159 511 187 161 512 184 158 513 185 159 514 186 160 515 188 162 516 189 163 517 190 164 518 191 165 519 192 166 520 189 163 521 188 162 522 191 165 523 189 163 524 193 167 525 190 164 526 194 168 527 195 169 528 188 162 529 190 164 530 193 167 531 195 169 532 190 164 533 196 170 534 194 168 535 197 171 536 198 172 537 193 167 538 194 168 539 196 170 540 198 172 541 194 168 542 199 173 543 197 171 544 7 7 545 199 173 546 196 170 547 197 171 548 200 174 549 199 173 550 7 7 551 6 6 552 200 174 553 7 7 554 201 175 555 202 176 556 192 166 557 191 165 558 201 175 559 192 166 560 203 177 561 204 178 562 202 176 563 181 155 564 184 158 565 205 179 566 201 175 567 203 177 568 202 176 569 206 180 570 207 181 571 204 178 572 181 155 573 205 179 574 208 182 575 203 177 576 206 180 577 204 178 578 209 183 579 210 184 580 207 181 581 181 155 582 208 182 583 211 185 584 206 180 585 209 183 586 207 181 587 209 183 588 212 186 589 210 184 590 213 187 591 211 185 592 214 188 593 215 189 594 181 155 595 211 185 596 215 189 597 211 185 598 213 187 599 216 190 600 217 191 601 212 186 602 218 192 603 219 193 604 220 194 605 221 195 606 216 190 607 212 186 608 209 183 609 221 195 610 212 186 611 222 196 612 223 197 613 217 191 614 224 198 615 220 194 616 225 199 617 226 200 618 222 196 619 217 191 620 216 190 621 226 200 622 217 191 623 218 192 624 220 194 625 224 198 626 227 201 627 228 202 628 223 197 629 229 203 630 225 199 631 230 204 632 231 205 633 227 201 634 223 197 635 222 196 636 231 205 637 223 197 638 224 198 639 225 199 640 229 203 641 232 206 642 233 207 643 228 202 644 234 208 645 230 204 646 235 209 647 236 210 648 232 206 649 228 202 650 227 201 651 236 210 652 228 202 653 237 211 654 230 204 655 234 208 656 229 203 657 230 204 658 237 211 659 238 212 660 239 213 661 233 207 662 240 214 663 235 209 664 241 215 665 242 216 666 238 212 667 233 207 668 232 206 669 242 216 670 233 207 671 243 217 672 235 209 673 240 214 674 234 208 675 235 209 676 243 217 677 244 218 678 245 219 679 239 213 680 246 220 681 241 215 682 247 221 683 238 212 684 244 218 685 239 213 686 248 222 687 241 215 688 246 220 689 240 214 690 241 215 691 248 222 692 249 223 693 250 224 694 245 219 695 251 225 696 247 221 697 252 226 698 244 218 699 249 223 700 245 219 701 246 220 702 247 221 703 251 225 704 253 227 705 254 228 706 250 224 707 255 229 708 252 226 709 256 230 710 249 223 711 253 227 712 250 224 713 251 225 714 252 226 715 255 229 716 253 227 717 257 231 718 254 228 719 258 232 720 256 230 721 259 233 722 260 234 723 256 230 724 258 232 725 255 229 726 256 230 727 260 234 728 261 235 729 262 236 730 257 231 731 263 237 732 259 233 733 264 238 734 253 227 735 261 235 736 257 231 737 258 232 738 259 233 739 263 237 740 265 239 741 266 240 742 262 236 743 267 241 744 264 238 745 268 242 746 261 235 747 265 239 748 262 236 749 263 237 750 264 238 751 267 241 752 269 243 753 270 244 754 266 240 755 271 245 756 268 242 757 272 246 758 265 239 759 269 243 760 266 240 761 267 241 762 268 242 763 271 245 764 273 247 765 274 248 766 270 244 767 275 249 768 272 246 769 276 250 770 269 243 771 273 247 772 270 244 773 271 245 774 272 246 775 275 249 776 277 251 777 278 252 778 274 248 779 279 253 780 276 250 781 280 254 782 273 247 783 277 251 784 274 248 785 275 249 786 276 250 787 279 253 788 281 255 789 282 256 790 278 252 791 283 257 792 280 254 793 284 258 794 277 251 795 281 255 796 278 252 797 279 253 798 280 254 799 283 257 800 285 259 801 286 260 802 282 256 803 287 261 804 284 258 805 288 262 806 281 255 807 285 259 808 282 256 809 283 257 810 284 258 811 287 261 812 289 263 813 290 264 814 286 260 815 291 265 816 288 262 817 292 266 818 285 259 819 289 263 820 286 260 821 287 261 822 288 262 823 291 265 824 293 267 825 294 268 826 290 264 827 295 269 828 292 266 829 296 270 830 289 263 831 293 267 832 290 264 833 291 265 834 292 266 835 295 269 836 297 271 837 298 272 838 294 268 839 299 273 840 296 270 841 300 274 842 293 267 843 297 271 844 294 268 845 301 275 846 296 270 847 299 273 848 295 269 849 296 270 850 301 275 851 302 276 852 303 277 853 298 272 854 304 278 855 300 274 856 305 279 857 297 271 858 302 276 859 298 272 860 306 280 861 300 274 862 304 278 863 299 273 864 300 274 865 306 280 866 307 281 867 308 282 868 303 277 869 309 283 870 305 279 871 310 284 872 302 276 873 307 281 874 303 277 875 311 285 876 305 279 877 309 283 878 304 278 879 305 279 880 311 285 881 312 286 882 313 287 883 308 282 884 314 288 885 310 284 886 315 289 887 307 281 888 312 286 889 308 282 890 316 290 891 310 284 892 314 288 893 317 291 894 310 284 895 316 290 896 309 283 897 310 284 898 317 291 899 318 292 900 319 293 901 313 287 902 320 294 903 315 289 904 321 295 905 312 286 906 318 292 907 313 287 908 322 296 909 315 289 910 320 294 911 323 297 912 315 289 913 322 296 914 314 288 915 315 289 916 323 297 917 324 298 918 325 299 919 326 300 920 327 301 921 321 295 922 328 302 923 329 303 924 328 302 925 321 295 926 330 304 927 321 295 928 327 301 929 320 294 930 321 295 931 330 304 932 331 305 933 325 299 934 324 298 935 332 306 936 333 306 937 334 306 938 335 307 939 334 307 940 336 307 941 332 308 942 334 308 943 335 308 944 337 309 945 336 309 946 338 309 947 335 308 948 336 308 949 337 308 950 339 308 951 338 308 952 340 308 953 337 308 954 338 308 955 339 308 956 341 308 957 340 308 958 342 308 959 339 308 960 340 308 961 341 308 962 343 308 963 342 308 964 344 308 965 341 308 966 342 308 967 343 308 968 345 308 969 344 308 970 346 308 971 345 310 972 343 310 973 344 310 974 347 308 975 346 308 976 348 308 977 349 308 978 345 308 979 346 308 980 347 308 981 349 308 982 346 308 983 350 308 984 348 308 985 351 308 986 350 311 987 347 311 988 348 311 989 350 312 990 351 312 991 352 312 992 353 308 993 352 308 994 354 308 995 353 313 996 350 313 997 352 313 998 355 308 999 354 308 1000 356 308 1001 355 314 1002 353 314 1003 354 314 1004 357 308 1005 356 308 1006 358 308 1007 359 308 1008 355 308 1009 356 308 1010 357 315 1011 359 315 1012 356 315 1013 360 308 1014 358 308 1015 361 308 1016 360 316 1017 357 316 1018 358 316 1019 360 308 1020 361 308 1021 362 308 1022 363 308 1023 362 308 1024 364 308 1025 363 317 1026 360 317 1027 362 317 1028 363 318 1029 364 318 1030 365 318 1031 366 319 1032 365 319 1033 367 319 1034 366 308 1035 363 308 1036 365 308 1037 366 320 1038 367 320 1039 368 320 1040 369 308 1041 368 308 1042 370 308 1043 369 321 1044 366 321 1045 368 321 1046 371 308 1047 370 308 1048 372 308 1049 371 322 1050 369 322 1051 370 322 1052 371 308 1053 372 308 1054 373 308 1055 374 308 1056 373 308 1057 375 308 1058 374 323 1059 371 323 1060 373 323 1061 374 308 1062 375 308 1063 376 308 1064 377 308 1065 376 308 1066 378 308 1067 377 324 1068 374 324 1069 376 324 1070 377 325 1071 378 325 1072 379 325 1073 380 308 1074 379 308 1075 381 308 1076 380 326 1077 377 326 1078 379 326 1079 380 308 1080 381 308 1081 382 308 1082 383 308 1083 382 308 1084 384 308 1085 383 327 1086 380 327 1087 382 327 1088 385 308 1089 384 308 1090 386 308 1091 385 308 1092 383 308 1093 384 308 1094 385 308 1095 386 308 1096 387 308 1097 388 328 1098 387 328 1099 389 328 1100 388 308 1101 385 308 1102 387 308 1103 390 308 1104 389 308 1105 391 308 1106 390 329 1107 388 329 1108 389 329 1109 392 330 1110 391 330 1111 393 330 1112 392 331 1113 390 331 1114 391 331 1115 394 308 1116 393 308 1117 395 308 1118 396 308 1119 393 308 1120 394 308 1121 397 332 1122 393 332 1123 396 332 1124 398 333 1125 392 333 1126 393 333 1127 397 308 1128 398 308 1129 393 308 1130 399 308 1131 395 308 1132 400 308 1133 394 308 1134 395 308 1135 399 308 1136 401 308 1137 400 308 1138 402 308 1139 399 308 1140 400 308 1141 401 308 1142 403 308 1143 402 308 1144 404 308 1145 401 334 1146 402 334 1147 403 334 1148 405 308 1149 404 308 1150 406 308 1151 403 335 1152 404 335 1153 405 335 1154 405 336 1155 406 336 1156 407 336 1157 408 337 1158 11 11 1159 10 10 1160 409 338 1161 131 105 1162 138 112 1163 410 339 1164 136 110 1165 411 340 1166 410 339 1167 134 108 1168 136 110 1169 412 341 1170 138 112 1171 141 115 1172 413 342 1173 138 112 1174 412 341 1175 409 338 1176 138 112 1177 413 342 1178 414 343 1179 141 115 1180 144 118 1181 412 341 1182 141 115 1183 414 343 1184 415 344 1185 144 118 1186 146 120 1187 414 343 1188 144 118 1189 415 344 1190 416 345 1191 146 120 1192 149 123 1193 415 344 1194 146 120 1195 416 345 1196 417 346 1197 149 123 1198 152 126 1199 416 345 1200 149 123 1201 417 346 1202 418 347 1203 152 126 1204 154 128 1205 417 346 1206 152 126 1207 418 347 1208 419 348 1209 154 128 1210 157 131 1211 418 347 1212 154 128 1213 419 348 1214 420 349 1215 157 131 1216 160 134 1217 419 348 1218 157 131 1219 420 349 1220 421 350 1221 160 134 1222 162 136 1223 420 349 1224 160 134 1225 421 350 1226 422 351 1227 162 136 1228 165 139 1229 421 350 1230 162 136 1231 422 351 1232 423 352 1233 165 139 1234 168 142 1235 422 351 1236 165 139 1237 423 352 1238 424 353 1239 168 142 1240 171 145 1241 423 352 1242 168 142 1243 424 353 1244 425 354 1245 171 145 1246 173 147 1247 424 353 1248 171 145 1249 425 354 1250 426 355 1251 173 147 1252 176 150 1253 425 354 1254 173 147 1255 426 355 1256 427 356 1257 176 150 1258 179 153 1259 426 355 1260 176 150 1261 427 356 1262 215 189 1263 179 153 1264 181 155 1265 427 356 1266 179 153 1267 215 189 1268 428 357 1269 429 358 1270 430 359 1271 431 360 1272 432 361 1273 433 362 1274 434 363 1275 428 357 1276 430 359 1277 435 364 1278 434 363 1279 430 359 1280 436 365 1281 435 364 1282 430 359 1283 437 366 1284 436 365 1285 430 359 1286 438 367 1287 437 366 1288 430 359 1289 439 368 1290 438 367 1291 430 359 1292 440 369 1293 439 368 1294 430 359 1295 441 370 1296 440 369 1297 430 359 1298 442 371 1299 441 370 1300 430 359 1301 443 372 1302 442 371 1303 430 359 1304 444 373 1305 443 372 1306 430 359 1307 445 374 1308 444 373 1309 430 359 1310 446 375 1311 445 374 1312 430 359 1313 447 376 1314 446 375 1315 430 359 1316 448 377 1317 447 376 1318 430 359 1319 449 378 1320 448 377 1321 430 359 1322 450 379 1323 449 378 1324 430 359 1325 451 380 1326 450 379 1327 430 359 1328 452 381 1329 451 380 1330 430 359 1331 453 382 1332 452 381 1333 430 359 1334 454 383 1335 453 382 1336 430 359 1337 455 384 1338 454 383 1339 430 359 1340 456 385 1341 455 384 1342 430 359 1343 457 386 1344 456 385 1345 430 359 1346 458 387 1347 459 388 1348 432 361 1349 460 389 1350 432 361 1351 431 360 1352 461 390 1353 432 361 1354 460 389 1355 462 391 1356 432 361 1357 461 390 1358 463 392 1359 432 361 1360 462 391 1361 464 393 1362 432 361 1363 463 392 1364 465 394 1365 432 361 1366 464 393 1367 466 395 1368 432 361 1369 465 394 1370 467 396 1371 432 361 1372 466 395 1373 468 397 1374 432 361 1375 467 396 1376 469 398 1377 432 361 1378 468 397 1379 470 399 1380 432 361 1381 469 398 1382 471 400 1383 432 361 1384 470 399 1385 472 401 1386 432 361 1387 471 400 1388 473 402 1389 432 361 1390 472 401 1391 474 403 1392 432 361 1393 473 402 1394 475 404 1395 432 361 1396 474 403 1397 476 405 1398 432 361 1399 475 404 1400 477 406 1401 432 361 1402 476 405 1403 478 407 1404 432 361 1405 477 406 1406 479 408 1407 432 361 1408 478 407 1409 480 409 1410 432 361 1411 479 408 1412 458 387 1413 432 361 1414 480 409 1415 431 360 1416 433 362 1417 481 410 1418 482 411 1419 428 357 1420 434 363 1421 483 412 1422 481 410 1423 484 413 1424 431 360 1425 481 410 1426 483 412 1427 485 414 1428 434 363 1429 435 364 1430 486 415 1431 482 411 1432 434 363 1433 485 414 1434 486 415 1435 434 363 1436 487 416 1437 435 364 1438 436 365 1439 487 416 1440 485 414 1441 435 364 1442 488 417 1443 436 365 1444 437 366 1445 488 417 1446 487 416 1447 436 365 1448 489 418 1449 437 366 1450 438 367 1451 489 418 1452 488 417 1453 437 366 1454 490 419 1455 438 367 1456 439 368 1457 491 420 1458 489 418 1459 438 367 1460 490 419 1461 491 420 1462 438 367 1463 492 421 1464 439 368 1465 440 369 1466 493 422 1467 490 419 1468 439 368 1469 492 421 1470 493 422 1471 439 368 1472 494 423 1473 440 369 1474 441 370 1475 494 423 1476 492 421 1477 440 369 1478 495 424 1479 441 370 1480 442 371 1481 495 424 1482 494 423 1483 441 370 1484 496 425 1485 442 371 1486 443 372 1487 496 425 1488 495 424 1489 442 371 1490 497 426 1491 443 372 1492 444 373 1493 497 426 1494 496 425 1495 443 372 1496 498 427 1497 444 373 1498 445 374 1499 498 427 1500 497 426 1501 444 373 1502 499 428 1503 445 374 1504 446 375 1505 499 428 1506 498 427 1507 445 374 1508 500 429 1509 446 375 1510 447 376 1511 500 429 1512 499 428 1513 446 375 1514 501 430 1515 447 376 1516 448 377 1517 501 430 1518 500 429 1519 447 376 1520 502 431 1521 448 377 1522 449 378 1523 502 431 1524 501 430 1525 448 377 1526 503 432 1527 449 378 1528 450 379 1529 503 432 1530 502 431 1531 449 378 1532 504 433 1533 450 379 1534 451 380 1535 504 433 1536 503 432 1537 450 379 1538 505 434 1539 451 380 1540 452 381 1541 505 434 1542 504 433 1543 451 380 1544 506 435 1545 452 381 1546 453 382 1547 506 435 1548 505 434 1549 452 381 1550 507 436 1551 453 382 1552 454 383 1553 507 436 1554 506 435 1555 453 382 1556 508 437 1557 454 383 1558 455 384 1559 508 437 1560 507 436 1561 454 383 1562 509 438 1563 455 384 1564 456 385 1565 509 438 1566 508 437 1567 455 384 1568 509 438 1569 456 385 1570 457 386 1571 509 438 1572 457 386 1573 510 439 1574 458 387 1575 511 440 1576 459 388 1577 512 441 1578 509 438 1579 510 439 1580 512 441 1581 510 439 1582 513 442 1583 514 443 1584 515 444 1585 511 440 1586 514 443 1587 511 440 1588 458 387 1589 329 303 1590 516 445 1591 328 302 1592 517 446 1593 493 422 1594 492 421 1595 518 447 1596 492 421 1597 494 423 1598 518 447 1599 517 446 1600 492 421 1601 519 448 1602 494 423 1603 495 424 1604 520 449 1605 518 447 1606 494 423 1607 521 450 1608 520 449 1609 494 423 1610 519 448 1611 521 450 1612 494 423 1613 522 451 1614 495 424 1615 496 425 1616 522 451 1617 519 448 1618 495 424 1619 523 452 1620 496 425 1621 497 426 1622 523 452 1623 522 451 1624 496 425 1625 524 453 1626 497 426 1627 498 427 1628 524 453 1629 523 452 1630 497 426 1631 525 454 1632 498 427 1633 499 428 1634 525 454 1635 524 453 1636 498 427 1637 526 455 1638 499 428 1639 500 429 1640 526 455 1641 525 454 1642 499 428 1643 527 456 1644 500 429 1645 501 430 1646 527 456 1647 526 455 1648 500 429 1649 528 457 1650 501 430 1651 502 431 1652 528 457 1653 527 456 1654 501 430 1655 529 458 1656 502 431 1657 503 432 1658 529 458 1659 528 457 1660 502 431 1661 530 459 1662 503 432 1663 504 433 1664 530 459 1665 529 458 1666 503 432 1667 531 460 1668 504 433 1669 505 434 1670 531 460 1671 530 459 1672 504 433 1673 532 461 1674 505 434 1675 506 435 1676 532 461 1677 531 460 1678 505 434 1679 533 462 1680 506 435 1681 507 436 1682 533 462 1683 532 461 1684 506 435 1685 534 463 1686 507 436 1687 508 437 1688 534 463 1689 533 462 1690 507 436 1691 512 441 1692 508 437 1693 509 438 1694 512 441 1695 534 463 1696 508 437 1697 535 464 1698 512 441 1699 513 442 1700 535 464 1701 513 442 1702 536 465 1703 537 466 1704 538 467 1705 515 444 1706 514 443 1707 537 466 1708 515 444 1709 539 468 1710 521 450 1711 519 448 1712 540 469 1713 519 448 1714 522 451 1715 541 470 1716 539 468 1717 519 448 1718 542 471 1719 541 470 1720 519 448 1721 540 469 1722 542 471 1723 519 448 1724 543 472 1725 522 451 1726 523 452 1727 543 472 1728 540 469 1729 522 451 1730 544 473 1731 523 452 1732 524 453 1733 544 473 1734 543 472 1735 523 452 1736 545 474 1737 524 453 1738 525 454 1739 545 474 1740 544 473 1741 524 453 1742 546 475 1743 525 454 1744 526 455 1745 546 475 1746 545 474 1747 525 454 1748 547 476 1749 526 455 1750 527 456 1751 547 476 1752 546 475 1753 526 455 1754 548 477 1755 527 456 1756 528 457 1757 548 477 1758 547 476 1759 527 456 1760 549 478 1761 528 457 1762 529 458 1763 549 478 1764 548 477 1765 528 457 1766 550 479 1767 529 458 1768 530 459 1769 550 479 1770 549 478 1771 529 458 1772 551 480 1773 530 459 1774 531 460 1775 551 480 1776 550 479 1777 530 459 1778 552 481 1779 531 460 1780 532 461 1781 552 481 1782 551 480 1783 531 460 1784 553 482 1785 532 461 1786 533 462 1787 553 482 1788 552 481 1789 532 461 1790 554 483 1791 533 462 1792 534 463 1793 554 483 1794 553 482 1795 533 462 1796 535 464 1797 534 463 1798 512 441 1799 535 464 1800 554 483 1801 534 463 1802 555 484 1803 535 464 1804 536 465 1805 555 484 1806 536 465 1807 556 485 1808 557 486 1809 558 487 1810 538 467 1811 537 466 1812 557 486 1813 538 467 1814 559 488 1815 542 471 1816 540 469 1817 560 489 1818 540 469 1819 543 472 1820 561 490 1821 559 488 1822 540 469 1823 560 489 1824 561 490 1825 540 469 1826 562 491 1827 543 472 1828 544 473 1829 562 491 1830 560 489 1831 543 472 1832 563 492 1833 544 473 1834 545 474 1835 563 492 1836 562 491 1837 544 473 1838 564 493 1839 545 474 1840 546 475 1841 564 493 1842 563 492 1843 545 474 1844 565 494 1845 546 475 1846 547 476 1847 565 494 1848 564 493 1849 546 475 1850 566 495 1851 547 476 1852 548 477 1853 566 495 1854 565 494 1855 547 476 1856 567 496 1857 548 477 1858 549 478 1859 567 496 1860 566 495 1861 548 477 1862 568 497 1863 549 478 1864 550 479 1865 568 497 1866 567 496 1867 549 478 1868 569 498 1869 550 479 1870 551 480 1871 569 498 1872 568 497 1873 550 479 1874 570 499 1875 551 480 1876 552 481 1877 570 499 1878 569 498 1879 551 480 1880 571 500 1881 552 481 1882 553 482 1883 571 500 1884 570 499 1885 552 481 1886 572 501 1887 553 482 1888 554 483 1889 572 501 1890 571 500 1891 553 482 1892 573 502 1893 554 483 1894 535 464 1895 573 502 1896 572 501 1897 554 483 1898 555 484 1899 573 502 1900 535 464 1901 574 503 1902 555 484 1903 556 485 1904 574 503 1905 556 485 1906 575 504 1907 576 505 1908 577 506 1909 558 487 1910 557 486 1911 576 505 1912 558 487 1913 578 507 1914 561 490 1915 560 489 1916 579 508 1917 560 489 1918 562 491 1919 580 509 1920 578 507 1921 560 489 1922 579 508 1923 580 509 1924 560 489 1925 581 510 1926 562 491 1927 563 492 1928 581 510 1929 579 508 1930 562 491 1931 582 511 1932 563 492 1933 564 493 1934 582 511 1935 581 510 1936 563 492 1937 583 512 1938 564 493 1939 565 494 1940 583 512 1941 582 511 1942 564 493 1943 584 513 1944 565 494 1945 566 495 1946 584 513 1947 583 512 1948 565 494 1949 585 514 1950 566 495 1951 567 496 1952 585 514 1953 584 513 1954 566 495 1955 586 515 1956 567 496 1957 568 497 1958 586 515 1959 585 514 1960 567 496 1961 587 516 1962 568 497 1963 569 498 1964 587 516 1965 586 515 1966 568 497 1967 588 517 1968 569 498 1969 570 499 1970 588 517 1971 587 516 1972 569 498 1973 589 518 1974 570 499 1975 571 500 1976 589 518 1977 588 517 1978 570 499 1979 590 519 1980 571 500 1981 572 501 1982 590 519 1983 589 518 1984 571 500 1985 591 520 1986 572 501 1987 573 502 1988 591 520 1989 590 519 1990 572 501 1991 592 521 1992 573 502 1993 555 484 1994 592 521 1995 591 520 1996 573 502 1997 574 503 1998 592 521 1999 555 484 2000 593 522 2001 574 503 2002 575 504 2003 593 522 2004 575 504 2005 594 523 2006 595 524 2007 596 525 2008 577 506 2009 576 505 2010 595 524 2011 577 506 2012 597 526 2013 580 509 2014 579 508 2015 598 527 2016 579 508 2017 581 510 2018 599 528 2019 597 526 2020 579 508 2021 598 527 2022 599 528 2023 579 508 2024 600 529 2025 581 510 2026 582 511 2027 600 529 2028 598 527 2029 581 510 2030 601 530 2031 582 511 2032 583 512 2033 601 530 2034 600 529 2035 582 511 2036 602 531 2037 583 512 2038 584 513 2039 602 531 2040 601 530 2041 583 512 2042 603 532 2043 584 513 2044 585 514 2045 603 532 2046 602 531 2047 584 513 2048 604 533 2049 585 514 2050 586 515 2051 604 533 2052 603 532 2053 585 514 2054 605 534 2055 586 515 2056 587 516 2057 605 534 2058 604 533 2059 586 515 2060 606 535 2061 587 516 2062 588 517 2063 606 535 2064 605 534 2065 587 516 2066 607 536 2067 588 517 2068 589 518 2069 607 536 2070 606 535 2071 588 517 2072 608 537 2073 589 518 2074 590 519 2075 608 537 2076 607 536 2077 589 518 2078 609 538 2079 590 519 2080 591 520 2081 609 538 2082 608 537 2083 590 519 2084 610 539 2085 591 520 2086 592 521 2087 610 539 2088 609 538 2089 591 520 2090 611 540 2091 592 521 2092 574 503 2093 611 540 2094 610 539 2095 592 521 2096 593 522 2097 611 540 2098 574 503 2099 612 541 2100 593 522 2101 594 523 2102 612 541 2103 594 523 2104 613 542 2105 614 543 2106 615 544 2107 596 525 2108 595 524 2109 614 543 2110 596 525 2111 616 545 2112 599 528 2113 598 527 2114 616 545 2115 617 546 2116 599 528 2117 618 547 2118 598 527 2119 600 529 2120 618 547 2121 616 545 2122 598 527 2123 619 548 2124 600 529 2125 601 530 2126 619 548 2127 618 547 2128 600 529 2129 620 549 2130 601 530 2131 602 531 2132 620 549 2133 619 548 2134 601 530 2135 621 550 2136 602 531 2137 603 532 2138 621 550 2139 620 549 2140 602 531 2141 622 551 2142 603 532 2143 604 533 2144 622 551 2145 621 550 2146 603 532 2147 623 552 2148 604 533 2149 605 534 2150 623 552 2151 622 551 2152 604 533 2153 624 553 2154 605 534 2155 606 535 2156 624 553 2157 623 552 2158 605 534 2159 625 554 2160 606 535 2161 607 536 2162 625 554 2163 624 553 2164 606 535 2165 626 555 2166 607 536 2167 608 537 2168 626 555 2169 625 554 2170 607 536 2171 627 556 2172 608 537 2173 609 538 2174 627 556 2175 626 555 2176 608 537 2177 628 557 2178 609 538 2179 610 539 2180 628 557 2181 627 556 2182 609 538 2183 629 558 2184 610 539 2185 611 540 2186 629 558 2187 628 557 2188 610 539 2189 612 541 2190 611 540 2191 593 522 2192 612 541 2193 629 558 2194 611 540 2195 630 559 2196 612 541 2197 613 542 2198 630 559 2199 613 542 2200 631 560 2201 632 561 2202 633 562 2203 615 544 2204 614 543 2205 632 561 2206 615 544 2207 616 545 2208 634 563 2209 617 546 2210 635 564 2211 634 563 2212 616 545 2213 635 564 2214 636 565 2215 634 563 2216 637 566 2217 616 545 2218 618 547 2219 637 566 2220 635 564 2221 616 545 2222 638 567 2223 618 547 2224 619 548 2225 638 567 2226 637 566 2227 618 547 2228 639 568 2229 619 548 2230 620 549 2231 639 568 2232 638 567 2233 619 548 2234 640 569 2235 620 549 2236 621 550 2237 640 569 2238 639 568 2239 620 549 2240 641 570 2241 621 550 2242 622 551 2243 641 570 2244 640 569 2245 621 550 2246 642 571 2247 622 551 2248 623 552 2249 642 571 2250 641 570 2251 622 551 2252 643 572 2253 623 552 2254 624 553 2255 643 572 2256 642 571 2257 623 552 2258 644 573 2259 624 553 2260 625 554 2261 644 573 2262 643 572 2263 624 553 2264 645 574 2265 625 554 2266 626 555 2267 645 574 2268 644 573 2269 625 554 2270 646 575 2271 626 555 2272 627 556 2273 646 575 2274 645 574 2275 626 555 2276 647 576 2277 627 556 2278 628 557 2279 647 576 2280 646 575 2281 627 556 2282 648 577 2283 628 557 2284 629 558 2285 648 577 2286 647 576 2287 628 557 2288 630 559 2289 629 558 2290 612 541 2291 630 559 2292 648 577 2293 629 558 2294 649 578 2295 630 559 2296 631 560 2297 649 578 2298 631 560 2299 650 579 2300 651 580 2301 652 581 2302 633 562 2303 632 561 2304 651 580 2305 633 562 2306 635 564 2307 653 582 2308 636 565 2309 654 583 2310 653 582 2311 635 564 2312 654 583 2313 655 584 2314 653 582 2315 656 585 2316 635 564 2317 637 566 2318 656 585 2319 654 583 2320 635 564 2321 657 586 2322 637 566 2323 638 567 2324 657 586 2325 656 585 2326 637 566 2327 658 587 2328 638 567 2329 639 568 2330 658 587 2331 657 586 2332 638 567 2333 659 588 2334 639 568 2335 640 569 2336 659 588 2337 658 587 2338 639 568 2339 660 589 2340 640 569 2341 641 570 2342 660 589 2343 659 588 2344 640 569 2345 661 590 2346 641 570 2347 642 571 2348 661 590 2349 660 589 2350 641 570 2351 662 591 2352 642 571 2353 643 572 2354 662 591 2355 661 590 2356 642 571 2357 663 592 2358 643 572 2359 644 573 2360 663 592 2361 662 591 2362 643 572 2363 664 593 2364 644 573 2365 645 574 2366 664 593 2367 663 592 2368 644 573 2369 665 594 2370 645 574 2371 646 575 2372 665 594 2373 664 593 2374 645 574 2375 666 595 2376 646 575 2377 647 576 2378 666 595 2379 665 594 2380 646 575 2381 667 596 2382 647 576 2383 648 577 2384 667 596 2385 666 595 2386 647 576 2387 649 578 2388 648 577 2389 630 559 2390 649 578 2391 667 596 2392 648 577 2393 668 597 2394 649 578 2395 650 579 2396 668 597 2397 650 579 2398 669 598 2399 670 599 2400 671 600 2401 652 581 2402 651 580 2403 670 599 2404 652 581 2405 654 583 2406 672 601 2407 655 584 2408 673 602 2409 672 601 2410 654 583 2411 673 602 2412 674 603 2413 672 601 2414 675 604 2415 654 583 2416 656 585 2417 675 604 2418 673 602 2419 654 583 2420 676 605 2421 656 585 2422 657 586 2423 676 605 2424 675 604 2425 656 585 2426 677 606 2427 657 586 2428 658 587 2429 677 606 2430 676 605 2431 657 586 2432 678 607 2433 658 587 2434 659 588 2435 678 607 2436 677 606 2437 658 587 2438 679 608 2439 659 588 2440 660 589 2441 679 608 2442 678 607 2443 659 588 2444 680 609 2445 660 589 2446 661 590 2447 680 609 2448 679 608 2449 660 589 2450 681 610 2451 661 590 2452 662 591 2453 681 610 2454 680 609 2455 661 590 2456 682 611 2457 662 591 2458 663 592 2459 682 611 2460 681 610 2461 662 591 2462 683 612 2463 663 592 2464 664 593 2465 683 612 2466 682 611 2467 663 592 2468 684 613 2469 664 593 2470 665 594 2471 684 613 2472 683 612 2473 664 593 2474 685 614 2475 665 594 2476 666 595 2477 685 614 2478 684 613 2479 665 594 2480 686 615 2481 666 595 2482 667 596 2483 686 615 2484 685 614 2485 666 595 2486 668 597 2487 667 596 2488 649 578 2489 668 597 2490 686 615 2491 667 596 2492 687 616 2493 668 597 2494 669 598 2495 670 599 2496 688 617 2497 671 600 2498 673 602 2499 689 618 2500 674 603 2501 690 619 2502 689 618 2503 673 602 2504 690 619 2505 691 620 2506 689 618 2507 692 621 2508 673 602 2509 675 604 2510 692 621 2511 690 619 2512 673 602 2513 693 622 2514 675 604 2515 676 605 2516 693 622 2517 692 621 2518 675 604 2519 694 623 2520 676 605 2521 677 606 2522 694 623 2523 693 622 2524 676 605 2525 695 624 2526 677 606 2527 678 607 2528 695 624 2529 694 623 2530 677 606 2531 696 625 2532 678 607 2533 679 608 2534 696 625 2535 695 624 2536 678 607 2537 697 626 2538 679 608 2539 680 609 2540 697 626 2541 696 625 2542 679 608 2543 698 627 2544 680 609 2545 681 610 2546 698 627 2547 697 626 2548 680 609 2549 699 628 2550 681 610 2551 682 611 2552 699 628 2553 698 627 2554 681 610 2555 700 629 2556 682 611 2557 683 612 2558 700 629 2559 699 628 2560 682 611 2561 701 630 2562 683 612 2563 684 613 2564 701 630 2565 700 629 2566 683 612 2567 702 631 2568 684 613 2569 685 614 2570 702 631 2571 701 630 2572 684 613 2573 703 632 2574 685 614 2575 686 615 2576 703 632 2577 702 631 2578 685 614 2579 704 633 2580 686 615 2581 668 597 2582 704 633 2583 703 632 2584 686 615 2585 705 634 2586 668 597 2587 687 616 2588 705 634 2589 704 633 2590 668 597 2591 705 634 2592 687 616 2593 706 635 2594 707 636 2595 708 637 2596 688 617 2597 707 636 2598 688 617 2599 670 599 2600 709 638 2601 705 634 2602 706 635 2603 707 636 2604 710 639 2605 708 637 2606 690 619 2607 711 640 2608 691 620 2609 712 641 2610 711 640 2611 690 619 2612 712 641 2613 713 642 2614 711 640 2615 714 643 2616 690 619 2617 692 621 2618 714 643 2619 712 641 2620 690 619 2621 715 644 2622 692 621 2623 693 622 2624 715 644 2625 714 643 2626 692 621 2627 716 645 2628 693 622 2629 694 623 2630 716 645 2631 715 644 2632 693 622 2633 717 646 2634 694 623 2635 695 624 2636 717 646 2637 716 645 2638 694 623 2639 718 647 2640 695 624 2641 696 625 2642 718 647 2643 717 646 2644 695 624 2645 719 648 2646 696 625 2647 697 626 2648 719 648 2649 718 647 2650 696 625 2651 720 649 2652 697 626 2653 698 627 2654 720 649 2655 719 648 2656 697 626 2657 721 650 2658 698 627 2659 699 628 2660 721 650 2661 720 649 2662 698 627 2663 722 651 2664 699 628 2665 700 629 2666 722 651 2667 721 650 2668 699 628 2669 723 652 2670 700 629 2671 701 630 2672 723 652 2673 722 651 2674 700 629 2675 724 653 2676 701 630 2677 702 631 2678 724 653 2679 723 652 2680 701 630 2681 725 654 2682 702 631 2683 703 632 2684 725 654 2685 724 653 2686 702 631 2687 726 655 2688 703 632 2689 704 633 2690 726 655 2691 725 654 2692 703 632 2693 727 656 2694 704 633 2695 705 634 2696 727 656 2697 726 655 2698 704 633 2699 727 656 2700 705 634 2701 709 638 2702 727 656 2703 709 638 2704 728 657 2705 729 658 2706 730 659 2707 710 639 2708 707 636 2709 729 658 2710 710 639 2711 731 660 2712 727 656 2713 728 657 2714 729 658 2715 732 661 2716 730 659 2717 712 641 2718 733 662 2719 713 642 2720 712 641 2721 734 663 2722 733 662 2723 735 664 2724 734 663 2725 712 641 2726 735 664 2727 736 665 2728 734 663 2729 737 666 2730 712 641 2731 714 643 2732 737 666 2733 735 664 2734 712 641 2735 738 667 2736 714 643 2737 715 644 2738 738 667 2739 737 666 2740 714 643 2741 739 668 2742 715 644 2743 716 645 2744 739 668 2745 738 667 2746 715 644 2747 740 669 2748 716 645 2749 717 646 2750 740 669 2751 739 668 2752 716 645 2753 741 670 2754 717 646 2755 718 647 2756 741 670 2757 740 669 2758 717 646 2759 742 671 2760 718 647 2761 719 648 2762 742 671 2763 741 670 2764 718 647 2765 743 672 2766 719 648 2767 720 649 2768 743 672 2769 742 671 2770 719 648 2771 744 673 2772 720 649 2773 721 650 2774 744 673 2775 743 672 2776 720 649 2777 745 674 2778 721 650 2779 722 651 2780 745 674 2781 744 673 2782 721 650 2783 746 675 2784 722 651 2785 723 652 2786 746 675 2787 745 674 2788 722 651 2789 747 676 2790 723 652 2791 724 653 2792 747 676 2793 746 675 2794 723 652 2795 748 677 2796 724 653 2797 725 654 2798 748 677 2799 747 676 2800 724 653 2801 749 678 2802 725 654 2803 726 655 2804 749 678 2805 748 677 2806 725 654 2807 750 679 2808 726 655 2809 727 656 2810 750 679 2811 749 678 2812 726 655 2813 751 680 2814 727 656 2815 731 660 2816 751 680 2817 750 679 2818 727 656 2819 751 680 2820 731 660 2821 752 681 2822 753 682 2823 754 683 2824 732 661 2825 729 658 2826 753 682 2827 732 661 2828 755 684 2829 751 680 2830 752 681 2831 753 682 2832 756 685 2833 754 683 2834 735 664 2835 213 187 2836 736 665 2837 215 189 2838 213 187 2839 735 664 2840 427 356 2841 735 664 2842 737 666 2843 427 356 2844 215 189 2845 735 664 2846 426 355 2847 737 666 2848 738 667 2849 426 355 2850 427 356 2851 737 666 2852 425 354 2853 738 667 2854 739 668 2855 425 354 2856 426 355 2857 738 667 2858 424 353 2859 739 668 2860 740 669 2861 424 353 2862 425 354 2863 739 668 2864 423 352 2865 740 669 2866 741 670 2867 423 352 2868 424 353 2869 740 669 2870 422 351 2871 741 670 2872 742 671 2873 422 351 2874 423 352 2875 741 670 2876 421 350 2877 742 671 2878 743 672 2879 421 350 2880 422 351 2881 742 671 2882 420 349 2883 743 672 2884 744 673 2885 420 349 2886 421 350 2887 743 672 2888 419 348 2889 744 673 2890 745 674 2891 419 348 2892 420 349 2893 744 673 2894 418 347 2895 745 674 2896 746 675 2897 418 347 2898 419 348 2899 745 674 2900 417 346 2901 746 675 2902 747 676 2903 417 346 2904 418 347 2905 746 675 2906 416 345 2907 747 676 2908 748 677 2909 416 345 2910 417 346 2911 747 676 2912 415 344 2913 748 677 2914 749 678 2915 415 344 2916 416 345 2917 748 677 2918 414 343 2919 749 678 2920 750 679 2921 414 343 2922 415 344 2923 749 678 2924 412 341 2925 750 679 2926 751 680 2927 412 341 2928 414 343 2929 750 679 2930 412 341 2931 751 680 2932 755 684 2933 412 341 2934 755 684 2935 757 686 2936 758 687 2937 759 688 2938 756 685 2939 753 682 2940 758 687 2941 756 685 2942 413 342 2943 412 341 2944 757 686 2945 758 687 2946 760 689 2947 759 688 2948 410 339 2949 411 340 2950 760 689 2951 758 687 2952 410 339 2953 760 689 2954 134 108 2955 761 690 2956 137 111 2957 130 104 2958 127 101 2959 762 691 2960 763 692 2961 764 693 2962 761 690 2963 765 694 2964 762 691 2965 766 695 2966 134 108 2967 763 692 2968 761 690 2969 765 694 2970 130 104 2971 762 691 2972 763 692 2973 767 696 2974 764 693 2975 768 697 2976 766 695 2977 769 698 2978 768 697 2979 765 694 2980 766 695 2981 770 699 2982 771 700 2983 767 696 2984 772 701 2985 769 698 2986 773 702 2987 763 692 2988 770 699 2989 767 696 2990 774 703 2991 768 697 2992 769 698 2993 772 701 2994 774 703 2995 769 698 2996 770 699 2997 775 704 2998 771 700 2999 776 705 3000 773 702 3001 777 706 3002 776 705 3003 772 701 3004 773 702 3005 778 707 3006 779 708 3007 775 704 3008 780 709 3009 777 706 3010 781 710 3011 770 699 3012 778 707 3013 775 704 3014 782 711 3015 776 705 3016 777 706 3017 783 712 3018 782 711 3019 777 706 3020 780 709 3021 783 712 3022 777 706 3023 784 713 3024 785 714 3025 779 708 3026 786 715 3027 781 710 3028 787 716 3029 778 707 3030 784 713 3031 779 708 3032 788 717 3033 781 710 3034 786 715 3035 789 718 3036 780 709 3037 781 710 3038 790 719 3039 789 718 3040 781 710 3041 788 717 3042 790 719 3043 781 710 3044 784 713 3045 791 720 3046 785 714 3047 792 721 3048 787 716 3049 793 722 3050 792 721 3051 786 715 3052 787 716 3053 794 723 3054 795 724 3055 791 720 3056 792 721 3057 793 722 3058 796 725 3059 784 713 3060 794 723 3061 791 720 3062 794 723 3063 797 726 3064 795 724 3065 798 727 3066 796 725 3067 799 728 3068 798 727 3069 792 721 3070 796 725 3071 800 729 3072 801 730 3073 797 726 3074 798 727 3075 799 728 3076 802 731 3077 794 723 3078 800 729 3079 797 726 3080 803 732 3081 804 733 3082 801 730 3083 805 734 3084 802 731 3085 806 735 3086 800 729 3087 803 732 3088 801 730 3089 805 734 3090 798 727 3091 802 731 3092 803 732 3093 807 736 3094 804 733 3095 805 734 3096 806 735 3097 808 737 3098 809 738 3099 810 739 3100 807 736 3101 811 740 3102 808 737 3103 812 741 3104 803 732 3105 809 738 3106 807 736 3107 811 740 3108 805 734 3109 808 737 3110 809 738 3111 813 742 3112 810 739 3113 811 740 3114 812 741 3115 814 743 3116 815 744 3117 816 745 3118 813 742 3119 817 746 3120 814 743 3121 818 747 3122 809 738 3123 815 744 3124 813 742 3125 817 746 3126 811 740 3127 814 743 3128 819 748 3129 820 749 3130 816 745 3131 817 746 3132 818 747 3133 821 750 3134 815 744 3135 819 748 3136 816 745 3137 819 748 3138 822 751 3139 820 749 3140 823 752 3141 821 750 3142 824 753 3143 823 752 3144 817 746 3145 821 750 3146 825 754 3147 826 755 3148 822 751 3149 823 752 3150 824 753 3151 827 756 3152 819 748 3153 825 754 3154 822 751 3155 825 754 3156 828 757 3157 826 755 3158 829 758 3159 827 756 3160 830 759 3161 829 758 3162 823 752 3163 827 756 3164 831 760 3165 832 761 3166 828 757 3167 829 758 3168 830 759 3169 833 762 3170 825 754 3171 831 760 3172 828 757 3173 831 760 3174 834 763 3175 832 761 3176 835 764 3177 833 762 3178 836 765 3179 835 764 3180 829 758 3181 833 762 3182 837 766 3183 838 767 3184 834 763 3185 835 764 3186 836 765 3187 839 768 3188 831 760 3189 837 766 3190 834 763 3191 840 769 3192 841 770 3193 838 767 3194 842 771 3195 839 768 3196 843 772 3197 837 766 3198 840 769 3199 838 767 3200 842 771 3201 835 764 3202 839 768 3203 840 769 3204 844 773 3205 841 770 3206 842 771 3207 843 772 3208 845 774 3209 846 775 3210 847 776 3211 844 773 3212 848 777 3213 845 774 3214 849 778 3215 840 769 3216 846 775 3217 844 773 3218 848 777 3219 842 771 3220 845 774 3221 846 775 3222 850 779 3223 847 776 3224 851 780 3225 849 778 3226 852 781 3227 851 780 3228 848 777 3229 849 778 3230 853 782 3231 854 783 3232 850 779 3233 855 784 3234 852 781 3235 856 785 3236 846 775 3237 853 782 3238 850 779 3239 855 784 3240 851 780 3241 852 781 3242 857 786 3243 858 787 3244 854 783 3245 859 788 3246 856 785 3247 860 789 3248 853 782 3249 857 786 3250 854 783 3251 859 788 3252 855 784 3253 856 785 3254 857 786 3255 861 790 3256 858 787 3257 862 791 3258 860 789 3259 863 792 3260 862 791 3261 859 788 3262 860 789 3263 864 793 3264 865 794 3265 861 790 3266 866 795 3267 863 792 3268 867 796 3269 857 786 3270 864 793 3271 861 790 3272 866 795 3273 862 791 3274 863 792 3275 868 797 3276 869 798 3277 870 799 3278 871 800 3279 867 796 3280 872 801 3281 873 802 3282 874 803 3283 869 798 3284 871 800 3285 866 795 3286 867 796 3287 875 804 3288 873 802 3289 869 798 3290 868 797 3291 875 804 3292 869 798 3293 876 805 3294 870 799 3295 877 806 3296 876 805 3297 868 797 3298 870 799 3299 878 807 3300 857 786 3301 853 782 3302 876 805 3303 877 806 3304 879 808 3305 880 809 3306 853 782 3307 846 775 3308 881 810 3309 878 807 3310 853 782 3311 882 811 3312 881 810 3313 853 782 3314 880 809 3315 882 811 3316 853 782 3317 883 812 3318 846 775 3319 840 769 3320 883 812 3321 880 809 3322 846 775 3323 884 813 3324 840 769 3325 837 766 3326 884 813 3327 883 812 3328 840 769 3329 885 814 3330 837 766 3331 831 760 3332 885 814 3333 884 813 3334 837 766 3335 886 815 3336 831 760 3337 825 754 3338 886 815 3339 885 814 3340 831 760 3341 887 816 3342 825 754 3343 819 748 3344 887 816 3345 886 815 3346 825 754 3347 888 817 3348 819 748 3349 815 744 3350 888 817 3351 887 816 3352 819 748 3353 889 818 3354 815 744 3355 809 738 3356 889 818 3357 888 817 3358 815 744 3359 890 819 3360 809 738 3361 803 732 3362 890 819 3363 889 818 3364 809 738 3365 891 820 3366 803 732 3367 800 729 3368 891 820 3369 890 819 3370 803 732 3371 892 821 3372 800 729 3373 794 723 3374 892 821 3375 891 820 3376 800 729 3377 893 822 3378 794 723 3379 784 713 3380 893 822 3381 892 821 3382 794 723 3383 894 823 3384 784 713 3385 778 707 3386 894 823 3387 893 822 3388 784 713 3389 895 824 3390 778 707 3391 770 699 3392 895 824 3393 894 823 3394 778 707 3395 896 825 3396 770 699 3397 763 692 3398 896 825 3399 895 824 3400 770 699 3401 410 339 3402 763 692 3403 134 108 3404 410 339 3405 896 825 3406 763 692 3407 897 826 3408 879 808 3409 898 827 3410 897 826 3411 876 805 3412 879 808 3413 899 828 3414 898 827 3415 900 829 3416 899 828 3417 897 826 3418 898 827 3419 901 830 3420 882 811 3421 880 809 3422 902 831 3423 900 829 3424 903 832 3425 902 831 3426 899 828 3427 900 829 3428 904 833 3429 880 809 3430 883 812 3431 905 834 3432 901 830 3433 880 809 3434 904 833 3435 905 834 3436 880 809 3437 906 835 3438 883 812 3439 884 813 3440 906 835 3441 904 833 3442 883 812 3443 907 836 3444 884 813 3445 885 814 3446 907 836 3447 906 835 3448 884 813 3449 908 837 3450 885 814 3451 886 815 3452 908 837 3453 907 836 3454 885 814 3455 909 838 3456 886 815 3457 887 816 3458 909 838 3459 908 837 3460 886 815 3461 910 839 3462 887 816 3463 888 817 3464 910 839 3465 909 838 3466 887 816 3467 911 840 3468 888 817 3469 889 818 3470 911 840 3471 910 839 3472 888 817 3473 912 841 3474 889 818 3475 890 819 3476 912 841 3477 911 840 3478 889 818 3479 913 842 3480 890 819 3481 891 820 3482 913 842 3483 912 841 3484 890 819 3485 914 843 3486 891 820 3487 892 821 3488 914 843 3489 913 842 3490 891 820 3491 915 844 3492 892 821 3493 893 822 3494 915 844 3495 914 843 3496 892 821 3497 916 845 3498 893 822 3499 894 823 3500 916 845 3501 915 844 3502 893 822 3503 917 846 3504 894 823 3505 895 824 3506 918 847 3507 916 845 3508 894 823 3509 917 846 3510 918 847 3511 894 823 3512 919 848 3513 895 824 3514 896 825 3515 920 849 3516 917 846 3517 895 824 3518 921 850 3519 920 849 3520 895 824 3521 922 851 3522 921 850 3523 895 824 3524 923 852 3525 922 851 3526 895 824 3527 919 848 3528 923 852 3529 895 824 3530 924 853 3531 896 825 3532 410 339 3533 925 854 3534 919 848 3535 896 825 3536 926 855 3537 925 854 3538 896 825 3539 924 853 3540 926 855 3541 896 825 3542 927 856 3543 924 853 3544 410 339 3545 928 857 3546 927 856 3547 410 339 3548 758 687 3549 928 857 3550 410 339 3551 929 858 3552 930 859 3553 931 860 3554 932 861 3555 902 831 3556 903 832 3557 933 862 3558 932 861 3559 903 832 3560 934 863 3561 905 834 3562 904 833 3563 929 858 3564 931 860 3565 935 864 3566 936 865 3567 904 833 3568 906 835 3569 937 866 3570 934 863 3571 904 833 3572 936 865 3573 937 866 3574 904 833 3575 938 867 3576 906 835 3577 907 836 3578 938 867 3579 936 865 3580 906 835 3581 939 868 3582 907 836 3583 908 837 3584 939 868 3585 938 867 3586 907 836 3587 940 869 3588 908 837 3589 909 838 3590 940 869 3591 939 868 3592 908 837 3593 941 870 3594 909 838 3595 910 839 3596 941 870 3597 940 869 3598 909 838 3599 942 871 3600 910 839 3601 911 840 3602 942 871 3603 941 870 3604 910 839 3605 943 872 3606 911 840 3607 912 841 3608 943 872 3609 942 871 3610 911 840 3611 944 873 3612 912 841 3613 913 842 3614 944 873 3615 943 872 3616 912 841 3617 945 874 3618 913 842 3619 914 843 3620 945 874 3621 944 873 3622 913 842 3623 946 875 3624 914 843 3625 915 844 3626 946 875 3627 945 874 3628 914 843 3629 947 876 3630 915 844 3631 916 845 3632 947 876 3633 946 875 3634 915 844 3635 948 877 3636 916 845 3637 918 847 3638 948 877 3639 947 876 3640 916 845 3641 949 878 3642 950 879 3643 951 880 3644 952 881 3645 948 877 3646 918 847 3647 949 878 3648 953 882 3649 950 879 3650 954 883 3651 951 880 3652 955 884 3653 949 878 3654 951 880 3655 954 883 3656 954 883 3657 955 884 3658 956 885 3659 957 886 3660 956 885 3661 958 887 3662 954 883 3663 956 885 3664 957 886 3665 959 888 3666 958 887 3667 960 889 3668 957 886 3669 958 887 3670 959 888 3671 961 890 3672 960 889 3673 962 891 3674 959 888 3675 960 889 3676 961 890 3677 961 890 3678 962 891 3679 963 892 3680 964 893 3681 965 893 3682 966 893 3683 967 894 3684 965 894 3685 964 894 3686 961 890 3687 963 892 3688 968 895 3689 969 896 3690 970 896 3691 971 896 3692 972 896 3693 973 896 3694 970 896 3695 969 896 3696 972 896 3697 970 896 3698 969 896 3699 971 896 3700 974 896 3701 975 897 3702 928 857 3703 758 687 3704 969 896 3705 974 896 3706 976 896 3707 975 897 3708 758 687 3709 753 682 3710 977 898 3711 935 864 3712 978 899 3713 929 858 3714 935 864 3715 977 898 3716 979 900 3717 937 866 3718 936 865 3719 977 898 3720 978 899 3721 980 901 3722 981 902 3723 936 865 3724 938 867 3725 982 903 3726 979 900 3727 936 865 3728 983 904 3729 982 903 3730 936 865 3731 981 902 3732 983 904 3733 936 865 3734 984 905 3735 938 867 3736 939 868 3737 984 905 3738 981 902 3739 938 867 3740 985 906 3741 939 868 3742 940 869 3743 985 906 3744 984 905 3745 939 868 3746 986 907 3747 940 869 3748 941 870 3749 986 907 3750 985 906 3751 940 869 3752 987 908 3753 941 870 3754 942 871 3755 988 909 3756 986 907 3757 941 870 3758 989 910 3759 988 909 3760 941 870 3761 987 908 3762 989 910 3763 941 870 3764 990 911 3765 942 871 3766 943 872 3767 991 912 3768 987 908 3769 942 871 3770 992 913 3771 991 912 3772 942 871 3773 990 911 3774 992 913 3775 942 871 3776 993 914 3777 943 872 3778 944 873 3779 994 915 3780 990 911 3781 943 872 3782 995 916 3783 994 915 3784 943 872 3785 996 917 3786 995 916 3787 943 872 3788 997 918 3789 996 917 3790 943 872 3791 998 919 3792 997 918 3793 943 872 3794 993 914 3795 998 919 3796 943 872 3797 999 920 3798 944 873 3799 945 874 3800 999 920 3801 993 914 3802 944 873 3803 1000 921 3804 945 874 3805 946 875 3806 1000 921 3807 999 920 3808 945 874 3809 1001 922 3810 946 875 3811 947 876 3812 1001 922 3813 1000 921 3814 946 875 3815 1002 923 3816 947 876 3817 948 877 3818 1002 923 3819 1001 922 3820 947 876 3821 1003 924 3822 1004 925 3823 948 877 3824 1005 926 3825 948 877 3826 1004 925 3827 1006 927 3828 1003 924 3829 948 877 3830 1007 928 3831 1006 927 3832 948 877 3833 1008 929 3834 1007 928 3835 948 877 3836 952 881 3837 1008 929 3838 948 877 3839 1005 926 3840 1002 923 3841 948 877 3842 1009 930 3843 1010 931 3844 1004 925 3845 1011 932 3846 1004 925 3847 1010 931 3848 1012 933 3849 1009 930 3850 1004 925 3851 1013 934 3852 1012 933 3853 1004 925 3854 1003 924 3855 1013 934 3856 1004 925 3857 1011 932 3858 1005 926 3859 1004 925 3860 975 897 3861 753 682 3862 1010 931 3863 729 658 3864 1010 931 3865 753 682 3866 1014 935 3867 975 897 3868 1010 931 3869 1009 930 3870 1014 935 3871 1010 931 3872 729 658 3873 1011 932 3874 1010 931 3875 1015 936 3876 1016 936 3877 1017 936 3878 1015 937 3879 1017 937 3880 1018 937 3881 1019 938 3882 1020 939 3883 1021 940 3884 1022 941 3885 1021 940 3886 1023 942 3887 1019 938 3888 1021 940 3889 1022 941 3890 1022 941 3891 1023 942 3892 1024 943 3893 1025 944 3894 1024 943 3895 1026 945 3896 1022 941 3897 1024 943 3898 1025 944 3899 1027 946 3900 1026 945 3901 1028 947 3902 1025 944 3903 1026 945 3904 1027 946 3905 1027 946 3906 1028 947 3907 1029 948 3908 949 878 3909 1029 948 3910 953 882 3911 1027 946 3912 1029 948 3913 949 878 3914 1030 949 3915 980 901 3916 1031 950 3917 977 898 3918 980 901 3919 1030 949 3920 1030 949 3921 1031 950 3922 1032 951 3923 1033 952 3924 983 904 3925 981 902 3926 1034 953 3927 1032 951 3928 1035 954 3929 1030 949 3930 1032 951 3931 1034 953 3932 1036 955 3933 981 902 3934 984 905 3935 1037 956 3936 1033 952 3937 981 902 3938 1036 955 3939 1037 956 3940 981 902 3941 1038 957 3942 984 905 3943 985 906 3944 1038 957 3945 1036 955 3946 984 905 3947 1039 958 3948 985 906 3949 986 907 3950 1039 958 3951 1038 957 3952 985 906 3953 1040 959 3954 986 907 3955 988 909 3956 1040 959 3957 1039 958 3958 986 907 3959 1041 960 3960 1042 961 3961 1043 962 3962 1044 963 3963 1040 959 3964 988 909 3965 1041 960 3966 1045 964 3967 1042 961 3968 1046 965 3969 1043 962 3970 1047 966 3971 1046 965 3972 1041 960 3973 1043 962 3974 1048 967 3975 1047 966 3976 1049 968 3977 1048 967 3978 1046 965 3979 1047 966 3980 1050 969 3981 1049 968 3982 1051 970 3983 1050 969 3984 1048 967 3985 1049 968 3986 1052 971 3987 1051 970 3988 1053 972 3989 1052 971 3990 1050 969 3991 1051 970 3992 1054 973 3993 1053 972 3994 1055 974 3995 1054 973 3996 1052 971 3997 1053 972 3998 1056 975 3999 1055 974 4000 1057 976 4001 1056 975 4002 1054 973 4003 1055 974 4004 1058 977 4005 1057 976 4006 1059 978 4007 1058 977 4008 1056 975 4009 1057 976 4010 1060 979 4011 1059 978 4012 1061 980 4013 1060 979 4014 1058 977 4015 1059 978 4016 1060 979 4017 1061 980 4018 1062 981 4019 1063 982 4020 998 919 4021 993 914 4022 1064 983 4023 1062 981 4024 1065 984 4025 1064 983 4026 1060 979 4027 1062 981 4028 1066 985 4029 993 914 4030 999 920 4031 1067 986 4032 993 914 4033 1066 985 4034 1068 987 4035 993 914 4036 1067 986 4037 1068 987 4038 1063 982 4039 993 914 4040 1069 988 4041 999 920 4042 1000 921 4043 1066 985 4044 999 920 4045 1069 988 4046 1070 989 4047 1000 921 4048 1001 922 4049 1069 988 4050 1000 921 4051 1070 989 4052 1071 990 4053 1001 922 4054 1002 923 4055 1070 989 4056 1001 922 4057 1071 990 4058 1072 991 4059 1002 923 4060 1005 926 4061 1071 990 4062 1002 923 4063 1072 991 4064 1073 992 4065 1005 926 4066 1011 932 4067 1072 991 4068 1005 926 4069 1073 992 4070 1074 993 4071 1011 932 4072 729 658 4073 1073 992 4074 1011 932 4075 1074 993 4076 1074 993 4077 729 658 4078 707 636 4079 1034 953 4080 1035 954 4081 1075 994 4082 1076 995 4083 1037 956 4084 1036 955 4085 1077 996 4086 1075 994 4087 1078 997 4088 1034 953 4089 1075 994 4090 1077 996 4091 1079 998 4092 1036 955 4093 1038 957 4094 1080 999 4095 1076 995 4096 1036 955 4097 1079 998 4098 1080 999 4099 1036 955 4100 1081 1000 4101 1038 957 4102 1039 958 4103 1081 1000 4104 1079 998 4105 1038 957 4106 1082 1001 4107 1039 958 4108 1040 959 4109 1082 1001 4110 1081 1000 4111 1039 958 4112 1083 1002 4113 1084 1003 4114 1040 959 4115 1085 1004 4116 1040 959 4117 1084 1003 4118 1086 1005 4119 1083 1002 4120 1040 959 4121 1087 1006 4122 1086 1005 4123 1040 959 4124 1088 1007 4125 1087 1006 4126 1040 959 4127 1044 963 4128 1088 1007 4129 1040 959 4130 1085 1004 4131 1082 1001 4132 1040 959 4133 1089 1008 4134 1090 1009 4135 1091 1010 4136 1092 1011 4137 1085 1004 4138 1084 1003 4139 1093 1012 4140 1094 1013 4141 1090 1009 4142 1089 1008 4143 1093 1012 4144 1090 1009 4145 1095 1014 4146 1091 1010 4147 1096 1015 4148 1095 1014 4149 1089 1008 4150 1091 1010 4151 1097 1016 4152 1096 1015 4153 1098 1017 4154 1097 1016 4155 1095 1014 4156 1096 1015 4157 1097 1016 4158 1098 1017 4159 1099 1018 4160 1100 1019 4161 1101 1020 4162 1045 964 4163 1102 1021 4164 1097 1016 4165 1099 1018 4166 1041 960 4167 1100 1019 4168 1045 964 4169 1077 996 4170 1078 997 4171 1103 1022 4172 1104 1023 4173 1080 999 4174 1079 998 4175 1105 1024 4176 1103 1022 4177 1106 1025 4178 1077 996 4179 1103 1022 4180 1105 1024 4181 1107 1026 4182 1079 998 4183 1081 1000 4184 1108 1027 4185 1104 1023 4186 1079 998 4187 1107 1026 4188 1108 1027 4189 1079 998 4190 1109 1028 4191 1081 1000 4192 1082 1001 4193 1109 1028 4194 1107 1026 4195 1081 1000 4196 1110 1029 4197 1082 1001 4198 1085 1004 4199 1110 1029 4200 1109 1028 4201 1082 1001 4202 1092 1011 4203 1111 1030 4204 1085 1004 4205 1112 1031 4206 1085 1004 4207 1111 1030 4208 1112 1031 4209 1110 1029 4210 1085 1004 4211 1113 1032 4212 1114 1033 4213 1111 1030 4214 1115 1034 4215 1111 1030 4216 1114 1033 4217 1116 1035 4218 1113 1032 4219 1111 1030 4220 1117 1036 4221 1116 1035 4222 1111 1030 4223 1118 1037 4224 1117 1036 4225 1111 1030 4226 1119 1038 4227 1118 1037 4228 1111 1030 4229 1092 1011 4230 1119 1038 4231 1111 1030 4232 1115 1034 4233 1112 1031 4234 1111 1030 4235 1067 986 4236 1120 1039 4237 1114 1033 4238 1121 1040 4239 1114 1033 4240 1120 1039 4241 1113 1032 4242 1067 986 4243 1114 1033 4244 1121 1040 4245 1115 1034 4246 1114 1033 4247 1066 985 4248 1122 1041 4249 1120 1039 4250 1123 1042 4251 1120 1039 4252 1122 1041 4253 1067 986 4254 1066 985 4255 1120 1039 4256 1123 1042 4257 1121 1040 4258 1120 1039 4259 1069 988 4260 1124 1043 4261 1122 1041 4262 1125 1044 4263 1122 1041 4264 1124 1043 4265 1066 985 4266 1069 988 4267 1122 1041 4268 1125 1044 4269 1123 1042 4270 1122 1041 4271 1070 989 4272 1126 1045 4273 1124 1043 4274 1127 1046 4275 1124 1043 4276 1126 1045 4277 1069 988 4278 1070 989 4279 1124 1043 4280 1127 1046 4281 1125 1044 4282 1124 1043 4283 1071 990 4284 1128 1047 4285 1126 1045 4286 1129 1048 4287 1126 1045 4288 1128 1047 4289 1070 989 4290 1071 990 4291 1126 1045 4292 1129 1048 4293 1127 1046 4294 1126 1045 4295 1072 991 4296 1130 1049 4297 1128 1047 4298 1131 1050 4299 1128 1047 4300 1130 1049 4301 1071 990 4302 1072 991 4303 1128 1047 4304 1131 1050 4305 1129 1048 4306 1128 1047 4307 1132 1051 4308 1133 1052 4309 1130 1049 4310 1134 1053 4311 1130 1049 4312 1133 1052 4313 1135 1054 4314 1132 1051 4315 1130 1049 4316 1136 1055 4317 1135 1054 4318 1130 1049 4319 1137 1056 4320 1136 1055 4321 1130 1049 4322 1138 1057 4323 1137 1056 4324 1130 1049 4325 1139 1058 4326 1138 1057 4327 1130 1049 4328 1140 1059 4329 1139 1058 4330 1130 1049 4331 1141 1060 4332 1140 1059 4333 1130 1049 4334 1142 1061 4335 1141 1060 4336 1130 1049 4337 1072 991 4338 1142 1061 4339 1130 1049 4340 1134 1053 4341 1131 1050 4342 1130 1049 4343 1143 1062 4344 1144 1063 4345 1133 1052 4346 1145 1064 4347 1133 1052 4348 1144 1063 4349 1132 1051 4350 1143 1062 4351 1133 1052 4352 1145 1064 4353 1134 1053 4354 1133 1052 4355 1146 1065 4356 1147 1065 4357 1148 1065 4358 1149 1066 4359 1145 1064 4360 1144 1063 4361 1146 1067 4362 1150 1067 4363 1147 1067 4364 1146 1068 4365 1148 1068 4366 1151 1068 4367 1152 1069 4368 1153 1070 4369 1154 1071 4370 1155 1072 4371 1154 1071 4372 1156 1073 4373 1152 1069 4374 1154 1071 4375 1155 1072 4376 1157 1074 4377 1156 1073 4378 1158 1075 4379 1155 1072 4380 1156 1073 4381 1157 1074 4382 1157 1074 4383 1158 1075 4384 1159 1076 4385 1160 1077 4386 1159 1076 4387 1161 1078 4388 1157 1074 4389 1159 1076 4390 1160 1077 4391 1162 1079 4392 1161 1078 4393 1163 1080 4394 1160 1077 4395 1161 1078 4396 1162 1079 4397 1162 1079 4398 1163 1080 4399 1164 1081 4400 1165 1082 4401 1164 1081 4402 1166 1083 4403 1162 1079 4404 1164 1081 4405 1165 1082 4406 1073 992 4407 1167 1084 4408 1142 1061 4409 1165 1082 4410 1166 1083 4411 1168 1085 4412 1072 991 4413 1073 992 4414 1142 1061 4415 1073 992 4416 1169 1086 4417 1167 1084 4418 1170 1087 4419 1168 1085 4420 1171 1088 4421 1165 1082 4422 1168 1085 4423 1170 1087 4424 1073 992 4425 1172 1089 4426 1169 1086 4427 1170 1087 4428 1171 1088 4429 1173 1090 4430 1073 992 4431 1174 1091 4432 1172 1089 4433 1175 1092 4434 1173 1090 4435 1176 1093 4436 1170 1087 4437 1173 1090 4438 1175 1092 4439 1073 992 4440 1177 1094 4441 1174 1091 4442 1178 1095 4443 1176 1093 4444 1179 1096 4445 1175 1092 4446 1176 1093 4447 1178 1095 4448 1074 993 4449 1180 1097 4450 1177 1094 4451 1178 1095 4452 1179 1096 4453 1181 1098 4454 1073 992 4455 1074 993 4456 1177 1094 4457 1182 1099 4458 1183 1099 4459 1184 1099 4460 1074 993 4461 1185 1100 4462 1180 1097 4463 1186 1101 4464 1183 1101 4465 1182 1101 4466 1178 1095 4467 1181 1098 4468 1187 1102 4469 1074 993 4470 1188 1103 4471 1185 1100 4472 1189 896 4473 1190 896 4474 1191 896 4475 707 636 4476 1192 1104 4477 1188 1103 4478 1193 896 4479 1190 896 4480 1189 896 4481 1074 993 4482 707 636 4483 1188 1103 4484 1194 896 4485 1190 896 4486 1193 896 4487 707 636 4488 1195 1105 4489 1192 1104 4490 707 636 4491 670 599 4492 1195 1105 4493 651 580 4494 1195 1105 4495 670 599 4496 1149 1066 4497 1195 1105 4498 651 580 4499 1196 1106 4500 1067 986 4501 1113 1032 4502 1197 1107 4503 1068 987 4504 1067 986 4505 1198 1108 4506 1197 1107 4507 1067 986 4508 1196 1106 4509 1198 1108 4510 1067 986 4511 1199 1109 4512 1200 1110 4513 1201 1111 4514 1199 1109 4515 1202 1112 4516 1200 1110 4517 1203 1113 4518 1201 1111 4519 1204 1114 4520 1203 1113 4521 1199 1109 4522 1201 1111 4523 1205 1115 4524 1204 1114 4525 1206 1116 4526 1205 1115 4527 1203 1113 4528 1204 1114 4529 1207 1117 4530 1206 1116 4531 1208 1118 4532 1207 1117 4533 1205 1115 4534 1206 1116 4535 1093 1012 4536 1208 1118 4537 1094 1013 4538 1093 1012 4539 1207 1117 4540 1208 1118 4541 1209 1119 4542 1106 1025 4543 1210 1120 4544 1105 1024 4545 1106 1025 4546 1209 1119 4547 1211 1121 4548 1108 1027 4549 1107 1026 4550 1212 1122 4551 1210 1120 4552 1213 1123 4553 1209 1119 4554 1210 1120 4555 1212 1122 4556 1214 1124 4557 1107 1026 4558 1109 1028 4559 1215 1125 4560 1211 1121 4561 1107 1026 4562 1214 1124 4563 1215 1125 4564 1107 1026 4565 1216 1126 4566 1109 1028 4567 1110 1029 4568 1216 1126 4569 1214 1124 4570 1109 1028 4571 1217 1127 4572 1110 1029 4573 1112 1031 4574 1217 1127 4575 1216 1126 4576 1110 1029 4577 1218 1128 4578 1112 1031 4579 1115 1034 4580 1218 1128 4581 1217 1127 4582 1112 1031 4583 1219 1129 4584 1115 1034 4585 1121 1040 4586 1219 1129 4587 1218 1128 4588 1115 1034 4589 1220 1130 4590 1121 1040 4591 1123 1042 4592 1220 1130 4593 1219 1129 4594 1121 1040 4595 1221 1131 4596 1123 1042 4597 1125 1044 4598 1221 1131 4599 1220 1130 4600 1123 1042 4601 1222 1132 4602 1125 1044 4603 1127 1046 4604 1222 1132 4605 1221 1131 4606 1125 1044 4607 1223 1133 4608 1127 1046 4609 1129 1048 4610 1223 1133 4611 1222 1132 4612 1127 1046 4613 1224 1134 4614 1129 1048 4615 1131 1050 4616 1224 1134 4617 1223 1133 4618 1129 1048 4619 1225 1135 4620 1131 1050 4621 1134 1053 4622 1225 1135 4623 1224 1134 4624 1131 1050 4625 1226 1136 4626 1134 1053 4627 1145 1064 4628 1226 1136 4629 1225 1135 4630 1134 1053 4631 1149 1066 4632 651 580 4633 1145 1064 4634 1227 1137 4635 1145 1064 4636 651 580 4637 1227 1137 4638 1226 1136 4639 1145 1064 4640 632 561 4641 1227 1137 4642 651 580 4643 1228 896 4644 1194 896 4645 1193 896 4646 1229 1138 4647 1213 1123 4648 1230 1139 4649 1212 1122 4650 1213 1123 4651 1229 1138 4652 1231 1140 4653 1215 1125 4654 1214 1124 4655 1232 1141 4656 1230 1139 4657 1233 1142 4658 1229 1138 4659 1230 1139 4660 1232 1141 4661 1234 1143 4662 1214 1124 4663 1216 1126 4664 1235 1144 4665 1231 1140 4666 1214 1124 4667 1234 1143 4668 1235 1144 4669 1214 1124 4670 1236 1145 4671 1216 1126 4672 1217 1127 4673 1236 1145 4674 1234 1143 4675 1216 1126 4676 1237 1146 4677 1217 1127 4678 1218 1128 4679 1237 1146 4680 1236 1145 4681 1217 1127 4682 1238 1147 4683 1218 1128 4684 1219 1129 4685 1238 1147 4686 1237 1146 4687 1218 1128 4688 1239 1148 4689 1219 1129 4690 1220 1130 4691 1239 1148 4692 1238 1147 4693 1219 1129 4694 1240 1149 4695 1220 1130 4696 1221 1131 4697 1240 1149 4698 1239 1148 4699 1220 1130 4700 1241 1150 4701 1221 1131 4702 1222 1132 4703 1241 1150 4704 1240 1149 4705 1221 1131 4706 1242 1151 4707 1222 1132 4708 1223 1133 4709 1242 1151 4710 1241 1150 4711 1222 1132 4712 1243 1152 4713 1223 1133 4714 1224 1134 4715 1243 1152 4716 1242 1151 4717 1223 1133 4718 1244 1153 4719 1224 1134 4720 1225 1135 4721 1244 1153 4722 1243 1152 4723 1224 1134 4724 1245 1154 4725 1225 1135 4726 1226 1136 4727 1246 1155 4728 1244 1153 4729 1225 1135 4730 1247 1156 4731 1246 1155 4732 1225 1135 4733 1248 1157 4734 1247 1156 4735 1225 1135 4736 1245 1154 4737 1248 1157 4738 1225 1135 4739 1249 1158 4740 1226 1136 4741 1227 1137 4742 1250 1159 4743 1245 1154 4744 1226 1136 4745 1251 1160 4746 1250 1159 4747 1226 1136 4748 1252 1161 4749 1251 1160 4750 1226 1136 4751 1253 1162 4752 1252 1161 4753 1226 1136 4754 1254 1163 4755 1253 1162 4756 1226 1136 4757 1249 1158 4758 1254 1163 4759 1226 1136 4760 1255 1164 4761 1227 1137 4762 632 561 4763 1255 1164 4764 1249 1158 4765 1227 1137 4766 1256 1165 4767 1255 1164 4768 632 561 4769 614 543 4770 1256 1165 4771 632 561 4772 1257 1166 4773 1233 1142 4774 1258 1167 4775 1232 1141 4776 1233 1142 4777 1257 1166 4778 1259 1168 4779 1235 1144 4780 1234 1143 4781 1260 1169 4782 1258 1167 4783 1261 1170 4784 1257 1166 4785 1258 1167 4786 1260 1169 4787 1262 1171 4788 1234 1143 4789 1236 1145 4790 1263 1172 4791 1259 1168 4792 1234 1143 4793 1262 1171 4794 1263 1172 4795 1234 1143 4796 1264 1173 4797 1236 1145 4798 1237 1146 4799 1264 1173 4800 1262 1171 4801 1236 1145 4802 1265 1174 4803 1237 1146 4804 1238 1147 4805 1265 1174 4806 1264 1173 4807 1237 1146 4808 1266 1175 4809 1238 1147 4810 1239 1148 4811 1266 1175 4812 1265 1174 4813 1238 1147 4814 1267 1176 4815 1239 1148 4816 1240 1149 4817 1267 1176 4818 1266 1175 4819 1239 1148 4820 1268 1177 4821 1240 1149 4822 1241 1150 4823 1268 1177 4824 1267 1176 4825 1240 1149 4826 1269 1178 4827 1241 1150 4828 1242 1151 4829 1269 1178 4830 1268 1177 4831 1241 1150 4832 1270 1179 4833 1242 1151 4834 1243 1152 4835 1270 1179 4836 1269 1178 4837 1242 1151 4838 1271 1180 4839 1243 1152 4840 1244 1153 4841 1271 1180 4842 1270 1179 4843 1243 1152 4844 1272 1181 4845 1273 1182 4846 1244 1153 4847 1274 1183 4848 1244 1153 4849 1273 1182 4850 1275 1184 4851 1272 1181 4852 1244 1153 4853 1246 1155 4854 1275 1184 4855 1244 1153 4856 1274 1183 4857 1271 1180 4858 1244 1153 4859 1276 1185 4860 1277 1186 4861 1278 1187 4862 1279 1188 4863 1274 1183 4864 1273 1182 4865 1280 1189 4866 1281 1190 4867 1277 1186 4868 1280 1189 4869 1277 1186 4870 1276 1185 4871 1276 1185 4872 1278 1187 4873 1282 1191 4874 1283 1192 4875 1282 1191 4876 1284 1193 4877 1276 1185 4878 1282 1191 4879 1283 1192 4880 1283 1192 4881 1284 1193 4882 1285 1194 4883 1286 1195 4884 1285 1194 4885 1287 1196 4886 1283 1192 4887 1285 1194 4888 1286 1195 4889 1286 1195 4890 1287 1196 4891 1288 1197 4892 1289 1198 4893 1288 1197 4894 1290 1199 4895 1286 1195 4896 1288 1197 4897 1289 1198 4898 1291 1200 4899 1290 1199 4900 1292 1201 4901 1289 1198 4902 1290 1199 4903 1291 1200 4904 1291 1200 4905 1292 1201 4906 1293 1202 4907 1294 1203 4908 1293 1202 4909 1295 1204 4910 1291 1200 4911 1293 1202 4912 1294 1203 4913 1294 1203 4914 1295 1204 4915 1296 1205 4916 1297 1206 4917 1298 1206 4918 1299 1206 4919 1300 1207 4920 1298 1207 4921 1297 1207 4922 1294 1203 4923 1296 1205 4924 1301 1208 4925 1302 896 4926 1303 896 4927 1304 896 4928 595 524 4929 1256 1165 4930 614 543 4931 1305 1209 4932 1256 1165 4933 595 524 4934 1302 896 4935 1304 896 4936 1306 896 4937 1263 1172 4938 1307 1210 4939 1259 1168 4940 1308 1211 4941 1261 1170 4942 1309 1212 4943 1260 1169 4944 1261 1170 4945 1308 1211 4946 1310 1213 4947 1307 1210 4948 1263 1172 4949 1310 1213 4950 1311 1214 4951 1307 1210 4952 1312 1215 4953 1309 1212 4954 1313 1216 4955 1308 1211 4956 1309 1212 4957 1312 1215 4958 1314 1217 4959 1263 1172 4960 1262 1171 4961 1314 1217 4962 1310 1213 4963 1263 1172 4964 1315 1218 4965 1262 1171 4966 1264 1173 4967 1315 1218 4968 1314 1217 4969 1262 1171 4970 1316 1219 4971 1264 1173 4972 1265 1174 4973 1316 1219 4974 1315 1218 4975 1264 1173 4976 1317 1220 4977 1265 1174 4978 1266 1175 4979 1317 1220 4980 1316 1219 4981 1265 1174 4982 1318 1221 4983 1266 1175 4984 1267 1176 4985 1318 1221 4986 1317 1220 4987 1266 1175 4988 1319 1222 4989 1267 1176 4990 1268 1177 4991 1319 1222 4992 1318 1221 4993 1267 1176 4994 1320 1223 4995 1268 1177 4996 1269 1178 4997 1320 1223 4998 1319 1222 4999 1268 1177 5000 1321 1224 5001 1269 1178 5002 1270 1179 5003 1321 1224 5004 1320 1223 5005 1269 1178 5006 1322 1225 5007 1270 1179 5008 1271 1180 5009 1322 1225 5010 1321 1224 5011 1270 1179 5012 1323 1226 5013 1271 1180 5014 1274 1183 5015 1323 1226 5016 1322 1225 5017 1271 1180 5018 1324 1227 5019 1325 1228 5020 1274 1183 5021 1326 1229 5022 1274 1183 5023 1325 1228 5024 1327 1230 5025 1324 1227 5026 1274 1183 5027 1328 1231 5028 1327 1230 5029 1274 1183 5030 1279 1188 5031 1328 1231 5032 1274 1183 5033 1326 1229 5034 1323 1226 5035 1274 1183 5036 1329 1232 5037 1330 1233 5038 1325 1228 5039 1331 1234 5040 1325 1228 5041 1330 1233 5042 1324 1227 5043 1329 1232 5044 1325 1228 5045 1331 1234 5046 1326 1229 5047 1325 1228 5048 1332 1235 5049 595 524 5050 1330 1233 5051 576 505 5052 1330 1233 5053 595 524 5054 1329 1232 5055 1332 1235 5056 1330 1233 5057 576 505 5058 1331 1234 5059 1330 1233 5060 1332 1235 5061 1305 1209 5062 595 524 5063 1302 896 5064 1306 896 5065 1333 896 5066 1334 1236 5067 1335 1236 5068 1336 1236 5069 1337 896 5070 1302 896 5071 1333 896 5072 1338 896 5073 1337 896 5074 1333 896 5075 1339 896 5076 1338 896 5077 1333 896 5078 1334 1237 5079 1336 1237 5080 1340 1237 5081 1341 1238 5082 1342 1239 5083 1343 1240 5084 1344 1241 5085 1343 1240 5086 1345 1242 5087 1341 1238 5088 1343 1240 5089 1344 1241 5090 1280 1189 5091 1345 1242 5092 1281 1190 5093 1344 1241 5094 1345 1242 5095 1280 1189 5096 1310 1213 5097 1346 1243 5098 1311 1214 5099 1347 1244 5100 1313 1216 5101 1348 1245 5102 1312 1215 5103 1313 1216 5104 1347 1244 5105 1349 1246 5106 1346 1243 5107 1310 1213 5108 1349 1246 5109 1350 1247 5110 1346 1243 5111 1347 1244 5112 1348 1245 5113 1351 1248 5114 1352 1249 5115 1310 1213 5116 1314 1217 5117 1352 1249 5118 1349 1246 5119 1310 1213 5120 1353 1250 5121 1314 1217 5122 1315 1218 5123 1353 1250 5124 1352 1249 5125 1314 1217 5126 1354 1251 5127 1315 1218 5128 1316 1219 5129 1354 1251 5130 1353 1250 5131 1315 1218 5132 1355 1252 5133 1316 1219 5134 1317 1220 5135 1355 1252 5136 1354 1251 5137 1316 1219 5138 1356 1253 5139 1317 1220 5140 1318 1221 5141 1356 1253 5142 1355 1252 5143 1317 1220 5144 1357 1254 5145 1318 1221 5146 1319 1222 5147 1357 1254 5148 1356 1253 5149 1318 1221 5150 1358 1255 5151 1319 1222 5152 1320 1223 5153 1358 1255 5154 1357 1254 5155 1319 1222 5156 1359 1256 5157 1320 1223 5158 1321 1224 5159 1359 1256 5160 1358 1255 5161 1320 1223 5162 1360 1257 5163 1321 1224 5164 1322 1225 5165 1361 1258 5166 1359 1256 5167 1321 1224 5168 1362 1259 5169 1361 1258 5170 1321 1224 5171 1363 1260 5172 1362 1259 5173 1321 1224 5174 1360 1257 5175 1363 1260 5176 1321 1224 5177 1364 1261 5178 1322 1225 5179 1323 1226 5180 1365 1262 5181 1360 1257 5182 1322 1225 5183 1366 1263 5184 1365 1262 5185 1322 1225 5186 1367 1264 5187 1366 1263 5188 1322 1225 5189 1368 1265 5190 1367 1264 5191 1322 1225 5192 1369 1266 5193 1368 1265 5194 1322 1225 5195 1364 1261 5196 1369 1266 5197 1322 1225 5198 1370 1267 5199 1323 1226 5200 1326 1229 5201 1370 1267 5202 1364 1261 5203 1323 1226 5204 1371 1268 5205 1326 1229 5206 1331 1234 5207 1372 1269 5208 1370 1267 5209 1326 1229 5210 1371 1268 5211 1372 1269 5212 1326 1229 5213 1373 1270 5214 1331 1234 5215 576 505 5216 1373 1270 5217 1371 1268 5218 1331 1234 5219 557 486 5220 1373 1270 5221 576 505 5222 1349 1246 5223 1374 1271 5224 1350 1247 5225 1375 1272 5226 1351 1248 5227 1376 1273 5228 1347 1244 5229 1351 1248 5230 1375 1272 5231 1377 1274 5232 1374 1271 5233 1349 1246 5234 1377 1274 5235 1378 1275 5236 1374 1271 5237 1379 1276 5238 1376 1273 5239 1380 1277 5240 1381 1278 5241 1375 1272 5242 1376 1273 5243 1382 1279 5244 1381 1278 5245 1376 1273 5246 1383 1280 5247 1382 1279 5248 1376 1273 5249 1384 1281 5250 1383 1280 5251 1376 1273 5252 1379 1276 5253 1384 1281 5254 1376 1273 5255 1385 1282 5256 1349 1246 5257 1352 1249 5258 1385 1282 5259 1377 1274 5260 1349 1246 5261 1386 1283 5262 1352 1249 5263 1353 1250 5264 1387 1284 5265 1385 1282 5266 1352 1249 5267 1386 1283 5268 1387 1284 5269 1352 1249 5270 1388 1285 5271 1353 1250 5272 1354 1251 5273 1389 896 5274 1390 896 5275 1391 896 5276 1392 1286 5277 1386 1283 5278 1353 1250 5279 1388 1285 5280 1392 1286 5281 1353 1250 5282 1393 1287 5283 1354 1251 5284 1355 1252 5285 1394 1288 5286 1388 1285 5287 1354 1251 5288 1395 1289 5289 1394 1288 5290 1354 1251 5291 1396 1290 5292 1395 1289 5293 1354 1251 5294 1397 1291 5295 1396 1290 5296 1354 1251 5297 1398 1292 5298 1397 1291 5299 1354 1251 5300 1399 1293 5301 1398 1292 5302 1354 1251 5303 1400 896 5304 1401 896 5305 1389 896 5306 1393 1287 5307 1399 1293 5308 1354 1251 5309 1402 1294 5310 1355 1252 5311 1356 1253 5312 1402 1294 5313 1393 1287 5314 1355 1252 5315 1403 1295 5316 1356 1253 5317 1357 1254 5318 1403 1295 5319 1402 1294 5320 1356 1253 5321 1404 1296 5322 1357 1254 5323 1358 1255 5324 1404 1296 5325 1403 1295 5326 1357 1254 5327 1405 1297 5328 1358 1255 5329 1359 1256 5330 1405 1297 5331 1404 1296 5332 1358 1255 5333 1406 1298 5334 1407 1299 5335 1359 1256 5336 1408 1300 5337 1359 1256 5338 1407 1299 5339 1409 1301 5340 1406 1298 5341 1359 1256 5342 1410 1302 5343 1409 1301 5344 1359 1256 5345 1411 1303 5346 1410 1302 5347 1359 1256 5348 1412 1304 5349 1411 1303 5350 1359 1256 5351 1361 1258 5352 1412 1304 5353 1359 1256 5354 1408 1300 5355 1405 1297 5356 1359 1256 5357 1413 1305 5358 1414 1305 5359 1415 1305 5360 1416 1306 5361 1408 1300 5362 1407 1299 5363 1417 1307 5364 1416 1306 5365 1407 1299 5366 1413 1308 5367 1418 1308 5368 1414 1308 5369 1419 1309 5370 1420 1310 5371 1421 1311 5372 1422 1312 5373 1421 1311 5374 1423 1313 5375 1424 1314 5376 1419 1309 5377 1421 1311 5378 1422 1312 5379 1424 1314 5380 1421 1311 5381 1422 1312 5382 1423 1313 5383 1425 1315 5384 1426 1316 5385 1425 1315 5386 1427 1317 5387 1426 1316 5388 1422 1312 5389 1425 1315 5390 1426 1316 5391 1427 1317 5392 1428 1318 5393 1429 1319 5394 1428 1318 5395 1430 1320 5396 1429 1319 5397 1426 1316 5398 1428 1318 5399 1429 1319 5400 1430 1320 5401 1431 1321 5402 1432 1322 5403 1431 1321 5404 1433 1323 5405 1432 1322 5406 1429 1319 5407 1431 1321 5408 1432 1322 5409 1433 1323 5410 1434 1324 5411 1435 1325 5412 1434 1324 5413 1436 1326 5414 1435 1325 5415 1432 1322 5416 1434 1324 5417 1437 1327 5418 1436 1326 5419 1438 1328 5420 1437 1327 5421 1435 1325 5422 1436 1326 5423 1437 1327 5424 1438 1328 5425 1439 1329 5426 1440 1330 5427 1439 1329 5428 1441 1331 5429 1440 1330 5430 1437 1327 5431 1439 1329 5432 1440 1330 5433 1441 1331 5434 1442 1332 5435 1443 1333 5436 1444 1333 5437 1445 1333 5438 1446 1334 5439 1444 1334 5440 1443 1334 5441 1447 1335 5442 1444 1335 5443 1446 1335 5444 1448 1336 5445 1444 1336 5446 1447 1336 5447 1449 1337 5448 1440 1330 5449 1442 1332 5450 1450 1338 5451 1371 1268 5452 1373 1270 5453 537 466 5454 1373 1270 5455 557 486 5456 537 466 5457 1451 1339 5458 1373 1270 5459 1450 1338 5460 1373 1270 5461 1451 1339 5462 1377 1274 5463 1452 1340 5464 1378 1275 5465 1453 1341 5466 1380 1277 5467 1454 1342 5468 1453 1341 5469 1379 1276 5470 1380 1277 5471 1377 1274 5472 1455 1343 5473 1452 1340 5474 1456 1344 5475 1454 1342 5476 1457 1345 5477 1458 1346 5478 1453 1341 5479 1454 1342 5480 1456 1344 5481 1458 1346 5482 1454 1342 5483 1459 1347 5484 1455 1343 5485 1377 1274 5486 1460 1348 5487 1461 1349 5488 1455 1343 5489 1456 1344 5490 1457 1345 5491 1462 1350 5492 1459 1347 5493 1460 1348 5494 1455 1343 5495 1463 1351 5496 1377 1274 5497 1385 1282 5498 1463 1351 5499 1459 1347 5500 1377 1274 5501 1464 1352 5502 1385 1282 5503 1387 1284 5504 1464 1352 5505 1463 1351 5506 1385 1282 5507 1465 1353 5508 1387 1284 5509 1386 1283 5510 1466 1354 5511 1464 1352 5512 1387 1284 5513 1467 1355 5514 1466 1354 5515 1387 1284 5516 1468 1356 5517 1467 1355 5518 1387 1284 5519 1465 1353 5520 1468 1356 5521 1387 1284 5522 1391 896 5523 1390 896 5524 1469 896 5525 1470 1357 5526 1471 1358 5527 1472 1359 5528 1473 1360 5529 1472 1359 5530 1474 1361 5531 1473 1360 5532 1470 1357 5533 1472 1359 5534 1473 1360 5535 1474 1361 5536 1475 1362 5537 1476 1363 5538 1475 1362 5539 1477 1364 5540 1476 1363 5541 1473 1360 5542 1475 1362 5543 1476 1363 5544 1477 1364 5545 1478 1365 5546 1479 1366 5547 1478 1365 5548 1480 1367 5549 1479 1366 5550 1476 1363 5551 1478 1365 5552 1481 1368 5553 1480 1367 5554 1482 1369 5555 1481 1368 5556 1479 1366 5557 1480 1367 5558 1481 1368 5559 1482 1369 5560 1483 1370 5561 1484 1371 5562 1483 1370 5563 1485 1372 5564 1484 1371 5565 1481 1368 5566 1483 1370 5567 1389 896 5568 1401 896 5569 1390 896 5570 1486 1373 5571 1399 1293 5572 1393 1287 5573 1484 1371 5574 1485 1372 5575 1487 1374 5576 1488 1375 5577 1393 1287 5578 1402 1294 5579 1489 1376 5580 1393 1287 5581 1488 1375 5582 1490 1377 5583 1393 1287 5584 1489 1376 5585 1491 1378 5586 1486 1373 5587 1393 1287 5588 1490 1377 5589 1491 1378 5590 1393 1287 5591 1492 1379 5592 1402 1294 5593 1403 1295 5594 1488 1375 5595 1402 1294 5596 1492 1379 5597 1493 1380 5598 1403 1295 5599 1404 1296 5600 1492 1379 5601 1403 1295 5602 1493 1380 5603 1494 1381 5604 1404 1296 5605 1405 1297 5606 1493 1380 5607 1404 1296 5608 1494 1381 5609 1495 1382 5610 1405 1297 5611 1408 1300 5612 1494 1381 5613 1405 1297 5614 1495 1382 5615 1496 1383 5616 1408 1300 5617 1416 1306 5618 1495 1382 5619 1408 1300 5620 1496 1383 5621 1417 1307 5622 1497 1384 5623 1416 1306 5624 1498 1385 5625 1416 1306 5626 1497 1384 5627 1496 1383 5628 1416 1306 5629 1498 1385 5630 1499 1386 5631 1500 1387 5632 1497 1384 5633 1501 1388 5634 1497 1384 5635 1500 1387 5636 1502 1389 5637 1499 1386 5638 1497 1384 5639 1417 1307 5640 1502 1389 5641 1497 1384 5642 1498 1385 5643 1497 1384 5644 1501 1388 5645 1450 1338 5646 1451 1339 5647 1500 1387 5648 1503 1390 5649 1500 1387 5650 1451 1339 5651 1504 1391 5652 1450 1338 5653 1500 1387 5654 1499 1386 5655 1504 1391 5656 1500 1387 5657 1501 1388 5658 1500 1387 5659 1503 1390 5660 514 443 5661 1451 1339 5662 537 466 5663 1503 1390 5664 1451 1339 5665 514 443 5666 1505 896 5667 1506 896 5668 1507 896 5669 1508 896 5670 1506 896 5671 1505 896 5672 1509 896 5673 1506 896 5674 1508 896 5675 1510 896 5676 1506 896 5677 1509 896 5678 1511 896 5679 1506 896 5680 1510 896 5681 1505 896 5682 1507 896 5683 1512 896 5684 1413 1392 5685 1513 1392 5686 1514 1392 5687 1413 1393 5688 1514 1393 5689 1418 1393 5690 1460 1348 5691 1515 1394 5692 1461 1349 5693 1516 1395 5694 1462 1350 5695 1517 1396 5696 1516 1395 5697 1456 1344 5698 1462 1350 5699 1460 1348 5700 1518 1397 5701 1515 1394 5702 1519 1398 5703 1517 1396 5704 1520 1399 5705 1516 1395 5706 1517 1396 5707 1519 1398 5708 1460 1348 5709 1521 1400 5710 1518 1397 5711 1519 1398 5712 1520 1399 5713 1522 1401 5714 464 393 5715 1521 1400 5716 1460 1348 5717 463 392 5718 1523 1402 5719 1521 1400 5720 1519 1398 5721 1522 1401 5722 1524 1403 5723 464 393 5724 463 392 5725 1521 1400 5726 465 394 5727 1460 1348 5728 1459 1347 5729 465 394 5730 464 393 5731 1460 1348 5732 466 395 5733 1459 1347 5734 1463 1351 5735 466 395 5736 465 394 5737 1459 1347 5738 467 396 5739 1463 1351 5740 1464 1352 5741 467 396 5742 466 395 5743 1463 1351 5744 468 397 5745 1464 1352 5746 1466 1354 5747 468 397 5748 467 396 5749 1464 1352 5750 1525 1404 5751 1526 1404 5752 1527 1404 5753 1528 1405 5754 468 397 5755 1466 1354 5756 1529 308 5757 1528 1405 5758 1466 1354 5759 1525 1404 5760 1530 1404 5761 1526 1404 5762 1531 1406 5763 1532 1407 5764 1533 1408 5765 1470 1357 5766 1533 1408 5767 1471 1358 5768 1470 1357 5769 1531 1406 5770 1533 1408 5771 463 392 5772 1534 1409 5773 1523 1402 5774 1535 1410 5775 1524 1403 5776 1536 1411 5777 1519 1398 5778 1524 1403 5779 1535 1410 5780 463 392 5781 1537 1412 5782 1534 1409 5783 1535 1410 5784 1536 1411 5785 1538 1413 5786 462 391 5787 1539 1414 5788 1537 1412 5789 1535 1410 5790 1538 1413 5791 1540 1415 5792 463 392 5793 462 391 5794 1537 1412 5795 461 390 5796 1541 1416 5797 1539 1414 5798 329 303 5799 1540 1415 5800 1542 1417 5801 462 391 5802 461 390 5803 1539 1414 5804 1535 1410 5805 1540 1415 5806 329 303 5807 460 389 5808 1543 1418 5809 1541 1416 5810 329 303 5811 1542 1417 5812 1544 1419 5813 461 390 5814 460 389 5815 1541 1416 5816 431 360 5817 483 412 5818 1543 1418 5819 329 303 5820 1544 1419 5821 516 445 5822 460 389 5823 431 360 5824 1543 1418 5825 1528 1405 5826 469 398 5827 468 397 5828 1545 1420 5829 470 399 5830 469 398 5831 1546 1421 5832 1545 1420 5833 469 398 5834 1528 1405 5835 1546 1421 5836 469 398 5837 1547 1422 5838 471 400 5839 470 399 5840 1545 1420 5841 1547 1422 5842 470 399 5843 1548 1423 5844 472 401 5845 471 400 5846 1547 1422 5847 1548 1423 5848 471 400 5849 1488 1375 5850 473 402 5851 472 401 5852 1548 1423 5853 1488 1375 5854 472 401 5855 1492 1379 5856 474 403 5857 473 402 5858 1488 1375 5859 1492 1379 5860 473 402 5861 1493 1380 5862 475 404 5863 474 403 5864 1492 1379 5865 1493 1380 5866 474 403 5867 1494 1381 5868 476 405 5869 475 404 5870 1493 1380 5871 1494 1381 5872 475 404 5873 1495 1382 5874 477 406 5875 476 405 5876 1494 1381 5877 1495 1382 5878 476 405 5879 1496 1383 5880 478 407 5881 477 406 5882 1495 1382 5883 1496 1383 5884 477 406 5885 1498 1385 5886 479 408 5887 478 407 5888 1496 1383 5889 1498 1385 5890 478 407 5891 1501 1388 5892 480 409 5893 479 408 5894 1498 1385 5895 1501 1388 5896 479 408 5897 1503 1390 5898 458 387 5899 480 409 5900 1501 1388 5901 1503 1390 5902 480 409 5903 1503 1390 5904 514 443 5905 458 387 5906 1549 1424 5907 1489 1376 5908 1488 1375 5909 1548 1423 5910 1549 1424 5911 1488 1375 5912 1550 308 5913 1551 308 5914 1552 308 5915 1553 308 5916 1551 308 5917 1550 308 5918 1554 896 5919 1555 896 5920 1556 896 5921 1557 896 5922 1555 896 5923 1554 896 5924 1558 308 5925 1553 308 5926 1550 308 5927 1559 896 5928 1555 896 5929 1557 896 5930 1560 896 5931 1556 896 5932 1561 896 5933 1554 896 5934 1556 896 5935 1560 896 5936 1525 1425 5937 1562 1425 5938 1530 1425 5939 1563 1426 5940 1487 1374 5941 1564 1427 5942 1563 1426 5943 1484 1371 5944 1487 1374 5945 1563 1426 5946 1564 1427 5947 1565 1428 5948 1566 1429 5949 1563 1426 5950 1565 1428 5951 1064 983 5952 1065 984 5953 1567 1430 5954 1568 1431 5955 1569 1432 5956 1570 1433 5957 1064 983 5958 1567 1430 5959 1571 1434 5960 1572 1435 5961 1570 1433 5962 1573 1436 5963 1572 1435 5964 1568 1431 5965 1570 1433 5966 1574 1437 5967 1573 1436 5968 1202 1112 5969 1574 1437 5970 1572 1435 5971 1573 1436 5972 1199 1109 5973 1574 1437 5974 1202 1112 5975 3 3 5976 1575 1438 5977 1576 1439 5978 1577 896 5979 1578 896 5980 1579 896 5981 13 13 5982 3 3 5983 1576 1439 5984 1580 1440 5985 10 10 5986 1581 1441 5987 1582 896 5988 1578 896 5989 1577 896 5990 1580 1440 5991 1581 1441 5992 1583 1442 5993 3 3 5994 1584 1443 5995 1575 1438 5996 1577 896 5997 1579 896 5998 1585 896 5999 1586 1444 6000 1587 1445 6001 1584 1443 6002 1588 1446 6003 1589 1446 6004 1590 1446 6005 3 3 6006 1586 1444 6007 1584 1443 6008 1591 1447 6009 1592 1448 6010 1587 1445 6011 1588 1449 6012 1590 1449 6013 1593 1449 6014 1586 1444 6015 1591 1447 6016 1587 1445 6017 1591 1447 6018 1594 1450 6019 1592 1448 6020 1595 1451 6021 1596 1452 6022 1597 1453 6023 1591 1447 6024 1598 1454 6025 1594 1450 6026 1599 1455 6027 1597 1453 6028 1600 1456 6029 1595 1451 6030 1597 1453 6031 1599 1455 6032 1591 1447 6033 1601 1457 6034 1598 1454 6035 1602 1458 6036 1600 1456 6037 1603 1459 6038 1599 1455 6039 1600 1456 6040 1602 1458 6041 1591 1447 6042 1604 1460 6043 1601 1457 6044 1602 1458 6045 1603 1459 6046 1605 1461 6047 1591 1447 6048 872 801 6049 1604 1460 6050 1606 1462 6051 1607 1463 6052 874 803 6053 1602 1458 6054 1605 1461 6055 1608 1464 6056 1609 1465 6057 1608 1464 6058 1605 1461 6059 1591 1447 6060 871 800 6061 872 801 6062 1610 1466 6063 874 803 6064 873 802 6065 1611 1467 6066 1606 1462 6067 874 803 6068 1612 1468 6069 1611 1467 6070 874 803 6071 1613 1469 6072 1612 1468 6073 874 803 6074 1614 1470 6075 1613 1469 6076 874 803 6077 1615 1471 6078 1614 1470 6079 874 803 6080 1616 1472 6081 1615 1471 6082 874 803 6083 1617 1473 6084 1616 1472 6085 874 803 6086 1618 1474 6087 1617 1473 6088 874 803 6089 1610 1466 6090 1618 1474 6091 874 803 6092 1619 1475 6093 1620 1476 6094 765 694 6095 1621 1477 6096 1622 1478 6097 765 694 6098 1619 1475 6099 765 694 6100 1622 1478 6101 768 697 6102 1621 1477 6103 765 694 6104 1623 1479 6105 786 715 6106 1620 1476 6107 1624 24 6108 120 24 6109 1625 24 6110 1626 1480 6111 1623 1479 6112 1620 1476 6113 1627 1481 6114 1626 1480 6115 1620 1476 6116 1628 1482 6117 1627 1481 6118 1620 1476 6119 1619 1475 6120 1628 1482 6121 1620 1476 6122 1624 24 6123 111 24 6124 120 24 6125 1629 24 6126 1625 24 6127 1630 24 6128 1631 1483 6129 788 717 6130 786 715 6131 1632 1484 6132 1631 1483 6133 786 715 6134 1623 1479 6135 1632 1484 6136 786 715 6137 1629 1485 6138 1624 1485 6139 1625 1485 6140 1633 1486 6141 1630 1486 6142 1634 1486 6143 1635 24 6144 1629 24 6145 1630 24 6146 1633 1487 6147 1635 1487 6148 1630 1487 6149 1636 24 6150 1634 24 6151 1637 24 6152 1636 1488 6153 1633 1488 6154 1634 1488 6155 1638 24 6156 1637 24 6157 1639 24 6158 1638 24 6159 1636 24 6160 1637 24 6161 1640 24 6162 1639 24 6163 1641 24 6164 1640 1489 6165 1638 1489 6166 1639 1489 6167 1642 1490 6168 1641 1490 6169 1643 1490 6170 1642 1491 6171 1640 1491 6172 1641 1491 6173 1644 24 6174 1643 24 6175 1645 24 6176 1644 24 6177 1642 24 6178 1643 24 6179 1646 1492 6180 1645 1492 6181 1647 1492 6182 1648 24 6183 1644 24 6184 1645 24 6185 1646 24 6186 1648 24 6187 1645 24 6188 1649 24 6189 1647 24 6190 1650 24 6191 1651 24 6192 1646 24 6193 1647 24 6194 1649 24 6195 1651 24 6196 1647 24 6197 1652 1493 6198 1650 1493 6199 1653 1493 6200 1652 1494 6201 1649 1494 6202 1650 1494 6203 1652 24 6204 1653 24 6205 1654 24 6206 1655 24 6207 1654 24 6208 1656 24 6209 1655 24 6210 1652 24 6211 1654 24 6212 1657 24 6213 1656 24 6214 1658 24 6215 1657 24 6216 1655 24 6217 1656 24 6218 1659 1495 6219 1658 1495 6220 1660 1495 6221 1659 1496 6222 1657 1496 6223 1658 1496 6224 1661 1497 6225 1660 1497 6226 1662 1497 6227 1661 1498 6228 1659 1498 6229 1660 1498 6230 1663 1499 6231 1662 1499 6232 1664 1499 6233 1663 1500 6234 1661 1500 6235 1662 1500 6236 1665 24 6237 1664 24 6238 1666 24 6239 1665 24 6240 1663 24 6241 1664 24 6242 28 1501 6243 1666 1501 6244 22 1501 6245 1667 1502 6246 1665 1502 6247 1666 1502 6248 28 1503 6249 1667 1503 6250 1666 1503 6251 1580 1440 6252 408 337 6253 10 10 6254 1668 896 6255 1669 896 6256 1670 896 6257 1671 1504 6258 1672 1504 6259 1673 1504 6260 1674 1505 6261 1673 1505 6262 1672 1505 6263 1675 896 6264 1670 896 6265 1676 896 6266 1677 896 6267 1668 896 6268 1670 896 6269 1678 896 6270 1677 896 6271 1670 896 6272 1679 896 6273 1678 896 6274 1670 896 6275 1675 896 6276 1679 896 6277 1670 896 6278 1680 1506 6279 1681 1506 6280 1682 1506 6281 1683 896 6282 1675 896 6283 1676 896 6284 1684 896 6285 1683 896 6286 1676 896 6287 1685 896 6288 1684 896 6289 1676 896 6290 1686 896 6291 1685 896 6292 1676 896 6293 1680 1507 6294 1682 1507 6295 1687 1507 6296 1688 1508 6297 1689 1509 6298 1690 1510 6299 1691 1511 6300 1690 1510 6301 1692 1512 6302 1688 1508 6303 1690 1510 6304 1691 1511 6305 1693 1513 6306 1692 1512 6307 1694 1514 6308 1691 1511 6309 1692 1512 6310 1693 1513 6311 1693 1513 6312 1694 1514 6313 1695 1515 6314 1696 1516 6315 1695 1515 6316 1697 1517 6317 1693 1513 6318 1695 1515 6319 1696 1516 6320 1696 1516 6321 1697 1517 6322 1698 1518 6323 1699 1519 6324 1698 1518 6325 1700 1520 6326 1696 1516 6327 1698 1518 6328 1699 1519 6329 1701 1521 6330 1700 1520 6331 1702 1522 6332 1699 1519 6333 1700 1520 6334 1701 1521 6335 1701 1521 6336 1702 1522 6337 1703 1523 6338 1704 1524 6339 1703 1523 6340 1705 1525 6341 1701 1521 6342 1703 1523 6343 1704 1524 6344 1706 1526 6345 1705 1525 6346 1707 1527 6347 1704 1524 6348 1705 1525 6349 1706 1526 6350 1708 1528 6351 1707 1527 6352 1709 1529 6353 1706 1526 6354 1707 1527 6355 1708 1528 6356 1708 1528 6357 1709 1529 6358 1710 1530 6359 1708 1528 6360 1710 1530 6361 1711 1531 6362 1712 896 6363 1713 896 6364 1714 896 6365 1715 1532 6366 1716 1532 6367 1717 1532 6368 1718 896 6369 1712 896 6370 1714 896 6371 1719 896 6372 1718 896 6373 1714 896 6374 1577 896 6375 1719 896 6376 1714 896 6377 1582 896 6378 1577 896 6379 1714 896 6380 1580 1440 6381 1583 1442 6382 1720 1533 6383 1721 1534 6384 1580 1440 6385 1720 1533 6386 1722 1535 6387 1721 1534 6388 1720 1533 6389 1723 1536 6390 1716 1536 6391 1715 1536 6392 1722 1535 6393 1720 1533 6394 1724 1537 6395 1725 896 6396 1726 896 6397 1713 896 6398 1727 1538 6399 1728 1539 6400 1729 1540 6401 1712 896 6402 1725 896 6403 1713 896 6404 1730 896 6405 1731 896 6406 1726 896 6407 1732 1541 6408 1729 1540 6409 1733 1542 6410 1725 896 6411 1730 896 6412 1726 896 6413 1734 1543 6414 1729 1540 6415 1732 1541 6416 1727 1538 6417 1729 1540 6418 1734 1543 6419 1730 896 6420 1735 896 6421 1731 896 6422 1736 1544 6423 1733 1542 6424 1737 1545 6425 1738 1546 6426 1733 1542 6427 1736 1544 6428 1732 1541 6429 1733 1542 6430 1738 1546 6431 1739 1547 6432 1737 1545 6433 1740 1548 6434 1736 1544 6435 1737 1545 6436 1739 1547 6437 1741 1549 6438 1740 1548 6439 1742 1550 6440 1743 1551 6441 1740 1548 6442 1741 1549 6443 1739 1547 6444 1740 1548 6445 1743 1551 6446 1609 1465 6447 1742 1550 6448 1608 1464 6449 1744 1552 6450 1742 1550 6451 1609 1465 6452 1741 1549 6453 1742 1550 6454 1744 1552 6455 1745 1553 6456 1746 1554 6457 1721 1534 6458 1747 1555 6459 1748 1555 6460 1721 1555 6461 1745 1553 6462 1721 1534 6463 1748 1556 6464 1722 1557 6465 1747 1557 6466 1721 1557 6467 1749 1558 6468 1750 1559 6469 1746 1554 6470 1745 1553 6471 1749 1558 6472 1746 1554 6473 1751 1560 6474 1752 1561 6475 1750 1559 6476 1753 1562 6477 1751 1560 6478 1750 1559 6479 1749 1558 6480 1753 1562 6481 1750 1559 6482 1610 1466 6483 873 802 6484 1752 1561 6485 397 308 6486 396 308 6487 1754 308 6488 1755 1563 6489 1610 1466 6490 1752 1561 6491 1756 1564 6492 1755 1563 6493 1752 1561 6494 1757 1565 6495 1756 1564 6496 1752 1561 6497 1751 1560 6498 1757 1565 6499 1752 1561 6500 1758 308 6501 1754 308 6502 1759 308 6503 1760 308 6504 397 308 6505 1754 308 6506 1758 308 6507 1760 308 6508 1754 308 6509 1761 308 6510 1759 308 6511 1762 308 6512 1761 1566 6513 1758 1566 6514 1759 1566 6515 1761 1567 6516 1762 1567 6517 1763 1567 6518 1764 308 6519 1763 308 6520 1765 308 6521 1764 1568 6522 1761 1568 6523 1763 1568 6524 1766 308 6525 1765 308 6526 1767 308 6527 1766 1569 6528 1764 1569 6529 1765 1569 6530 1768 308 6531 1767 308 6532 1769 308 6533 1770 308 6534 1766 308 6535 1767 308 6536 1768 1570 6537 1770 1570 6538 1767 1570 6539 1771 308 6540 1769 308 6541 1772 308 6542 1771 1571 6543 1768 1571 6544 1769 1571 6545 933 862 6546 1773 1572 6547 932 861 6548 1771 308 6549 1772 308 6550 1774 308 6551 933 862 6552 1775 1573 6553 1773 1572 6554 1776 308 6555 1774 308 6556 1777 308 6557 1776 1574 6558 1771 1574 6559 1774 1574 6560 1778 1575 6561 1779 1576 6562 1775 1573 6563 1776 1577 6564 1777 1577 6565 1780 1577 6566 933 862 6567 1778 1575 6568 1775 1573 6569 1778 1575 6570 1781 1578 6571 1779 1576 6572 1782 1579 6573 1780 1579 6574 1783 1579 6575 1782 308 6576 1776 308 6577 1780 308 6578 1784 1580 6579 1785 1581 6580 1781 1578 6581 1782 1582 6582 1783 1582 6583 1786 1582 6584 1778 1575 6585 1784 1580 6586 1781 1578 6587 1784 1580 6588 1787 1583 6589 1785 1581 6590 1788 308 6591 1786 308 6592 1789 308 6593 1788 1584 6594 1782 1584 6595 1786 1584 6596 1790 1585 6597 1791 1586 6598 1787 1583 6599 1792 308 6600 1789 308 6601 1793 308 6602 1784 1580 6603 1790 1585 6604 1787 1583 6605 1792 1587 6606 1788 1587 6607 1789 1587 6608 1790 1585 6609 1794 1588 6610 1791 1586 6611 1792 308 6612 1793 308 6613 1795 308 6614 1796 1589 6615 1797 1590 6616 1794 1588 6617 1798 308 6618 1795 308 6619 1799 308 6620 1790 1585 6621 1796 1589 6622 1794 1588 6623 1798 1591 6624 1792 1591 6625 1795 1591 6626 1796 1589 6627 1800 1592 6628 1797 1590 6629 1798 308 6630 1799 308 6631 1801 308 6632 1802 1593 6633 1803 1594 6634 1800 1592 6635 1804 308 6636 1801 308 6637 1805 308 6638 1796 1589 6639 1802 1593 6640 1800 1592 6641 1804 1595 6642 1798 1595 6643 1801 1595 6644 1806 1596 6645 1807 1597 6646 1803 1594 6647 1804 1598 6648 1805 1598 6649 1808 1598 6650 1809 1599 6651 1806 1596 6652 1803 1594 6653 1802 1593 6654 1809 1599 6655 1803 1594 6656 1810 1600 6657 1811 1601 6658 1807 1597 6659 1812 308 6660 1808 308 6661 1813 308 6662 1806 1596 6663 1810 1600 6664 1807 1597 6665 1812 1602 6666 1804 1602 6667 1808 1602 6668 1814 1603 6669 1815 1604 6670 1811 1601 6671 1812 308 6672 1813 308 6673 1816 308 6674 1810 1600 6675 1814 1603 6676 1811 1601 6677 1817 1605 6678 1818 1606 6679 1815 1604 6680 1819 308 6681 1816 308 6682 1820 308 6683 1814 1603 6684 1817 1605 6685 1815 1604 6686 1819 1607 6687 1812 1607 6688 1816 1607 6689 1821 1608 6690 1822 1609 6691 1818 1606 6692 1823 308 6693 1820 308 6694 1824 308 6695 1817 1605 6696 1821 1608 6697 1818 1606 6698 1823 308 6699 1819 308 6700 1820 308 6701 1825 1610 6702 1826 1611 6703 1822 1609 6704 1823 308 6705 1824 308 6706 1827 308 6707 1821 1608 6708 1825 1610 6709 1822 1609 6710 1828 1612 6711 1829 1613 6712 1826 1611 6713 1830 1614 6714 1827 1614 6715 1831 1614 6716 1825 1610 6717 1828 1612 6718 1826 1611 6719 1830 308 6720 1823 308 6721 1827 308 6722 1832 1615 6723 1833 1616 6724 1829 1613 6725 1834 308 6726 1831 308 6727 1835 308 6728 1828 1612 6729 1832 1615 6730 1829 1613 6731 1834 1617 6732 1830 1617 6733 1831 1617 6734 1836 1618 6735 1837 1619 6736 1833 1616 6737 1838 1620 6738 1835 1620 6739 343 1620 6740 1832 1615 6741 1839 1621 6742 1833 1616 6743 1840 1622 6744 1833 1616 6745 1839 1621 6746 1841 1623 6747 1836 1618 6748 1833 1616 6749 1842 1624 6750 1841 1623 6751 1833 1616 6752 1840 1622 6753 1842 1624 6754 1833 1616 6755 1838 1625 6756 1834 1625 6757 1835 1625 6758 1843 1626 6759 1844 1627 6760 1837 1619 6761 1845 1628 6762 1843 1626 6763 1837 1619 6764 1836 1618 6765 1845 1628 6766 1837 1619 6767 1846 308 6768 343 308 6769 345 308 6770 1846 1629 6771 1838 1629 6772 343 1629 6773 1847 1630 6774 1848 1631 6775 1844 1627 6776 1849 1632 6777 1847 1630 6778 1844 1627 6779 1843 1626 6780 1849 1632 6781 1844 1627 6782 1850 1633 6783 1851 1634 6784 1848 1631 6785 1847 1630 6786 1850 1633 6787 1848 1631 6788 1852 1635 6789 1853 1636 6790 1851 1634 6791 1854 1637 6792 1852 1635 6793 1851 1634 6794 1855 1638 6795 1856 1638 6796 1851 1638 6797 1857 1639 6798 1851 1634 6799 1856 1640 6800 1850 1641 6801 1855 1641 6802 1851 1641 6803 1858 1642 6804 1854 1637 6805 1851 1634 6806 1857 1639 6807 1858 1642 6808 1851 1634 6809 1859 1643 6810 324 298 6811 1853 1636 6812 1852 1635 6813 1859 1643 6814 1853 1636 6815 1859 1643 6816 331 305 6817 324 298 6818 1860 1644 6819 1535 1410 6820 1861 1645 6821 1862 1646 6822 1519 1398 6823 1535 1410 6824 1860 1644 6825 1862 1646 6826 1535 1410 6827 1863 1647 6828 1864 1648 6829 1852 1635 6830 1860 1644 6831 1861 1645 6832 1865 1649 6833 1863 1647 6834 1852 1635 6835 1854 1637 6836 1866 1650 6837 1867 1651 6838 1864 1648 6839 1868 1652 6840 1865 1649 6841 1869 1653 6842 1863 1647 6843 1866 1650 6844 1864 1648 6845 1868 1652 6846 1860 1644 6847 1865 1649 6848 1870 1654 6849 1871 1655 6850 1867 1651 6851 1872 1656 6852 1869 1653 6853 1873 1657 6854 1874 1658 6855 1870 1654 6856 1867 1651 6857 1875 1659 6858 1874 1658 6859 1867 1651 6860 1866 1650 6861 1875 1659 6862 1867 1651 6863 1872 1656 6864 1868 1652 6865 1869 1653 6866 1876 1660 6867 1839 1621 6868 1871 1655 6869 1877 1661 6870 1873 1657 6871 1375 1272 6872 1878 1662 6873 1876 1660 6874 1871 1655 6875 1879 1663 6876 1878 1662 6877 1871 1655 6878 1870 1654 6879 1879 1663 6880 1871 1655 6881 1880 1664 6882 1872 1656 6883 1873 1657 6884 1877 1661 6885 1880 1664 6886 1873 1657 6887 1881 1665 6888 1840 1622 6889 1839 1621 6890 1876 1660 6891 1881 1665 6892 1839 1621 6893 1882 1666 6894 1877 1661 6895 1375 1272 6896 1883 1667 6897 1882 1666 6898 1375 1272 6899 1884 1668 6900 1883 1667 6901 1375 1272 6902 1885 1669 6903 1884 1668 6904 1375 1272 6905 1381 1278 6906 1885 1669 6907 1375 1272 6908 1886 1670 6909 1887 1671 6910 1614 1470 6911 1615 1471 6912 1886 1670 6913 1614 1470 6914 1886 1670 6915 1888 1672 6916 1887 1671 6917 1886 1670 6918 1889 1673 6919 1888 1672 6920 1890 1674 6921 1891 1675 6922 1889 1673 6923 1886 1670 6924 1890 1674 6925 1889 1673 6926 1890 1674 6927 1892 1676 6928 1891 1675 6929 1893 1677 6930 1724 1537 6931 1892 1676 6932 1890 1674 6933 1893 1677 6934 1892 1676 6935 1894 1678 6936 1722 1535 6937 1724 1537 6938 1893 1677 6939 1894 1678 6940 1724 1537 6941 1895 896 6942 1896 896 6943 1897 896 6944 1898 1679 6945 1899 1679 6946 1900 1679 6947 1901 1680 6948 1900 1680 6949 1899 1680 6950 1902 1681 6951 1856 1640 6952 1903 1682 6953 1902 1681 6954 1857 1639 6955 1856 1640 6956 1904 896 6957 1905 896 6958 1896 896 6959 1895 896 6960 1904 896 6961 1896 896 6962 1906 896 6963 1897 896 6964 1907 896 6965 1908 896 6966 1895 896 6967 1897 896 6968 1909 896 6969 1908 896 6970 1897 896 6971 1906 896 6972 1909 896 6973 1897 896 6974 1910 1683 6975 1911 1683 6976 1912 1683 6977 1913 896 6978 1906 896 6979 1907 896 6980 1914 896 6981 1913 896 6982 1907 896 6983 1915 896 6984 1914 896 6985 1907 896 6986 1910 1684 6987 1912 1684 6988 1916 1684 6989 1917 1685 6990 1918 1686 6991 1919 1687 6992 1920 1688 6993 1919 1687 6994 1921 1689 6995 1917 1685 6996 1919 1687 6997 1920 1688 6998 1922 1690 6999 1921 1689 7000 1923 1691 7001 1920 1688 7002 1921 1689 7003 1922 1690 7004 1922 1690 7005 1923 1691 7006 1924 1692 7007 1925 1693 7008 1924 1692 7009 1926 1694 7010 1922 1690 7011 1924 1692 7012 1925 1693 7013 1925 1693 7014 1926 1694 7015 1927 1695 7016 1928 1696 7017 1927 1695 7018 1929 1697 7019 1925 1693 7020 1927 1695 7021 1928 1696 7022 1876 1660 7023 1930 1698 7024 1881 1665 7025 1928 1696 7026 1929 1697 7027 1931 1699 7028 1876 1660 7029 1932 1700 7030 1930 1698 7031 1933 1701 7032 1931 1699 7033 1934 1702 7034 1928 1696 7035 1931 1699 7036 1933 1701 7037 1935 1703 7038 1936 1704 7039 1932 1700 7040 1937 1705 7041 1934 1702 7042 1938 1706 7043 1876 1660 7044 1935 1703 7045 1932 1700 7046 1933 1701 7047 1934 1702 7048 1937 1705 7049 1939 1707 7050 1940 1708 7051 1936 1704 7052 1937 1705 7053 1938 1706 7054 1941 1709 7055 1942 1710 7056 1939 1707 7057 1936 1704 7058 1935 1711 7059 1942 1711 7060 1936 1711 7061 1943 1712 7062 1944 1713 7063 1940 1708 7064 1945 1714 7065 1941 1709 7066 1946 1715 7067 1939 1707 7068 1943 1712 7069 1940 1708 7070 1937 1705 7071 1941 1709 7072 1945 1714 7073 1947 1716 7074 1948 1717 7075 1944 1713 7076 1949 1718 7077 1946 1715 7078 1950 1719 7079 1951 1720 7080 1947 1716 7081 1944 1713 7082 1943 1712 7083 1951 1720 7084 1944 1713 7085 1945 1714 7086 1946 1715 7087 1949 1718 7088 1952 1721 7089 1903 1682 7090 1948 1717 7091 1947 1716 7092 1952 1721 7093 1948 1717 7094 1953 1722 7095 1950 1719 7096 1954 1723 7097 1949 1718 7098 1950 1719 7099 1953 1722 7100 1952 1721 7101 1902 1681 7102 1903 1682 7103 1955 896 7104 1956 896 7105 1957 896 7106 1958 1724 7107 1959 1724 7108 1960 1724 7109 1961 1725 7110 1960 1725 7111 1959 1725 7112 1962 896 7113 1957 896 7114 1963 896 7115 1964 896 7116 1955 896 7117 1957 896 7118 1965 896 7119 1964 896 7120 1957 896 7121 1966 896 7122 1965 896 7123 1957 896 7124 1962 896 7125 1966 896 7126 1957 896 7127 1967 1726 7128 1968 1726 7129 1969 1726 7130 1970 896 7131 1962 896 7132 1963 896 7133 1971 896 7134 1970 896 7135 1963 896 7136 1972 896 7137 1971 896 7138 1963 896 7139 1973 896 7140 1972 896 7141 1963 896 7142 1967 1727 7143 1969 1727 7144 1974 1727 7145 1975 1728 7146 1976 1729 7147 1977 1730 7148 1978 1731 7149 1977 1730 7150 1979 1732 7151 1980 1733 7152 1977 1730 7153 1978 1731 7154 1981 1734 7155 1977 1730 7156 1980 1733 7157 1975 1728 7158 1977 1730 7159 1981 1734 7160 1978 1731 7161 1979 1732 7162 1982 1735 7163 1983 1736 7164 1982 1735 7165 1984 1737 7166 1978 1731 7167 1982 1735 7168 1983 1736 7169 1985 1738 7170 1984 1737 7171 1986 1739 7172 1983 1736 7173 1984 1737 7174 1985 1738 7175 1985 1738 7176 1986 1739 7177 1987 1740 7178 1988 1741 7179 1987 1740 7180 1989 1742 7181 1985 1738 7182 1987 1740 7183 1988 1741 7184 1988 1741 7185 1989 1742 7186 1990 1743 7187 1991 1744 7188 1990 1743 7189 1992 1745 7190 1988 1741 7191 1990 1743 7192 1991 1744 7193 1991 1744 7194 1992 1745 7195 1993 1746 7196 1994 1747 7197 1993 1746 7198 1995 1748 7199 1991 1744 7200 1993 1746 7201 1994 1747 7202 1996 1749 7203 1995 1748 7204 1997 1750 7205 1994 1747 7206 1995 1748 7207 1996 1749 7208 1996 1749 7209 1997 1750 7210 1998 1751 7211 1996 1749 7212 1998 1751 7213 1999 1752 7214 2000 896 7215 2001 896 7216 2002 896 7217 2003 1753 7218 2004 1753 7219 2005 1753 7220 2006 1754 7221 2005 1754 7222 2004 1754 7223 2007 896 7224 2008 896 7225 2001 896 7226 2000 896 7227 2007 896 7228 2001 896 7229 2009 896 7230 2002 896 7231 2010 896 7232 2011 896 7233 2000 896 7234 2002 896 7235 2012 896 7236 2011 896 7237 2002 896 7238 2009 896 7239 2012 896 7240 2002 896 7241 2013 1755 7242 2014 1755 7243 2015 1755 7244 2016 896 7245 2009 896 7246 2010 896 7247 2017 896 7248 2016 896 7249 2010 896 7250 2018 896 7251 2017 896 7252 2010 896 7253 2013 1756 7254 2015 1756 7255 2019 1756 7256 2020 1757 7257 2021 1758 7258 2022 1759 7259 2023 1760 7260 2022 1759 7261 2024 1761 7262 2020 1757 7263 2022 1759 7264 2023 1760 7265 2025 1762 7266 2024 1761 7267 2026 1763 7268 2023 1760 7269 2024 1761 7270 2025 1762 7271 2025 1762 7272 2026 1763 7273 2027 1764 7274 2028 1765 7275 2027 1764 7276 2029 1766 7277 2025 1762 7278 2027 1764 7279 2028 1765 7280 2028 1765 7281 2029 1766 7282 2030 1767 7283 2031 1768 7284 2030 1767 7285 2032 1769 7286 2028 1765 7287 2030 1767 7288 2031 1768 7289 2031 1768 7290 2032 1769 7291 2033 1770 7292 2034 1771 7293 2033 1770 7294 2035 1772 7295 2031 1768 7296 2033 1770 7297 2034 1771 7298 2036 1773 7299 2035 1772 7300 2037 1774 7301 2034 1771 7302 2035 1772 7303 2036 1773 7304 2036 1773 7305 2037 1774 7306 2038 1775 7307 2039 1776 7308 2038 1775 7309 2040 1777 7310 2036 1773 7311 2038 1775 7312 2039 1776 7313 2041 1778 7314 2040 1777 7315 2042 1779 7316 2039 1776 7317 2040 1777 7318 2041 1778 7319 2043 1780 7320 2042 1779 7321 2044 1781 7322 2041 1778 7323 2042 1779 7324 2043 1780 7325 2045 1782 7326 2046 1783 7327 2047 1784 7328 2048 1785 7329 2049 1786 7330 2050 1787 7331 2048 1785 7332 2050 1787 7333 2051 1788 7334 2052 1789 7335 2047 1784 7336 2053 1790 7337 2054 1791 7338 2045 1782 7339 2047 1784 7340 2052 1789 7341 2054 1791 7342 2047 1784 7343 2055 1792 7344 2053 1790 7345 2056 1793 7346 2055 1792 7347 2052 1789 7348 2053 1790 7349 2057 1794 7350 2056 1793 7351 2058 1795 7352 2057 1794 7353 2055 1792 7354 2056 1793 7355 2059 1796 7356 2058 1795 7357 2060 1797 7358 2059 1796 7359 2057 1794 7360 2058 1795 7361 2061 1798 7362 2060 1797 7363 2062 1799 7364 2061 1798 7365 2059 1796 7366 2060 1797 7367 2061 1798 7368 2062 1799 7369 2063 1800 7370 2064 1801 7371 2063 1800 7372 2065 1802 7373 2064 1801 7374 2061 1798 7375 2063 1800 7376 2066 1803 7377 2065 1802 7378 2067 1804 7379 2066 1803 7380 2064 1801 7381 2065 1802 7382 2068 1805 7383 2067 1804 7384 2069 1806 7385 2068 1805 7386 2066 1803 7387 2067 1804 7388 2070 1807 7389 2069 1806 7390 2071 1808 7391 2070 1807 7392 2068 1805 7393 2069 1806 7394 2072 1809 7395 2071 1808 7396 2073 1810 7397 2072 1809 7398 2070 1807 7399 2071 1808 7400 2074 1811 7401 2073 1810 7402 2075 1812 7403 2074 1811 7404 2072 1809 7405 2073 1810 7406 2076 1813 7407 2075 1812 7408 2077 1814 7409 2076 1813 7410 2074 1811 7411 2075 1812 7412 2078 1815 7413 2077 1814 7414 2079 1816 7415 2078 1815 7416 2076 1813 7417 2077 1814 7418 2080 1817 7419 2079 1816 7420 2081 1818 7421 2080 1817 7422 2078 1815 7423 2079 1816 7424 2082 1819 7425 2081 1818 7426 2083 1820 7427 2084 1821 7428 2080 1817 7429 2081 1818 7430 2082 1819 7431 2084 1821 7432 2081 1818 7433 2085 1822 7434 2083 1820 7435 2086 1823 7436 2085 1822 7437 2082 1819 7438 2083 1820 7439 2087 1824 7440 2086 1823 7441 2088 1825 7442 2087 1824 7443 2085 1822 7444 2086 1823 7445 2089 1826 7446 2088 1825 7447 2090 1827 7448 2089 1826 7449 2087 1824 7450 2088 1825 7451 2091 1828 7452 2090 1827 7453 2092 1829 7454 2091 1828 7455 2089 1826 7456 2090 1827 7457 2091 1828 7458 2092 1829 7459 2093 1830 7460 2094 1831 7461 2095 1832 7462 2096 1833 7463 2097 1834 7464 2091 1828 7465 2093 1830 7466 2098 1835 7467 2096 1833 7468 2099 1836 7469 2100 1837 7470 2094 1831 7471 2096 1833 7472 2098 1835 7473 2100 1837 7474 2096 1833 7475 2101 1838 7476 2099 1836 7477 2102 1839 7478 2101 1838 7479 2098 1835 7480 2099 1836 7481 2103 1840 7482 2102 1839 7483 2104 1841 7484 2103 1840 7485 2101 1838 7486 2102 1839 7487 2105 1842 7488 2104 1841 7489 2106 1843 7490 2105 1842 7491 2103 1840 7492 2104 1841 7493 2107 1844 7494 2106 1843 7495 2108 1845 7496 2107 1844 7497 2105 1842 7498 2106 1843 7499 2107 1844 7500 2108 1845 7501 2109 1846 7502 2110 1847 7503 2109 1846 7504 2111 1848 7505 2110 1847 7506 2107 1844 7507 2109 1846 7508 2112 1849 7509 2111 1848 7510 2113 1850 7511 2112 1849 7512 2110 1847 7513 2111 1848 7514 2114 1851 7515 2113 1850 7516 2115 1852 7517 2114 1851 7518 2112 1849 7519 2113 1850 7520 2116 1853 7521 2115 1852 7522 2117 1854 7523 2116 1853 7524 2114 1851 7525 2115 1852 7526 2118 1855 7527 2117 1854 7528 2119 1856 7529 2118 1855 7530 2116 1853 7531 2117 1854 7532 2120 1857 7533 2119 1856 7534 2121 1858 7535 2120 1857 7536 2118 1855 7537 2119 1856 7538 2122 1859 7539 2121 1858 7540 2123 1860 7541 2122 1859 7542 2120 1857 7543 2121 1858 7544 2124 1861 7545 2123 1860 7546 2125 1862 7547 2124 1861 7548 2122 1859 7549 2123 1860 7550 2126 1863 7551 2125 1862 7552 2127 1864 7553 2126 1863 7554 2124 1861 7555 2125 1862 7556 2128 1865 7557 2127 1864 7558 2129 1866 7559 2130 1867 7560 2126 1863 7561 2127 1864 7562 2128 1865 7563 2130 1867 7564 2127 1864 7565 2131 1868 7566 2129 1866 7567 2132 1869 7568 2131 1868 7569 2128 1865 7570 2129 1866 7571 2133 1870 7572 2132 1869 7573 2134 1871 7574 2133 1870 7575 2131 1868 7576 2132 1869 7577 2135 1872 7578 2134 1871 7579 2136 1873 7580 2135 1872 7581 2133 1870 7582 2134 1871 7583 2048 1785 7584 2136 1873 7585 2049 1786 7586 2048 1785 7587 2135 1872 7588 2136 1873 7589 2137 1874 7590 2138 1874 7591 2139 1874 7592 2140 1404 7593 2141 1404 7594 2138 1404 7595 2140 1404 7596 2138 1404 7597 2137 1404 7598 2137 1404 7599 2139 1404 7600 2142 1404 7601 2137 1404 7602 2142 1404 7603 2143 1404 7604 2144 1404 7605 2143 1404 7606 2145 1404 7607 2144 1875 7608 2137 1875 7609 2143 1875 7610 2146 1404 7611 2145 1404 7612 2147 1404 7613 2146 1404 7614 2144 1404 7615 2145 1404 7616 2148 1404 7617 2147 1404 7618 2149 1404 7619 2150 1404 7620 2146 1404 7621 2147 1404 7622 2148 1876 7623 2150 1876 7624 2147 1876 7625 2151 1404 7626 2149 1404 7627 2152 1404 7628 2151 1877 7629 2148 1877 7630 2149 1877 7631 2153 1878 7632 2152 1878 7633 2154 1878 7634 2155 1404 7635 2151 1404 7636 2152 1404 7637 2153 1404 7638 2155 1404 7639 2152 1404 7640 2156 1879 7641 2154 1879 7642 2157 1879 7643 2156 1404 7644 2153 1404 7645 2154 1404 7646 2158 1404 7647 2157 1404 7648 2159 1404 7649 2158 1880 7650 2156 1880 7651 2157 1880 7652 2160 1404 7653 2159 1404 7654 2161 1404 7655 2160 1881 7656 2158 1881 7657 2159 1881 7658 2162 1404 7659 2161 1404 7660 2163 1404 7661 2162 1404 7662 2160 1404 7663 2161 1404 7664 2164 1404 7665 2163 1404 7666 2165 1404 7667 2164 1882 7668 2162 1882 7669 2163 1882 7670 2166 1404 7671 2165 1404 7672 2167 1404 7673 2166 1883 7674 2164 1883 7675 2165 1883 7676 2166 1404 7677 2167 1404 7678 2168 1404 7679 2169 1884 7680 2168 1884 7681 2170 1884 7682 2169 1404 7683 2166 1404 7684 2168 1404 7685 2169 1885 7686 2170 1885 7687 2171 1885 7688 2169 1404 7689 2171 1404 7690 2172 1404 7691 2173 1404 7692 2172 1404 7693 2174 1404 7694 2173 1886 7695 2169 1886 7696 2172 1886 7697 2175 1887 7698 2174 1887 7699 2176 1887 7700 2175 1404 7701 2173 1404 7702 2174 1404 7703 2175 1404 7704 2176 1404 7705 2177 1404 7706 2178 1404 7707 2177 1404 7708 2179 1404 7709 2178 1404 7710 2175 1404 7711 2177 1404 7712 2180 1888 7713 2179 1888 7714 2181 1888 7715 2180 1404 7716 2178 1404 7717 2179 1404 7718 2180 1404 7719 2181 1404 7720 2182 1404 7721 2180 1404 7722 2182 1404 7723 2183 1404 7724 2184 1404 7725 2183 1404 7726 2185 1404 7727 2184 1889 7728 2180 1889 7729 2183 1889 7730 2186 1404 7731 2185 1404 7732 2187 1404 7733 2186 1404 7734 2184 1404 7735 2185 1404 7736 2188 1404 7737 2187 1404 7738 2189 1404 7739 2190 1404 7740 2186 1404 7741 2187 1404 7742 2188 1890 7743 2190 1890 7744 2187 1890 7745 2191 1404 7746 2189 1404 7747 2192 1404 7748 2191 1891 7749 2188 1891 7750 2189 1891 7751 2193 1892 7752 2192 1892 7753 2194 1892 7754 2195 1404 7755 2191 1404 7756 2192 1404 7757 2193 1404 7758 2195 1404 7759 2192 1404 7760 2196 1893 7761 2194 1893 7762 2197 1893 7763 2196 1404 7764 2193 1404 7765 2194 1404 7766 2198 1404 7767 2197 1404 7768 2199 1404 7769 2198 1894 7770 2196 1894 7771 2197 1894 7772 2200 1404 7773 2199 1404 7774 2201 1404 7775 2200 1895 7776 2198 1895 7777 2199 1895 7778 2202 1404 7779 2201 1404 7780 2203 1404 7781 2202 1404 7782 2200 1404 7783 2201 1404 7784 2204 1404 7785 2203 1404 7786 2205 1404 7787 2204 1896 7788 2202 1896 7789 2203 1896 7790 2206 1404 7791 2205 1404 7792 2207 1404 7793 2206 1897 7794 2204 1897 7795 2205 1897 7796 2206 1404 7797 2207 1404 7798 2208 1404 7799 2209 1898 7800 2208 1898 7801 2210 1898 7802 2209 1404 7803 2206 1404 7804 2208 1404 7805 2209 1899 7806 2210 1899 7807 2211 1899 7808 2209 1404 7809 2211 1404 7810 2212 1404 7811 2213 1404 7812 2212 1404 7813 2214 1404 7814 2213 1900 7815 2209 1900 7816 2212 1900 7817 2215 1901 7818 2214 1901 7819 2216 1901 7820 2215 1404 7821 2213 1404 7822 2214 1404 7823 2215 1404 7824 2216 1404 7825 2141 1404 7826 2140 1404 7827 2215 1404 7828 2141 1404 7829 2217 1404 7830 2218 1404 7831 2219 1404 7832 2220 1902 7833 2221 1903 7834 2222 1904 7835 2223 1905 7836 2224 1906 7837 2225 1907 7838 2223 1905 7839 2225 1907 7840 2226 1908 7841 2227 1404 7842 2228 1404 7843 2218 1404 7844 2229 1909 7845 2222 1904 7846 2230 1910 7847 2217 1911 7848 2227 1911 7849 2218 1911 7850 2231 1912 7851 2220 1902 7852 2222 1904 7853 2229 1909 7854 2231 1912 7855 2222 1904 7856 2232 1913 7857 2137 1913 7858 2228 1913 7859 2233 1914 7860 2230 1910 7861 2234 1915 7862 2227 1916 7863 2232 1916 7864 2228 1916 7865 2233 1914 7866 2229 1909 7867 2230 1910 7868 2235 1917 7869 2234 1915 7870 2236 1918 7871 2232 1404 7872 2140 1404 7873 2137 1404 7874 2235 1917 7875 2233 1914 7876 2234 1915 7877 2235 1917 7878 2236 1918 7879 2237 1919 7880 2238 1920 7881 2237 1919 7882 2239 1921 7883 2238 1920 7884 2235 1917 7885 2237 1919 7886 2238 1920 7887 2239 1921 7888 2240 1922 7889 2241 1923 7890 2240 1922 7891 2242 1924 7892 2241 1923 7893 2238 1920 7894 2240 1922 7895 2241 1923 7896 2242 1924 7897 2243 1925 7898 2244 1926 7899 2243 1925 7900 2245 1927 7901 2244 1926 7902 2241 1923 7903 2243 1925 7904 2246 1928 7905 2245 1927 7906 2247 1929 7907 2246 1928 7908 2244 1926 7909 2245 1927 7910 2248 1930 7911 2247 1929 7912 2249 1931 7913 2248 1930 7914 2246 1928 7915 2247 1929 7916 2250 1932 7917 2249 1931 7918 2251 1933 7919 2250 1932 7920 2248 1930 7921 2249 1931 7922 2252 1934 7923 2251 1933 7924 2253 1935 7925 2252 1934 7926 2250 1932 7927 2251 1933 7928 2254 1936 7929 2253 1935 7930 2255 1937 7931 2254 1936 7932 2252 1934 7933 2253 1935 7934 2256 1938 7935 2255 1937 7936 2257 1939 7937 2256 1938 7938 2254 1936 7939 2255 1937 7940 2258 1940 7941 2257 1939 7942 2259 1941 7943 2258 1940 7944 2256 1938 7945 2257 1939 7946 2260 1942 7947 2259 1941 7948 2261 1943 7949 2260 1942 7950 2258 1940 7951 2259 1941 7952 2262 1944 7953 2261 1943 7954 2263 1945 7955 2262 1944 7956 2260 1942 7957 2261 1943 7958 2264 1946 7959 2263 1945 7960 2265 1947 7961 2264 1946 7962 2262 1944 7963 2263 1945 7964 2180 1404 7965 2266 1404 7966 2178 1404 7967 2267 1948 7968 2265 1947 7969 2268 1949 7970 2267 1948 7971 2264 1946 7972 2265 1947 7973 2269 1404 7974 2270 1404 7975 2266 1404 7976 2271 1950 7977 2268 1949 7978 2272 1951 7979 2180 1952 7980 2269 1952 7981 2266 1952 7982 2271 1950 7983 2267 1948 7984 2268 1949 7985 2273 1404 7986 2274 1404 7987 2270 1404 7988 2275 1953 7989 2272 1951 7990 2276 1954 7991 2269 1955 7992 2273 1955 7993 2270 1955 7994 2275 1953 7995 2271 1950 7996 2272 1951 7997 2273 1956 7998 2277 1956 7999 2274 1956 8000 2275 1953 8001 2276 1954 8002 2278 1957 8003 2279 1958 8004 2280 1959 8005 2281 1960 8006 2282 1961 8007 2275 1953 8008 2278 1957 8009 2283 1962 8010 2281 1960 8011 2284 1963 8012 2285 1964 8013 2279 1958 8014 2281 1960 8015 2283 1962 8016 2285 1964 8017 2281 1960 8018 2286 1965 8019 2284 1963 8020 2287 1966 8021 2286 1965 8022 2283 1962 8023 2284 1963 8024 2288 1967 8025 2287 1966 8026 2289 1968 8027 2288 1967 8028 2286 1965 8029 2287 1966 8030 2288 1967 8031 2289 1968 8032 2290 1969 8033 2291 1970 8034 2290 1969 8035 2292 1971 8036 2291 1970 8037 2288 1967 8038 2290 1969 8039 2291 1970 8040 2292 1971 8041 2293 1972 8042 2294 1973 8043 2293 1972 8044 2295 1974 8045 2294 1973 8046 2291 1970 8047 2293 1972 8048 2294 1973 8049 2295 1974 8050 2296 1975 8051 2297 1976 8052 2296 1975 8053 2298 1977 8054 2297 1976 8055 2294 1973 8056 2296 1975 8057 2299 1978 8058 2298 1977 8059 2300 1979 8060 2299 1978 8061 2297 1976 8062 2298 1977 8063 2301 1980 8064 2300 1979 8065 2302 1981 8066 2301 1980 8067 2299 1978 8068 2300 1979 8069 2303 1982 8070 2302 1981 8071 2304 1983 8072 2303 1982 8073 2301 1980 8074 2302 1981 8075 2305 1984 8076 2304 1983 8077 2306 1985 8078 2305 1984 8079 2303 1982 8080 2304 1983 8081 2307 1986 8082 2306 1985 8083 2308 1987 8084 2307 1986 8085 2305 1984 8086 2306 1985 8087 2309 1988 8088 2308 1987 8089 2310 1989 8090 2309 1988 8091 2307 1986 8092 2308 1987 8093 2311 1990 8094 2310 1989 8095 2312 1991 8096 2311 1990 8097 2309 1988 8098 2310 1989 8099 2313 1992 8100 2312 1991 8101 2314 1993 8102 2313 1992 8103 2311 1990 8104 2312 1991 8105 2315 1994 8106 2314 1993 8107 2316 1995 8108 2315 1994 8109 2313 1992 8110 2314 1993 8111 2317 1996 8112 2316 1995 8113 2318 1997 8114 2317 1996 8115 2315 1994 8116 2316 1995 8117 2319 1998 8118 2318 1997 8119 2320 1999 8120 2319 1998 8121 2317 1996 8122 2318 1997 8123 2321 2000 8124 2320 1999 8125 2322 2001 8126 2321 2000 8127 2319 1998 8128 2320 1999 8129 2223 1905 8130 2322 2001 8131 2224 1906 8132 2223 1905 8133 2321 2000 8134 2322 2001 8135 2323 308 8136 2324 308 8137 2325 308 8138 2326 308 8139 2325 308 8140 2327 308 8141 2323 2002 8142 2325 2002 8143 2326 2002 8144 2328 308 8145 2327 308 8146 2329 308 8147 2326 308 8148 2327 308 8149 2328 308 8150 2330 308 8151 2329 308 8152 2331 308 8153 2328 2003 8154 2329 2003 8155 2330 2003 8156 2330 308 8157 2331 308 8158 2332 308 8159 2333 2004 8160 2332 2004 8161 2334 2004 8162 2330 2005 8163 2332 2005 8164 2335 2005 8165 2333 2006 8166 2335 2006 8167 2332 2006 8168 2336 2007 8169 2334 2007 8170 2337 2007 8171 2338 308 8172 2333 308 8173 2334 308 8174 2339 2008 8175 2338 2008 8176 2334 2008 8177 2336 2009 8178 2339 2009 8179 2334 2009 8180 2340 308 8181 2337 308 8182 2341 308 8183 2342 308 8184 2336 308 8185 2337 308 8186 2340 2010 8187 2342 2010 8188 2337 2010 8189 2343 308 8190 2341 308 8191 2344 308 8192 2345 2011 8193 2340 2011 8194 2341 2011 8195 2343 308 8196 2345 308 8197 2341 308 8198 2346 2012 8199 2344 2012 8200 2347 2012 8201 2346 308 8202 2343 308 8203 2344 308 8204 2348 308 8205 2347 308 8206 2349 308 8207 2348 2013 8208 2346 2013 8209 2347 2013 8210 2350 308 8211 2349 308 8212 2351 308 8213 2352 2014 8214 2348 2014 8215 2349 2014 8216 2350 2015 8217 2352 2015 8218 2349 2015 8219 2353 308 8220 2351 308 8221 2354 308 8222 2353 2016 8223 2350 2016 8224 2351 2016 8225 2355 308 8226 2354 308 8227 2356 308 8228 2355 2017 8229 2353 2017 8230 2354 2017 8231 2357 308 8232 2356 308 8233 2358 308 8234 2357 308 8235 2355 308 8236 2356 308 8237 2359 308 8238 2358 308 8239 2360 308 8240 2361 308 8241 2357 308 8242 2358 308 8243 2359 308 8244 2361 308 8245 2358 308 8246 2362 308 8247 2360 308 8248 2363 308 8249 2364 2018 8250 2360 2018 8251 2362 2018 8252 2365 308 8253 2359 308 8254 2360 308 8255 2366 308 8256 2365 308 8257 2360 308 8258 2367 308 8259 2366 308 8260 2360 308 8261 2364 308 8262 2367 308 8263 2360 308 8264 2368 2019 8265 2363 2019 8266 2369 2019 8267 2370 308 8268 2363 308 8269 2368 308 8270 2362 2020 8271 2363 2020 8272 2370 2020 8273 2371 308 8274 2369 308 8275 2372 308 8276 2368 308 8277 2369 308 8278 2371 308 8279 2373 2021 8280 2372 2021 8281 2374 2021 8282 2371 308 8283 2372 308 8284 2373 308 8285 2373 308 8286 2374 308 8287 2375 308 8288 2364 2022 8289 2362 2022 8290 2376 2022 8291 2377 2023 8292 2376 2023 8293 2378 2023 8294 2379 308 8295 2364 308 8296 2376 308 8297 2380 2024 8298 2379 2024 8299 2376 2024 8300 2377 2025 8301 2380 2025 8302 2376 2025 8303 2381 308 8304 2378 308 8305 2382 308 8306 2383 308 8307 2377 308 8308 2378 308 8309 2381 2026 8310 2383 2026 8311 2378 2026 8312 2384 308 8313 2382 308 8314 2385 308 8315 2386 2027 8316 2381 2027 8317 2382 2027 8318 2384 308 8319 2386 308 8320 2382 308 8321 2387 2028 8322 2385 2028 8323 2388 2028 8324 2387 308 8325 2384 308 8326 2385 308 8327 2389 308 8328 2388 308 8329 2390 308 8330 2389 2029 8331 2387 2029 8332 2388 2029 8333 2391 308 8334 2390 308 8335 2392 308 8336 2393 2030 8337 2389 2030 8338 2390 2030 8339 2391 2031 8340 2393 2031 8341 2390 2031 8342 2394 308 8343 2392 308 8344 2395 308 8345 2394 2032 8346 2391 2032 8347 2392 2032 8348 2396 308 8349 2395 308 8350 2397 308 8351 2396 2033 8352 2394 2033 8353 2395 2033 8354 2398 308 8355 2397 308 8356 2399 308 8357 2398 308 8358 2396 308 8359 2397 308 8360 2400 308 8361 2399 308 8362 2335 308 8363 2401 308 8364 2398 308 8365 2399 308 8366 2400 308 8367 2401 308 8368 2399 308 8369 2402 308 8370 2335 308 8371 2333 308 8372 2403 308 8373 2400 308 8374 2335 308 8375 2404 308 8376 2403 308 8377 2335 308 8378 2402 308 8379 2404 308 8380 2335 308 8381 2405 2034 8382 2406 2035 8383 2407 2036 8384 2408 2037 8385 2409 2038 8386 2410 2039 8387 2408 2037 8388 2410 2039 8389 2411 2040 8390 2412 2041 8391 2407 2036 8392 2413 2042 8393 2414 2043 8394 2405 2034 8395 2407 2036 8396 2412 2041 8397 2414 2043 8398 2407 2036 8399 2415 2044 8400 2413 2042 8401 2416 2045 8402 2417 2046 8403 2412 2041 8404 2413 2042 8405 2415 2044 8406 2417 2046 8407 2413 2042 8408 2418 2047 8409 2416 2045 8410 2419 2048 8411 2418 2047 8412 2415 2044 8413 2416 2045 8414 2420 2049 8415 2419 2048 8416 2421 2050 8417 2420 2049 8418 2418 2047 8419 2419 2048 8420 2422 2051 8421 2421 2050 8422 2423 2052 8423 2422 2051 8424 2420 2049 8425 2421 2050 8426 2424 2053 8427 2423 2052 8428 2425 2054 8429 2424 2053 8430 2422 2051 8431 2423 2052 8432 2426 2055 8433 2425 2054 8434 2427 2056 8435 2426 2055 8436 2424 2053 8437 2425 2054 8438 2428 2057 8439 2427 2056 8440 2429 2058 8441 2428 2057 8442 2426 2055 8443 2427 2056 8444 2430 2059 8445 2429 2058 8446 2431 2060 8447 2430 2059 8448 2428 2057 8449 2429 2058 8450 2432 2061 8451 2431 2060 8452 2433 2062 8453 2432 2061 8454 2430 2059 8455 2431 2060 8456 2434 2063 8457 2433 2062 8458 2435 2064 8459 2434 2063 8460 2432 2061 8461 2433 2062 8462 2436 2065 8463 2435 2064 8464 2437 2066 8465 2436 2065 8466 2434 2063 8467 2435 2064 8468 2438 2067 8469 2437 2066 8470 2439 2068 8471 2438 2067 8472 2436 2065 8473 2437 2066 8474 2440 2069 8475 2439 2068 8476 2441 2070 8477 2440 2069 8478 2438 2067 8479 2439 2068 8480 2442 2071 8481 2441 2070 8482 2443 2072 8483 2442 2071 8484 2440 2069 8485 2441 2070 8486 2444 2073 8487 2443 2072 8488 2445 2074 8489 2444 2073 8490 2442 2071 8491 2443 2072 8492 2444 2073 8493 2445 2074 8494 2446 2075 8495 2447 2076 8496 2446 2075 8497 2448 2077 8498 2447 2076 8499 2444 2073 8500 2446 2075 8501 2447 2076 8502 2448 2077 8503 2449 2078 8504 2450 2079 8505 2451 2080 8506 2452 2081 8507 2453 2082 8508 2447 2076 8509 2449 2078 8510 2454 2083 8511 2452 2081 8512 2455 2084 8513 2456 2085 8514 2450 2079 8515 2452 2081 8516 2454 2083 8517 2456 2085 8518 2452 2081 8519 2457 2086 8520 2455 2084 8521 2458 2087 8522 2459 2088 8523 2454 2083 8524 2455 2084 8525 2457 2086 8526 2459 2088 8527 2455 2084 8528 2460 2089 8529 2458 2087 8530 2461 2090 8531 2460 2089 8532 2457 2086 8533 2458 2087 8534 2462 2091 8535 2461 2090 8536 2463 2092 8537 2462 2091 8538 2460 2089 8539 2461 2090 8540 2464 2093 8541 2463 2092 8542 2465 2094 8543 2464 2093 8544 2462 2091 8545 2463 2092 8546 2466 2095 8547 2465 2094 8548 2467 2096 8549 2466 2095 8550 2464 2093 8551 2465 2094 8552 2468 2097 8553 2467 2096 8554 2469 2098 8555 2468 2097 8556 2466 2095 8557 2467 2096 8558 2470 2099 8559 2469 2098 8560 2471 2100 8561 2470 2099 8562 2468 2097 8563 2469 2098 8564 2472 2101 8565 2471 2100 8566 2473 2102 8567 2472 2101 8568 2470 2099 8569 2471 2100 8570 2474 2103 8571 2473 2102 8572 2475 2104 8573 2474 2103 8574 2472 2101 8575 2473 2102 8576 2476 2105 8577 2475 2104 8578 2477 2106 8579 2476 2105 8580 2474 2103 8581 2475 2104 8582 2478 2107 8583 2477 2106 8584 2479 2108 8585 2478 2107 8586 2476 2105 8587 2477 2106 8588 2480 2109 8589 2479 2108 8590 2481 2110 8591 2480 2109 8592 2478 2107 8593 2479 2108 8594 2482 2111 8595 2481 2110 8596 2483 2112 8597 2482 2111 8598 2480 2109 8599 2481 2110 8600 2484 2113 8601 2483 2112 8602 2485 2114 8603 2484 2113 8604 2482 2111 8605 2483 2112 8606 2486 2115 8607 2485 2114 8608 2487 2116 8609 2486 2115 8610 2484 2113 8611 2485 2114 8612 2486 2115 8613 2487 2116 8614 2488 2117 8615 2408 2037 8616 2488 2117 8617 2409 2038 8618 2408 2037 8619 2486 2115 8620 2488 2117 8621 2489 2118 8622 2490 2118 8623 2491 2118 8624 2489 308 8625 2491 308 8626 2492 308 8627 2489 308 8628 2492 308 8629 2493 308 8630 2494 308 8631 2493 308 8632 2495 308 8633 2489 308 8634 2493 308 8635 2494 308 8636 2496 2119 8637 2495 2119 8638 2497 2119 8639 2494 2120 8640 2495 2120 8641 2496 2120 8642 2498 308 8643 2497 308 8644 2499 308 8645 2496 2121 8646 2497 2121 8647 2498 2121 8648 2500 308 8649 2499 308 8650 2501 308 8651 2498 308 8652 2499 308 8653 2500 308 8654 2502 308 8655 2501 308 8656 2503 308 8657 2500 2122 8658 2501 2122 8659 2502 2122 8660 2504 308 8661 2503 308 8662 2505 308 8663 2502 2123 8664 2503 2123 8665 2504 2123 8666 2506 308 8667 2505 308 8668 2507 308 8669 2504 2124 8670 2505 2124 8671 2506 2124 8672 2508 2125 8673 2507 2125 8674 2509 2125 8675 2506 2126 8676 2507 2126 8677 2508 2126 8678 2510 2127 8679 2509 2127 8680 2511 2127 8681 2508 2128 8682 2509 2128 8683 2510 2128 8684 2512 308 8685 2511 308 8686 2513 308 8687 2510 2129 8688 2511 2129 8689 2512 2129 8690 2514 308 8691 2513 308 8692 2515 308 8693 2512 2130 8694 2513 2130 8695 2514 2130 8696 2516 2131 8697 2515 2131 8698 2517 2131 8699 2514 2132 8700 2515 2132 8701 2516 2132 8702 2518 308 8703 2517 308 8704 2519 308 8705 2516 2133 8706 2517 2133 8707 2518 2133 8708 2520 2134 8709 2519 2134 8710 2521 2134 8711 2518 308 8712 2519 308 8713 2520 308 8714 2522 2135 8715 2521 2135 8716 2523 2135 8717 2520 2136 8718 2521 2136 8719 2522 2136 8720 2524 2137 8721 2523 2137 8722 2525 2137 8723 2522 308 8724 2523 308 8725 2524 308 8726 2526 308 8727 2525 308 8728 2527 308 8729 2528 308 8730 2525 308 8731 2526 308 8732 2524 308 8733 2525 308 8734 2528 308 8735 2529 896 8736 2530 896 8737 2531 896 8738 2532 2138 8739 2533 2138 8740 2534 2138 8741 2535 2139 8742 2534 2139 8743 2533 2139 8744 2529 896 8745 2531 896 8746 2536 896 8747 2537 2140 8748 2538 2140 8749 2539 2140 8750 2540 896 8751 2529 896 8752 2536 896 8753 2541 896 8754 2540 896 8755 2536 896 8756 2537 2141 8757 2539 2141 8758 2542 2141 8759 2543 2142 8760 2544 2143 8761 2545 2144 8762 2546 2145 8763 2545 2144 8764 2547 2146 8765 2543 2142 8766 2545 2144 8767 2546 2145 8768 2548 2147 8769 2547 2146 8770 2549 2148 8771 2546 2145 8772 2547 2146 8773 2548 2147 8774 2548 2147 8775 2549 2148 8776 2550 2149 8777 2551 2150 8778 2550 2149 8779 2552 2151 8780 2548 2147 8781 2550 2149 8782 2551 2150 8783 2551 2150 8784 2552 2151 8785 2553 2152 8786 2554 2153 8787 2553 2152 8788 2555 2154 8789 2551 2150 8790 2553 2152 8791 2554 2153 8792 2554 2153 8793 2555 2154 8794 2556 2155 8795 2557 2156 8796 2556 2155 8797 2558 2157 8798 2554 2153 8799 2556 2155 8800 2557 2156 8801 2557 2156 8802 2558 2157 8803 2559 2158 8804 2560 2159 8805 2559 2158 8806 2561 2160 8807 2557 2156 8808 2559 2158 8809 2560 2159 8810 2562 2161 8811 2561 2160 8812 2563 2162 8813 2560 2159 8814 2561 2160 8815 2562 2161 8816 2564 2163 8817 2563 2162 8818 2565 2164 8819 2562 2161 8820 2563 2162 8821 2564 2163 8822 2564 2163 8823 2565 2164 8824 2566 2165 8825 2564 2163 8826 2566 2165 8827 2567 2166 8828 2541 896 8829 2568 896 8830 2540 896 8831 2541 896 8832 2569 896 8833 2568 896 8834 2541 896 8835 2570 896 8836 2569 896 8837 2571 896 8838 2572 896 8839 2570 896 8840 2541 896 8841 2571 896 8842 2570 896 8843 2573 896 8844 2574 896 8845 2572 896 8846 2571 896 8847 2573 896 8848 2572 896 8849 2575 896 8850 2576 896 8851 1905 896 8852 1904 896 8853 2575 896 8854 1905 896 8855 2577 896 8856 2578 896 8857 1972 896 8858 1973 896 8859 2577 896 8860 1972 896 8861 2579 896 8862 2580 896 8863 2008 896 8864 2007 896 8865 2579 896 8866 2008 896 8867 2581 2167 8868 2582 2168 8869 2583 2169 8870 2584 2170 8871 2585 2171 8872 2586 2172 8873 2584 2170 8874 2586 2172 8875 2587 2173 8876 2588 2174 8877 2583 2169 8878 2589 2175 8879 2590 2176 8880 2581 2167 8881 2583 2169 8882 2588 2174 8883 2590 2176 8884 2583 2169 8885 2591 2177 8886 2589 2175 8887 2592 2178 8888 2591 2177 8889 2588 2174 8890 2589 2175 8891 2593 2179 8892 2592 2178 8893 2594 2180 8894 2593 2179 8895 2591 2177 8896 2592 2178 8897 2595 2181 8898 2594 2180 8899 2596 2182 8900 2595 2181 8901 2593 2179 8902 2594 2180 8903 2597 2183 8904 2596 2182 8905 2598 2184 8906 2597 2183 8907 2595 2181 8908 2596 2182 8909 2597 2183 8910 2598 2184 8911 2599 2185 8912 2600 2186 8913 2599 2185 8914 2601 2187 8915 2600 2186 8916 2597 2183 8917 2599 2185 8918 2602 2188 8919 2601 2187 8920 2603 2189 8921 2602 2188 8922 2600 2186 8923 2601 2187 8924 2604 2190 8925 2603 2189 8926 2605 2191 8927 2604 2190 8928 2602 2188 8929 2603 2189 8930 2606 2192 8931 2605 2191 8932 2607 2193 8933 2606 2192 8934 2604 2190 8935 2605 2191 8936 2608 2194 8937 2607 2193 8938 2609 2195 8939 2608 2194 8940 2606 2192 8941 2607 2193 8942 2610 2196 8943 2609 2195 8944 2611 2197 8945 2610 2196 8946 2608 2194 8947 2609 2195 8948 2612 2198 8949 2611 2197 8950 2613 2199 8951 2612 2198 8952 2610 2196 8953 2611 2197 8954 2614 2200 8955 2613 2199 8956 2615 2201 8957 2614 2200 8958 2612 2198 8959 2613 2199 8960 2616 2202 8961 2615 2201 8962 2617 2203 8963 2616 2202 8964 2614 2200 8965 2615 2201 8966 2618 2204 8967 2617 2203 8968 2619 2205 8969 2620 2206 8970 2616 2202 8971 2617 2203 8972 2618 2204 8973 2620 2206 8974 2617 2203 8975 2621 2207 8976 2619 2205 8977 2622 2208 8978 2621 2207 8979 2618 2204 8980 2619 2205 8981 2623 2209 8982 2622 2208 8983 2624 2210 8984 2623 2209 8985 2621 2207 8986 2622 2208 8987 2625 2211 8988 2624 2210 8989 2626 2212 8990 2625 2211 8991 2623 2209 8992 2624 2210 8993 2627 2213 8994 2626 2212 8995 2628 2214 8996 2627 2213 8997 2625 2211 8998 2626 2212 8999 2627 2213 9000 2628 2214 9001 2629 2215 9002 2630 2216 9003 2631 2217 9004 2632 2218 9005 2633 2219 9006 2627 2213 9007 2629 2215 9008 2634 2220 9009 2632 2218 9010 2635 2221 9011 2636 2222 9012 2630 2216 9013 2632 2218 9014 2634 2220 9015 2636 2222 9016 2632 2218 9017 2637 2223 9018 2635 2221 9019 2638 2224 9020 2637 2223 9021 2634 2220 9022 2635 2221 9023 2639 2225 9024 2638 2224 9025 2640 2226 9026 2639 2225 9027 2637 2223 9028 2638 2224 9029 2641 2227 9030 2640 2226 9031 2642 2228 9032 2641 2227 9033 2639 2225 9034 2640 2226 9035 2643 2229 9036 2642 2228 9037 2644 2230 9038 2643 2229 9039 2641 2227 9040 2642 2228 9041 2643 2229 9042 2644 2230 9043 2645 2231 9044 2646 2232 9045 2645 2231 9046 2647 2233 9047 2646 2232 9048 2643 2229 9049 2645 2231 9050 2648 2234 9051 2647 2233 9052 2649 2235 9053 2648 2234 9054 2646 2232 9055 2647 2233 9056 2650 2236 9057 2649 2235 9058 2651 2237 9059 2650 2236 9060 2648 2234 9061 2649 2235 9062 2652 2238 9063 2651 2237 9064 2653 2239 9065 2652 2238 9066 2650 2236 9067 2651 2237 9068 2654 2240 9069 2653 2239 9070 2655 2241 9071 2654 2240 9072 2652 2238 9073 2653 2239 9074 2656 2242 9075 2655 2241 9076 2657 2243 9077 2656 2242 9078 2654 2240 9079 2655 2241 9080 2658 2244 9081 2657 2243 9082 2659 2245 9083 2658 2244 9084 2656 2242 9085 2657 2243 9086 2660 2246 9087 2659 2245 9088 2661 2247 9089 2660 2246 9090 2658 2244 9091 2659 2245 9092 2662 2248 9093 2661 2247 9094 2663 2249 9095 2662 2248 9096 2660 2246 9097 2661 2247 9098 2664 2250 9099 2663 2249 9100 2665 2251 9101 2666 2252 9102 2662 2248 9103 2663 2249 9104 2664 2250 9105 2666 2252 9106 2663 2249 9107 2667 2253 9108 2665 2251 9109 2668 2254 9110 2667 2253 9111 2664 2250 9112 2665 2251 9113 2669 2255 9114 2668 2254 9115 2670 2256 9116 2669 2255 9117 2667 2253 9118 2668 2254 9119 2671 2257 9120 2670 2256 9121 2672 2258 9122 2671 2257 9123 2669 2255 9124 2670 2256 9125 2584 2170 9126 2672 2258 9127 2585 2171 9128 2584 2170 9129 2671 2257 9130 2672 2258 9131 2673 2259 9132 2674 2259 9133 2675 2259 9134 2676 24 9135 2674 24 9136 2673 24 9137 2677 2260 9138 2674 2260 9139 2676 2260 9140 2678 2261 9141 2675 2261 9142 2679 2261 9143 2673 2262 9144 2675 2262 9145 2678 2262 9146 2680 2263 9147 2679 2263 9148 2681 2263 9149 2678 24 9150 2679 24 9151 2680 24 9152 2682 2264 9153 2681 2264 9154 2683 2264 9155 2680 2265 9156 2681 2265 9157 2682 2265 9158 2684 2266 9159 2683 2266 9160 2685 2266 9161 2682 2267 9162 2683 2267 9163 2684 2267 9164 2686 2268 9165 2685 2268 9166 2687 2268 9167 2684 2269 9168 2685 2269 9169 2686 2269 9170 2688 2270 9171 2687 2270 9172 2689 2270 9173 2686 24 9174 2687 24 9175 2688 24 9176 2690 2271 9177 2689 2271 9178 2691 2271 9179 2692 24 9180 2689 24 9181 2690 24 9182 2688 2272 9183 2689 2272 9184 2692 2272 9185 2693 2273 9186 2691 2273 9187 2694 2273 9188 2690 24 9189 2691 24 9190 2693 24 9191 2695 2274 9192 2694 2274 9193 2696 2274 9194 2693 2275 9195 2694 2275 9196 2695 2275 9197 2695 2276 9198 2696 2276 9199 2697 2276 9200 2677 2277 9201 2676 2277 9202 2698 2277 9203 2699 2278 9204 2698 2278 9205 2700 2278 9206 2677 24 9207 2698 24 9208 2699 24 9209 2701 2279 9210 2700 2279 9211 2702 2279 9212 2699 2280 9213 2700 2280 9214 2701 2280 9215 2703 2281 9216 2702 2281 9217 2704 2281 9218 2701 2282 9219 2702 2282 9220 2703 2282 9221 2705 2283 9222 2704 2283 9223 2706 2283 9224 2703 2284 9225 2704 2284 9226 2705 2284 9227 2707 2285 9228 2706 2285 9229 2708 2285 9230 2705 24 9231 2706 24 9232 2707 24 9233 2709 2286 9234 2708 2286 9235 2710 2286 9236 2711 24 9237 2708 24 9238 2709 24 9239 2707 2287 9240 2708 2287 9241 2711 2287 9242 2712 2288 9243 2710 2288 9244 2713 2288 9245 2709 24 9246 2710 24 9247 2712 24 9248 2714 2289 9249 2713 2289 9250 2715 2289 9251 2712 2290 9252 2713 2290 9253 2714 2290 9254 2714 2291 9255 2715 2291 9256 2716 2291 9257 1686 896 9258 2717 896 9259 1685 896 9260 2718 896 9261 2719 896 9262 973 896 9263 972 896 9264 2718 896 9265 973 896 9266 2720 896 9267 2721 896 9268 2719 896 9269 2718 896 9270 2720 896 9271 2719 896 9272 2722 896 9273 2723 896 9274 2721 896 9275 2720 896 9276 2722 896 9277 2721 896 9278 2722 896 9279 2724 896 9280 2723 896 9281 1228 896 9282 2725 896 9283 1194 896 9284 1228 896 9285 2726 896 9286 2725 896 9287 2727 896 9288 2728 896 9289 2726 896 9290 1228 896 9291 2727 896 9292 2726 896 9293 2729 896 9294 2730 896 9295 2728 896 9296 2727 896 9297 2729 896 9298 2728 896 9299 2731 896 9300 2732 896 9301 2730 896 9302 2729 896 9303 2731 896 9304 2730 896 9305 1559 896 9306 1557 896 9307 2733 896 9308 2734 896 9309 2733 896 9310 2735 896 9311 2736 896 9312 2733 896 9313 2734 896 9314 1559 896 9315 2733 896 9316 2736 896 9317 2737 896 9318 2735 896 9319 2738 896 9320 2734 896 9321 2735 896 9322 2737 896 9323 2737 896 9324 2738 896 9325 2739 896 9326 1511 896 9327 1510 896 9328 2740 896 9329 2741 896 9330 2740 896 9331 2742 896 9332 1511 896 9333 2740 896 9334 2741 896 9335 2743 896 9336 2742 896 9337 2744 896 9338 2741 896 9339 2742 896 9340 2743 896 9341 1339 896 9342 2745 896 9343 1338 896 9344 1339 896 9345 2746 896 9346 2745 896 9347 2747 896 9348 2748 896 9349 2746 896 9350 1339 896 9351 2747 896 9352 2746 896 9353 2749 896 9354 2750 896 9355 2748 896 9356 2747 896 9357 2749 896 9358 2748 896 9359 2751 2292 9360 2752 2292 9361 2753 2292 9362 2754 896 9363 2752 896 9364 2751 896 9365 2755 2293 9366 2752 2293 9367 2754 2293 9368 2756 896 9369 2753 896 9370 2757 896 9371 2758 896 9372 2753 896 9373 2756 896 9374 2751 2294 9375 2753 2294 9376 2758 2294 9377 2759 896 9378 2757 896 9379 2760 896 9380 2756 2295 9381 2757 2295 9382 2759 2295 9383 2761 896 9384 2760 896 9385 2762 896 9386 2759 896 9387 2760 896 9388 2761 896 9389 2763 896 9390 2762 896 9391 2764 896 9392 2761 896 9393 2762 896 9394 2763 896 9395 2765 2296 9396 2754 2296 9397 2766 2296 9398 2755 896 9399 2754 896 9400 2765 896 9401 1400 896 9402 2766 896 9403 1401 896 9404 2765 896 9405 2766 896 9406 1400 896 9407 2767 358 9408 2768 358 9409 2769 358 9410 2770 2297 9411 2771 2297 9412 2772 2297 9413 2773 358 9414 2767 358 9415 2769 358 9416 2774 358 9417 2773 358 9418 2769 358 9419 2775 2298 9420 2776 2298 9421 2777 2299 9422 2775 2298 9423 2777 2299 9424 2778 2299 9425 2779 358 9426 2780 358 9427 2768 358 9428 2781 2300 9429 2782 2300 9430 2783 2301 9431 2767 358 9432 2779 358 9433 2768 358 9434 2784 2302 9435 2770 2302 9436 2772 2302 9437 2779 358 9438 2785 358 9439 2780 358 9440 2786 2301 9441 2783 2301 9442 2787 2303 9443 2786 2301 9444 2781 2300 9445 2783 2301 9446 2788 2303 9447 2787 2303 9448 2789 2304 9449 2786 2301 9450 2787 2303 9451 2788 2303 9452 2790 2304 9453 2789 2304 9454 2791 2305 9455 2790 2304 9456 2788 2303 9457 2789 2304 9458 2792 2306 9459 2793 2306 9460 2794 2306 9461 2790 2304 9462 2791 2305 9463 2795 2305 9464 2774 358 9465 2796 358 9466 2773 358 9467 2797 2307 9468 2798 2307 9469 2799 2308 9470 2792 2309 9471 2794 2309 9472 2800 2309 9473 2801 358 9474 2802 358 9475 2796 358 9476 2803 2308 9477 2799 2308 9478 2804 2310 9479 2774 358 9480 2801 358 9481 2796 358 9482 2803 2308 9483 2797 2307 9484 2799 2308 9485 2805 358 9486 2806 358 9487 2802 358 9488 2807 308 9489 2808 308 9490 2809 308 9491 2801 358 9492 2805 358 9493 2802 358 9494 2803 2308 9495 2804 2310 9496 2810 2310 9497 2811 358 9498 2812 358 9499 2806 358 9500 2813 2311 9501 2814 2311 9502 2815 2312 9503 2805 358 9504 2811 358 9505 2806 358 9506 2807 308 9507 2809 308 9508 2816 308 9509 2817 358 9510 2818 358 9511 2812 358 9512 2819 2312 9513 2815 2312 9514 2820 2313 9515 2811 358 9516 2817 358 9517 2812 358 9518 2819 2312 9519 2813 2311 9520 2815 2312 9521 2821 358 9522 2822 358 9523 2818 358 9524 2823 2314 9525 2824 2314 9526 2825 2314 9527 2817 358 9528 2821 358 9529 2818 358 9530 2819 2312 9531 2820 2313 9532 2826 2313 9533 2827 358 9534 2828 358 9535 2822 358 9536 2829 2315 9537 2830 2315 9538 2831 2316 9539 2821 358 9540 2827 358 9541 2822 358 9542 2823 2317 9543 2825 2317 9544 2832 2317 9545 2827 358 9546 2833 358 9547 2828 358 9548 2834 2316 9549 2831 2316 9550 2835 24 9551 2834 2316 9552 2829 2315 9553 2831 2316 9554 2836 24 9555 2835 24 9556 2837 2318 9557 2836 24 9558 2834 2316 9559 2835 24 9560 2838 2318 9561 2837 2318 9562 2839 2319 9563 2838 2318 9564 2836 24 9565 2837 2318 9566 2840 2320 9567 2841 2320 9568 2842 2320 9569 2838 2318 9570 2839 2319 9571 2843 2319 9572 2844 2321 9573 2845 2321 9574 2846 2322 9575 2840 2323 9576 2842 2323 9577 2847 2323 9578 2848 2322 9579 2846 2322 9580 2849 2324 9581 2848 2322 9582 2844 2321 9583 2846 2322 9584 2850 1404 9585 2851 1404 9586 2852 1404 9587 2848 2322 9588 2849 2324 9589 2853 2324 9590 2854 2325 9591 2855 2325 9592 2776 2298 9593 2850 1404 9594 2852 1404 9595 2856 1404 9596 2775 2298 9597 2854 2325 9598 2776 2298 9599 2857 896 9600 2858 896 9601 2859 896 9602 2860 896 9603 2861 896 9604 2858 896 9605 2857 2326 9606 2860 2326 9607 2858 2326 9608 2862 2327 9609 2863 2327 9610 2859 2327 9611 2864 896 9612 2859 896 9613 2863 896 9614 2865 896 9615 2862 896 9616 2859 896 9617 2866 896 9618 2857 896 9619 2859 896 9620 2864 896 9621 2866 896 9622 2859 896 9623 2860 2328 9624 2867 2328 9625 2861 2328 9626 2868 896 9627 2869 896 9628 2867 896 9629 2870 896 9630 2868 896 9631 2867 896 9632 2860 896 9633 2870 896 9634 2867 896 9635 2871 2329 9636 2872 2329 9637 2869 2329 9638 2868 2330 9639 2871 2330 9640 2869 2330 9641 2873 2331 9642 2874 2331 9643 2872 2331 9644 2875 2332 9645 2876 2332 9646 2874 2332 9647 2877 2333 9648 2875 2333 9649 2874 2333 9650 2873 2334 9651 2877 2334 9652 2874 2334 9653 2871 896 9654 2873 896 9655 2872 896 9656 2878 896 9657 2876 896 9658 2875 896 9659 2879 896 9660 2876 896 9661 2878 896 9662 2880 896 9663 2881 896 9664 2875 896 9665 2882 896 9666 2875 896 9667 2877 896 9668 2882 896 9669 2880 896 9670 2875 896 9671 2879 896 9672 2878 896 9673 2883 896 9674 2884 2335 9675 2885 2335 9676 2881 2335 9677 2880 896 9678 2884 896 9679 2881 896 9680 2884 2336 9681 2886 2336 9682 2885 2336 9683 2887 896 9684 2888 896 9685 2886 896 9686 2889 896 9687 2887 896 9688 2886 896 9689 2884 896 9690 2889 896 9691 2886 896 9692 2890 2337 9693 2891 2337 9694 2888 2337 9695 2887 896 9696 2890 896 9697 2888 896 9698 2892 2338 9699 2863 2338 9700 2891 2338 9701 2892 896 9702 2864 896 9703 2863 896 9704 2890 896 9705 2892 896 9706 2891 896 9707 2865 2339 9708 2893 2339 9709 2862 2339 9710 2865 896 9711 2894 896 9712 2893 896 9713 2895 2340 9714 2896 2341 9715 2897 2342 9716 2898 2343 9717 2899 2344 9718 2900 2345 9719 2898 2343 9720 2900 2345 9721 2901 2346 9722 2902 2347 9723 2897 2342 9724 2903 2348 9725 2904 2349 9726 2895 2340 9727 2897 2342 9728 2902 2347 9729 2904 2349 9730 2897 2342 9731 2905 2350 9732 2903 2348 9733 2906 2351 9734 2905 2350 9735 2902 2347 9736 2903 2348 9737 2907 2352 9738 2906 2351 9739 2908 2353 9740 2907 2352 9741 2905 2350 9742 2906 2351 9743 2909 2354 9744 2908 2353 9745 2910 2355 9746 2909 2354 9747 2907 2352 9748 2908 2353 9749 2911 2356 9750 2910 2355 9751 2912 2357 9752 2911 2356 9753 2909 2354 9754 2910 2355 9755 2913 2358 9756 2912 2357 9757 2914 2359 9758 2913 2358 9759 2911 2356 9760 2912 2357 9761 2913 2358 9762 2914 2359 9763 2915 2360 9764 2916 2361 9765 2917 2362 9766 2918 2363 9767 2919 2364 9768 2913 2358 9769 2915 2360 9770 2920 2365 9771 2918 2363 9772 2921 2366 9773 2922 2367 9774 2916 2361 9775 2918 2363 9776 2920 2365 9777 2922 2367 9778 2918 2363 9779 2923 2368 9780 2921 2366 9781 2924 2369 9782 2923 2368 9783 2920 2365 9784 2921 2366 9785 2925 2370 9786 2924 2369 9787 2926 2371 9788 2925 2370 9789 2923 2368 9790 2924 2369 9791 2927 2372 9792 2926 2371 9793 2928 2373 9794 2927 2372 9795 2925 2370 9796 2926 2371 9797 2929 2374 9798 2928 2373 9799 2930 2375 9800 2929 2374 9801 2927 2372 9802 2928 2373 9803 2898 2343 9804 2930 2375 9805 2899 2344 9806 2898 2343 9807 2929 2374 9808 2930 2375 9809 2931 2376 9810 2932 2376 9811 2933 2376 9812 2931 2377 9813 2933 2377 9814 2934 2377 9815 2935 896 9816 2934 896 9817 2936 896 9818 2935 896 9819 2931 896 9820 2934 896 9821 2937 896 9822 2936 896 9823 2938 896 9824 2939 896 9825 2935 896 9826 2936 896 9827 2937 896 9828 2939 896 9829 2936 896 9830 2940 896 9831 2938 896 9832 2941 896 9833 2942 896 9834 2937 896 9835 2938 896 9836 2940 896 9837 2942 896 9838 2938 896 9839 2943 896 9840 2941 896 9841 2944 896 9842 2945 896 9843 2940 896 9844 2941 896 9845 2943 896 9846 2945 896 9847 2941 896 9848 2946 896 9849 2944 896 9850 2947 896 9851 2946 896 9852 2943 896 9853 2944 896 9854 2948 2378 9855 2947 2378 9856 2949 2378 9857 2950 896 9858 2947 896 9859 2948 896 9860 2951 896 9861 2947 896 9862 2950 896 9863 2951 896 9864 2946 896 9865 2947 896 9866 2951 2379 9867 2950 2379 9868 2952 2379 9869 2953 896 9870 2952 896 9871 2954 896 9872 2955 896 9873 2951 896 9874 2952 896 9875 2953 896 9876 2955 896 9877 2952 896 9878 2956 896 9879 2954 896 9880 2957 896 9881 2958 896 9882 2953 896 9883 2954 896 9884 2956 896 9885 2958 896 9886 2954 896 9887 2959 896 9888 2957 896 9889 2960 896 9890 2961 896 9891 2956 896 9892 2957 896 9893 2959 896 9894 2961 896 9895 2957 896 9896 2962 896 9897 2960 896 9898 2931 896 9899 2962 896 9900 2959 896 9901 2960 896 9902 2962 896 9903 2931 896 9904 2935 896 9905 2963 2380 9906 2964 2381 9907 2965 2382 9908 2966 2383 9909 2967 2384 9910 2968 2385 9911 2966 2383 9912 2968 2385 9913 2969 2386 9914 2970 2387 9915 2965 2382 9916 2971 2388 9917 2970 2387 9918 2963 2380 9919 2965 2382 9920 2972 2389 9921 2971 2388 9922 2973 2390 9923 2972 2389 9924 2970 2387 9925 2971 2388 9926 2972 2389 9927 2973 2390 9928 2974 2391 9929 2975 2392 9930 2974 2391 9931 2976 2393 9932 2975 2392 9933 2972 2389 9934 2974 2391 9935 2977 2394 9936 2976 2393 9937 2978 2395 9938 2977 2394 9939 2975 2392 9940 2976 2393 9941 2979 2396 9942 2978 2395 9943 2980 2397 9944 2981 2398 9945 2977 2394 9946 2978 2395 9947 2979 2396 9948 2981 2398 9949 2978 2395 9950 2982 2399 9951 2980 2397 9952 2983 2400 9953 2982 2399 9954 2979 2396 9955 2980 2397 9956 2984 2401 9957 2985 2402 9958 2986 2403 9959 2987 2404 9960 2982 2399 9961 2983 2400 9962 2988 2405 9963 2986 2403 9964 2989 2406 9965 2988 2405 9966 2984 2401 9967 2986 2403 9968 2990 2407 9969 2989 2406 9970 2991 2408 9971 2990 2407 9972 2988 2405 9973 2989 2406 9974 2990 2407 9975 2991 2408 9976 2992 2409 9977 2993 2410 9978 2992 2409 9979 2994 2411 9980 2993 2410 9981 2990 2407 9982 2992 2409 9983 2995 2412 9984 2994 2411 9985 2996 2413 9986 2995 2412 9987 2993 2410 9988 2994 2411 9989 2997 2414 9990 2996 2413 9991 2967 2384 9992 2998 2415 9993 2995 2412 9994 2996 2413 9995 2997 2414 9996 2998 2415 9997 2996 2413 9998 2966 2383 9999 2997 2414 10000 2967 2384 10001 2999 896 10002 3000 896 10003 3001 896 10004 3002 2416 10005 3001 2416 10006 3003 2416 10007 2999 896 10008 3001 896 10009 3002 896 10010 3004 2417 10011 3003 2417 10012 3005 2417 10013 3002 896 10014 3003 896 10015 3004 896 10016 3006 896 10017 3005 896 10018 3007 896 10019 3008 896 10020 3005 896 10021 3006 896 10022 3004 2418 10023 3005 2418 10024 3008 2418 10025 3006 2419 10026 3007 2419 10027 3009 2419 10028 3010 2420 10029 3009 2420 10030 3011 2420 10031 3006 896 10032 3009 896 10033 3010 896 10034 3012 896 10035 3011 896 10036 3013 896 10037 3010 896 10038 3011 896 10039 3012 896 10040 3012 896 10041 3013 896 10042 3014 896 10043

+
+
+
+
+ + + + + -4.37108e-11 -1.62919e-10 -9.99987e-4 0 -9.99987e-4 -2.98019e-11 4.37108e-11 0 -2.98019e-11 9.99987e-4 -1.62919e-10 -0.2604 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl new file mode 100644 index 0000000000000000000000000000000000000000..6b12b270c95d7c36209551d9a87d81f3a5333232 GIT binary patch literal 17884 zcmb81d3aPs*2WKtvZ#nG3L=sZbp}SAK@z~FZ#Vj>K_cp)jsh|e2>WUXK{iDMF>zzx zkzEBvwt%9!-8zb95S0L;IDjZ9IOsP91RPPB_f*~Les7yU=Hq#IQsmU{oLWv*omwup zJT!DjenGFijNbV}24&ndu-D+cUinwI{9~KzGMWt=-Xo($bNPS$$*bbBk4tFkvYf4v zJ9oV6FP&THmFC=K(v!a$@2O0GU#oDUN$bBY!IHak?kd$>(?A?;ztyByL6hduKjRYZ zbBDKPN$Z??z7iSVclBz-BPQKE9szNv-n`b%21}}a-__*ml2gx{Key2D0Qy#x+FEb~ zOP>8|yvbGd_PZh|ze#WF@OWm5=$m`I6-%ZD#5mMvMPQ?P&el>UhPP(P#VD1Qq%G>x z6!p+_9sEoYnqo;ujvP=DS=?eo4U z6-%^K>R0VhA1$q>^=HaP``qKE9!`Stn_P84@+e3Vno5@_t#x3Z7J0fyUMnrt*@fOl zmareQhlXviguRmeEk#5Z{JeoB>|^XbDMC{$VUJ;7ND+4|7}JU+-2dFODPqimF(oYF ze&&7>dAQ~+P1!o3!5^|>#sU8%$?O`a)X3AZ%2p)J+v(~l&kH+d$DCERY@BB^>z zX;P~dOSl!dej*=z{AHHfSlFc229|K0xU?d(du5bpJsuc!WIao`glt>n;r$aZYmH01 zIj=m`tRCzKNU*nj_84L-to;cFE1b_ z_wN+hxxC0LSTn$P^ty$qwAEAxHU@!s`{pOtJH4u_GTIV1ESesz`BTAfO2syoZ`~D{ zvFuT=_tyR>)wM*h#HCfQqpgkaI#)zzZO%0|rXFeJ?d#Of)RqaCwl;Qym>&@5=6@S$ zF>b7Pd;UP*(Y-qNOs1`k3%gWAp8`?qP@Pt+t1{XWv->oSoq6z<-;|1Ne3^f%r+>GU z_e9O-fH)%{SmM&E*U{F7=AI8q`(i(8Jq5K_2@@`DZL|c@9mLG)OETwo>fsF=cDWZh zJjmBJQ~LTJ`uVI0tIUC0Vv9gbIkluE>tZ@gJd1X!j`n({Wg?R$Y(x87+p)a4dZPB; zx9AhC2TNR9>%^Kw&WBGmgr_i}xg4Q-bp#y4NGP4z8#dGny?|heOEax$k-_lvCh&N* zp(E%mf9*9YVZx=Y4ILZj2gKgR#onv=H6j;m8t6MZ>$3jIbjrq-(lW2-&U3O@S7o#% z)W+%3GSo;!i9=Pol&Zwp;I!Hk83JNYKm>YAwN#GQvb(gkq4P)^zs&!nqI0IxtGX(q zEm0e-TW`^HGuyB(msT4y(dUb{?kfGz^!Yg;G6RAoF0FbUZEZ}per0TME|*rlfsgs> z#~4u{zU*8PFM=nsB=99)^*Y+xsEYA1vrp5+^pguS18+CEm|#sJ)j-Swq5Tnz313H) zqd&mdc4=$lauE3-qIFi5u&&BzOX$pik{KJU%ca$Zj$V|~?}NF^&Lw9B1WR06^*Y+x z_zL51_U2q;1HBYMyO^3Y;nLPdeLE)_f+epuJ{h^<`BDDPW&?buY0vw^P^u%aF*C5i z1m|*TTdLn<#Gd<8fw8gAu4<-KoXe%HjY~n)0uj6Kjdi+)KRtB3iG=qD^sKStebyv$ z8;EKkhJL%T73*R;Oz1j@F_O6O`4?NZeJ`;NW5kq-bFn>@nYGU7Qu@)NB2y~P#r8xZo67u= zfeqbrOhKu1&*A79Xe*bt{V@YJFasr47QdFox+uNnVVDwK5{EGFuwAvH- zD~PHAp|MXfdQkUEj{X?FlkP@Wi=C8u`01a#X^4 zU0Usl{0L$ih@%4@Y|WA`Q>yzvtR3br$;$JcrZ+CoRqa$jaLrX0=W=OVss)%8ssy8! zB`&RckL2I#{{w%w{$F3%m;vJKfMAJBt6oQ28+DL-QZQeAjapAa?N!2rOIsUCJP{E4 z6Sw;Xo1^~Y_YCwMJ*GqdWZK%moS4vARBO(<|EY_r`5oRJ=sWtJ*YlETYhyYH?UVNkyb`BZbyY@Nq8@ze#6r8OIlU@z zX|+*~QMLwaaEpZYxz0Qdf>n(rF3q&Hp|irr!RpMpTw3+&4AHjUGntEz4}=XJfBy^! zmbkR)b+olH0K_k;NXF<=i6d0+hp5L5XLN~NY3iZ#2*$dnJ;)N5X4=}&S^AnFzT#Xi zt$L@RXWz%#(iQCn#UKg-f+a4kdL3oNW*GwM?)kk$;20$c<^AcU%5)>G53?yi0Qj`;P9J+bfy2Ha-W@0K}ok zUMOK*mC=^?7UNIjYPI3?s>G$$hRQI)JiFUI1VVQd`dj^zlBD+MjJ1?8t5-f2$FSVg@yY9SfJ(ysL zwgB&`+)hU1b1D_@0XSCYh+Jd`5iH>t*F~JRR7+2E#i_Hc2TNQ8sJS?v6FHOmgC!ha zxk$#^0Fi86mbmyqbA?yuC#fDRajU2jZtb!*-a4^2Sr3-DHA-`ZSA$(-gC%Y?P$E3< zau2e^&5ugBS;>})36}8u5gzAEu!P5X`Y3Qrczm$uvroI+`g2@@CG5xSp(4K@pOiC068!X}e=bjDQUb*?`EN8#7~tHx$JirxBdX&5!nk z6AH+kEqIi!qf^)HL zk*=%y#PVR{s%9(VY@JIrWyl8a)CWgOJ6Q!O z{v+6n%tk#x_$lJzhIJFSt%=2+hK)^!x0im58W*MrPl*mUclT%iWv*v!{It7zETd_5 zY-p-fp7uxStg^`c$W>|yFGajRqC;$RcKyWYWfEUmG0H2eKGr|umDQzOr*J*CfOro? zM-VL08$TW*RJ*exJ^{qrd0~Qc=^fjrOGf$j7P%^H zJPzW2V51FgC=b6l+}t%^@yd6lZ_OF)_jzTI$F_0*0b(?W^FgpKro#kARN|o0&+jfmDy|1~0V@8+mi-w-=H zUl%*lH#@oyHAfGckqU43;O!o~U47U4ab`R7`(yBH^f^j&R=@1%2J|9JSg-b=j+^(< ziy}V{I~9$t-56apI44A~4W>nU<(5ZB?$3x_fO>E)u2Yz3wyNAOxO;K*EtHBSL5rI9 z370C~pl$q{t#xCoQ7R_5t(X?M20i$2cKz6eC>7`8z6ld=E?QyE7|Kv8mIP_zmEltT zxo;ygqMkyjn5d-B4K4B|yksP1IQ0_F#oo^LM6|7j-@Q1lZN-wH6@2xKaH(!=*f#$8 z*1Cz8Ql&E1+1vG&v|YTwx9>7`qjf7lyZ}O9Z{#!@YF=-Q?K9$yIyFc5m#&}SJki(_ zc^||95Np$HuwK?A@*;@CAhZX$9-NEol=R)W`Yub@kHa+&d^fJX%S7Onx*DX74;@hl z`)0>=L~$-2U2IRJ)!RK|jqX_-{bREgQJ%@z^O+WT2BoR{LEYFl4cdkXo)eiCY1FW8 ztR2>En-R4grD7sTn^m7_6Emm{ zjQ|{Ba`A`?6G0EgsRs?gy~e(PlhhOQqq+_rSSF$V;FkVP>qdjtjdKs8eUdQ)(;|I0 zZHWXu80TEjn~YJy1lHOFVuo0uEmg8VxZSvKj3*}46Tik-KxjPV*{kk6+;1S79eXOu`KJ7zlkkcIe`vzP=q}d#p)h8i;DJaVpJ*zDRL;SrcAz zAbM@TCYG3x>JL-i9UY^7pPVuN58JNy^%YwE>cjmQA{~*&AZ`S)5CluO9^q0UPBbS` zh!fp>WyS~EN+a(GyzpfnD`wOh0;4t_s^xzKC6-!U;`m^gsl z#6Zj?h?d;0$mC)=*iD#wb$C07u92c>+cbi6xqX}6u?TivXTe4-5W(Kbyn5jG3|vBy zZ(ySvht#)- zIf!u}5GRIgu->%($SseLwefC(XJ#ihlo z7qr#V{TYeFDH~=MHdrs0R%8`+5!iXf)?wb|8uFaz?sV*n#=*a9 z8;v09TRJEw;m*JH{U-MyYZ7@GHVy_hSQpb_;sdN78CVVSv3_v-xKn3cKX`P(U$B1s zY3;`NO4NfTTyxeW@r!eow3E{fNT!EjXeY@AQ3zew7A0@ht$}6UE+I*`VYw z2$tx(aE*}kojbn~$7|fchQ2sVC)`VNwvE?Rc=e)ws_)|Tr+W*o=}*2YFz>>7A1#s{ z+|LgM!4lpHYg#qwHx#&Cf{p6OHfHJ_VLFk@#kMB~FD&prBXr`$XIYw7+Mba;9T2rZ zu!O(O;L|UW3l`cpmThoX&)*pEDux*Se zw2|7Vk2fZ~YvA1kzje1SQk1v|1WT0Gn(OX`HHj<1_mehCPc@F?QZCGrA@ zPOWN`tVkm`7u&Wkm#g+0l$C`Zf`cSQLq& zH2NEzOZY1Ye%I%2N$uOgZqHfb&mdUB?-Tj!Dv{Q(;bZnu8|j3O4?S;S+al-2?P|~; zZ=_f+zlYSc(x?Ykjt7GELtk#OgiFGjQmw1+uvjn8yWu%;6JC*PTj_f;mask6Byt{R zxSV}8vh<}8f7Qk(2ppH4dQocHdrrfvNtB!L7LkomLT@gdmN*e&#y(E3sz^$ zqM^M3NBaCNp$NXqFs=J5`h_Lj2i!Lz?{=t&4#BBfd&Jbij@Q?F&Kt{PUTu5(X6E{R zxK~4|;k(VScYX$h?&vj^(t9?4C44TbX|<;(tk%Yi zDa9ptSN$8p8Z7coimu-va zcP!dg_?9KAWp?o=?^wdS32h@Kt_Hypj!Rh+)<48m-S*WenFjyjy$tVhcTsG56`=fI2Qy z=WV{uOl*QDzGOWyDdF*`X*Yr~*Ws<&b=cPqNxfAwF&yvocyEZ}d}dy^CH@M6XB?ha z!m-bB*ti@v9t6RBK4IfEQKT5e`5-bt@Or1C%e{x=n?{jI zAT9>64QH2ZgY~i|5q-5&55$)sSi*W)6aL=^+@*HJsq<~9Ij@6Sb9bJ|b;AGkftMUN R;r11;4MXRNtd}*3{0EBqy08EM literal 0 HcmV?d00001 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae new file mode 100644 index 0000000000..4c18808193 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae @@ -0,0 +1,181 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T14:39:21 + 2019-01-15T14:39:21 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.31 0.33 0.33 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.973 0.71 0 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + + + + + + + 147.1821 586.3167 -51.70481 141.8451 593.5132 -51.54813 148.0296 587.1405 -51.83827 151.8905 591.4855 -51.78149 148.0296 587.1405 -51.83827 141.8451 593.5132 -51.54813 154.4627 579.7385 -52.16218 147.1821 586.3167 -51.70481 148.0296 587.1405 -51.83827 157.3284 581.1897 -52.17074 154.4627 579.7385 -52.16218 135.6829 599.8162 -51.26036 135.6829 599.8162 -51.26036 135.0501 599.1939 -51.18709 133.4308 600.8645 -51.12577 135.6829 599.8162 -51.26036 135.0501 599.1939 -51.18709 133.9128 601.5067 -51.18113 133.9128 601.5067 -51.18113 134.8133 598.9592 -51.11772 132.8595 599.439 -50.69397 134.8133 598.9592 -51.11772 140.1886 591.8713 -50.99227 134.0013 598.1451 -50.68305 134.0013 598.1451 -50.68305 146.3874 585.5314 -51.29747 144.1774 583.6867 -49.7794 134.0013 598.1451 -50.68305 140.1886 591.8713 -50.99227 134.6165 595.5949 -50.03851 131.8069 597.9547 -49.89383 134.0013 598.1451 -50.68305 134.6165 595.5949 -50.03851 132.8595 599.439 -50.69397 146.3874 585.5314 -51.29747 153.6216 578.911 -52.03116 146.3874 585.5314 -51.29747 152.7586 578.2153 -51.6268 155.6281 574.2968 -51.78174 146.3874 585.5314 -51.29747 152.7586 578.2153 -51.6268 144.1774 583.6867 -49.7794 159.2641 570.7716 -52.35687 162.8215 567.0674 -52.67032 165.2659 562.3912 -52.84667 172.9984 550.0427 -53.33465 165.2659 562.3912 -52.84667 162.8215 567.0674 -52.67032 164.1523 561.8378 -52.68573 166.9693 556.039 -52.89651 164.1523 561.8378 -52.68573 165.2659 562.3912 -52.84667 167.53 556.3164 -53.01939 166.6854 559.4944 -52.95425 166.6854 559.4944 -52.95425 160.2062 571.5173 -52.49746 162.6554 570.8572 -52.5591 160.2062 571.5173 -52.49746 158.3187 570.1608 -51.93267 155.6281 574.2968 -51.78174 163.1142 561.3106 -52.22069 164.5175 558.413 -52.31974 163.1142 561.3106 -52.22069 165.9166 555.5091 -52.41862 166.4283 555.7683 -52.69495 158.3187 570.1608 -51.93267 163.1142 561.3106 -52.22069 153.4136 572.1343 -50.17359 164.6611 550.312 -50.55076 163.1142 561.3106 -52.22069 164.5175 558.413 -52.31974 161.0109 559.1158 -50.62105 161.0109 559.1158 -50.62105 168.0995 556.595 -53.06182 168.0995 556.595 -53.06182 171.2369 548.7321 -53.34135 167.53 556.3164 -53.01939 168.0995 556.595 -53.06182 171.2369 548.7321 -53.34135 165.9166 555.5091 -52.41862 169.5452 546.6098 -52.83352 165.9166 555.5091 -52.41862 166.4283 555.7683 -52.69495 168.5294 547.8276 -52.4199 164.6611 550.312 -50.55076 165.9166 555.5091 -52.41862 168.5294 547.8276 -52.4199 170.2308 546.8281 -53.1365 166.9693 556.039 -52.89651 170.9542 547.0538 -53.32364 173.5952 507.5234 -54.38581 174.2601 503.0798 -54.69903 173.1549 497.0505 -54.85206 170.8541 471.9127 -55.5304 173.1549 497.0505 -54.85206 174.2601 503.0798 -54.69903 171.7653 497.3518 -54.6093 168.5805 476.1851 -55.36858 171.7653 497.3518 -54.6093 173.1549 497.0505 -54.85206 168.5805 476.1851 -55.36858 175.0395 508.9087 -54.54603 175.0395 508.9087 -54.54603 174.3966 517.6433 -54.14333 175.4834 514.5324 -54.39304 178.2054 513.6084 -54.46698 175.4834 514.5324 -54.39304 175.5904 519.9503 -54.24005 178.8611 517.616 -54.36388 175.5904 519.9503 -54.24005 174.2275 527.6387 -53.88474 175.4405 525.2023 -54.08731 179.3099 521.5034 -54.26061 175.4405 525.2023 -54.08731 175.0387 530.3076 -53.93437 179.5789 525.2778 -54.15742 175.0387 530.3076 -53.93437 173.1037 537.4588 -53.61153 173.558 539.9431 -53.6331 179.2601 532.3463 -53.94981 173.558 539.9431 -53.6331 179.5871 528.9169 -54.05355 176.257 542.774 -53.59931 178.6049 535.7296 -53.84166 177.5732 539.2233 -53.72379 174.7415 546.3803 -53.46977 172.2361 537.294 -53.35007 173.2317 527.5505 -53.54014 173.2888 517.6509 -53.70773 172.3947 507.6486 -53.85226 170.4954 497.6169 -53.97182 166.3603 472.2097 -55.25035 170.4954 497.6169 -53.97182 171.3751 507.7449 -53.02009 169.4566 497.8222 -52.9879 165.1294 472.457 -54.66093 169.4566 497.8222 -52.9879 171.4316 537.1356 -52.93074 172.3313 527.4636 -52.99239 172.3161 517.6491 -53.02165 169.9478 503.7025 -51.87728 168.7326 497.9518 -51.74511 164.1041 472.6525 -53.74756 168.7326 497.9518 -51.74511 169.3761 544.4937 -52.4235 171.2169 532.6634 -52.33491 170.3756 539.2626 -52.38768 171.6387 524.9704 -52.23549 171.4328 529.911 -52.30222 171.3465 514.6817 -52.0771 171.6403 520.768 -52.17933 171.6194 519.9016 -52.16589 170.8032 509.2817 -51.98393 170.7922 509.195 -51.9824 166.6344 501.5209 -45.94777 169.9478 503.7025 -51.87728 168.7326 497.9518 -51.74511 168.4406 496.6146 -51.78708 163.9953 490.058 -44.6771 168.7326 497.9518 -51.74511 168.4406 496.6146 -51.78708 163.9953 490.058 -44.6771 169.3761 544.4937 -52.4235 166.4565 535.6899 -48.41067 170.3756 539.2626 -52.38768 163.2963 545.3479 -48.49355 171.2169 532.6634 -52.33491 167.6005 523.8228 -47.38319 171.4328 529.911 -52.30222 171.6387 524.9704 -52.23549 171.6403 520.768 -52.17933 167.2904 511.7811 -46.03887 171.6194 519.9016 -52.16589 171.3465 514.6817 -52.0771 170.8032 509.2817 -51.98393 170.7922 509.195 -51.9824 147.9977 370.8482 -57.88861 147.8802 362.2853 -58.26272 145.5586 345.2029 -58.71044 146.6722 347.2275 -58.67202 145.5586 345.2029 -58.71044 147.8802 362.2853 -58.26272 144.4947 345.3371 -58.57054 144.3674 339.324 -58.85768 144.4947 345.3371 -58.57054 145.5586 345.2029 -58.71044 137.904 305.8088 -59.70278 144.3674 339.324 -58.85768 150.5246 379.9121 -57.80507 150.5246 379.9121 -57.80507 151.9789 396.2892 -57.21645 153.4917 398.0839 -57.33747 155.0872 388.7207 -57.63296 153.4917 398.0839 -57.33747 156.3956 421.6591 -56.55326 156.7821 416.8031 -56.85988 156.7821 416.8031 -56.85988 160.3944 436.0628 -56.37245 163.1481 430.284 -56.58572 160.3944 436.0628 -56.37245 161.2016 446.9597 -55.89827 164.327 455.856 -55.87538 164.327 455.856 -55.87538 160.0106 447.184 -55.3559 155.2463 421.8587 -56.0568 150.8733 396.4633 -56.76457 146.9375 370.9956 -57.47976 144.1478 345.3795 -58.47243 143.0155 339.6945 -58.62051 144.1478 345.3795 -58.47243 143.4817 345.4588 -58.20291 143.4817 345.4588 -58.20291 159.0014 447.3643 -54.5122 154.2565 422.0219 -55.28169 149.9064 396.6075 -56.05662 145.9969 371.119 -56.8371 142.8599 345.5298 -57.83806 141.7799 340.0235 -57.9988 142.8599 345.5298 -57.83806 142.571 345.5616 -57.62332 140.7599 340.2846 -57.04233 142.571 345.5616 -57.62332 160.0603 456.6887 -53.11503 164.2462 477.0548 -52.42534 156.2013 436.8481 -53.78924 152.6687 417.5324 -54.43879 146.5953 380.5044 -55.68289 149.4661 398.7487 -55.06816 144.045 362.8009 -56.28057 141.8051 345.6408 -56.8616 141.8051 345.6408 -56.8616 139.7875 377.2972 -46.64912 144.045 362.8009 -56.28057 141.8051 345.6408 -56.8616 139.5207 340.6835 -55.45215 141.8051 345.6408 -56.8616 140.7599 340.2846 -57.04233 140.6004 345.889 -55.33434 140.6004 345.889 -55.33434 161.0911 466.8387 -50.64106 164.2462 477.0548 -52.42534 160.0603 456.6887 -53.11503 156.2013 436.8481 -53.78924 153.8413 437.0227 -49.41643 152.6687 417.5324 -54.43879 146.7377 407.1754 -48.08734 149.4661 398.7487 -55.06816 146.5953 380.5044 -55.68289 141.058 334.2219 -58.74307 142.3414 333.6596 -58.98421 142.3414 333.6596 -58.98421 122.7934 293.4137 -59.556 141.058 334.2219 -58.74307 142.3414 333.6596 -58.98421 133.2809 313.2206 -59.4102 133.2809 313.2206 -59.4102 139.8839 334.7278 -58.11659 138.9169 335.1351 -57.15695 137.839 335.6145 -55.70791 138.9169 335.1351 -57.15695 131.3666 318.3132 -57.39713 138.9169 335.1351 -57.15695 139.8839 334.7278 -58.11659 125.0363 320.3262 -48.45126 138.9169 335.1351 -57.15695 131.3666 318.3132 -57.39713 137.839 335.6145 -55.70791 121.5477 293.9556 -58.8296 129.8333 314.9069 -57.44483 120.56 294.3742 -57.7254 124.1763 292.8011 -59.83487 124.1763 292.8011 -59.83487 119.7885 284.8053 -59.9868 122.7934 293.4137 -59.556 124.1763 292.8011 -59.83487 128.7824 264.4633 -60.72529 119.7885 284.8053 -59.9868 120.3433 302.0181 -52.90182 129.8333 314.9069 -57.44483 120.56 294.3742 -57.7254 117.8102 286.1043 -59.30879 120.56 294.3742 -57.7254 121.5477 293.9556 -58.8296 118.9 290.4598 -58.13595 118.5959 297.0349 -53.91913 120.56 294.3742 -57.7254 118.9 290.4598 -58.13595 120.3433 302.0181 -52.90182 118.7687 285.4836 -59.79577 100.5721 266.186 -60.13474 102.1089 267.2483 -60.14162 96.02827 262.1213 -60.22027 102.2963 267.0047 -60.18058 98.03209 265.3815 -60.07365 100.5721 266.186 -60.13474 96.02827 262.1213 -60.22027 101.103 265.699 -60.20662 128.2531 262.1374 -60.78252 96.02827 262.1213 -60.22027 101.103 265.699 -60.20662 74 271.301 -58.85924 98.03209 265.3815 -60.07365 96.02827 262.1213 -60.22027 74 262.1103 -59.83592 126.484 252.8308 -60.30329 74 262.1103 -59.83592 96.02827 262.1213 -60.22027 128.2531 262.1374 -60.78252 104.6728 270.2503 -59.94817 107.8586 272.8487 -59.96598 102.9414 268.4804 -60.04117 112.2894 279.2928 -59.26791 113.1565 279.0881 -59.68856 108.2695 272.401 -60.10156 111.667 278.44 -59.34709 108.3906 274.3378 -59.68344 108.186 274.1004 -59.70054 116.8875 286.4681 -58.57391 113.8282 278.5053 -59.97569 115.6302 284.2937 -58.79717 114.4789 282.4699 -58.97194 118.3663 289.3334 -58.25959 118.3663 289.3334 -58.25959 116.3608 291.51 -55.33208 116.8875 286.4681 -58.57391 115.6302 284.2937 -58.79717 113.5529 286.1064 -56.61441 114.4789 282.4699 -58.97194 112.2894 279.2928 -59.26791 110.2009 281.238 -57.5789 111.667 278.44 -59.34709 108.3906 274.3378 -59.68344 108.186 274.1004 -59.70054 105.7498 275.1887 -58.78062 104.6728 270.2503 -59.94817 102.9414 268.4804 -60.04117 99.80713 268.5841 -59.75295 102.6659 274.7716 -58.62486 105.7512 269.3789 -60.18261 109.991 273.1805 -60.14798 117.0051 280.9045 -60.04969 113.7681 277.0449 -60.10348 105.7512 269.3789 -60.18261 128.5193 263.3 -60.75394 109.991 273.1805 -60.14798 113.7681 277.0449 -60.10348 117.0051 280.9045 -60.04969 104.6403 280.6888 -56.88534 107.6876 281.9181 -56.68606 105.7718 286.3627 -54.55187 108.6713 288.4594 -53.76598 111.2763 288.1916 -54.56865 106.091 291.8146 -51.61164 108.6855 294.6445 -50.0622 111.3907 294.7669 -50.7171 105.6094 297.042 -48.03109 107.7987 300.3302 -45.65637 110.6077 300.8064 -46.11263 104.3362 302.0016 -43.77494 106.1317 305.4107 -40.64809 109.0463 306.1928 -40.86519 100.9576 308.8366 -35.96826 103.8321 309.8187 -35.13884 106.8545 310.8526 -35.0879 102.252 306.6863 -38.73141 97.94578 312.6266 -30.0976 101.0485 313.5175 -29.21953 104.1824 314.7463 -28.88302 99.53195 310.7973 -33.11986 96.17863 314.3472 -26.82267 97.91443 316.4868 -22.96849 101.1651 317.854 -22.33954 92.13552 317.3186 -19.5331 94.55517 318.7109 -16.46019 97.92856 320.1612 -15.54193 94.23913 315.9154 -23.31775 87.43457 319.4504 -11.15536 91.07698 320.1785 -9.764601 89.86763 318.5125 -15.47365 90.40032 320.3808 -8.379012 91.07698 320.1785 -9.764601 87.43457 319.4504 -11.15536 94.57913 321.6595 -8.569125 94.57913 321.6595 -8.569125 74 319.5466 -9.215085 87.43457 319.4504 -11.15536 89.86763 318.5125 -15.47365 87.05075 319.5746 -10.43833 87.05075 319.5746 -10.43833 74 317.4272 -18.19599 92.13552 317.3186 -19.5331 94.23913 315.9154 -23.31775 96.17863 314.3472 -26.82267 74 313.9562 -26.73733 97.94578 312.6266 -30.0976 99.53195 310.7973 -33.11986 74 309.2187 -34.63909 100.9576 308.8366 -35.96826 102.252 306.6863 -38.73141 74 303.327 -41.71799 104.3362 302.0016 -43.77494 105.6094 297.042 -48.03109 74 296.4193 -47.80942 106.091 291.8146 -51.61164 74 288.6561 -52.77069 105.7718 286.3627 -54.55187 104.6403 280.6888 -56.88534 74 280.2175 -56.48415 102.6659 274.7716 -58.62486 99.80713 268.5841 -59.75295 114.0125 292.6706 -53.18174 113.6885 298.8069 -49.04492 112.6571 304.4006 -44.28948 111.0262 309.3736 -39.01021 108.9142 313.6788 -33.29713 106.435 317.2898 -27.23118 103.6919 320.1926 -20.88459 100.7813 322.3758 -14.32703 97.78395 323.8331 -7.623662 94.01329 321.8245 -7.34283 97.78395 323.8331 -7.623662 116.2592 298.3331 -51.06222 115.3868 304.5847 -46.09148 113.8546 310.1668 -40.52394 111.7903 315.0183 -34.46133 109.32 319.1054 -27.99522 106.5576 322.4097 -21.20639 103.6092 324.916 -14.17249 100.5634 326.6137 -6.96619 97.31938 323.9871 -6.525541 100.5634 326.6137 -6.96619 117.9492 304.1825 -48.74486 116.5345 310.6071 -42.86675 114.4944 316.2239 -36.40189 111.9751 320.9854 -29.45577 109.1086 324.8645 -22.12004 106.0182 327.8388 -14.48173 102.8076 329.8898 -6.622463 100.1761 326.7796 -5.962963 102.8076 329.8898 -6.622463 119.2829 309.2303 -47.1708 118.4568 312.6174 -43.98402 116.2624 318.8771 -36.98008 117.4458 315.8406 -40.58421 113.6297 324.0159 -29.69225 114.9169 321.7186 -33.16708 110.0847 328.8605 -20.60647 113.4264 324.3474 -29.15506 111.8114 326.7275 -24.97146 106.377 332.2646 -11.42634 108.2681 330.7086 -16.09114 104.4319 333.5263 -6.603205 104.2523 333.644 -6.145844 104.4319 333.5263 -6.603205 102.464 330.0803 -5.677928 104.0875 333.7477 -5.681748 119.2829 309.2303 -47.1708 118.4568 312.6174 -43.98402 117.4458 315.8406 -40.58421 119.1202 322.2314 -39.20741 116.2624 318.8771 -36.98008 114.9169 321.7186 -33.16708 113.6297 324.0159 -29.69225 121.1775 343.6825 -29.77928 113.4264 324.3474 -29.15506 122.1814 343.1452 -31.57093 122.9678 342.7313 -32.94909 123.7842 342.3073 -34.35767 124.6325 341.8722 -35.79812 125.513 341.4261 -37.26944 126.4263 340.9688 -38.77067 120.2241 344.2027 -28.04314 111.8114 326.7275 -24.97146 118.4502 345.2036 -24.71389 110.0847 328.8605 -20.60647 119.3162 344.7093 -26.35575 116.1061 346.6198 -20.08871 108.2681 330.7086 -16.09114 116.8458 346.1582 -21.57902 117.6268 345.686 -23.12108 114.1263 347.9689 -15.92387 106.377 332.2646 -11.42634 114.7476 347.5234 -17.26177 115.4068 347.0751 -18.64865 111.5344 350.374 -9.82049 104.4319 333.5263 -6.603205 112.218 349.5962 -11.54942 112.9827 348.8746 -13.36506 113.5384 348.4207 -14.62415 110.5493 352.4901 -6.686539 104.4319 333.5263 -6.603205 104.2523 333.644 -6.145844 110.5346 352.3898 -6.721432 110.977 351.3055 -8.210206 110.5346 352.3898 -6.721432 74 252.885 -59.38658 74 271.301 -58.85924 74 262.1103 -59.83592 74 252.885 -59.38658 86.63513 319.7108 -9.588829 86.63513 319.7108 -9.588829 85.57209 320.0695 -6.858551 89.40941 320.6886 -5.657611 86.63513 319.7108 -9.588829 85.57209 320.0695 -6.858551 90.40032 320.3808 -8.379012 74 320.2604 0 85.45708 320.1087 -6.489296 85.45708 320.1087 -6.489296 84.76541 320.3463 -3.498599 88.80091 320.8785 -2.854199 84.76541 320.3463 -3.498599 84.73252 320.3578 -3.284728 84.73252 320.3578 -3.284728 84.4897 320.4435 0 88.58245 320.9403 0 84.4897 320.4435 0 74 320.235 1.742307 84.4897 320.4435 0 74 320.2604 0 84.55893 320.4191 1.751782 88.80207 320.8781 2.862216 84.4897 320.4435 0 84.55893 320.4191 1.751782 88.58245 320.9403 0 74 317.4 0 74 320.2604 0 74 319.5466 -9.215085 74 316.6148 9.428307 74 320.235 1.742307 74 316.6241 -9.373581 74 317.4272 -18.19599 74 314.3113 -18.50794 74 313.9562 -26.73733 74 310.5245 -27.13714 74 309.2187 -34.63909 74 305.4026 -34.9838 74 303.327 -41.71799 74 299.0168 -41.92382 74 296.4193 -47.80942 74 283.2396 -52.22257 74 288.6561 -52.77069 74 291.5526 -47.73216 74 274.319 -55.27311 74 280.2175 -56.48415 74 265.0384 -56.80979 74 243.8531 -57.52735 74 320.1589 3.483137 74 320.1589 3.483137 74 319.6776 8.327116 84.76554 320.3465 3.494072 74 319.6776 8.327116 84.7341 320.3576 3.289787 74 318.8127 13.08544 86.63505 319.7108 9.588647 74 318.8127 13.08544 85.45862 320.1065 6.509946 110 316.6148 -9.428307 110 316.6241 9.373581 110 317.4 0 74 314.2817 18.59349 74 317.5593 17.77374 89.92848 318.488 15.56974 74 317.5593 17.77374 86.97251 319.6001 10.28472 87.43457 319.4504 11.15536 74 315.928 22.35795 92.24659 317.2567 19.71825 74 315.928 22.35795 74 310.4753 27.22747 74 313.9327 26.78267 94.38862 315.8047 23.58644 74 313.9327 26.78267 74 311.581 31.04283 96.35285 314.189 27.14535 74 311.581 31.04283 74 305.3457 35.05654 74 308.9127 35.06959 99.76937 310.4836 33.59988 74 308.9127 35.06959 98.14414 312.4176 30.46409 74 298.974 41.96307 74 305.9239 38.87071 101.2271 308.4236 36.52563 74 305.9239 38.87071 74 302.6316 42.42091 102.504 306.2308 39.27611 74 302.6316 42.42091 74 291.5473 47.73582 74 299.0349 45.72173 104.5141 301.4682 44.27994 74 299.0349 45.72173 74 295.1938 48.70882 105.7116 296.4107 48.50841 74 295.1938 48.70882 74 283.2843 52.20334 74 291.1036 51.38469 74 291.1036 51.38469 74 286.8281 53.71015 106.0953 291.1454 52.01316 74 286.8281 53.71015 74 274.4084 55.25072 74 282.3655 55.68323 105.6813 285.7073 54.85723 74 282.3655 55.68323 74 265.1531 56.80035 74 277.7762 57.28282 104.4852 280.1208 57.0819 74 277.7762 57.28282 74 244.2717 57.64558 74 273.0647 58.50398 102.4925 274.3397 58.72595 74 273.0647 58.50398 74 255.7616 56.80979 74 248.9798 58.76075 74 268.2845 59.33881 74 268.2845 59.33881 74 253.7706 59.49101 74 263.4502 59.78145 99.68023 268.3403 59.78361 74 263.4502 59.78145 74 258.603 59.83331 96.02826 262.1213 60.22027 74 258.603 59.83331 128.249 262.1374 60.78245 74 253.7706 59.49101 126.4879 253.0824 60.3344 74 248.9798 58.76075 125.0955 244.2028 58.55326 74 244.2717 57.64558 74 239.6597 56.1523 74 239.6597 56.1523 74 246.4811 55.27311 74 235.1944 54.29383 124.0571 235.6645 55.46878 74 235.1944 54.29383 74 237.5604 52.22257 74 230.8794 52.0746 74 230.8794 52.0746 74 229.2474 47.73216 74 226.7692 49.51859 123.2887 227.635 51.12199 74 226.7692 49.51859 74 222.8622 46.62725 74 222.8622 46.62725 74 221.7832 41.92382 74 219.216 43.43968 122.6917 220.3196 45.59934 74 219.216 43.43968 74 215.8264 39.95335 74 215.8264 39.95335 74 215.3974 34.9838 74 212.7494 36.23196 122.17 213.9074 39.02651 74 212.7494 36.23196 74 209.9841 32.27398 74 209.9841 32.27398 74 210.2755 27.13714 74 207.5485 28.10411 121.6883 208.5652 31.57165 74 207.5485 28.10411 74 205.439 23.71424 74 205.439 23.71424 74 206.4887 18.50794 74 203.6942 19.17467 121.3255 204.4163 23.42362 74 203.6942 19.17467 74 202.3215 14.49043 121.1867 201.5327 14.73729 74 202.3215 14.49043 74 204.1759 9.373581 74 201.3339 9.718449 74 201.3339 9.718449 74 200.7415 4.893649 121.199 199.9812 5.670078 74 200.7415 4.893649 74 203.4 0 74 200.5396 0 121.206 199.7251 1.073406 74 200.5396 0 74 204.1852 -9.428307 74 200.565 -1.742307 74 200.565 -1.742307 74 200.6411 -3.483137 74 200.6411 -3.483137 74 201.8884 -12.63455 121.2172 199.8183 -3.531095 74 201.8884 -12.63455 74 206.5183 -18.59349 74 204.5234 -21.47105 121.1897 201.0881 -12.83183 74 204.5234 -21.47105 121.1868 200.2742 -8.212285 74 210.3247 -27.22747 74 208.4804 -29.79117 121.2877 203.7551 -21.77414 74 208.4804 -29.79117 121.2212 202.2514 -17.35966 74 215.4543 -35.05654 74 213.6632 -37.40055 121.6128 207.7612 -30.20948 74 213.6632 -37.40055 121.4191 205.5951 -26.06664 74 221.826 -41.96307 74 219.9491 -44.12306 122.0851 213.0321 -37.95697 74 219.9491 -44.12306 121.8344 210.2441 -34.18056 74 229.2527 -47.73582 74 227.1912 -49.80265 122.604 219.4432 -44.81178 74 227.1912 -49.80265 122.3475 216.1047 -41.50831 74 237.5157 -52.20334 74 235.2212 -54.30639 123.2015 226.8246 -50.59164 74 235.2212 -54.30639 122.8829 223.0249 -47.84601 74 255.6469 -56.80035 123.9924 234.9757 -55.15524 74 243.8531 -57.52735 74 246.3916 -55.25072 123.563 230.8188 -53.03334 125.0663 243.6983 -58.41084 110 203.4 0 74 203.4 0 74 204.1759 9.373581 110 204.1759 -9.373581 74 204.1852 -9.428307 74 203.4 0 110 203.4 0 110 204.1852 9.428307 74 206.4887 18.50794 110 206.5183 18.59349 74 210.2755 27.13714 110 210.3247 27.22747 74 215.3974 34.9838 110 215.4543 35.05654 74 221.7832 41.92382 110 221.826 41.96307 74 229.2474 47.73216 110 229.2527 47.73582 74 237.5604 52.22257 110 246.3916 55.25072 74 246.4811 55.27311 110 237.5157 52.20334 110 255.6469 56.80035 74 255.7616 56.80979 110 265.0384 56.80979 74 265.1531 56.80035 110 274.319 55.27311 74 274.4084 55.25072 110 283.2396 52.22257 74 283.2843 52.20334 74 291.5473 47.73582 110 291.5526 47.73216 74 298.974 41.96307 110 299.0168 41.92382 74 305.3457 35.05654 110 305.4026 34.9838 74 310.4753 27.22747 110 310.5245 27.13714 74 314.2817 18.59349 110 314.3113 18.50794 74 316.6148 9.428307 110 316.6241 9.373581 74 317.4 0 110 317.4 0 74 317.4 0 74 316.6241 -9.373581 110 317.4 0 110 316.6148 -9.428307 74 314.3113 -18.50794 110 314.2817 -18.59349 74 310.5245 -27.13714 110 310.4753 -27.22747 74 305.4026 -34.9838 110 305.3457 -35.05654 74 299.0168 -41.92382 110 298.974 -41.96307 74 291.5526 -47.73216 110 291.5473 -47.73582 74 283.2396 -52.22257 110 274.4084 -55.25072 74 274.319 -55.27311 110 283.2843 -52.20334 110 265.1531 -56.80035 74 265.0384 -56.80979 110 255.7616 -56.80979 74 255.6469 -56.80035 110 246.4811 -55.27311 74 246.3916 -55.25072 110 237.5604 -52.22257 74 237.5157 -52.20334 74 229.2527 -47.73582 110 229.2474 -47.73216 74 221.826 -41.96307 110 221.7832 -41.92382 74 215.4543 -35.05654 110 215.3974 -34.9838 74 210.3247 -27.22747 110 210.2755 -27.13714 74 206.5183 -18.59349 110 206.4887 -18.50794 84.7341 320.3576 3.289787 89.41407 320.6871 5.673157 84.76554 320.3465 3.494072 85.45862 320.1065 6.509946 110 314.2817 -18.59349 110 314.3113 18.50794 90.40033 320.3808 8.379034 86.63505 319.7108 9.588647 91.07701 320.1785 9.764589 86.63505 319.7108 9.588647 86.97251 319.6001 10.28472 90.40033 320.3808 8.379034 87.43457 319.4504 11.15536 91.07701 320.1785 9.764589 87.43457 319.4504 11.15536 89.92848 318.488 15.56974 94.55227 318.7122 16.45559 92.24659 317.2567 19.71825 94.38862 315.8047 23.58644 97.90721 316.4928 22.95389 96.35285 314.189 27.14535 101.0357 313.5312 29.19467 98.14414 312.4176 30.46409 99.76937 310.4836 33.59988 103.8183 309.8407 35.10761 101.2271 308.4236 36.52563 102.504 306.2308 39.27611 106.1178 305.4436 40.61151 104.5141 301.4682 44.27994 107.7877 300.3761 45.61631 105.7116 296.4107 48.50841 108.6815 294.7035 50.0222 106.0953 291.1454 52.01316 108.6765 288.5307 53.7286 105.6813 285.7073 54.85723 107.7059 282.0015 56.6545 104.4852 280.1208 57.0819 105.7828 275.2829 58.75719 102.4925 274.3397 58.72595 102.9891 268.5362 60.03713 99.68023 268.3403 59.78361 96.58053 262.6059 60.21524 96.02826 262.1213 60.22027 110 310.4753 -27.22747 110 310.5245 27.13714 97.3738 263.2861 60.20641 97.45468 263.357 60.20529 97.87651 263.732 60.19865 98.44198 264.2419 60.18793 99.13787 264.8717 60.17274 99.93679 265.6062 60.15193 100.8656 266.476 60.12306 101.4574 267.0398 60.10194 101.9742 267.5385 60.08173 102.6678 268.2176 60.05197 128.5181 263.2998 60.75393 96.02826 262.1213 60.22027 128.249 262.1374 60.78245 96.96992 262.7546 60.21861 110 305.3457 -35.05654 110 305.4026 34.9838 96.88724 262.806 60.215 96.02826 262.1213 60.22027 96.96992 262.7546 60.21861 96.70634 262.7042 60.21442 96.58053 262.6059 60.21524 129.6118 261.815 60.6164 128.249 262.1374 60.78245 126.4879 253.0824 60.3344 128.5181 263.2998 60.75393 128.249 262.1374 60.78245 129.6118 261.815 60.6164 126.4433 244.1812 58.37969 125.0955 244.2028 58.55326 127.8409 252.9016 60.14357 125.3992 235.8737 55.39252 124.0571 235.6645 55.46878 124.6229 228.1184 51.25273 123.2887 227.635 51.12199 124.0114 221.0509 46.04731 122.6917 220.3196 45.59934 123.481 214.8315 39.90142 122.17 213.9074 39.02651 122.9784 209.5894 32.96654 121.6883 208.5652 31.57165 122.5566 205.393 25.35414 121.3255 204.4163 23.42362 122.338 202.3162 17.19005 121.1867 201.5327 14.73729 122.29 200.4432 8.672803 121.199 199.9812 5.670078 121.206 199.7251 1.073406 122.303 199.8158 0.005465984 121.2172 199.8183 -3.531095 121.1868 200.2742 -8.212285 122.3015 200.4403 -8.655743 121.1897 201.0881 -12.83183 122.3416 202.3096 -17.16872 121.2212 202.2514 -17.35966 121.2877 203.7551 -21.77414 122.5593 205.3839 -25.33296 121.4191 205.5951 -26.06664 121.6128 207.7612 -30.20948 122.9728 209.5758 -32.94645 121.8344 210.2441 -34.18056 122.0851 213.0321 -37.95697 123.4713 214.813 -39.87993 122.3475 216.1047 -41.50831 122.604 219.4432 -44.81178 123.9879 221.0283 -46.02692 122.8829 223.0249 -47.84601 123.2015 226.8246 -50.59164 124.6053 228.1009 -51.24126 123.563 230.8188 -53.03334 123.9924 234.9757 -55.15524 125.4115 235.8686 -55.39023 125.0663 243.6983 -58.41084 126.4862 244.184 -58.38125 126.484 252.8308 -60.30329 127.8804 252.9022 -60.14422 128.2531 262.1374 -60.78252 130.1483 264.1517 -60.55881 128.2531 262.1374 -60.78252 128.5193 263.3 -60.75394 129.6163 261.819 -60.61502 129.6163 261.819 -60.61502 93.18964 322.0723 4.96096 92.68201 322.225 2.499225 92.50154 322.2723 0 96.6286 324.2044 4.403673 96.20971 324.3409 2.21635 99.5867 326.9953 4.024808 99.23437 327.1367 2.025759 96.06967 324.3874 0 101.9412 330.3274 3.839929 101.628 330.4926 1.935426 99.12419 327.1936 0 103.4028 334.1868 2.868255 103.2813 334.2694 1.940771 101.5302 330.5617 0 103.5851 334.0661 3.848743 108.5547 350.8091 1.585274 103.2813 334.2694 1.940771 103.4028 334.1868 2.868255 103.1797 334.3393 0 103.1797 334.3393 0 108.8226 350.8756 3.15175 103.5851 334.0661 3.848743 104.085 333.7485 5.682728 109.0939 351.0652 4.022743 104.085 333.7485 5.682728 108.9399 350.9356 3.585469 100.1761 326.7796 5.96298 102.464 330.0803 5.677945 97.31939 323.9871 6.525559 94.01332 321.8245 7.342851 104.2338 333.656 6.095947 104.085 333.7485 5.682728 102.464 330.0803 5.677945 107.0321 342.8895 5.707075 104.085 333.7485 5.682728 110.0661 352.2416 5.7785 110.164 352.3941 5.90829 109.7733 351.8569 5.343812 107.0321 342.8895 5.707075 109.2862 351.2665 4.464313 109.5137 351.5326 4.906021 104.2338 333.656 6.095947 102.8076 329.8898 6.622468 100.1761 326.7796 5.96298 104.4319 333.5263 6.603207 100.5634 326.6137 6.966196 97.31939 323.9871 6.525559 97.78395 323.8331 7.623665 94.01332 321.8245 7.342851 94.57915 321.6595 8.569121 92.50154 322.2723 0 92.68103 322.2253 -2.492198 96.06967 324.3874 0 99.23371 327.137 -2.019999 99.12419 327.1936 0 96.20891 324.3411 -2.210086 101.6274 330.493 -1.929889 101.5302 330.5617 0 103.1797 334.3393 0 103.2863 334.2656 -1.988729 108.5549 350.809 -1.586725 103.2863 334.2656 -1.988729 108.465 350.7871 -9.69e-4 94.01329 321.8245 -7.34283 96.62548 324.2054 -4.391651 97.31938 323.9871 -6.525541 93.18581 322.0735 -4.947367 99.58414 326.9963 -4.013919 100.1761 326.7796 -5.962963 101.9389 330.3287 -3.829689 102.464 330.0803 -5.677928 103.5932 334.0606 -3.886435 104.0875 333.7477 -5.681748 109.773 351.8563 -5.343484 104.0875 333.7477 -5.681748 103.5932 334.0606 -3.886435 110.3509 352.6057 -6.185422 104.0875 333.7477 -5.681748 107.0318 342.8896 -5.707177 110.0629 352.2426 -5.779816 110.1457 352.3677 -5.884371 107.0318 342.8896 -5.707177 110.2215 352.4698 -5.987438 103.4393 334.1628 -3.090584 108.94 350.9357 -3.585777 103.4393 334.1628 -3.090584 109.5133 351.5319 -4.905634 109.286 351.2661 -4.464278 109.094 351.0652 -4.023076 108.8226 350.8756 -3.15177 110.5456 352.6433 -6.578977 110 299.0168 41.92382 110.4576 352.6611 -6.381585 110.0629 352.2426 -5.779816 110.3491 353.2406 -5.735692 110.1457 352.3677 -5.884371 110.0629 352.2426 -5.779816 110.152 352.6683 -5.681579 110.0629 352.2426 -5.779816 109.773 351.8563 -5.343484 110.152 352.6683 -5.681579 111.0758 353.3021 -7.211934 110.5346 352.3898 -6.721432 110.5493 352.4901 -6.686539 110.8108 352.8443 -6.96391 111.3602 351.7477 -8.67147 110.5346 352.3898 -6.721432 110.8108 352.8443 -6.96391 110.977 351.3055 -8.210206 110 298.974 -41.96307 111.0256 353.407 -7.051347 110.9674 353.4841 -6.89061 110.5456 352.6433 -6.578977 110 283.2843 -52.20334 110 291.5526 47.73216 110 291.5473 -47.73582 110.9029 353.5314 -6.734655 110.6931 353.0963 -6.580119 110.5456 352.6433 -6.578977 110.4576 352.6611 -6.381585 110.6931 353.0963 -6.580119 110.6576 353.5238 -6.238432 110.3509 352.6057 -6.185422 110.8337 353.5511 -6.585107 110.7504 353.5541 -6.414313 110.5589 353.4603 -6.065168 110.2215 352.4698 -5.987438 110.4557 353.365 -5.896948 110.0661 352.2416 5.7785 109.9655 352.6959 5.183135 109.7733 351.8569 5.343812 110.0661 352.2416 5.7785 110.152 352.6683 5.681578 110.0661 352.2416 5.7785 110.164 352.3941 5.90829 110.152 352.6683 5.681578 109.7152 352.3532 -4.771897 109.5133 351.5319 -4.905634 110.2416 353.0938 -5.583175 109.9632 352.6929 -5.179328 109.4969 352.0714 -4.360017 109.286 351.2661 -4.464278 109.3123 351.857 -3.947366 109.094 351.0652 -4.023076 109.1651 351.7195 -3.537776 108.94 350.9357 -3.585777 108.8226 350.8756 -3.15177 108.9366 351.2662 -3.14153 108.8226 350.8756 -3.15177 108.5549 350.809 -1.586725 108.9366 351.2662 -3.14153 109.0538 351.6558 -3.130634 108.465 350.7871 -9.69e-4 108.703 351.5699 0 108.5547 350.8091 1.585274 108.8226 350.8756 3.15175 108.9366 351.2662 3.141521 108.8226 350.8756 3.15175 108.9399 350.9356 3.585469 108.9366 351.2662 3.141521 109.1668 351.7215 3.542412 109.0939 351.0652 4.022743 109.0538 351.6558 3.130626 109.3153 351.8605 3.954563 109.2862 351.2665 4.464313 109.5006 352.076 4.367617 109.5137 351.5326 4.906021 109.7188 352.3579 4.778213 110.5566 352.5632 6.65388 104.4319 333.5263 6.603207 110.5345 352.3895 6.72144 106.3885 332.2547 11.45554 110.5345 352.3895 6.72144 104.4319 333.5263 6.603207 111.0294 353.3995 7.063343 110.5566 352.5632 6.65388 110.5345 352.3895 6.72144 110.9239 351.3999 8.05247 110.8107 352.8439 6.96387 110.5345 352.3895 6.72144 110.9239 351.3999 8.05247 110.8107 352.8439 6.96387 110.4111 352.6452 6.291219 110.5449 352.6439 6.577274 110 274.4084 -55.25072 110 283.2396 52.22257 106.0205 327.8363 14.48867 106.3885 332.2547 11.45554 104.4319 333.5263 6.603207 102.8076 329.8898 6.622468 110.2558 352.5116 6.036361 110.4621 353.372 5.906848 110.2558 352.5116 6.036361 110.2416 353.0938 5.583174 110.3533 353.246 5.741737 110.4111 352.6452 6.291219 110.6639 353.5277 6.249513 110.5449 352.6439 6.577274 110.6912 353.0925 6.578598 110.9731 353.4772 6.906038 110.5449 352.6439 6.577274 110.9072 353.5288 6.744768 110.8337 353.5513 6.585051 110.6912 353.0925 6.578598 111.4124 350.5408 9.492228 111.4936 351.5705 9.029276 111.4124 350.5408 9.492228 112.0113 349.815 11.03912 112.0113 349.815 11.03912 112.68 349.1436 12.65987 112.3941 350.6996 11.22295 112.68 349.1436 12.65987 108.2888 330.6885 16.14306 113.4178 348.5155 14.35437 113.3942 350.0263 13.43649 113.4178 348.5155 14.35437 114.2179 347.9008 16.12354 114.4531 349.4539 15.64866 114.2179 347.9008 16.12354 115.0841 347.2908 17.97419 115.5535 348.9369 17.85282 115.0841 347.2908 17.97419 110.1119 328.8298 20.67453 116.0176 346.6758 19.90836 116.0176 346.6758 19.90836 117.0302 346.0441 21.94665 116.6863 348.4525 20.04538 117.0302 346.0441 21.94665 111.8419 326.6861 25.04942 118.1242 345.3934 24.08683 117.8476 347.9899 22.22541 118.1242 345.3934 24.08683 118.8949 344.948 25.56124 119.0343 347.5399 24.39231 118.8949 344.948 25.56124 113.5332 324.1746 29.43671 119.7005 344.4931 27.07427 120.2441 347.096 26.5456 119.7005 344.4931 27.07427 120.5431 344.0266 28.62841 120.5431 344.0266 28.62841 121.4223 343.549 30.22045 121.4758 346.6557 28.68489 121.4223 343.549 30.22045 118.997 322.271 39.00466 122.3427 343.0579 31.85637 122.7288 346.2168 30.80981 122.3427 343.0579 31.85637 123.3101 342.5505 33.54366 124.0022 345.7778 32.92007 123.3101 342.5505 33.54366 124.3242 342.0272 35.27857 125.2956 345.3382 35.01551 124.3242 342.0272 35.27857 125.3847 341.4888 37.05754 125.3847 341.4888 37.05754 126.4921 340.9351 38.87838 126.6088 344.897 37.09596 126.4921 340.9351 38.87838 127.6488 340.3653 40.74189 127.9414 344.4537 39.16123 127.6488 340.3653 40.74189 124.9702 320.3474 48.35301 128.8567 339.7781 42.6484 129.293 344.0076 41.21117 128.8567 339.7781 42.6484 130.1169 339.1735 44.59606 130.6632 343.5578 43.24559 130.1169 339.1735 44.59606 131.0983 338.7079 46.08485 132.0517 343.1039 45.26432 131.0983 338.7079 46.08485 132.1119 338.2314 47.59766 133.4584 342.6455 47.26726 132.1119 338.2314 47.59766 133.1577 337.744 49.1331 133.1577 337.744 49.1331 131.3665 318.3131 57.39713 134.2374 337.2455 50.69192 134.883 342.1826 49.2543 134.2374 337.2455 50.69192 135.3528 336.7355 52.27475 136.3255 341.715 51.22537 135.3528 336.7355 52.27475 136.5041 336.2139 53.88052 137.7858 341.2428 53.18036 136.5041 336.2139 53.88052 137.692 335.6805 55.50824 139.2637 340.7659 55.11919 137.692 335.6805 55.50824 138.9169 335.1351 57.15715 138.9169 335.1351 57.15715 120.61 294.3535 57.80041 138.9169 335.1351 57.15715 131.3665 318.3131 57.39713 140.7599 340.2839 57.04258 141.7803 340.023 57.9992 140.7599 340.2839 57.04258 138.9169 335.1351 57.15715 139.8844 334.7275 58.117 121.5469 293.956 58.82896 139.8844 334.7275 58.117 120.3469 301.9743 52.93262 129.8333 314.9069 57.44483 129.8333 314.9069 57.44483 120.56 294.3743 57.72541 119.297 309.1636 47.23015 114.9479 321.6585 33.25259 118.4764 312.5463 44.05452 117.4704 315.7701 40.66286 116.2909 318.8104 37.06379 111.9767 320.9818 29.46196 113.5332 324.1746 29.43671 111.8419 326.6861 25.04942 114.9479 321.6585 33.25259 109.1118 324.8612 22.12753 110.1119 328.8298 20.67453 108.2888 330.6885 16.14306 120.56 294.3743 57.72541 118.5966 297.0234 53.9268 120.56 294.3743 57.72541 120.3469 301.9743 52.93262 120.049 293.0682 57.86926 120.61 294.3535 57.80041 120.56 294.3743 57.72541 120.049 293.0682 57.86926 117.9506 304.1734 48.75226 119.297 309.1636 47.23015 116.5365 310.5995 42.87437 118.4764 312.5463 44.05452 117.4704 315.7701 40.66286 114.497 316.2181 36.4092 116.2909 318.8104 37.06379 141.8054 345.6408 56.86187 141.8054 345.6408 56.86187 140.5925 345.891 55.3242 144.0459 362.8073 56.28039 140.5925 345.891 55.3242 141.8054 345.6408 56.86187 142.5709 345.5615 57.62332 145.997 371.1189 56.83715 141.8054 345.6408 56.86187 142.5709 345.5615 57.62332 144.0459 362.8073 56.28039 139.4196 346.1306 53.81512 138.2858 346.3597 52.33514 137.1909 346.5784 50.88531 135.7906 346.854 49.00115 134.4541 347.1132 47.17043 131.9637 347.5856 43.67092 132.9928 347.3921 45.13122 133.1789 347.3569 45.39314 130.8018 347.8016 41.99718 129.6927 348.0052 40.37422 127.618 348.3808 37.26832 128.633 348.1976 38.79955 126.648 348.5545 35.78371 125.268 348.8005 33.63377 123.9745 349.0303 31.57679 124.736 348.8951 32.79285 122.757 349.2466 29.60158 121.6112 349.4509 27.70665 120.5285 349.6464 25.8818 118.5309 350.0182 22.42049 119.5035 349.835 24.12163 117.6033 350.202 20.76632 116.7179 350.3881 19.15614 117.1377 350.2981 19.92367 115.0689 350.7842 16.06045 115.8723 350.5814 17.58589 114.3157 350.9992 14.5949 112.9338 351.5171 11.77864 113.6066 351.2408 13.17347 111.8057 352.2357 9.245554 112.3313 351.8466 10.46549 111.0757 353.3019 7.211991 111.0757 353.3019 7.211991 123.7592 374.6646 20.33613 111.0757 353.3019 7.211991 111.8057 352.2357 9.245554 111.0294 353.3995 7.063343 112.3313 351.8466 10.46549 117.1377 350.2981 19.92367 112.9338 351.5171 11.77864 115.8723 350.5814 17.58589 113.6066 351.2408 13.17347 116.7179 350.3881 19.15614 115.0689 350.7842 16.06045 114.3157 350.9992 14.5949 118.5309 350.0182 22.42049 117.6033 350.202 20.76632 119.5035 349.835 24.12163 120.5285 349.6464 25.8818 121.6112 349.4509 27.70665 122.757 349.2466 29.60158 123.9745 349.0303 31.57679 124.736 348.8951 32.79285 126.648 348.5545 35.78371 125.268 348.8005 33.63377 127.618 348.3808 37.26832 128.633 348.1976 38.79955 129.6927 348.0052 40.37422 131.3688 375.6854 33.70275 130.8018 347.8016 41.99718 131.9637 347.5856 43.67092 132.9928 347.3921 45.13122 133.1789 347.3569 45.39314 139.7854 377.2149 46.67034 134.4541 347.1132 47.17043 135.7906 346.854 49.00115 137.1909 346.5784 50.88531 138.2858 346.3597 52.33514 139.4196 346.1306 53.81512 144.4946 345.337 58.57052 144.3688 339.3236 58.85772 145.5585 345.2028 58.71045 146.6721 347.2275 58.67202 145.5585 345.2028 58.71045 144.3688 339.3236 58.85772 147.8803 362.2859 58.26271 144.4946 345.337 58.57052 145.5585 345.2028 58.71045 147.8803 362.2859 58.26271 144.1478 345.3794 58.47244 143.0164 339.694 58.62085 142.3414 333.6596 58.98421 137.904 305.8088 59.70278 142.3414 333.6596 58.98421 143.4817 345.4587 58.20293 141.0574 334.2221 58.74288 142.8599 345.5297 57.83806 146.9375 370.9955 57.4798 142.8599 345.5297 57.83806 143.4817 345.4587 58.20293 147.9978 370.8481 57.88864 144.1478 345.3794 58.47244 133.2809 313.2206 59.4102 142.3414 333.6596 58.98421 141.0574 334.2221 58.74288 133.2809 313.2206 59.4102 124.1763 292.8011 59.83487 122.7929 293.4139 59.5558 110 274.319 55.27311 110 265.1531 -56.80035 110 265.0384 56.80979 166.3609 472.2095 55.25054 168.5806 476.1858 55.36856 173.1549 497.0505 54.85206 178.2055 513.6084 54.46698 173.1549 497.0505 54.85206 168.5806 476.1858 55.36856 171.766 497.3516 54.60955 174.26 503.0787 54.69906 171.766 497.3516 54.60955 173.1549 497.0505 54.85206 174.26 503.0787 54.69906 164.3272 455.8572 55.87535 170.8541 471.9127 55.5304 164.3272 455.8572 55.87535 161.2021 446.9596 55.89841 160.3947 436.0644 56.37241 160.3947 436.0644 56.37241 156.3959 421.659 56.55335 156.7824 416.8048 56.85984 163.1481 430.284 56.58572 156.7824 416.8048 56.85984 151.9791 396.289 57.21651 153.492 398.0855 57.33743 153.492 398.0855 57.33743 150.5248 379.9133 57.80504 155.0871 388.7207 57.63296 150.5248 379.9133 57.80504 150.8735 396.4632 56.76467 155.2466 421.8587 56.05695 160.011 447.1838 55.35612 165.1299 472.4569 54.66123 170.4959 497.6167 53.97222 173.399 506.0709 54.41917 170.4959 497.6167 53.97222 164.1044 472.6524 53.7479 169.4569 497.8221 52.98835 172.1869 506.2147 53.87122 169.4569 497.8221 52.98835 149.9065 396.6074 56.05672 154.2567 422.0218 55.28186 159.0016 447.3642 54.51245 164.2475 477.0611 52.42507 168.3509 496.2026 51.80006 168.7324 497.9516 51.74466 171.1627 506.326 53.01771 168.7324 497.9516 51.74466 146.5969 380.5155 55.68253 149.4683 398.7625 55.06765 156.2039 436.8619 53.78875 152.6712 417.5472 54.43826 160.0624 456.6997 53.11461 164.0247 490.1041 44.72381 168.3509 496.2026 51.80006 168.7324 497.9516 51.74466 169.948 503.7039 51.87721 166.6361 501.5234 45.95058 168.7324 497.9516 51.74466 169.948 503.7039 51.87721 164.0247 490.1041 44.72381 146.5969 380.5155 55.68253 149.4683 398.7625 55.06765 146.7149 407.0116 48.10616 152.6712 417.5472 54.43826 153.797 436.7776 49.4334 156.2039 436.8619 53.78875 160.0624 456.6997 53.11461 161.0246 466.5125 50.65669 164.2475 477.0611 52.42507 159.288 482.8614 36.91776 170.5533 548.4019 53.28125 171.2375 548.7301 53.34142 168.0995 556.595 53.06182 172.9983 550.0427 53.33465 168.0995 556.595 53.06182 171.2375 548.7301 53.34142 167.5299 556.3164 53.01937 164.1524 561.8379 52.68492 167.5299 556.3164 53.01937 168.0995 556.595 53.06182 166.6854 559.4943 52.95426 162.6549 570.858 52.55907 166.6854 559.4943 52.95426 172.6011 540.2249 53.53088 173.5587 539.9397 53.63321 174.7145 546.4393 53.46762 173.5587 539.9397 53.63321 173.8647 531.8702 53.76949 175.0391 530.3038 53.93449 177.5261 539.3657 53.71889 175.0391 530.3038 53.93449 176.2141 542.8803 53.59553 174.4167 523.3727 53.99752 175.4407 525.1987 54.08742 179.5793 529.0911 54.04843 175.4407 525.1987 54.08742 178.5632 535.8959 53.83618 179.2341 532.5231 53.9443 175.5904 519.947 54.24014 179.3227 521.6325 54.25714 175.5904 519.947 54.24014 179.5843 525.4379 54.15293 174.2691 514.7611 54.2145 175.4833 514.5297 54.39311 178.8717 517.6911 54.36192 175.4833 514.5297 54.39311 175.0393 508.9067 54.54608 175.0393 508.9067 54.54608 173.1327 514.8001 53.75165 173.3707 523.323 53.61487 172.9218 531.747 53.46156 171.7731 540.0413 53.2916 169.8518 548.1684 53.10395 166.9693 556.0391 52.89651 166.9693 556.0391 52.89651 169.1853 547.9423 52.81647 166.4284 555.7684 52.69499 166.4284 555.7684 52.69499 172.1437 514.825 53.02455 172.4362 523.2709 53.00893 172.0597 531.6279 52.97018 171.0001 539.8648 52.90684 168.5286 547.8304 52.41991 165.9167 555.5092 52.41864 164.5174 558.4131 52.31973 165.9167 555.5092 52.41864 163.1142 561.3107 52.22074 170.7922 509.1944 51.98234 171.6197 519.9062 52.16606 170.8036 509.2846 51.98394 171.3469 514.6856 52.0772 171.6385 524.9754 52.23556 171.6403 520.7675 52.17942 171.2168 532.6635 52.33491 171.4324 529.916 52.30224 169.376 544.494 52.42348 170.3748 539.267 52.38773 164.6562 550.2944 50.54376 168.5286 547.8304 52.41991 165.9167 555.5092 52.41864 163.1142 561.3107 52.22074 165.9167 555.5092 52.41864 164.5174 558.4131 52.31973 164.6562 550.2944 50.54376 170.7922 509.1944 51.98234 167.292 511.7838 46.04125 170.8036 509.2846 51.98394 171.3469 514.6856 52.0772 171.6197 519.9062 52.16606 171.6403 520.7675 52.17942 167.6018 523.8251 47.38499 171.6385 524.9754 52.23556 171.4324 529.916 52.30224 171.2168 532.6635 52.33491 166.4567 535.691 48.41112 170.3748 539.267 52.38773 169.376 544.494 52.42348 163.2871 545.3167 48.47967 161.8168 540.5763 46.21861 165.2659 562.3909 52.84667 165.2659 562.3909 52.84667 162.8202 567.0697 52.67023 164.1524 561.8379 52.68492 165.2659 562.3909 52.84667 162.8202 567.0697 52.67023 160.5555 568.6147 52.43857 163.1142 561.3107 52.22074 158.3195 570.1597 51.93275 153.3019 572.0261 50.08963 163.1142 561.3107 52.22074 158.3195 570.1597 51.93275 161.0086 559.1134 50.61926 161.0086 559.1134 50.61926 152.0888 580.8278 51.9498 154.4604 579.7416 52.16205 148.0295 587.1405 51.83827 157.3284 581.1897 52.17074 148.0295 587.1405 51.83827 154.4604 579.7416 52.16205 147.182 586.3167 51.7048 134.8133 598.9592 51.11772 147.182 586.3167 51.7048 148.0295 587.1405 51.83827 141.867 593.4888 51.5492 151.8901 591.4863 51.78147 141.867 593.4888 51.5492 156.5378 574.9403 52.19377 160.204 571.5211 52.49731 160.204 571.5211 52.49731 155.6287 574.2962 51.78184 152.7599 578.2138 51.62692 146.3873 585.5314 51.29741 140.2549 591.8026 50.9951 146.3873 585.5314 51.29741 134.0013 598.1451 50.68305 152.7599 578.2138 51.62692 146.3873 585.5314 51.29741 155.6287 574.2962 51.78184 144.1758 583.6853 49.77828 134.0013 598.1451 50.68305 146.3873 585.5314 51.29741 140.2549 591.8026 50.9951 144.1758 583.6853 49.77828 135.6829 599.8162 51.26036 140.7409 611.8579 51.0045 135.6829 599.8162 51.26036 133.1687 602.1738 51.14907 134.8133 598.9592 51.11772 135.6829 599.8162 51.26036 133.1687 602.1738 51.14907 131.5618 602.2122 51.02228 134.0013 598.1451 50.68305 131.645 600.7431 50.71829 131.8065 597.9566 49.89427 134.0013 598.1451 50.68305 131.645 600.7431 50.71829 132.6506 593.6193 48.6554 134.9257 593.6296 49.46018 134.9257 593.6296 49.46018 119.1336 609.8837 50.66552 119.7207 609.8464 50.68941 115.2703 611.8452 50.56008 119.5332 610.1948 50.6817 117.1636 610.4385 50.61376 119.1336 609.8837 50.66552 115.2703 611.8452 50.56008 115.2703 611.8452 50.56008 119.5332 610.1948 50.6817 78.5 608.9732 49.91852 117.1636 610.4385 50.61376 115.2703 611.8452 50.56008 78.5 613.4347 49.84507 138.7921 615.8198 50.70246 140.7409 611.8579 51.0045 122.7147 607.8389 50.73527 123.9713 607.6068 50.80988 123.4579 608.4023 50.80147 126.0319 605.6458 50.77231 127.9405 605.0765 50.92054 127.0504 606.4672 50.91951 124.939 606.409 50.76372 130.2421 602.1396 50.74643 130.2931 604.3908 51.03549 129.0185 603.2642 50.76527 130.2421 602.1396 50.74643 129.1733 598.8491 49.63616 129.0185 603.2642 50.76527 127.385 602.7887 50.37024 126.0319 605.6458 50.77231 124.939 606.409 50.76372 121.9553 606.1175 50.51622 122.7147 607.8389 50.73527 124.4046 603.1265 50.21614 118.9087 609.0128 50.62524 123.4579 608.4023 50.80147 127.0504 606.4672 50.91951 130.2931 604.3908 51.03549 126.2537 599.9367 49.68259 127.4652 596.4736 48.84715 130.1616 594.7393 48.51872 127.8962 592.8582 47.6764 130.3263 590.6307 47.01794 127.533 589.1442 46.13349 129.7663 586.6801 45.17837 132.7772 589.3378 47.05366 126.4853 585.5353 44.27186 128.6415 582.9792 43.05879 132.2838 585.2465 45.13525 124.8235 582.0162 42.06745 127.1019 579.5585 40.70761 131.3067 581.4178 42.95297 125.7251 583.7717 43.21847 122.5726 578.5219 39.43481 125.266 576.4224 38.16274 129.9687 577.8713 40.54899 123.774 580.2745 40.81544 121.4774 574.3645 35.7929 123.2199 573.5654 35.45221 128.3696 574.6078 37.95738 119.7156 575.0375 36.27345 121.2197 576.7714 37.92153 118.6558 570.7945 31.84792 123.2199 573.5654 35.45221 121.4774 574.3645 35.7929 124.9272 572.6475 35.25468 120.9163 569.6375 31.31516 124.9272 572.6475 35.25468 119.7156 575.0375 36.27345 78.5 571.7433 31.61563 119.7156 575.0375 36.27345 121.2197 576.7714 37.92153 116.3443 571.7053 32.60404 116.3443 571.7053 32.60404 78.5 577.6932 37.73798 122.5726 578.5219 39.43481 123.774 580.2745 40.81544 124.8235 582.0162 42.06745 125.7251 583.7717 43.21847 78.5 584.6002 42.75815 126.4853 585.5353 44.27186 127.533 589.1442 46.13349 78.5 592.2657 46.52997 127.8962 592.8582 47.6764 127.4652 596.4736 48.84715 126.2537 599.9367 49.68259 78.5 600.4689 48.94146 124.4046 603.1265 50.21614 121.9553 606.1175 50.51622 118.9087 609.0128 50.62524 135.1815 588.6961 47.71107 134.7836 583.8903 45.57441 133.7784 579.2586 43.02811 134.3468 581.5752 44.3612 132.1284 574.4915 39.82436 133.064 576.9384 41.55553 126.5816 571.6195 35.20318 130.9869 571.9301 37.81912 123.0939 568.2579 31.02131 126.5816 571.6195 35.20318 128.1647 570.4938 35.29719 125.1521 566.6788 30.97128 128.1647 570.4938 35.29719 142.049 581.8507 48.18965 135.1815 588.6961 47.71107 140.0076 580.0281 46.53654 134.7836 583.8903 45.57441 138.0488 578.2212 44.82304 134.3468 581.5752 44.3612 136.1766 576.4271 43.05395 133.7784 579.2586 43.02811 133.064 576.9384 41.55553 134.4013 574.637 41.23545 132.1284 574.4915 39.82436 132.7261 572.8475 39.37314 130.9869 571.9301 37.81912 129.6642 569.2796 35.53549 131.1472 571.0619 37.47154 129.6642 569.2796 35.53549 128.3637 566.9689 33.33068 129.6642 569.2796 35.53549 136.211 557.1171 33.97536 138.1851 558.7699 36.24005 129.6642 569.2796 35.53549 131.1472 571.0619 37.47154 128.3637 566.9689 33.33068 127.0522 564.9207 31.15779 78.5 617.8348 49.38235 78.5 608.9732 49.91852 78.5 613.4347 49.84507 78.5 600.4689 48.94146 78.5 617.8348 49.38235 136.9802 619.7331 50.09773 78.5 622.1904 48.52596 78.5 622.1904 48.52596 133.7673 627.3227 48.00833 78.5 626.451 47.28908 78.5 626.451 47.28908 78.5 630.5824 45.67768 78.5 610.4229 46.99877 78.5 630.5824 45.67768 131.1066 634.4725 44.79914 78.5 634.5541 43.70889 78.5 626.4625 44.16893 78.5 634.5541 43.70889 78.5 618.568 46.28363 128.9701 641.0275 40.55387 78.5 638.3334 41.39453 78.5 638.3334 41.39453 78.5 641.8932 38.75652 78.5 633.8741 40.71679 78.5 641.8932 38.75652 127.313 646.8435 35.37791 78.5 645.2034 35.812 78.5 640.5817 36.02696 78.5 645.2034 35.812 78.5 648.2413 32.58721 78.5 648.2413 32.58721 126.0749 651.7964 29.39153 78.5 650.9799 29.10419 78.5 646.3702 30.25212 78.5 650.9799 29.10419 78.5 653.4012 25.39265 78.5 653.4012 25.39265 125.1906 655.7803 22.72857 78.5 655.4826 21.4788 78.5 651.0531 23.5842 78.5 655.4826 21.4788 124.6028 658.7102 15.52574 78.5 657.2113 17.39518 78.5 657.2113 17.39518 78.5 658.5694 13.17166 78.5 654.5388 16.14717 78.5 658.5694 13.17166 124.2663 660.5187 7.901792 78.5 659.5498 8.842516 78.5 659.5498 8.842516 78.5 660.138 4.457489 78.5 656.6793 8.199214 78.5 660.138 4.457489 124.1562 661.1359 0 78.5 660.3389 0 78.5 660.3389 0 124.2661 660.5195 -7.896456 78.5 659.6052 -8.528938 78.5 657.4 0 78.5 659.6052 -8.528938 124.6021 658.7137 -15.51457 78.5 657.429 -16.79783 78.5 654.5664 -16.07196 78.5 657.429 -16.79783 78.5 656.6873 -8.154454 125.1889 655.7884 -22.71232 78.5 653.8776 -24.56804 78.5 651.1028 -23.49881 78.5 653.8776 -24.56804 126.0716 651.8102 -29.372 78.5 649.0567 -31.61563 78.5 646.4336 -30.17697 78.5 649.0567 -31.61563 127.3078 646.8629 -35.35772 78.5 643.1068 -37.73798 78.5 640.6393 -35.97861 78.5 643.1068 -37.73798 128.963 641.0512 -40.53584 78.5 636.1998 -42.75815 78.5 633.9048 -40.69878 78.5 636.1998 -42.75815 131.098 634.4974 -44.78562 78.5 628.5343 -46.52997 78.5 626.4565 -44.17075 78.5 628.5343 -46.52997 133.7588 627.3443 -48.00055 78.5 620.3311 -48.94146 78.5 610.3771 -46.99877 78.5 620.3311 -48.94146 78.5 618.5329 -46.28967 115.2705 611.8453 -50.56008 78.5 611.8269 -49.91852 78.5 602.9652 -49.38235 78.5 611.8269 -49.91852 140.7409 611.858 -51.00449 138.7887 615.8271 -50.70162 136.9742 619.7464 -50.09514 78.5 594.349 -47.28908 118.7483 609.1484 -50.62597 78.5 611.8269 -49.91852 115.2705 611.8453 -50.56008 124.0568 603.6107 -50.27778 78.5 602.9652 -49.38235 121.671 606.4177 -50.5358 117.2875 611.0849 -50.61704 115.2705 611.8453 -50.56008 140.7409 611.858 -51.00449 117.2439 610.8673 -50.61784 118.7483 609.1484 -50.62597 115.2705 611.8453 -50.56008 117.5019 610.9129 -50.62501 117.2439 610.8673 -50.61784 115.2705 611.8453 -50.56008 117.2875 611.0849 -50.61704 142.0285 612.5706 -50.78311 140.7409 611.858 -51.00449 138.7887 615.8271 -50.70162 126.2759 606.9213 -50.893 128.3409 605.6928 -50.96418 124.3914 607.9334 -50.83117 122.6767 608.7795 -50.77705 121.1225 609.4939 -50.72948 119.7163 610.103 -50.68752 142.0285 612.5706 -50.78311 151.8905 591.4855 -51.78149 140.7409 611.858 -51.00449 138.3491 620.0554 -49.86093 136.9742 619.7464 -50.09514 135.1014 627.5009 -47.77825 133.7588 627.3443 -48.00055 132.3505 634.7138 -44.49734 131.098 634.4974 -44.78562 128.963 641.0512 -40.53584 130.115 641.4616 -40.04162 127.3078 646.8629 -35.35772 128.3884 647.5084 -34.47186 126.0716 651.8102 -29.372 127.1216 652.6332 -27.91795 125.1889 655.7884 -22.71232 126.2508 656.6492 -20.5526 124.6021 658.7137 -15.51457 125.713 659.4107 -12.58124 124.2661 660.5195 -7.896456 125.4574 660.8162 -4.235906 124.1562 661.1359 0 125.4574 660.8162 4.23553 124.2663 660.5187 7.901792 125.7129 659.4107 12.58088 124.6028 658.7102 15.52574 126.2508 656.6494 20.55225 125.1906 655.7803 22.72857 127.1216 652.6334 27.91764 126.0749 651.7964 29.39153 128.3883 647.5086 34.47159 127.313 646.8435 35.37791 130.1149 641.4619 40.0414 128.9701 641.0275 40.55387 131.1066 634.4725 44.79914 132.3504 634.7141 44.49716 133.7673 627.3227 48.00833 135.1012 627.5012 47.77812 136.9802 619.7331 50.09773 138.3489 620.0557 49.86088 138.7921 615.8198 50.70246 140.7409 611.8579 51.0045 152.9316 592.0364 51.64148 140.7409 611.8579 51.0045 151.8901 591.4863 51.78147 142.0285 612.5706 50.7831 142.0285 612.5706 50.7831 116.1409 571.5244 32.38267 114.4536 568.3213 28.19561 116.1409 571.5244 32.38267 112.8997 568.8838 28.82068 112.8997 568.8838 28.82068 78.5 566.9224 24.56804 108.6952 566.0571 24.09399 110.9778 565.2873 23.11461 112.8997 568.8838 28.82068 108.6952 566.0571 24.09399 114.4536 568.3213 28.19561 78.5 563.371 16.79783 108.2548 565.7937 23.58629 106.9211 563.0407 17.96873 108.2548 565.7937 23.58629 104.4406 563.7774 19.122 104.4406 563.7774 19.122 104.0042 563.5744 18.59887 103.3827 561.186 12.3453 104.0042 563.5744 18.59887 100.1948 562.0475 13.92465 100.1948 562.0475 13.92465 78.5 561.1948 8.528938 99.61602 561.8473 13.17115 102.3898 560.8727 10.95642 100.1948 562.0475 13.92465 99.61602 561.8473 13.17115 103.3827 561.186 12.3453 99.06661 561.655 12.40175 99.06661 561.655 12.40175 96.93304 560.8729 8.55534 99.94689 560.4176 7.700881 99.06661 561.655 12.40175 96.93304 560.8729 8.55534 102.3898 560.8727 10.95642 78.5 560.4611 0 96.87654 560.8514 8.424215 98.76642 559.9996 3.924756 96.87654 560.8514 8.424215 95.60169 560.3526 4.365003 95.60169 560.3526 4.365003 95.57309 560.3413 4.227624 98.99383 559.7287 3e-6 95.57309 560.3413 4.227624 95.14901 560.1705 10e-7 95.14901 560.1705 10e-7 78.5 561.2502 -8.842516 95.14901 560.1705 10e-7 78.5 560.4611 0 95.41001 560.2744 -3.29899 98.59183 559.9362 -2.950436 95.14901 560.1705 10e-7 95.41001 560.2744 -3.29899 98.99383 559.7287 3e-6 78.5 563.4 0 78.5 560.4611 0 78.5 561.1948 8.528938 78.5 564.1207 -8.199214 78.5 561.2502 -8.842516 78.5 566.2337 16.07196 78.5 563.371 16.79783 78.5 564.1127 8.154454 78.5 569.6973 23.49881 78.5 566.9224 24.56804 78.5 574.3664 30.17697 78.5 571.7433 31.61563 78.5 580.1607 35.97861 78.5 577.6932 37.73798 78.5 586.8952 40.69878 78.5 584.6002 42.75815 78.5 594.3435 44.17075 78.5 592.2657 46.52997 78.5 602.2671 46.28967 78.5 566.2612 -16.14717 78.5 563.5887 -17.39518 97.3918 561.0478 -9.554949 78.5 563.5887 -17.39518 95.61922 560.3598 -4.449745 96.16342 560.5751 -6.50106 96.96234 560.8843 -8.624381 78.5 569.7469 -23.5842 78.5 567.3988 -25.39265 106.5881 564.8574 -21.6559 78.5 567.3988 -25.39265 99.06665 561.655 -12.40181 99.61609 561.8473 -13.17119 100.1949 562.0475 -13.92463 78.5 574.4298 -30.25212 78.5 572.5587 -32.58721 112.8995 568.8836 -28.82038 78.5 572.5587 -32.58721 78.5 580.2183 -36.02696 78.5 578.9068 -38.75652 119.7156 575.0375 -36.27345 78.5 578.9068 -38.75652 116.1619 571.5431 -32.40568 116.3444 571.7055 -32.6043 78.5 586.9259 -40.71679 78.5 586.2459 -43.70889 122.7797 578.8086 -39.6695 78.5 586.2459 -43.70889 121.3381 576.9173 -38.05316 78.5 602.2321 -46.28363 126.7613 586.2964 -44.69626 78.5 594.349 -47.28908 78.5 594.3375 -44.16893 124.0394 580.6923 -41.12624 125.1163 582.5513 -42.42966 126.0208 584.4182 -43.61623 127.238 597.3388 -49.08148 127.3241 588.1755 -45.67068 127.6945 590.0641 -46.54939 127.862 593.8004 -48.01192 125.9218 600.6184 -49.81539 110 657.4 0 78.5 657.4 0 78.5 656.6873 -8.154454 110 656.6873 8.154454 78.5 656.6793 8.199214 78.5 657.4 0 110 657.4 0 110 656.6793 -8.199214 78.5 654.5664 -16.07196 110 654.5388 -16.14717 78.5 651.1028 -23.49881 110 651.0531 -23.5842 78.5 646.4336 -30.17697 110 646.3702 -30.25212 78.5 640.6393 -35.97861 110 640.5817 -36.02696 78.5 633.9048 -40.69878 110 633.8741 -40.71679 78.5 626.4565 -44.17075 110 618.568 -46.28363 78.5 618.5329 -46.28967 110 626.4625 -44.16893 110 610.4229 -46.99877 78.5 610.3771 -46.99877 110 602.2671 -46.28967 78.5 602.2321 -46.28363 110 594.3435 -44.17075 78.5 594.3375 -44.16893 78.5 586.9259 -40.71679 110 586.8952 -40.69878 78.5 580.2183 -36.02696 110 580.1607 -35.97861 78.5 574.4298 -30.25212 110 574.3664 -30.17697 78.5 569.7469 -23.5842 110 569.6973 -23.49881 78.5 566.2612 -16.14717 110 566.2337 -16.07196 78.5 564.1207 -8.199214 110 564.1127 -8.154454 78.5 563.4 0 110 563.4 0 78.5 563.4 0 78.5 564.1127 8.154454 110 563.4 0 110 564.1207 8.199214 78.5 566.2337 16.07196 110 566.2612 16.14717 78.5 569.6973 23.49881 110 569.7469 23.5842 78.5 574.3664 30.17697 110 574.4298 30.25212 78.5 580.1607 35.97861 110 580.2183 36.02696 78.5 586.8952 40.69878 110 586.9259 40.71679 78.5 594.3435 44.17075 110 602.2321 46.28363 78.5 602.2671 46.28967 110 594.3375 44.16893 110 610.3771 46.99877 78.5 610.4229 46.99877 110 618.5329 46.28967 78.5 618.568 46.28363 110 626.4565 44.17075 78.5 626.4625 44.16893 78.5 633.8741 40.71679 110 633.9048 40.69878 78.5 640.5817 36.02696 110 640.6393 35.97861 78.5 646.3702 30.25212 110 646.4336 30.17697 78.5 651.0531 23.5842 110 651.1028 23.49881 78.5 654.5388 16.14717 110 654.5664 16.07196 99.26033 560.1768 -5.837806 95.61922 560.3598 -4.449745 96.16342 560.5751 -6.50106 100.3539 560.557 -8.596796 96.96234 560.8843 -8.624381 97.3918 561.0478 -9.554949 102.3898 560.8727 -10.95643 99.06665 561.655 -12.40181 103.3827 561.186 -12.34529 99.06665 561.655 -12.40181 99.61609 561.8473 -13.17119 102.3898 560.8727 -10.95643 100.1949 562.0475 -13.92463 108.9461 564.0877 -20.56344 100.1949 562.0475 -13.92463 106.5881 564.8574 -21.6559 103.3827 561.186 -12.34529 114.4533 568.3211 -28.19537 112.8995 568.8836 -28.82038 118.6555 570.794 -31.84755 112.8995 568.8836 -28.82038 116.1619 571.5431 -32.40568 114.4533 568.3211 -28.19537 116.3444 571.7055 -32.6043 121.4773 574.3646 -35.79299 119.7156 575.0375 -36.27345 121.4773 574.3646 -35.79299 119.7156 575.0375 -36.27345 121.3381 576.9173 -38.05316 125.2661 576.4223 -38.16285 122.7797 578.8086 -39.6695 123.2196 573.5657 -35.45232 127.1014 579.5584 -40.70759 124.0394 580.6923 -41.12624 125.1163 582.5513 -42.42966 128.6435 582.9823 -43.0604 126.0208 584.4182 -43.61623 126.7613 586.2964 -44.69626 129.7668 586.6841 -45.18038 127.3241 588.1755 -45.67068 127.6945 590.0641 -46.54939 130.3264 590.6347 -47.01959 127.862 593.8004 -48.01192 130.1609 594.7438 -48.5202 127.238 597.3388 -49.08148 129.1707 598.855 -49.63746 125.9218 600.6184 -49.81539 127.3832 602.794 -50.37115 124.0568 603.6107 -50.27778 124.9392 606.4075 -50.76353 121.671 606.4177 -50.5358 122.7411 607.8225 -50.73566 120.9819 608.8649 -50.7051 119.1491 609.877 -50.66594 110.6863 554.1456 -6.153379 111.1912 554.8843 -8.090171 113.3827 551.9147 -7.739598 113.6942 552.0335 -8.312893 113.3827 551.9147 -7.739598 111.1912 554.8843 -8.090171 112.5726 551.6276 -5.963892 118.7353 541.8316 -5.381076 112.5726 551.6276 -5.963892 113.3827 551.9147 -7.739598 116.7397 546.8134 -7.757017 113.6942 552.0335 -8.312893 116.7397 546.8134 -7.757017 113.3827 551.9147 -7.739598 108.4645 556.3466 -6.524834 108.5642 557.4264 -8.760393 111.8506 555.1072 -9.20232 108.5642 557.4264 -8.760393 113.9768 552.1536 -8.809001 105.9595 558.1774 -7.065448 105.5944 559.447 -9.727527 109.3155 557.6549 -9.941179 105.5944 559.447 -9.727527 103.2334 559.5925 -7.761888 106.4591 559.7053 -11.00136 102.2726 559.2841 -5.265081 105.1203 557.9187 -4.789512 107.7305 556.1154 -4.42329 110.0369 553.9204 -4.1757 112.3583 551.546 -5.366928 112.3583 551.546 -5.366928 111.9811 551.3902 -4.056224 111.9811 551.3902 -4.056224 101.6873 559.0886 -2.65909 104.6107 557.754 -2.417872 107.286 555.9667 -2.233075 109.6438 553.7734 -2.109467 111.721 551.2752 -2.758919 117.8801 541.895 -2.768899 111.721 551.2752 -2.758919 111.6226 551.2316 -2.055087 111.6226 551.2316 -2.055087 102.6918 558.5502 2e-6 106.0961 556.6774 2e-6 109.0713 554.185 2e-6 111.5029 551.1741 2e-6 117.5859 541.9093 -0.0215469 111.5029 551.1741 2e-6 109.7462 553.8125 2.806405 109.0713 554.185 2e-6 111.5029 551.1741 2e-6 117.872 541.8955 2.730965 111.7159 551.2728 2.726644 111.7159 551.2728 2.726644 101.84 559.1402 3.53784 102.6918 558.5502 2e-6 104.7435 557.7975 3.21726 106.0961 556.6774 2e-6 107.4017 556.0061 2.971343 120.1153 541.6721 -7.778103 120.1153 541.6721 -7.778103 122.3464 535.7144 -4.803707 118.7353 541.8316 -5.381076 120.1153 541.6721 -7.778103 120.1806 541.6594 -7.864698 120.242 541.654 -7.951237 120.1153 541.6721 -7.778103 120.1806 541.6594 -7.864698 121.9491 538.9362 -7.902199 121.8323 538.9238 -7.712584 121.8323 538.9238 -7.712584 118.7252 541.8323 5.358079 112.3499 551.5425 5.341565 110.4437 554.0641 5.510762 112.3499 551.5425 5.341565 116.7396 546.8135 7.757017 113.3827 551.9146 7.739622 111.1912 554.8843 8.090186 113.3827 551.9146 7.739622 120.1153 541.6721 7.778121 120.1806 541.6594 7.864728 113.3827 551.9146 7.739622 116.7396 546.8135 7.757017 120.242 541.654 7.951237 120.3997 541.6967 8.218363 113.6568 552.0183 8.245432 111.8506 555.1072 9.202322 113.3827 551.9146 7.739622 113.6568 552.0183 8.245432 111.1912 554.8843 8.090186 120.1153 541.6721 7.778121 121.8324 538.9238 7.71264 120.1153 541.6721 7.778121 118.7252 541.8323 5.358079 121.9491 538.9362 7.902199 120.1153 541.6721 7.778121 121.8324 538.9238 7.71264 120.242 541.654 7.951237 120.1806 541.6594 7.864728 122.3458 535.7131 4.799978 117.872 541.8955 2.730965 123.5104 536.151 7.67235 121.749 535.4329 1.613872 117.5859 541.9093 -0.0215469 121.751 535.4336 -1.634611 117.8801 541.895 -2.768899 120.2163 542.6206 -8.777219 117.0264 547.5346 -8.820595 120.0919 542.8812 -8.835422 117.4372 554.5147 -15.02437 120.0919 542.8812 -8.835422 117.0264 547.5346 -8.820595 124.8001 537.1064 -10.24172 120.2163 542.6206 -8.777219 120.0919 542.8812 -8.835422 119.9382 544.9479 -10.3257 122.5173 540.1406 -9.682824 120.0919 542.8812 -8.835422 119.9382 544.9479 -10.3257 122.5173 540.1406 -9.682824 113.9768 552.1536 -8.809001 113.9768 552.1536 -8.809001 120.504 541.833 -8.482464 120.4974 541.9274 -8.555276 120.463 542.0417 -8.607999 120.4279 542.1372 -8.643524 120.3781 542.26 -8.682888 120.3055 542.4264 -8.729269 111.8506 555.1072 -9.20232 117.4372 554.5147 -15.02437 113.9768 552.1536 -8.809001 120.242 541.654 -7.951237 120.395 541.6925 -8.207969 121.9491 538.9362 -7.902199 120.242 541.654 -7.951237 120.395 541.6925 -8.207969 123.7901 536.2987 -8.222597 120.504 541.833 -8.482464 123.6248 536.1984 -7.874366 122.2432 539.1483 -8.508129 120.504 541.833 -8.482464 120.4974 541.9274 -8.555276 122.2432 539.1483 -8.508129 124.3647 536.572 -9.235679 120.463 542.0417 -8.607999 123.9383 536.4362 -8.566074 124.1681 536.4835 -8.898372 120.4279 542.1372 -8.643524 124.5357 536.7075 -9.574007 120.3781 542.26 -8.682888 124.6809 536.8866 -9.910348 120.3055 542.4264 -8.729269 119.9687 547.1384 -12.11716 122.8188 542.3347 -11.7848 119.9687 547.1384 -12.11716 120.2056 549.525 -14.26402 123.5368 544.2259 -14.0821 120.2056 549.525 -14.26402 120.6255 551.9228 -16.56215 124.5365 545.9096 -16.45768 120.6255 551.9228 -16.56215 119.1744 555.9575 -18.04604 121.1829 554.0738 -18.74924 125.7376 547.4674 -18.86133 121.1829 554.0738 -18.74924 120.8883 557.5578 -20.97384 121.9425 556.2501 -21.08072 121.9425 556.2501 -21.08072 122.5977 557.8419 -22.82303 127.0863 548.9545 -21.26213 122.5977 557.8419 -22.82303 123.3708 559.5151 -24.67343 128.5484 550.411 -23.64291 123.3708 559.5151 -24.67343 124.2687 561.2742 -26.62472 130.1054 551.8609 -25.99463 124.2687 561.2742 -26.62472 117.4677 558.0633 -18.12041 124.2687 561.2742 -26.62472 120.8883 557.5578 -20.97384 131.7455 553.3195 -28.31096 125.4754 562.7521 -28.58107 123.0606 562.5604 -26.53309 125.4754 562.7521 -28.58107 124.2687 561.2742 -26.62472 123.0606 562.5604 -26.53309 119.1744 555.9575 -18.04604 151.2768 570.1245 -48.53383 142.0517 581.8531 -48.19173 158.9845 557.1276 -49.01092 149.1528 568.1881 -46.81325 140.0109 580.0313 -46.53939 157.0264 555.3497 -47.39955 147.0502 566.3195 -45.01543 138.0525 578.2247 -44.8264 155.1343 553.7712 -45.79566 144.9763 564.515 -43.14399 136.1801 576.4309 -43.05755 151.5937 551.0852 -42.65053 142.9379 562.7702 -41.20262 134.4043 574.6405 -41.23888 153.3249 552.3484 -44.20937 149.9234 549.9376 -41.10354 140.9405 561.0812 -39.19528 132.7284 572.8504 -39.37594 146.748 547.9545 -38.05085 138.9892 559.4437 -37.126 131.1486 571.0635 -37.47323 148.3053 548.8966 -39.56676 145.2529 547.1017 -36.56046 137.0888 557.8535 -34.99883 129.6626 569.2763 -35.53127 142.4606 545.6451 -33.68619 135.2444 556.3063 -32.81779 128.8309 567.7609 -34.11412 143.8203 546.3353 -35.10179 141.168 545.03 -32.31553 133.4611 554.7977 -30.58698 127.8827 566.1874 -32.529 138.7677 543.9705 -29.69543 139.9376 544.4715 -30.9838 127.0548 564.924 -31.16191 126.9136 564.718 -30.93009 137.6533 543.5137 -28.44486 135.5836 542.7184 -26.06041 133.6195 542.0167 -23.71524 130.1961 540.8516 -19.38315 131.8096 541.3991 -21.46988 128.7041 540.3095 -17.35126 127.3258 539.7155 -15.33519 126.1701 539.0427 -13.45399 124.8933 537.3678 -10.56913 125.3534 538.2713 -11.85714 124.8933 537.3678 -10.56913 141.5214 506.6333 -8.06471 124.8933 537.3678 -10.56913 125.3534 538.2713 -11.85714 124.8001 537.1064 -10.24172 126.1701 539.0427 -13.45399 127.3258 539.7155 -15.33519 145.2864 510.2185 -16.5437 128.7041 540.3095 -17.35126 130.1961 540.8516 -19.38315 131.8096 541.3991 -21.46988 133.6195 542.0167 -23.71524 149.2142 514.9315 -24.50076 135.5836 542.7184 -26.06041 137.6533 543.5137 -28.44486 138.7677 543.9705 -29.69543 139.9376 544.4715 -30.9838 141.168 545.03 -32.31553 153.1544 520.8908 -31.82075 142.4606 545.6451 -33.68619 143.8203 546.3353 -35.10179 145.2529 547.1017 -36.56046 146.748 547.9545 -38.05085 156.8872 527.9812 -38.26179 148.3053 548.8966 -39.56676 149.9234 549.9376 -41.10354 151.5937 551.0852 -42.65053 160.2692 536.1252 -43.78109 153.3249 552.3484 -44.20937 155.1343 553.7712 -45.79566 161.8298 540.6166 -46.23907 157.0264 555.3497 -47.39955 163.2963 545.3479 -48.49355 158.9845 557.1276 -49.01092 142.0517 581.8531 -48.19173 135.1864 590.0863 -48.25038 140.0109 580.0313 -46.53939 135.0057 592.9119 -49.23141 134.8223 584.1998 -45.72327 138.0525 578.2247 -44.8264 135.1319 587.1671 -47.08467 134.2608 581.1887 -44.14717 136.1801 576.4309 -43.05755 133.4362 578.134 -42.32442 134.4043 574.6405 -41.23888 132.3814 575.0996 -40.27448 132.7284 572.8504 -39.37594 131.1215 572.1521 -38.01985 131.1486 571.0635 -37.47323 129.6626 569.2763 -35.53127 125.1519 566.6782 -30.97086 129.6626 569.2763 -35.53127 128.8309 567.7609 -34.11412 128.369 574.607 -37.95673 131.1215 572.1521 -38.01985 129.6626 569.2763 -35.53127 128.1645 570.494 -35.29723 128.1645 570.494 -35.29723 127.8827 566.1874 -32.529 127.0548 564.924 -31.16191 126.9136 564.718 -30.93009 132.6509 593.617 -48.65469 135.0057 592.9119 -49.23141 135.1864 590.0863 -48.25038 132.7767 589.3366 -47.05311 135.1319 587.1671 -47.08467 132.2836 585.2463 -45.1351 134.8223 584.1998 -45.72327 134.2608 581.1887 -44.14717 131.3071 581.4177 -42.95249 133.4362 578.134 -42.32442 129.9671 577.8695 -40.54754 132.3814 575.0996 -40.27448 131.6596 600.7254 -50.71719 131.6596 600.7254 -50.71719 130.2444 602.137 -50.74616 131.7214 602.4273 -51.06499 130.2444 602.137 -50.74616 129.0458 603.2405 -50.76493 129.9216 603.8884 -51.00407 129.0458 603.2405 -50.76493 126.5812 571.6199 -35.20323 126.5812 571.6199 -35.20323 124.9269 572.6478 -35.25477 123.0936 568.2573 -31.0209 124.9269 572.6478 -35.25477 127.6041 604.4528 -50.77521 127.6041 604.4528 -50.77521 126.0626 605.6224 -50.77227 128.0344 605.2553 -50.94276 126.0626 605.6224 -50.77227 126.0639 606.5345 -50.88083 124.9392 606.4075 -50.76353 124.0159 607.7331 -50.81811 122.7411 607.8225 -50.73566 120.916 569.637 -31.31476 123.2196 573.5657 -35.45232 121.8991 608.858 -50.75453 120.9819 608.8649 -50.7051 119.7241 609.9155 -50.69014 119.1491 609.877 -50.66594 132.2153 602.9476 -51.1103 132.2153 602.9476 -51.1103 130.5994 604.1737 -51.04704 130.5994 604.1737 -51.04704 128.3409 605.6928 -50.96418 126.2759 606.9213 -50.893 124.3914 607.9334 -50.83117 122.6767 608.7795 -50.77705 121.1225 609.4939 -50.72948 119.7163 610.103 -50.68752 163.7024 571.3837 -52.42132 172.9984 550.0427 -53.33465 162.6554 570.8572 -52.5591 174.3064 550.6689 -53.12287 174.7415 546.3803 -53.46977 172.9984 550.0427 -53.33465 174.3064 550.6689 -53.12287 152.9315 592.0366 -51.64146 157.3284 581.1897 -52.17074 128.7824 264.4633 -60.72529 130.1483 264.1517 -60.55881 128.7824 264.4633 -60.72529 137.904 305.8088 -59.70278 141.0649 313.7784 -59.32577 146.6722 347.2275 -58.67202 151.4744 363.5154 -58.08203 155.0872 388.7207 -57.63296 161.3756 413.3598 -56.8263 163.1481 430.284 -56.58572 170.7665 463.3024 -55.55879 170.8541 471.9127 -55.5304 178.2054 513.6084 -54.46698 179.6486 513.3562 -54.2792 178.2054 513.6084 -54.46698 178.8611 517.616 -54.36388 179.6486 513.3562 -54.2792 180.624 520.0272 -54.10552 179.3099 521.5034 -54.26061 179.5789 525.2778 -54.15742 181.0804 526.4918 -53.92919 179.5871 528.9169 -54.05355 180.7165 532.5394 -53.75119 179.2601 532.3463 -53.94981 178.6049 535.7296 -53.84166 179.3549 538.4431 -53.55994 177.5732 539.2233 -53.72379 176.257 542.774 -53.59931 177.1025 544.5309 -53.34714 176.5055 551.6755 -51.5207 166.8339 572.8691 -49.46423 177.2065 551.9689 -50.2708 164.251 577.9165 -49.26804 177.2065 551.9689 -50.2708 166.8339 572.8691 -49.46423 179.3545 545.4199 -51.74967 176.5055 551.6755 -51.5207 177.2065 551.9689 -50.2708 166.3751 579.04 -42.93542 180.0807 545.6546 -50.50285 177.2065 551.9689 -50.2708 180.1872 545.4 -50.51172 184.223 547.07 -38.54461 180.0807 545.6546 -50.50285 166.5196 578.832 -42.84918 171.2187 572.9039 -38.6561 181.0969 553.8546 -38.36448 181.0969 553.8546 -38.36448 168.8866 575.6576 -41.0796 166.3052 572.637 -50.49342 164.251 577.9165 -49.26804 165.5792 572.2998 -51.36051 155.5155 593.3439 -49.69342 156.0372 593.5831 -48.65551 161.4916 583.2438 -49.06035 175.5111 551.2299 -52.50223 164.6957 571.8743 -52.01497 154.7964 592.9927 -50.56887 153.9191 592.5488 -51.23028 175.5111 551.2299 -52.50223 178.3362 545.0272 -52.72901 144.1806 613.713 -49.12994 144.8537 614.041 -47.84741 140.4887 620.8195 -48.24004 144.8537 614.041 -47.84741 144.1806 613.713 -49.12994 150.5523 603.7369 -48.25563 142.7282 617.9666 -47.51324 150.5523 603.7369 -48.25563 144.8537 614.041 -47.84741 142.7282 617.9666 -47.51324 143.211 613.2084 -50.14118 139.5121 620.5144 -49.20986 143.211 613.2084 -50.14118 162.1038 586.0386 -44.20133 156.0372 593.5831 -48.65551 161.4916 583.2438 -49.06035 140.7767 621.8076 -46.85733 138.9932 625.5721 -45.87087 137.3768 629.2387 -44.56545 137.1443 629.7883 -44.33964 152.0114 604.5595 -43.8332 154.4623 600.1329 -43.92152 164.2181 582.345 -43.90257 182.0652 512.9013 -52.69934 183.8219 519.5413 -51.27045 182.8258 512.7386 -51.44998 185.2274 512.3189 -45.37658 182.8258 512.7386 -51.44998 183.8219 519.5413 -51.27045 182.8107 512.6459 -51.45027 182.0652 512.9013 -52.69934 182.8258 512.7386 -51.44998 185.2274 512.3189 -45.37658 182.8107 512.6459 -51.45027 182.8258 512.7386 -51.44998 183.0592 519.7023 -52.52221 183.8555 519.8355 -51.2628 183.8555 519.8355 -51.2628 183.53 526.4088 -52.34244 184.3017 526.3343 -51.09211 188.3265 519.3201 -39.1394 184.3017 526.3343 -51.09211 184.3054 526.6326 -51.08407 184.3054 526.6326 -51.08407 183.1379 532.8378 -52.16124 183.9086 532.8824 -50.91156 188.7736 526.5771 -38.99782 183.9086 532.8824 -50.91156 182.5258 538.9916 -50.72674 188.3043 533.4923 -38.86124 182.5258 538.9916 -50.72674 182.4523 539.2322 -50.71894 181.6895 539.1097 -51.96658 182.4523 539.2322 -50.71894 186.7483 540.2479 -38.71454 180.1872 545.4 -50.51172 180.6343 538.8172 -52.94461 182.0444 532.7113 -53.139 182.4246 526.4537 -53.31998 181.9606 519.8559 -53.49868 180.975 513.1133 -53.67425 173.1655 462.826 -54.00699 180.975 513.1133 -53.67425 175.4358 470.9249 -52.55602 172.0807 463.048 -54.96514 175.4358 470.9249 -52.55602 173.9296 462.6512 -52.7745 167.7062 429.2745 -53.6532 163.7569 412.8621 -55.30213 173.9296 462.6512 -52.7745 159.6235 387.7008 -54.74167 153.8375 362.9969 -56.5852 162.6776 413.094 -56.24377 164.5111 412.6131 -54.09023 151.1865 346.1976 -55.8217 143.4095 313.2394 -57.85597 152.7642 363.2386 -57.51049 154.5818 362.6828 -55.39349 133.2475 263.39 -57.95711 132.4747 263.5925 -59.11532 142.3422 313.4907 -58.76507 142.3942 304.7586 -56.89356 144.142 312.8594 -56.68454 131.9392 261.2483 -59.17296 132.4747 263.5925 -59.11532 133.2475 263.39 -57.95711 131.4127 263.8536 -60.00743 131.4127 263.8536 -60.00743 144.142 312.8594 -56.68454 133.2475 263.39 -57.95711 142.3942 304.7586 -56.89356 134.6265 263.0755 -55.02589 132.9809 262.2131 -57.98686 133.2475 263.39 -57.95711 134.6265 263.0755 -55.02589 132.9809 262.2131 -57.98686 154.5818 362.6828 -55.39349 151.1865 346.1976 -55.8217 148.1987 312.0684 -47.2067 147.2892 309.9442 -48.40665 145.5154 304.1515 -49.83339 146.2955 307.0918 -49.40263 164.5111 412.6131 -54.09023 159.6235 387.7008 -54.74167 167.9624 411.9879 -45.65198 159.3421 361.7684 -43.64249 167.7062 429.2745 -53.6532 178.5072 461.8685 -40.74309 130.8795 261.5144 -60.0655 165.3794 360.6109 19.0055 159.5327 331.0264 19.55412 162.3594 338.8992 7.685924 148.7239 342.0973 7.685924 162.3594 338.8992 7.685924 159.5327 331.0264 19.55412 166.5984 360.3771 6.355204 162.7312 340.1766 5.304825 149.0745 343.5924 4.795983 162.7312 340.1766 5.304825 162.3594 338.8992 7.685924 148.7239 342.0973 7.685924 162.953 361.0761 31.47413 155.6894 323.5661 31.18036 155.6894 323.5661 31.18036 150.9001 316.5932 42.43747 150.9001 316.5932 42.43747 159.3423 361.7683 43.64189 149.6193 314.7272 44.9185 143.1673 318.407 42.43747 150.9001 316.5932 42.43747 149.6193 314.7272 44.9185 143.1673 318.407 42.43747 154.5819 362.6836 55.39369 148.4114 312.5102 46.89611 142.5713 315.8657 45.38776 148.4114 312.5102 46.89611 148.1986 312.0682 47.20684 148.1986 312.0682 47.20684 151.1866 346.1985 55.82187 144.1429 312.8636 56.68451 147.288 309.9411 48.40807 141.8389 312.7431 47.67559 147.288 309.9411 48.40807 143.4013 313.2019 57.85704 144.1429 312.8636 56.68451 151.1866 346.1985 55.82187 146.2949 307.0899 49.40311 145.5154 304.1515 49.83339 140.7726 283.4475 50.94654 135.9338 262.7761 52.05916 134.6269 263.0756 55.02532 133.2476 263.39 57.95693 132.4735 263.5928 59.11447 133.2476 263.39 57.95693 154.5819 362.6836 55.39369 164.5111 412.6139 54.09046 153.8309 362.9652 56.58614 164.5111 412.6139 54.09046 170.8217 411.4693 36.98854 167.9625 411.9878 45.65161 169.3968 390.1758 27.44999 173.1209 411.4455 28.2493 169.9813 393.8752 27.90511 169.6639 391.9974 27.76976 168.8453 378.7987 18.91822 169.0071 386.7027 26.25589 168.8047 383.5891 24.37974 168.7616 380.9096 21.88657 162.731 340.1757 -5.306997 166.5984 360.3771 -6.35584 169.5242 374.9269 -0.002903938 162.9667 340.9621 -2.706577 163.0472 341.2269 -0.002899885 162.9669 340.9629 2.702928 169.0298 377.2937 15.47472 169.3945 375.5145 7.835719 162.3594 338.8992 -7.685924 165.3793 360.6109 -19.00613 169.3948 375.5135 -7.828681 155.6894 323.5661 -31.18037 162.9528 361.0761 -31.47474 168.7615 380.9217 -21.90046 159.5327 331.0264 -19.55413 169.0298 377.2937 -15.47473 168.8451 378.8005 -18.92147 150.9001 316.5932 -42.43747 170.8217 411.4693 -36.98872 168.8059 383.6169 -24.40065 169.0106 386.7414 -26.27382 169.401 390.2073 -27.45707 169.6667 392.0161 -27.77282 169.9813 393.8752 -27.9051 173.1209 411.4455 -28.24927 148.4129 312.5132 -46.89389 149.6204 314.729 -44.91647 141.8389 312.7431 -47.67559 148.1987 312.0684 -47.2067 148.4129 312.5132 -46.89389 147.2892 309.9442 -48.40665 142.5713 315.8657 -45.38776 149.6204 314.729 -44.91647 150.9001 316.5932 -42.43747 143.1673 318.407 -42.43747 150.9001 316.5932 -42.43747 155.6894 323.5661 -31.18037 143.1673 318.407 -42.43747 159.5327 331.0264 -19.55413 162.3594 338.8992 -7.685924 148.7239 342.0973 -7.685924 162.3594 338.8992 -7.685924 162.731 340.1757 -5.306997 148.7239 342.0973 -7.685924 149.0745 343.5924 -4.796211 162.9667 340.9621 -2.706577 149.2545 344.3597 -1.630087 163.0472 341.2269 -0.002899885 149.2545 344.3598 1.629722 162.9669 340.9629 2.702928 141.0077 309.1994 49.18325 146.2949 307.0899 49.40311 145.5154 304.1515 49.83339 140.1205 305.4169 49.83339 145.5154 304.1515 49.83339 140.7726 283.4475 50.94654 140.1205 305.4169 49.83339 135.9338 262.7761 52.05916 135.6894 261.7295 52.1044 135.9338 262.7761 52.05916 134.6269 263.0756 55.02532 135.6894 261.7295 52.1044 130.4224 264.0687 52.05916 135.9338 262.7761 52.05916 130.4224 264.0687 52.05916 134.1155 260.8545 55.08932 133.2476 263.39 57.95693 135.4545 260.6966 52.12728 132.9783 262.2061 57.98685 132.4735 263.5928 59.11447 132.9783 262.2061 57.98685 133.2476 263.39 57.95693 167.7062 429.2754 53.65342 163.7531 412.8434 55.30274 167.7062 429.2754 53.65342 178.5074 461.8684 40.74235 173.9293 462.6504 52.7747 177.8632 438.3558 28.51972 173.8777 415.2987 27.71158 173.1209 411.4455 28.2493 169.9813 393.8752 27.90511 177.651 436.7327 27.96464 177.8632 438.3558 28.51972 170.0524 393.8763 27.26987 169.9813 393.8752 27.90511 169.6639 391.9974 27.76976 170.0524 393.8763 27.26987 169.5002 390.41 26.83971 169.3968 390.1758 27.44999 169.1181 387.1024 25.69883 169.0071 386.7027 26.25589 168.9095 384.1022 23.87414 168.8047 383.5891 24.37974 168.8542 381.5271 21.44541 168.7616 380.9096 21.88657 168.9238 379.4908 18.53393 168.8453 378.7987 18.91822 169.0913 378.0699 15.22799 169.0298 377.2937 15.47472 169.0913 378.0699 15.22799 169.0298 377.2937 15.47472 169.3945 375.5145 7.835719 169.4439 376.2711 7.692096 169.5242 374.9269 -0.002903938 169.4441 376.2702 -7.686034 169.3948 375.5135 -7.828681 169.5687 375.6875 0.004703998 169.0298 377.2937 -15.47473 169.0913 378.07 -15.22799 169.0298 377.2937 -15.47473 168.8451 378.8005 -18.92147 169.0913 378.07 -15.22799 168.9239 379.4899 -18.53252 168.7615 380.9217 -21.90046 168.8542 381.5253 -21.44341 168.8059 383.6169 -24.40065 168.9094 384.1001 -23.87265 169.0106 386.7414 -26.27382 169.118 387.1002 -25.69773 169.401 390.2073 -27.45707 169.4998 390.4069 -26.83894 169.6667 392.0161 -27.77282 169.9813 393.8752 -27.9051 170.0524 393.8763 -27.27005 169.9813 393.8752 -27.9051 173.1209 411.4455 -28.24927 170.0524 393.8763 -27.27005 177.8632 438.3557 -28.51969 173.8777 415.2988 -27.71194 177.8632 438.3557 -28.51969 181.9269 461.7002 -28.44472 173.9293 462.6504 52.7747 182.8108 512.6458 51.45027 173.1632 462.814 54.00743 182.8108 512.6458 51.45027 181.9269 461.7001 28.44474 187.3652 511.9454 39.05834 182.8258 512.7386 51.44998 185.2508 512.3148 45.31264 181.3834 458.1704 27.97901 181.9269 461.7001 28.44474 185.0248 479.6176 28.14456 185.0868 479.596 27.6903 185.0248 479.6176 28.14456 182.0651 512.901 52.69948 182.8258 512.7386 51.44998 183.8104 519.4428 51.27305 182.8258 512.7386 51.44998 185.2508 512.3148 45.31264 182.0651 512.901 52.69948 182.8258 512.7386 51.44998 183.8104 519.4428 51.27305 188.3265 519.3201 39.1395 187.3652 511.9454 39.05834 183.8552 519.8327 51.26292 186.5585 486.7821 26.58442 190.6412 511.373 26.26406 191.6215 518.9355 26.43464 190.6412 511.373 26.26406 185.7558 483.3937 27.69218 185.3808 481.554 27.99964 189.8232 496.0992 16.41859 192.6201 511.0272 13.19884 193.6376 518.7002 13.3212 192.6201 511.0272 13.19884 189.0916 494.5148 19.73408 188.2785 492.4139 22.53555 187.4163 489.8098 24.83992 191.3236 498.8241 -0.00287497 193.2819 510.9116 -0.00286895 194.3193 518.6206 5e-5 193.2819 510.9116 -0.00286895 191.1468 498.5184 5.704702 190.6266 497.5934 11.27093 191.1459 498.517 -5.718338 193.2816 510.9116 -0.272887 193.2816 510.9116 -0.272887 193.2808 510.9118 -0.543032 193.2808 510.9118 -0.543032 190.6262 497.593 -11.2745 192.5786 511.0345 -13.60609 193.6376 518.7002 -13.3211 192.5786 511.0345 -13.60609 187.4273 489.8464 -24.81453 190.5866 511.3825 -26.53132 191.6215 518.9355 -26.43454 190.5866 511.3825 -26.53132 188.2915 492.4495 -22.49541 189.1034 494.5438 -19.68916 189.8232 496.0991 -16.4186 185.0248 479.6176 -28.14452 187.3248 511.9524 -39.18848 187.3248 511.9524 -39.18848 185.3762 481.5354 -28.0063 185.7501 483.3696 -27.70013 186.1461 485.1231 -27.22353 186.5627 486.7964 -26.57573 181.3834 458.1706 -27.98 181.9269 461.7002 -28.44472 185.0248 479.6176 -28.14452 185.0868 479.596 -27.69137 185.0248 479.6176 -28.14452 185.3762 481.5354 -28.0063 185.0868 479.596 -27.69137 185.7566 483.0888 -27.29599 185.7501 483.3696 -27.70013 186.1461 485.1231 -27.22353 186.529 486.3942 -26.24131 186.5627 486.7964 -26.57573 187.3664 489.3939 -24.53354 187.4273 489.8464 -24.81453 188.2158 491.9855 -22.23196 188.2915 492.4495 -22.49541 189.0155 494.0735 -19.43232 189.1034 494.5438 -19.68916 189.7137 495.5927 -16.21235 189.8232 496.0991 -16.4186 189.7137 495.5927 -16.21235 189.8232 496.0991 -16.4186 190.6262 497.593 -11.2745 190.6477 497.3438 -9.930324 191.1459 498.517 -5.718338 191.1317 498.2058 -3.334875 191.3236 498.8241 -0.00287497 191.1323 498.2067 3.319776 191.1468 498.5184 5.704702 190.6478 497.3439 9.927291 190.6266 497.5934 11.27093 189.8232 496.0992 16.41859 189.7137 495.5927 16.21236 189.8232 496.0992 16.41859 189.0916 494.5148 19.73408 189.7137 495.5927 16.21236 189.0156 494.0736 19.43194 188.2785 492.4139 22.53555 188.216 491.986 22.23081 187.4163 489.8098 24.83992 187.3664 489.3932 24.53312 186.5585 486.7821 26.58442 186.5291 486.3941 26.24009 185.7558 483.3937 27.69218 185.7565 483.0879 27.2951 185.3808 481.554 27.99964 185.0248 479.6176 28.14456 185.0868 479.596 27.6903 177.6511 436.7329 -27.96531 135.9337 262.7759 -52.05917 135.6923 261.7379 -52.10412 135.9337 262.7759 -52.05917 135.4587 260.7008 -52.12722 134.1214 260.8649 -55.08931 132.7125 261.0416 -58.01598 140.7725 283.4473 -50.94655 130.4224 264.0686 -52.05917 135.9337 262.7759 -52.05917 140.7725 283.4473 -50.94655 130.1107 262.7397 -52.11282 135.9337 262.7759 -52.05917 130.4224 264.0686 -52.05917 135.6923 261.7379 -52.10412 145.5154 304.1515 -49.83339 140.1205 305.4169 -49.83339 145.5154 304.1515 -49.83339 146.2955 307.0918 -49.40263 140.1205 305.4169 -49.83339 141.0077 309.1994 -49.18325 148.7239 342.0973 -7.685924 148.7239 342.0973 7.685924 143.1673 318.407 42.43747 149.0745 343.5924 -4.796211 149.0745 343.5924 4.795983 143.1673 318.407 -42.43747 142.5713 315.8657 45.38776 149.2545 344.3597 -1.630087 149.2545 344.3598 1.629722 142.5713 315.8657 -45.38776 140.1205 305.4169 49.83339 140.1205 305.4169 -49.83339 141.0077 309.1994 -49.18325 130.4224 264.0687 52.05916 130.4224 264.0686 -52.05917 141.0077 309.1994 49.18325 141.8389 312.7431 -47.67559 141.8389 312.7431 47.67559 130.1107 262.7397 52.11282 130.1107 262.7397 -52.11282 130.1107 262.7397 52.11282 129.7991 261.4111 52.13068 135.325 260.115 52.13068 129.7991 261.4111 52.13068 135.3896 260.4062 52.12983 135.4545 260.6966 52.12728 129.7991 261.4111 -52.13068 128.7519 256.9465 51.92697 133.7188 251.9276 51.45958 128.7519 256.9465 51.92697 127.7333 252.6035 -51.33979 127.7217 252.554 51.3307 127.7217 252.554 51.3307 128.7583 256.9737 -51.93012 126.7201 248.2837 -50.35484 126.7044 248.2167 50.33634 133.0495 247.8092 50.6098 126.7044 248.2167 50.33634 125.7271 244.0503 -48.98562 125.7085 243.971 48.95572 132.474 243.717 49.41178 125.7085 243.971 48.95572 124.769 239.9654 -47.24639 124.7491 239.8802 47.20563 131.9746 239.7042 47.87209 124.7491 239.8802 47.20563 123.8464 236.0317 -45.14372 123.8264 235.9465 45.09283 131.5621 235.7946 45.995 123.8264 235.9465 45.09283 122.9755 232.3188 -42.71715 122.9568 232.239 42.6599 131.2124 232.0579 43.80944 122.9568 232.239 42.6599 122.1548 228.8193 -39.96305 122.1385 228.75 39.90301 130.9371 228.53 41.34471 122.1385 228.75 39.90301 121.3911 225.5635 -36.90022 121.3781 225.5081 36.84383 130.6987 225.1947 38.58524 121.3781 225.5081 36.84383 120.6839 222.5483 -33.52634 120.675 222.5103 33.47986 130.4886 222.056 35.51883 120.675 222.5103 33.47986 120.0498 219.8447 -29.91198 120.0447 219.8231 29.88065 130.3029 219.1706 32.18438 120.0447 219.8231 29.88065 119.4886 217.4519 -26.05267 119.4871 217.4457 26.04219 130.1115 216.5848 28.6219 119.4871 217.4457 26.04219 119.0096 215.4101 22.02435 129.9399 214.3096 24.85331 119.0096 215.4101 22.02435 119.0084 215.4049 -22.01299 118.6129 213.7186 17.82632 129.8356 212.3583 20.92107 118.6129 213.7186 17.82632 118.6101 213.7068 -17.79204 118.3016 212.3912 13.50692 129.7946 210.7416 16.85197 118.3016 212.3912 13.50692 118.2982 212.377 -13.45304 118.077 211.4337 9.073374 129.792 209.4715 12.66442 118.077 211.4337 9.073374 118.0743 211.4221 -9.00459 117.941 210.8539 4.577673 129.8384 208.5523 8.376645 117.941 210.8539 4.577673 117.9394 210.8472 -4.49941 117.8953 210.6591 0.04063689 129.8812 208.0103 4.075517 117.8953 210.6591 0.04063689 129.8892 208.0341 -4.383086 117.9394 210.8472 -4.49941 129.8957 207.8433 -0.161536 129.8469 208.5942 -8.635335 118.0743 211.4221 -9.00459 129.7963 209.518 -12.84789 118.2982 212.377 -13.45304 129.7969 210.7747 -16.94731 118.6101 213.7068 -17.79204 129.8354 212.3565 -20.91703 119.0084 215.4049 -22.01299 129.9357 214.2557 -24.75467 119.4886 217.4519 -26.05267 130.1018 216.4604 -28.43318 120.0498 219.8447 -29.91198 130.2854 218.9703 -31.9292 120.6839 222.5483 -33.52634 130.461 221.7808 -35.22189 121.3911 225.5635 -36.90022 130.6618 224.8569 -38.27605 122.1548 228.8193 -39.96305 130.8932 228.1587 -41.05672 122.9755 232.3188 -42.71715 131.1665 231.6807 -43.56349 123.8464 236.0317 -45.14372 131.5239 235.4365 -45.80254 124.769 239.9654 -47.24639 131.9526 239.3929 -47.73811 125.7271 244.0503 -48.98562 132.468 243.4705 -49.32996 126.7201 248.2837 -50.35484 133.0607 247.6485 -50.57152 127.7333 252.6035 -51.33979 133.7386 251.8407 -51.44653 128.7583 256.9737 -51.93012 135.3296 260.1139 -52.13068 129.7991 261.4111 -52.13068 134.4982 256.0021 -51.96178 135.4587 260.7008 -52.12722 135.3944 260.4097 -52.1298 134.1214 260.8649 -55.08931 135.4587 260.7008 -52.12722 135.3944 260.4097 -52.1298 132.7125 261.0416 -58.01598 135.3296 260.1139 -52.13068 134.4982 256.0021 -51.96178 130.9856 252.6883 -57.5843 133.7386 251.8407 -51.44653 133.0607 247.6485 -50.57152 129.5455 244.1552 -55.83937 132.468 243.4705 -49.32996 128.8071 238.9385 -54.09314 131.9526 239.3929 -47.73811 129.4943 243.817 -55.74235 129.4423 243.4698 -55.64037 128.2631 234.5467 -52.18323 131.5239 235.4365 -45.80254 127.7932 230.3103 -49.92063 131.1665 231.6807 -43.56349 128.2512 234.4454 -52.13431 128.2395 234.3444 -52.085 127.4121 226.4772 -47.4543 130.8932 228.1587 -41.05672 127.2485 224.7514 -46.20344 130.6618 224.8569 -38.27605 127.3293 225.6095 -46.83724 126.6838 218.5796 -40.84441 130.461 221.7808 -35.22189 130.2854 218.9703 -31.9292 126.1575 213.2189 -34.67388 130.1018 216.4604 -28.43318 125.6517 208.7336 -27.75555 129.9357 214.2557 -24.75467 129.8354 212.3565 -20.91703 125.3208 205.5512 -21.0577 129.7969 210.7747 -16.94731 129.7963 209.518 -12.84789 125.1507 203.2636 -14.11682 129.8469 208.5942 -8.635335 125.0954 201.8883 -7.044929 129.8892 208.0341 -4.383086 129.8957 207.8433 -0.161536 125.0814 201.4376 0.01704895 129.8812 208.0103 4.075517 125.0862 201.8916 7.043741 129.8384 208.5523 8.376645 125.1444 203.2531 14.06396 129.792 209.4715 12.66442 129.7946 210.7416 16.85197 125.3154 205.5139 20.95629 129.8356 212.3583 20.92107 125.6431 208.6544 27.61153 129.9399 214.3096 24.85331 125.6561 208.768 27.81709 130.1115 216.5848 28.6219 126.2432 213.9794 35.66227 130.3029 219.1706 32.18438 125.6692 208.8824 28.02234 125.9471 211.2825 31.94316 126.543 216.9547 39.15246 130.4886 222.056 35.51883 126.8492 220.1918 42.39552 130.6987 225.1947 38.58524 127.1706 223.6719 45.37207 130.9371 228.53 41.34471 127.5184 227.3704 48.06593 131.2124 232.0579 43.80944 127.9066 231.2685 50.46771 131.5621 235.7946 45.995 128.3469 235.3212 52.55168 131.9746 239.7042 47.87209 128.8554 239.5026 54.30893 132.474 243.717 49.41178 129.4472 243.7794 55.7326 133.0495 247.8092 50.6098 130.1306 248.1143 56.81779 133.7188 251.9276 51.45958 130.9052 252.4677 57.55865 135.325 260.115 52.13068 135.3896 260.4062 52.12983 135.4545 260.6966 52.12728 134.1155 260.8545 55.08932 132.7056 261.0285 58.01602 132.7056 261.0285 58.01602 132.7056 261.0285 58.01602 130.1486 252.6385 58.70692 130.9052 252.4677 57.55865 132.7056 261.0285 58.01602 131.9338 261.2372 59.17397 131.9338 261.2372 59.17397 131.9392 261.2483 -59.17296 132.7125 261.0416 -58.01598 130.9856 252.6883 -57.5843 132.7125 261.0416 -58.01598 130.1903 252.6461 -58.70673 129.5455 244.1552 -55.83937 128.7856 244.2159 -56.98663 129.4943 243.817 -55.74235 129.4423 243.4698 -55.64037 128.8071 238.9385 -54.09314 127.6948 236.1642 -54.09151 128.2631 234.5467 -52.18323 128.2512 234.4454 -52.13431 128.2395 234.3444 -52.085 127.7932 230.3103 -49.92063 126.8624 228.614 -50.08031 127.4121 226.4772 -47.4543 127.3293 225.6095 -46.83724 127.2485 224.7514 -46.20344 126.2097 221.6981 -45.02363 126.6838 218.5796 -40.84441 125.6533 215.5864 -39.03352 126.1575 213.2189 -34.67388 125.1146 210.4206 -32.25635 125.6517 208.7336 -27.75555 124.6566 206.28 -24.83366 125.3208 205.5512 -21.0577 124.3876 203.2246 -16.88055 125.1507 203.2636 -14.11682 124.3005 201.3362 -8.532841 125.0954 201.8883 -7.044929 124.2833 200.6991 0.007544994 125.0814 201.4376 0.01704895 125.0862 201.8916 7.043741 124.2907 201.341 8.550171 125.1444 203.2531 14.06396 124.3853 203.2314 16.89774 125.3154 205.5139 20.95629 124.6548 206.2917 24.85595 125.6431 208.6544 27.61153 125.6561 208.768 27.81709 125.6692 208.8824 28.02234 125.1199 210.4319 32.27432 125.9471 211.2825 31.94316 126.2432 213.9794 35.66227 125.6632 215.6028 39.05213 126.543 216.9547 39.15246 126.8492 220.1918 42.39552 126.2331 221.7186 45.04209 127.1706 223.6719 45.37207 127.5184 227.3704 48.06593 126.8805 228.6354 50.09407 127.9066 231.2685 50.46771 128.3469 235.3212 52.55168 127.6834 236.1779 54.09777 128.8554 239.5026 54.30893 129.4472 243.7794 55.7326 128.7427 244.2177 56.98765 130.1306 248.1143 56.81779 129.1314 252.7361 -59.58673 130.8795 261.5144 -60.0655 127.7281 244.144 -57.8347 126.6411 235.9445 -54.87915 125.8168 228.2718 -50.78409 125.176 221.266 -45.63135 124.6339 215.0934 -39.54415 124.11 209.8859 -32.66979 123.6688 205.7176 -25.13347 123.4197 202.6542 -17.05753 123.3514 200.7779 -8.610383 123.3418 200.1484 0.006572902 123.3409 200.7816 8.627658 123.4169 202.6607 17.07679 123.6666 205.7279 25.15535 124.1155 209.8983 32.68881 124.6437 215.1109 39.5642 125.1995 221.2875 45.65079 125.8347 228.2914 50.79685 126.6293 235.9542 54.88356 127.6851 244.1437 57.83436 129.0906 252.7317 59.5863 130.8738 261.5066 60.06554 131.4126 263.8536 60.0075 130.8738 261.5066 60.06554 130.1478 264.1518 60.55745 128.7825 264.4632 60.72529 97.89824 263.3917 60.21661 128.7825 264.4632 60.72529 141.0567 313.741 59.32672 128.7825 264.4632 60.72529 130.1478 264.1518 60.55745 115.3549 278.8574 60.07938 137.904 305.8088 59.70278 98.81324 264.0327 60.21427 99.71492 264.6774 60.21158 100.6033 265.3259 60.20856 101.4783 265.9782 60.2052 102.3399 266.6343 60.20149 103.1883 267.2942 60.19744 104.0233 267.9579 60.19305 104.845 268.6254 60.18832 105.6534 269.2967 60.18325 106.5288 270.0409 60.17726 107.3904 270.792 60.17084 108.2373 271.549 60.16399 109.0684 272.3109 60.15673 109.8827 273.0768 60.14905 110.6791 273.8456 60.14099 111.4567 274.6165 60.13253 112.2143 275.3884 60.1237 112.9511 276.1604 60.1145 113.6658 276.9315 60.10494 114.5274 277.8943 60.09246 142.334 313.4533 58.76607 131.4126 263.8536 60.0075 163.7013 571.3861 52.42126 157.3284 581.1897 52.17074 162.6549 570.858 52.55907 174.3064 550.669 53.12287 172.9983 550.0427 53.33465 174.3064 550.669 53.12287 172.9983 550.0427 53.33465 174.7145 546.4393 53.46762 177.1106 544.5113 53.34785 176.2141 542.8803 53.59553 177.5261 539.3657 53.71889 179.3599 538.4271 53.56048 178.5632 535.8959 53.83618 179.2341 532.5231 53.9443 180.7188 532.5227 53.75171 179.5793 529.0911 54.04843 181.08 526.4833 53.92944 179.5843 525.4379 54.15293 179.3227 521.6325 54.25714 180.6233 520.0225 54.10566 178.8717 517.6911 54.36192 178.2055 513.6084 54.46698 179.6485 513.356 54.27924 178.2055 513.6084 54.46698 170.8541 471.9127 55.5304 179.6485 513.356 54.27924 170.7643 463.2911 55.5591 163.1481 430.284 56.58572 161.372 413.3416 56.82678 155.0871 388.7207 57.63296 151.4679 363.484 58.08284 146.6721 347.2275 58.67202 116.1505 279.822 60.0657 116.9162 280.7891 60.05143 117.654 281.7597 60.03657 118.3662 282.7351 60.02113 119.0548 283.7163 60.00511 119.7218 284.7044 59.98852 120.3662 285.6987 59.97135 120.9855 286.6982 59.95359 121.5799 287.7027 59.93526 122.1492 288.7122 59.91635 122.6935 289.7269 59.89685 123.2128 290.7466 59.87677 123.7071 291.7713 59.85611 124.1763 292.8011 59.83487 97.78306 263.4266 60.21291 97.89824 263.3917 60.21661 98.6568 264.0917 60.20829 98.81324 264.0327 60.21427 99.52873 264.7671 60.20298 99.71492 264.6774 60.21158 100.3968 265.452 60.19698 100.6033 265.3259 60.20856 101.2595 266.1453 60.19028 101.4783 265.9782 60.2052 102.1164 266.8474 60.18288 102.3399 266.6343 60.20149 102.9676 267.5591 60.17473 103.1883 267.2942 60.19744 104.0233 267.9579 60.19305 103.8131 268.2812 60.16582 104.845 268.6254 60.18832 104.6526 269.0141 60.15613 105.6534 269.2967 60.18325 105.4858 269.7584 60.14565 106.5288 270.0409 60.17726 106.3124 270.5146 60.13435 107.3904 270.792 60.17084 107.132 271.2831 60.12221 108.2373 271.549 60.16399 107.9442 272.0646 60.10921 109.0684 272.3109 60.15673 108.7489 272.8596 60.09533 109.8827 273.0768 60.14905 109.5456 273.6689 60.08054 110.6791 273.8456 60.14099 110.334 274.4929 60.06482 111.4567 274.6165 60.13253 111.1135 275.3321 60.04816 112.2143 275.3884 60.1237 111.8836 276.187 60.03053 112.9511 276.1604 60.1145 112.6435 277.0579 60.01192 113.6658 276.9315 60.10494 113.3926 277.9452 59.99231 114.5274 277.8943 60.09246 114.1302 278.8492 59.97167 115.3549 278.8574 60.07938 114.8558 279.7704 59.95 116.1505 279.822 60.0657 115.5686 280.709 59.92728 116.9162 280.7891 60.05143 116.2679 281.6655 59.90348 117.654 281.7597 60.03657 116.9529 282.6399 59.87859 118.3662 282.7351 60.02113 117.6227 283.6325 59.8526 119.0548 283.7163 60.00511 118.2764 284.6435 59.82548 119.7218 284.7044 59.98852 118.9133 285.6731 59.79723 120.3662 285.6987 59.97135 119.5325 286.7214 59.76782 120.9855 286.6982 59.95359 120.1331 287.7886 59.73725 121.5799 287.7027 59.93526 120.7141 288.8746 59.7055 122.1492 288.7122 59.91635 121.2745 289.979 59.67257 122.6935 289.7269 59.89685 121.8131 291.1017 59.63843 123.2128 290.7466 59.87677 122.3291 292.2425 59.6031 123.7071 291.7713 59.85611 124.1763 292.8011 59.83487 122.7929 293.4139 59.5558 144.1806 613.713 49.12994 150.5523 603.7368 48.25563 144.8537 614.041 47.84741 152.0114 604.5595 43.8332 144.8537 614.041 47.84741 150.5523 603.7368 48.25563 142.7289 617.9652 47.51362 144.1806 613.713 49.12994 144.8537 614.041 47.84741 142.7289 617.9652 47.51362 156.0368 593.5839 48.65548 164.2026 582.3703 43.90727 156.0368 593.5839 48.65548 162.1038 586.0386 44.20133 154.4623 600.1329 43.92152 155.5156 593.3437 49.69347 161.4916 583.2438 49.06035 166.3742 579.0411 42.93588 161.4916 583.2438 49.06035 154.7965 592.9926 50.56891 166.3041 572.6394 50.49336 166.8334 572.8699 49.46419 164.251 577.9165 49.26804 143.211 613.2084 50.14118 153.9191 592.5487 51.23032 165.5782 572.3022 51.36046 164.6946 571.8767 52.01491 139.5119 620.5147 49.20981 143.211 613.2084 50.14118 140.4885 620.8198 48.23997 176.5055 551.6755 51.5207 177.2065 551.9689 50.2708 179.3628 545.3996 51.75041 177.2065 551.9689 50.2708 176.5055 551.6755 51.5207 181.0969 553.8546 38.36449 166.8334 572.8699 49.46419 177.2065 551.9689 50.2708 184.2229 547.07 38.54487 181.0969 553.8546 38.36449 177.2065 551.9689 50.2708 178.7092 548.7779 50.39107 178.7092 548.7779 50.39107 175.511 551.2299 52.50223 178.3444 545.0072 52.72974 175.511 551.2299 52.50223 164.251 577.9165 49.26804 140.7767 621.8076 -46.85733 137.2383 627.8955 -46.22619 138.9932 625.5721 -45.87087 137.3768 629.2387 -44.56545 134.4937 634.7561 -43.05211 137.1443 629.7883 -44.33964 134.6446 636.1583 -41.06157 135.9309 632.7675 -42.96383 135.9309 632.7675 -42.96383 138.6098 630.7319 -39.21366 140.161 627.0417 -40.91883 146.6318 614.1234 -43.64167 143.209 620.5344 -42.90381 134.6446 636.1583 -41.06157 132.2714 641.1787 -38.74078 133.5082 639.3922 -38.87458 133.5082 639.3922 -38.87458 132.5112 642.4612 -36.39892 137.5396 633.4479 -37.66285 132.5112 642.4612 -36.39892 130.5624 646.937 -33.35136 131.6497 645.3276 -33.66073 131.6497 645.3276 -33.66073 130.9108 647.9857 -30.65422 135.4479 639.283 -33.33993 130.9108 647.9857 -30.65422 129.3147 651.8192 -27.00988 130.2894 650.3947 -27.41702 133.8033 644.4712 -27.98234 130.2894 650.3947 -27.41702 129.773 652.5478 -23.94338 129.773 652.5478 -23.94338 128.4613 655.6464 -19.88366 129.3552 654.4079 -20.28384 132.589 648.7422 -21.7977 129.3552 654.4079 -20.28384 129.0261 655.9661 -16.43661 129.0261 655.9661 -16.43661 127.9368 658.2784 -12.17156 128.7785 657.1955 -12.46049 131.7471 651.9782 -14.8394 128.7785 657.1955 -12.46049 128.6071 658.0855 -8.364795 128.6071 658.0855 -8.364795 127.6884 659.6182 -4.097973 128.5053 658.6244 -4.203634 131.2661 653.9467 -7.497923 128.5053 658.6244 -4.203634 128.4725 658.8038 -0.001616895 128.4725 658.8038 -0.001616895 127.6884 659.6182 4.097492 128.5053 658.6246 4.200415 131.1106 654.6039 7.8e-5 128.5053 658.6246 4.200415 127.9368 658.2785 12.1711 128.607 658.086 8.361636 131.2607 653.9692 7.369343 128.607 658.086 8.361636 128.7784 657.1963 12.45741 128.7784 657.1963 12.45741 128.4613 655.6466 19.88322 129.0259 655.9672 16.43358 131.7286 652.0523 14.63422 129.0259 655.9672 16.43358 129.3549 654.4093 20.28085 129.3549 654.4093 20.28085 129.3146 651.8195 27.00948 129.7726 652.5496 23.94034 132.5544 648.8706 21.57272 129.7726 652.5496 23.94034 130.2889 650.3969 27.4139 130.2889 650.3969 27.4139 130.5623 646.9373 33.35102 130.9102 647.988 30.65138 133.7524 644.642 27.77298 130.9102 647.988 30.65138 131.6492 645.3298 33.65845 135.3853 639.4697 33.17555 131.6492 645.3298 33.65845 132.2713 641.179 38.7405 132.5106 642.4631 36.3972 132.5106 642.4631 36.3972 133.5076 639.3937 38.87341 137.4745 633.6186 37.55643 133.5076 639.3937 38.87341 134.4935 634.7565 43.05188 134.6441 636.1596 41.06082 138.6084 630.7348 39.21209 134.6441 636.1596 41.06082 135.9304 632.7686 42.96331 135.9304 632.7686 42.96331 137.2381 627.8959 46.22603 137.1443 629.7884 44.33963 137.1443 629.7884 44.33963 137.3766 629.2393 44.5652 137.3766 629.2393 44.5652 146.6318 614.1234 43.64167 140.1031 627.174 40.8652 143.1741 620.6042 42.88915 138.9937 625.5711 45.87108 138.9937 625.5711 45.87108 140.7776 621.8057 46.8578 140.7776 621.8057 46.8578 136.2537 627.7846 47.13966 133.5002 634.8302 43.89337 131.2684 641.4246 39.49308 129.5497 647.337 33.99746 128.293 652.3506 27.53321 127.4321 656.2813 20.26943 126.9022 658.985 12.40796 126.651 660.3614 4.177354 126.651 660.3614 -4.177754 126.9022 658.9849 -12.40835 127.4322 656.2811 -20.2698 128.2931 652.3504 -27.53354 129.5498 647.3367 -33.99774 131.2685 641.4243 -39.49331 133.5004 634.8298 -43.89356 136.2539 627.7842 -47.13979 158.3315 583.913 44.20133 162.1038 586.0386 44.20133 164.2026 582.3703 43.90727 142.5916 611.8469 43.64167 154.4623 600.1329 43.92152 162.1038 586.0386 44.20133 158.3315 583.913 44.20133 160.4487 580.1557 43.89316 166.3742 579.0411 42.93588 166.4954 578.8665 42.86375 166.4954 578.8665 42.86375 152.0114 604.5595 43.8332 146.6318 614.1234 43.64167 168.863 575.6873 41.10057 162.4992 576.5166 42.83259 168.863 575.6873 41.10057 171.2033 572.921 38.67455 164.4272 573.0949 41.05356 171.2033 572.921 38.67455 172.3499 571.6901 37.2059 166.1709 570.0004 38.61319 172.3499 571.6901 37.2059 183.9261 555.2258 26.09408 173.4692 570.582 35.57449 173.4692 570.582 35.57449 179.9611 563.6656 24.69684 167.6809 567.3205 35.57449 173.4692 570.582 35.57449 179.9611 563.6656 24.69684 167.6809 567.3205 35.57449 185.6661 556.0692 13.57591 185.6661 556.0692 13.57591 187.1929 548.3034 26.02262 185.6661 556.0692 13.57591 183.9261 555.2258 26.09408 186.3608 555.0039 12.07742 189.009 549.0576 13.11036 186.3608 555.0039 12.07742 135.3536 624.6921 40.80042 138.6084 630.7348 39.21209 140.1031 627.174 40.8652 132.0294 630.5918 37.53371 137.4745 633.6186 37.55643 138.9079 618.3844 42.85827 143.1741 620.6042 42.88915 146.6318 614.1234 43.64167 142.5916 611.8469 43.64167 135.3538 624.6918 -40.80059 138.6098 630.7319 -39.21366 137.5396 633.4479 -37.66285 140.161 627.0417 -40.91883 132.0296 630.5913 -37.53402 135.4479 639.283 -33.33993 129.032 635.9111 -33.15777 133.8033 644.4712 -27.98234 126.4478 640.4975 -27.80087 132.589 648.7422 -21.7977 124.352 644.2169 -21.6192 131.7471 651.9782 -14.8394 122.8067 646.9594 -14.79147 131.2661 653.9467 -7.497923 121.8586 648.6419 -7.516479 131.1106 654.6039 7.8e-5 121.5384 649.2102 0 131.2607 653.9692 7.369343 121.8586 648.642 7.516211 131.7286 652.0523 14.63422 122.8066 646.9596 14.79102 132.5544 648.8706 21.57272 124.3519 644.2171 21.61866 133.7524 644.642 27.77298 126.4476 640.4979 27.80035 135.3853 639.4697 33.17555 129.0318 635.9116 33.15733 158.3315 583.913 -44.20133 152.0114 604.5595 -43.8332 146.6318 614.1234 -43.64167 154.4623 600.1329 -43.92152 142.5916 611.8469 -43.64167 146.6318 614.1234 -43.64167 143.209 620.5344 -42.90381 142.5916 611.8469 -43.64167 138.908 618.3842 -42.85832 160.4487 580.1557 -43.89316 166.3751 579.04 -42.93542 164.2181 582.345 -43.90257 162.4992 576.5166 -42.83259 166.5196 578.832 -42.84918 162.1038 586.0386 -44.20133 162.1038 586.0386 -44.20133 158.3315 583.913 -44.20133 173.4698 570.5823 -35.57449 183.9261 555.2258 -26.09408 183.9261 555.2258 -26.09408 172.3583 571.6813 -37.19436 179.9613 563.6653 -24.69651 185.6663 556.0693 -13.57591 187.193 548.3034 -26.02234 185.6663 556.0693 -13.57591 178.0647 548.8922 -10.59914 185.6663 556.0693 -13.57591 179.9613 563.6653 -24.69651 186.3608 555.0039 -12.07741 189.009 549.0576 -13.11007 186.3608 555.0039 -12.07741 173.4698 570.5823 -35.57449 167.6809 567.3205 -35.57449 173.4698 570.5823 -35.57449 172.3583 571.6813 -37.19436 167.6809 567.3205 -35.57449 166.1709 570.0004 -38.61319 171.2187 572.9039 -38.6561 164.4272 573.0949 -41.05356 168.8866 575.6576 -41.0796 158.3315 583.913 -44.20133 158.3315 583.913 44.20133 160.4487 580.1557 43.89316 142.5916 611.8469 -43.64167 142.5916 611.8469 43.64167 160.4487 580.1557 -43.89316 162.4992 576.5166 42.83259 162.4992 576.5166 -42.83259 164.4272 573.0949 41.05356 164.4272 573.0949 -41.05356 166.1709 570.0004 38.61319 166.1709 570.0004 -38.61319 167.6809 567.3205 35.57449 167.6809 567.3205 -35.57449 178.0647 548.8922 10.59914 187.0239 553.9404 10.59914 178.0647 548.8922 10.59914 138.908 618.3842 -42.85832 138.9079 618.3844 42.85827 135.3538 624.6918 -40.80059 135.3536 624.6921 40.80042 132.0296 630.5913 -37.53402 132.0294 630.5918 37.53371 129.032 635.9111 -33.15777 129.0318 635.9116 33.15733 126.4478 640.4975 -27.80087 126.4476 640.4979 27.80035 124.352 644.2169 -21.6192 124.3519 644.2171 21.61866 122.8067 646.9594 -14.79147 122.8066 646.9596 14.79102 121.8586 648.6419 -7.516479 121.8586 648.642 7.516211 121.5384 649.2102 0 178.0647 548.8922 -10.59914 187.0237 553.9403 -10.59914 179.1045 547.0468 -7.405182 187.0237 553.9403 -10.59914 178.0647 548.8922 -10.59914 187.0237 553.9403 -10.59914 188.129 552.1275 -7.397813 188.129 552.1275 -7.397813 179.1045 547.0468 7.405182 179.1045 547.0468 -7.405182 187.0239 553.9404 10.59914 188.129 552.1276 7.398019 178.0647 548.8922 10.59914 187.0239 553.9404 10.59914 188.129 552.1276 7.398019 189.623 549.3126 1.44e-4 188.8155 551.0028 3.800323 179.7522 545.8975 3.806247 188.8155 551.0028 3.800323 179.1045 547.0468 7.405182 189.0482 550.6215 2.08e-4 189.0482 550.6215 2.08e-4 188.8156 551.0026 -3.799961 179.972 545.5073 0 188.8156 551.0026 -3.799961 179.7522 545.8975 -3.806247 189.8571 541.1773 -26.14004 191.7583 541.7456 -13.17029 192.401 541.9378 1.58e-4 191.7582 541.7456 13.1706 189.857 541.1773 26.14035 180.1249 545.5491 50.5066 180.1883 545.3974 50.51189 186.7482 540.2479 38.71483 181.6947 539.093 51.96718 180.1883 545.3974 50.51189 180.1249 545.5491 50.5066 182.5003 539.0759 50.72386 182.5003 539.0759 50.72386 191.5427 533.9421 -26.24178 193.5235 534.2172 -13.22251 194.1932 534.3102 -1.34e-4 193.5235 534.2172 13.22224 191.5427 533.9421 26.24152 182.527 538.9879 50.72671 188.3044 533.4923 38.86099 183.1403 532.8201 52.16183 182.527 538.9879 50.72671 183.9081 532.8854 50.91166 183.9081 532.8854 50.91166 192.0663 526.531 -26.33639 194.0806 526.5027 -13.27087 194.7617 526.4932 1.3e-5 194.0806 526.5027 13.27089 192.0663 526.531 26.33642 188.7736 526.5771 38.99784 183.9361 532.6879 50.91719 183.5295 526.4 52.34276 183.9361 532.6879 50.91719 184.3054 526.6277 51.08412 184.3054 526.6277 51.08412 184.2991 526.1784 51.09623 184.2991 526.1784 51.09623 183.0584 519.6976 52.52244 183.8552 519.8327 51.26292 179.7522 545.8975 3.806247 179.7522 545.8975 -3.806247 179.972 545.5073 0 180.6394 538.8008 52.94518 182.0468 532.6939 53.13956 182.4241 526.445 53.32026 181.9598 519.8511 53.49885 180.9748 513.1129 53.67434 180.9748 513.1129 53.67434 172.0784 463.0363 54.96551 152.7576 363.207 57.51136 162.6739 413.0755 56.24431 97.73546 263.4947 60.20806 98.58457 264.1935 60.19943 99.43112 264.9023 60.18903 100.2732 265.62 60.17686 101.1091 266.3456 60.16293 101.9386 267.0793 60.14721 102.7618 267.822 60.12968 103.5786 268.5742 60.11031 104.3886 269.3364 60.08909 105.1916 270.1091 60.06602 105.9872 270.8926 60.04106 106.7751 271.6873 60.01422 107.555 272.4938 59.98547 108.3264 273.3126 59.95481 109.0892 274.1442 59.92222 109.8429 274.9892 59.88769 110.587 275.8479 59.85121 111.321 276.7207 59.8128 112.0442 277.6078 59.77245 112.7561 278.5096 59.73017 113.4559 279.4263 59.68595 114.1431 280.3583 59.63981 114.8171 281.3058 59.59174 115.4772 282.2691 59.54175 116.1226 283.2483 59.48985 116.7526 284.2436 59.43604 117.3663 285.2551 59.38034 117.9631 286.283 59.32274 118.5422 287.3275 59.26326 119.1026 288.3885 59.2019 119.6436 289.4659 59.13868 120.1642 290.5595 59.0736 120.6635 291.6691 59.00669 121.1405 292.7945 58.93794 121.5469 293.956 58.82896 97.3738 263.2861 60.20641 98.29032 264.0967 60.19166 97.45468 263.357 60.20529 99.13787 264.8717 60.17274 99.93679 265.6062 60.15193 100.7619 266.3583 60.12945 101.5728 267.1273 60.1015 102.3768 267.9043 60.06992 103.1738 268.6899 60.03469 103.9636 269.4845 59.99581 104.7361 270.3161 59.94446 105.52 271.1018 59.90715 106.2861 271.9253 59.85736 107.0437 272.759 59.80397 107.7622 273.6219 59.73214 108.5322 274.4595 59.6864 109.2626 275.327 59.62226 109.9831 276.2067 59.55461 110.6933 277.0987 59.48348 111.3926 278.0032 59.40893 112.0805 278.9206 59.33104 112.7564 279.8511 59.24984 113.4198 280.7949 59.16539 114.0702 281.7523 59.07776 114.7069 282.7236 58.98699 115.3292 283.7088 58.89316 115.9366 284.7081 58.79632 116.5283 285.7217 58.69656 117.1036 286.7498 58.59392 117.662 287.7926 58.48847 118.2025 288.85 58.38027 118.7245 289.922 58.2694 119.2271 291.0086 58.15592 119.7095 292.1094 58.0399 120.1708 293.2244 57.92139 110 255.7616 -56.80979 97.87651 263.732 60.19865 98.44198 264.2419 60.18793 110 255.6469 56.80035 110 246.4811 -55.27311 110 237.5604 -52.22257 110 246.3916 55.25072 100.8656 266.476 60.12306 101.9742 267.5385 60.08173 101.4574 267.0398 60.10194 102.6678 268.2176 60.05197 103.4366 268.9843 60.01535 102.9891 268.5362 60.03713 104.1266 269.6856 59.97914 110 229.2474 -47.73216 110 237.5157 52.20334 106.0198 271.6807 59.86279 105.3653 270.9786 59.90592 106.5453 272.2547 59.82585 107.132 272.9071 59.78213 108.1912 274.1173 59.69629 110 221.7832 -41.92382 110 221.826 41.96307 110 229.2527 47.73582 109.0604 275.1444 59.61899 108.4506 274.4205 59.67389 109.7682 276.0053 59.55128 110.5192 276.9454 59.47453 111.2274 277.8587 59.39733 111.8141 278.6371 59.32964 112.3051 279.3045 59.27029 112.8884 280.1179 59.19644 112.3808 279.4088 59.26092 113.4644 280.9447 59.11977 114.0968 281.8815 59.03108 115.1895 283.581 58.86577 114.6278 282.6937 58.95276 115.622 284.2853 58.79574 116.3911 285.5887 58.66407 115.7816 284.5502 58.76919 117.027 286.7212 58.54767 117.502 287.604 58.45581 117.9959 288.5597 58.35532 118.3558 289.2828 58.27864 119.0156 290.675 58.12953 118.5021 289.5837 58.24657 119.5326 291.8359 58.00387 103.4366 268.9843 60.01535 104.1266 269.6856 59.97914 104.7361 270.3161 59.94446 105.3653 270.9786 59.90592 106.0198 271.6807 59.86279 106.5453 272.2547 59.82585 107.132 272.9071 59.78213 107.7622 273.6219 59.73214 108.1912 274.1173 59.69629 110.2081 281.2723 57.56626 108.4506 274.4205 59.67389 109.0604 275.1444 59.61899 109.7682 276.0053 59.55128 110.5192 276.9454 59.47453 111.2274 277.8587 59.39733 111.8141 278.6371 59.32964 112.3051 279.3045 59.27029 113.5589 286.1458 56.59712 112.3808 279.4088 59.26092 112.8884 280.1179 59.19644 113.4644 280.9447 59.11977 114.0968 281.8815 59.03108 114.6278 282.6937 58.95276 115.1895 283.581 58.86577 115.622 284.2853 58.79574 116.3616 291.5393 55.31562 115.7816 284.5502 58.76919 116.3911 285.5887 58.66407 117.027 286.7212 58.54767 117.502 287.604 58.45581 117.9959 288.5597 58.35532 118.3558 289.2828 58.27864 118.5021 289.5837 58.24657 119.0156 290.675 58.12953 119.5326 291.8359 58.00387 116.2574 298.3574 51.04507 115.383 304.6037 46.07479 113.8499 310.1799 40.50921 111.7859 315.0267 34.44927 109.3159 319.1107 27.98619 106.5565 322.4111 21.20323 103.6091 324.9154 14.17383 100.5634 326.6137 6.966196 94.57915 321.6595 8.569121 97.92844 320.1609 15.54284 101.1635 317.8557 22.33567 104.1775 314.7518 28.87338 106.8497 310.8612 35.07564 109.0412 306.2062 40.85038 110.6037 300.8258 46.09599 111.3898 294.7919 50.70075 111.2789 288.2211 54.55361 97.78395 323.8331 7.623665 103.69 320.1944 20.88009 100.781 322.3756 14.32765 106.4299 317.2958 27.22035 108.9084 313.6884 33.28253 111.0202 309.3885 38.99261 112.6518 304.4216 44.26963 113.6851 298.8342 49.02401 114.0127 292.7045 53.16154 169.9905 393.9013 26.63747 174.0454 416.5027 27.14129 169.9905 393.9013 26.63747 169.4482 390.549 26.20628 168.8418 384.5766 23.33894 169.0675 387.4113 25.09697 168.7563 382.1387 21.00284 168.7913 380.2055 18.20705 168.8488 379.4397 16.63206 168.9325 378.8296 14.97311 169.2949 377.0207 7.575 168.9325 378.8296 14.97311 167.0729 384.1044 13.19409 168.8488 379.4397 16.63206 168.9325 378.8296 14.97311 168.0046 381.1903 12.83763 168.9325 378.8296 14.97311 169.2949 377.0207 7.575 168.0046 381.1903 12.83763 168.6688 394.1462 20.30819 169.9905 393.9013 26.63747 169.4482 390.549 26.20628 172.6146 415.5353 20.26457 174.0454 416.5027 27.14129 169.9905 393.9013 26.63747 168.6688 394.1462 20.30819 168.1955 391.5476 19.98609 169.0675 387.4113 25.09697 168.4276 392.8358 20.22779 167.7703 389.1058 19.03304 168.8418 384.5766 23.33894 167.9747 390.2963 19.58488 167.4261 386.9719 17.51789 168.7563 382.1387 21.00284 167.5863 387.9918 18.3413 167.1899 385.2797 15.54609 168.7913 380.2055 18.20705 169.4212 376.435 0.007477939 169.2953 377.0188 -7.562598 168.9325 378.8296 -14.97312 168.9325 378.8296 -14.97312 167.0396 383.5763 -5.235938 169.2953 377.0188 -7.562598 168.9325 378.8296 -14.97312 168.849 379.4382 -16.62885 168.0046 381.1903 -12.83764 168.9325 378.8296 -14.97312 168.849 379.4382 -16.62885 168.0046 381.1903 -12.83764 167.0385 383.5737 4.563882 169.4212 376.435 0.007477939 167.0826 383.5504 10.70187 167.0245 383.5981 -0.3832 168.7915 380.2028 -18.20246 168.7563 382.1353 -20.99894 168.7601 381.1041 -19.65665 168.8417 384.5747 -23.33751 168.7827 383.2983 -22.23323 169.0675 387.4117 -25.09704 168.9359 385.9494 -24.29519 169.7008 392.2082 -26.50967 169.2377 388.9475 -25.73466 169.4482 390.5491 -26.20623 169.9905 393.9013 -26.63743 169.9905 393.9013 -26.63743 168.4243 392.8179 -20.22566 169.7008 392.2082 -26.50967 169.9905 393.9013 -26.63743 174.0454 416.503 -27.14124 168.6688 394.1462 -20.30819 169.9905 393.9013 -26.63743 174.0454 416.503 -27.14124 168.6688 394.1462 -20.30819 167.0728 384.1019 -13.1872 168.7915 380.2028 -18.20246 167.0826 383.5504 -10.70187 167.0624 383.7501 -11.94885 167.1145 384.6085 -14.38568 168.7601 381.1041 -19.65665 167.1869 385.2561 -15.51026 168.7563 382.1353 -20.99894 167.2885 386.0284 -16.53857 168.7827 383.2983 -22.23323 167.4189 386.9239 -17.4737 168.8417 384.5747 -23.33751 167.579 387.9466 -18.30915 168.9359 385.9494 -24.29519 167.764 389.0689 -19.01286 169.0675 387.4117 -25.09704 167.9687 390.262 -19.5713 169.2377 388.9475 -25.73466 168.1902 391.5177 -19.97852 169.4482 390.5491 -26.20623 177.9001 438.3255 -27.42485 181.5722 459.3571 -27.46382 185.08 479.5862 -27.23261 185.08 479.5862 -27.23261 180.5141 458.3121 -20.17555 181.5722 459.3571 -27.46382 185.08 479.5862 -27.23261 185.4008 481.3431 -27.1233 184.4679 479.6997 -20.13058 185.08 479.5862 -27.23261 185.4008 481.3431 -27.1233 184.4679 479.6997 -20.13058 176.563 436.9239 -20.22028 177.9001 438.3255 -27.42485 172.6146 415.5353 -20.26457 185.7448 483.0532 -26.83948 186.4884 486.2579 -25.79085 186.1087 484.6951 -26.3907 187.6827 490.4311 -23.07304 186.8801 487.7388 -25.03274 187.2801 489.1325 -24.12601 188.4635 492.6828 -20.59437 188.0794 491.6187 -21.88762 189.1827 494.4448 -17.63132 188.8325 493.627 -19.17462 189.5067 495.1201 -16.00011 190.4225 496.8454 -9.82236 189.5067 495.1201 -16.00011 186.4752 489.8092 -11.73555 189.1827 494.4448 -17.63132 189.5067 495.1201 -16.00011 188.0256 492.5462 -13.23624 189.5067 495.1201 -16.00011 190.4225 496.8454 -9.82236 188.0256 492.5462 -13.23624 184.9369 482.2176 -19.80795 185.7448 483.0532 -26.83948 184.7035 480.9651 -20.04744 185.1666 483.4424 -19.41007 186.1087 484.6951 -26.3907 186.4884 486.2579 -25.79085 185.3884 484.6135 -18.85927 186.8801 487.7388 -25.03274 185.5995 485.7138 -18.16202 187.2801 489.1325 -24.12601 185.796 486.7199 -17.3287 187.6827 490.4311 -23.07304 185.9741 487.6074 -16.383 188.0794 491.6187 -21.88762 186.1328 488.3699 -15.33742 188.4635 492.6828 -20.59437 186.271 488.9998 -14.19801 188.8325 493.627 -19.17462 186.386 489.4837 -12.98573 190.919 497.7342 -3.301383 190.9195 497.7352 3.286555 190.423 496.8464 9.816722 189.5068 495.1202 16.00012 189.5068 495.1202 16.00012 186.5351 489.9821 6.326436 190.423 496.8464 9.816722 189.5068 495.1202 16.00012 188.8366 493.6369 19.1588 188.0256 492.546 13.23617 189.5068 495.1202 16.00012 188.8366 493.6369 19.1588 188.0256 492.546 13.23617 186.5307 489.9755 -5.02226 190.919 497.7342 -3.301383 186.5387 489.9789 -10.47796 186.5248 489.9665 -0.308484 190.9195 497.7352 3.286555 186.5277 489.9713 2.818029 188.0843 491.6326 21.87275 186.4891 486.2607 25.78905 187.2832 489.143 24.11813 185.7439 483.0487 26.84048 185.4001 481.3394 27.12366 185.0801 479.5862 27.23373 185.0801 479.5862 27.23373 184.9328 482.1951 19.8144 185.4001 481.3394 27.12366 185.0801 479.5862 27.23373 181.5722 459.3567 27.46384 184.4679 479.6997 20.13058 185.0801 479.5862 27.23373 181.5722 459.3567 27.46384 184.4679 479.6997 20.13058 186.1367 488.388 15.30931 188.0843 491.6326 21.87275 186.3852 489.4803 12.99633 186.5387 489.9789 10.47782 185.9744 487.6087 16.38173 187.2832 489.143 24.11813 185.5925 485.678 18.18754 186.4891 486.2607 25.78905 185.791 486.6943 17.35243 185.3811 484.5757 18.87966 185.7439 483.0487 26.84048 185.1605 483.4097 19.42317 177.9001 438.3251 27.42489 180.5141 458.3121 20.17555 177.9001 438.3251 27.42489 176.563 436.9239 20.22028 168.6206 394.1558 19.99723 184.4679 479.6997 20.13058 180.5141 458.3121 20.17555 168.6032 394.158 19.68498 184.4595 479.7015 19.99992 184.9042 482.1102 19.55355 184.4679 479.6997 20.13058 184.4595 479.7015 19.99992 184.9328 482.1951 19.8144 176.563 436.9239 20.22028 172.6146 415.5353 20.26457 168.6688 394.1462 20.30819 168.6206 394.1558 19.99723 168.6688 394.1462 20.30819 168.4276 392.8358 20.22779 168.2307 392.0493 19.76514 168.1955 391.5476 19.98609 167.9747 390.2963 19.58488 167.8688 390.0718 19.09556 167.7703 389.1058 19.03304 167.5478 388.2943 18.02928 167.5863 387.9918 18.3413 167.4261 386.9719 17.51789 167.2784 386.7696 16.60483 167.1899 385.2797 15.54609 167.073 385.5625 14.86862 167.0729 384.1044 13.19409 167.0826 383.5504 10.70187 166.9431 384.7367 12.87951 167.0826 383.5504 10.70187 166.8982 384.35 10.68884 166.8989 384.3496 -10.68885 166.8982 384.35 10.68884 167.0826 383.5504 10.70187 167.0385 383.5737 4.563882 168.6032 394.158 19.68498 168.1772 391.8594 19.37818 167.7775 389.7025 18.47792 167.4326 387.8418 17.04177 167.1669 386.4081 15.16941 166.9982 385.4981 12.99563 166.9365 385.165 10.67302 166.9223 385.0887 0.115271 166.9365 385.165 10.67302 166.9365 385.1649 -10.67326 168.6033 394.1582 -19.68497 168.6032 394.158 19.68498 168.1772 391.8594 19.37818 184.458 479.7027 19.86907 181.7077 464.8632 7.7298 184.458 479.7027 19.86907 170.8813 406.449 -9.600602 173.6769 421.5332 7.538402 173.9192 422.8403 6.984919 174.7811 427.4909 7.7298 173.4144 420.1165 7.7298 170.8813 406.449 7.7298 175.4809 431.2666 7.7298 176.0433 434.3007 7.7298 176.7072 437.8829 7.7298 178.4299 447.1776 7.7298 168.1758 391.8515 -19.37622 167.7775 389.7025 18.47792 167.7753 389.691 -18.47154 167.4326 387.8418 17.04177 167.4306 387.8311 -17.03148 167.1669 386.4081 15.16941 167.1656 386.4011 -15.15799 166.9982 385.4981 12.99563 166.9978 385.4956 -12.98757 166.9365 385.165 10.67302 166.9223 385.0887 0.115271 166.9365 385.1649 -10.67326 184.458 479.7027 19.86907 184.4581 479.7032 -19.86927 184.9042 482.1102 19.55355 181.8154 465.4443 -6.2688 166.9432 384.7367 -12.88127 166.9978 385.4956 -12.98757 166.9365 385.1649 -10.67326 166.8989 384.3496 -10.68885 184.9042 482.1104 -19.55359 185.3192 484.349 18.6183 185.3192 484.349 18.6183 185.3192 484.3492 -18.61814 185.6755 486.2715 17.12988 185.3811 484.5757 18.87966 185.6755 486.2715 17.12988 185.1605 483.4097 19.42317 185.9498 487.7519 -15.18744 185.9498 487.7518 15.18775 185.791 486.6943 17.35243 185.9498 487.7518 15.18775 185.6755 486.2716 -17.12959 185.5925 485.678 18.18754 186.1239 488.691 -12.91878 186.1239 488.691 12.91899 186.1367 488.388 15.30931 186.1239 488.691 12.91899 185.9744 487.6087 16.38173 186.1853 489.0225 -10.47169 186.1853 489.0224 10.47174 186.3852 489.4803 12.99633 186.1853 489.0224 10.47174 186.1887 489.0404 0.131875 186.3211 489.5158 -10.47522 186.1853 489.0224 10.47174 186.1887 489.0404 0.131875 186.3211 489.5156 10.47518 186.3211 489.5156 10.47518 186.1853 489.0225 -10.47169 186.3211 489.5158 -10.47522 186.1853 489.0225 -10.47169 186.1239 488.691 -12.91878 186.271 488.9998 -14.19801 185.9498 487.7519 -15.18744 186.5387 489.9789 -10.47796 186.4752 489.8092 -11.73555 186.386 489.4837 -12.98573 185.9741 487.6074 -16.383 185.6755 486.2716 -17.12959 186.1328 488.3699 -15.33742 185.5995 485.7138 -18.16202 185.3192 484.3492 -18.61814 185.796 486.7199 -17.3287 185.1666 483.4424 -19.41007 184.9042 482.1104 -19.55359 185.3884 484.6135 -18.85927 184.7035 480.9651 -20.04744 184.4581 479.7032 -19.86927 184.9369 482.2176 -19.80795 168.6206 394.1558 -19.9974 184.4581 479.7032 -19.86927 168.6033 394.1582 -19.68497 171.5393 409.9994 -9.600602 174.7811 427.4909 -9.600602 175.4809 431.2666 -9.600602 176.0433 434.3007 -9.600602 178.077 445.2738 -9.600602 178.394 446.9841 -9.600602 181.8154 465.4443 -9.600602 184.4596 479.7015 -20.00017 184.4596 479.7015 -20.00017 168.6206 394.1558 -19.9974 168.6033 394.1582 -19.68497 168.1758 391.8515 -19.37622 167.8689 390.072 -19.09587 167.7753 389.691 -18.47154 168.2308 392.0494 -19.76575 167.5478 388.2943 -18.0295 167.4306 387.8311 -17.03148 167.2784 386.7693 -16.60452 167.1656 386.4011 -15.15799 167.0731 385.5628 -14.86982 171.5393 409.9994 -3.3318 174.7811 427.4909 -9.600602 174.2865 424.8222 -0.571245 174.1269 423.9612 -1.710942 174.7781 424.731 -0.571502 174.1269 423.9612 -1.710942 174.2865 424.8222 -0.571245 174.6185 423.8698 -1.711179 174.7811 427.4909 7.7298 174.3874 425.3664 3.640013 174.7811 427.4909 -9.600602 175.9725 431.1755 -9.600602 175.4809 431.2666 -9.600602 175.4809 431.2666 7.7298 175.9725 431.1755 -9.600602 175.2727 427.3998 -9.600602 175.4809 431.2666 -9.600602 175.9725 431.1755 7.7298 175.4809 431.2666 7.7298 174.7811 427.4909 7.7298 174.879 425.2753 3.639833 174.9139 425.4635 2.199 174.3874 425.3664 3.640013 174.7781 424.7311 4.969245 178.9215 447.0865 4.398 178.4299 447.1776 4.398 180.7529 459.7118 4.398 178.9215 447.0865 7.7298 178.4299 447.1776 7.7298 178.4299 447.1776 4.398 178.9215 447.0865 4.398 181.2445 459.6207 4.398 180.7529 459.7118 4.398 178.394 446.9841 -6.2688 181.2445 459.6207 4.398 178.8856 446.893 -6.2688 178.394 446.9841 -6.2688 178.394 446.9841 -9.600602 178.8856 446.893 -6.2688 178.8856 446.893 -9.600602 178.394 446.9841 -9.600602 181.8154 465.4443 -9.600602 178.8856 446.893 -9.600602 182.307 465.3532 -9.600602 181.8154 465.4443 -9.600602 181.8154 465.4443 -6.2688 182.307 465.3532 -9.600602 176.7072 437.8829 7.7298 176.7072 437.8829 -6.2688 178.077 445.2738 -6.2688 176.0433 434.3007 -9.600602 175.4809 431.2666 7.7298 175.4809 431.2666 -9.600602 174.879 425.2753 0.757987 174.2865 424.8222 -0.571245 174.3874 425.3665 0.758167 174.7781 424.731 -0.571502 173.906 420.0253 -3.3318 173.4144 420.1165 -3.3318 173.677 421.5334 -3.14035 172.0309 409.9082 -3.3318 173.4144 420.1165 -3.3318 173.906 420.0253 -3.3318 174.7811 427.4909 -9.600602 174.3874 425.3665 0.758167 174.2865 424.8222 -0.571245 172.0309 409.9082 -9.600602 171.5393 409.9994 -9.600602 171.5393 409.9994 -3.3318 171.3729 406.3579 -9.600602 170.8813 406.449 -9.600602 171.5393 409.9994 -9.600602 172.0309 409.9082 -9.600602 178.394 446.9841 -6.2688 178.4299 447.1776 4.398 176.7072 437.8829 7.7298 178.4299 447.1776 7.7298 174.7781 424.7311 4.969245 174.3874 425.3664 3.640013 174.2865 424.8221 4.969502 173.4144 420.1165 0 171.5393 409.9994 4.398 171.5393 409.9994 0 173.4144 420.1165 4.398 173.4948 420.5507 0.04708188 173.4948 420.5507 4.350918 173.5689 420.9503 0.170127 173.5689 420.9503 4.227873 173.6376 421.3208 0.37357 173.6376 421.3208 4.02443 173.6977 421.6453 0.644106 173.6977 421.6453 3.753894 173.747 421.9113 0.974163 173.747 421.9113 3.423837 173.7841 422.1114 1.350976 173.7841 422.1114 3.047024 173.8065 422.2323 1.757344 173.8065 422.2323 2.640656 173.8151 422.2786 2.199 174.4109 422.7495 6.984769 174.1269 423.9609 6.109179 173.9192 422.8403 6.984919 174.6186 423.8701 6.108942 174.1686 421.4422 7.53835 173.6769 421.5332 7.538402 173.4144 420.1165 7.7298 173.906 420.0253 7.7298 173.4144 420.1165 7.7298 170.8813 406.449 7.7298 173.906 420.0253 7.7298 171.3729 406.3579 7.7298 170.8813 406.449 7.7298 170.8813 406.449 -9.600602 171.3729 406.3579 7.7298 171.3729 406.3579 -9.600602 175.2727 427.3998 -9.600602 174.7811 427.4909 -9.600602 175.4809 431.2666 -9.600602 175.2727 427.3998 7.7298 174.7811 427.4909 7.7298 174.7811 427.4909 -9.600602 175.2727 427.3998 -9.600602 167.0396 383.5763 -5.235938 167.0826 383.5504 -10.70187 166.8989 384.3496 -10.68885 167.0624 383.7501 -11.94885 166.8989 384.3496 -10.68885 167.0826 383.5504 -10.70187 167.0245 383.5981 -0.3832 167.0385 383.5737 4.563882 166.9432 384.7367 -12.88127 168.0046 381.1903 -12.83764 167.0826 383.5504 -10.70187 167.0396 383.5763 -5.235938 167.0728 384.1019 -13.1872 167.1145 384.6085 -14.38568 167.0731 385.5628 -14.86982 167.1869 385.2561 -15.51026 167.2885 386.0284 -16.53857 167.2784 386.7693 -16.60452 167.4189 386.9239 -17.4737 167.579 387.9466 -18.30915 167.5478 388.2943 -18.0295 167.764 389.0689 -19.01286 167.8689 390.072 -19.09587 167.9687 390.262 -19.5713 168.1902 391.5177 -19.97852 168.2308 392.0494 -19.76575 168.4243 392.8179 -20.22566 168.6688 394.1462 -20.30819 168.6206 394.1558 -19.9974 168.6206 394.1558 -19.9974 168.6688 394.1462 -20.30819 172.6146 415.5353 -20.26457 176.563 436.9239 -20.22028 180.5141 458.3121 -20.17555 184.4679 479.6997 -20.13058 184.4596 479.7015 -20.00017 184.7035 480.9651 -20.04744 184.4596 479.7015 -20.00017 184.4679 479.6997 -20.13058 186.3211 489.5156 10.47518 186.3211 489.5158 -10.47522 186.5387 489.9789 -10.47796 188.0256 492.5462 -13.23624 186.5387 489.9789 -10.47796 186.4752 489.8092 -11.73555 186.5307 489.9755 -5.02226 186.5351 489.9821 6.326436 186.5387 489.9789 10.47782 186.3852 489.4803 12.99633 186.3211 489.5156 10.47518 186.5387 489.9789 10.47782 186.5277 489.9713 2.818029 186.5248 489.9665 -0.308484 188.0256 492.546 13.23617 186.5387 489.9789 10.47782 186.5351 489.9821 6.326436 182.307 465.3532 -6.2688 181.8154 465.4443 -6.2688 179.3487 452.1355 -6.2688 171.3729 406.3579 7.7298 171.3729 406.3579 -9.600602 172.0309 409.9082 -9.600602 172.0309 409.9082 -3.3318 173.906 420.0253 4.398 173.906 420.0253 7.7298 172.0309 409.9082 0 172.0309 409.9082 4.398 174.1292 421.2297 4.02443 174.1686 421.4422 7.53835 174.0605 420.8592 4.227873 173.9865 420.4596 4.350918 173.906 420.0253 0 173.906 420.0253 -3.3318 174.1686 421.4421 -3.140402 174.1893 421.5542 0.644106 174.4108 422.7492 -2.586919 173.9865 420.4596 0.04708188 174.0605 420.8592 0.170127 174.1292 421.2297 0.37357 174.4109 422.7495 6.984769 174.6185 423.8698 -1.711179 174.2981 422.1412 2.640656 174.2386 421.8202 0.974163 174.2757 422.0202 1.350976 174.2981 422.1412 1.757344 174.3067 422.1875 2.199 174.6186 423.8701 6.108942 174.7781 424.731 -0.571502 174.7781 424.7311 4.969245 174.879 425.2753 0.757987 174.879 425.2753 3.639833 174.9139 425.4635 2.199 174.2757 422.0202 3.047024 174.2386 421.8202 3.423837 174.1893 421.5542 3.753894 171.5393 409.9994 4.398 172.0309 409.9082 4.398 172.0309 409.9082 0 173.4144 420.1165 4.398 173.906 420.0253 4.398 172.0309 409.9082 4.398 171.5393 409.9994 4.398 171.5393 409.9994 0 172.0309 409.9082 0 173.906 420.0253 0 171.5393 409.9994 0 173.4144 420.1165 0 173.906 420.0253 0 173.9865 420.4596 0.04708188 173.4144 420.1165 0 173.4948 420.5507 0.04708188 174.0605 420.8592 0.170127 173.5689 420.9503 0.170127 174.1292 421.2297 0.37357 173.6376 421.3208 0.37357 174.1893 421.5542 0.644106 173.6977 421.6453 0.644106 174.2386 421.8202 0.974163 173.747 421.9113 0.974163 174.2757 422.0202 1.350976 173.7841 422.1114 1.350976 174.2981 422.1412 1.757344 173.8065 422.2323 1.757344 174.3067 422.1875 2.199 173.8151 422.2786 2.199 174.2981 422.1412 2.640656 173.8065 422.2323 2.640656 174.2757 422.0202 3.047024 173.7841 422.1114 3.047024 174.2386 421.8202 3.423837 173.747 421.9113 3.423837 174.1893 421.5542 3.753894 173.6977 421.6453 3.753894 174.1292 421.2297 4.02443 173.6376 421.3208 4.02443 174.0605 420.8592 4.227873 173.5689 420.9503 4.227873 173.9865 420.4596 4.350918 173.4948 420.5507 4.350918 173.906 420.0253 4.398 173.4144 420.1165 4.398 115.993 567.6346 -27.66399 118.6555 570.794 -31.84755 120.916 569.637 -31.31476 114.4533 568.3211 -28.19537 118.9822 565.9119 -26.89754 123.0936 568.2573 -31.0209 117.5065 566.8297 -27.2301 120.4072 564.8883 -26.66989 125.1519 566.6782 -30.97086 121.77 563.7681 -26.54829 123.0606 562.5604 -26.53309 108.9461 564.0877 -20.56344 114.4533 568.3211 -28.19537 115.993 567.6346 -27.66399 111.2551 563.0012 -19.6484 117.5065 566.8297 -27.2301 118.9822 565.9119 -26.89754 113.4718 561.6182 -18.92751 120.4072 564.8883 -26.66989 115.5549 559.9614 -18.4157 121.77 563.7681 -26.54829 117.4677 558.0633 -18.12041 123.0606 562.5604 -26.53309 103.3827 561.186 -12.34529 106.4591 559.7053 -11.00136 109.3155 557.6549 -9.941179 111.8506 555.1072 -9.20232 123.7901 536.2987 -8.222597 122.2432 539.1483 -8.508129 123.9383 536.4362 -8.566074 141.5214 506.6333 -8.06471 123.9383 536.4362 -8.566074 124.1681 536.4835 -8.898372 123.7901 536.2987 -8.222597 123.9383 536.4362 -8.566074 141.5214 506.6333 -8.06471 124.3647 536.572 -9.235679 124.5357 536.7075 -9.574007 124.6809 536.8866 -9.910348 124.8001 537.1064 -10.24172 145.4696 499.8197 -9.201619 141.5214 506.6333 -8.06471 145.2864 510.2185 -16.5437 141.3924 506.487 -7.741603 145.4696 499.8197 -9.201619 141.3924 506.487 -7.741603 141.5214 506.6333 -8.06471 152.5168 508.2346 -24.96564 149.2142 514.9315 -24.50076 148.9042 503.5869 -17.35784 156.1893 513.799 -31.93395 153.1544 520.8908 -31.82075 159.8029 520.2748 -38.18756 156.8872 527.9812 -38.26179 163.2518 527.6049 -43.68167 160.2692 536.1252 -43.78109 166.4565 535.6899 -48.41067 161.8298 540.6166 -46.23907 163.2963 545.3479 -48.49355 141.2709 506.3385 -7.416421 141.2709 506.3385 -7.416421 123.6248 536.1984 -7.874366 141.0422 505.7369 -6.335302 123.6248 536.1984 -7.874366 141.2709 506.3385 -7.416421 145.2196 499.4637 -8.478413 141.0422 505.7369 -6.335302 141.2709 506.3385 -7.416421 145.2196 499.4637 -8.478413 123.5651 536.1705 -7.77547 121.8323 538.9238 -7.712584 123.6248 536.1984 -7.874366 123.5651 536.1705 -7.77547 121.9491 538.9362 -7.902199 150.3471 477.0908 -14.90921 150.7507 477.6445 -15.88967 150.1506 470.3296 -19.0209 154.4228 482.5574 -24.1649 150.1506 470.3296 -19.0209 150.7507 477.6445 -15.88967 149.9104 470.0209 -18.48197 144.2166 447.5814 -21.1855 149.9104 470.0209 -18.48197 150.1506 470.3296 -19.0209 151.2508 471.7543 -21.42986 151.2508 471.7543 -21.42986 149.8181 484.6406 -12.27648 150.1591 485.1284 -13.16222 154.113 490.325 -22.44476 150.1591 485.1284 -13.16222 148.0938 492.1642 -10.1139 148.3838 492.5827 -10.91401 151.9743 496.9908 -19.5519 148.3838 492.5827 -10.91401 144.8154 498.6332 -6.99114 148.0938 492.1642 -10.1139 147.4653 491.0985 -8.146356 149.8181 484.6406 -12.27648 149.1513 475.5271 -11.82195 150.3471 477.0908 -14.90921 148.9233 483.329 -9.77073 149.6711 469.718 -17.93948 148.1596 467.9143 -14.28653 149.6711 469.718 -17.93948 149.6711 469.718 -17.93948 148.1596 467.9143 -14.28653 151.9528 455.8706 -35.90971 161.0911 466.8387 -50.64106 153.8413 437.0227 -49.41643 159.2468 482.8015 -36.84574 163.9953 490.058 -44.6771 159.0583 482.5252 -36.51741 144.9603 429.172 -35.24451 146.7377 407.1754 -48.08734 138.0929 402.4429 -34.50053 139.7875 377.2972 -46.64912 133.2218 347.3463 -45.45401 132.9658 347.3948 -45.09379 131.353 375.6837 -33.67647 134.1692 347.1653 -46.77661 135.1508 346.976 -48.12942 136.1664 346.7784 -49.51065 137.2179 346.5715 -50.92166 138.3072 346.3542 -52.36348 139.4345 346.1268 -53.83471 140.6004 345.889 -55.33434 131.1901 343.3833 -44.01745 132.9658 347.3948 -45.09379 133.2218 347.3463 -45.45401 131.8465 347.6056 -43.50381 131.8465 347.6056 -43.50381 132.3431 343.0064 -45.68364 134.1692 347.1653 -46.77661 133.5087 342.6268 -47.33906 135.1508 346.976 -48.12942 134.6866 342.2444 -48.98363 136.1664 346.7784 -49.51065 135.8769 341.859 -50.61728 137.2179 346.5715 -50.92166 138.3072 346.3542 -52.36348 137.0794 341.4704 -52.23997 139.4345 346.1268 -53.83471 138.2941 341.0787 -53.85161 140.6004 345.889 -55.33434 139.5207 340.6835 -55.45215 162.4574 494.4964 -39.26535 163.9953 490.058 -44.6771 159.2468 482.8015 -36.84574 166.6344 501.5209 -45.94777 159.0583 482.5252 -36.51741 154.5944 476.2149 -28.2808 158.3548 488.1705 -31.98192 154.5944 476.2149 -28.2808 137.2841 423.3066 -20.95327 130.4609 399.0015 -20.66094 125.678 348.7298 -34.27653 124.7026 348.903 -32.73908 123.746 374.6672 -20.30914 126.7 348.5474 -35.86322 127.6703 348.3733 -37.34729 128.6849 348.1894 -38.87688 129.7434 347.996 -40.44884 130.7722 347.806 -41.95449 124.5409 345.5963 -33.79759 124.7026 348.903 -32.73908 125.678 348.7298 -34.27653 124.0221 349.0234 -31.65262 123.4789 345.9592 -32.0579 124.0221 349.0234 -31.65262 125.6165 345.2323 -35.52706 126.7 348.5474 -35.86322 127.6703 348.3733 -37.34729 126.7053 344.8668 -37.24618 128.6849 348.1894 -38.87688 127.8072 344.4993 -38.95484 129.7434 347.996 -40.44884 128.922 344.1296 -40.65298 130.7722 347.806 -41.95449 130.0497 343.7577 -42.34054 136.5414 437.3221 -6.496051 147.4998 467.1984 -12.54607 146.747 466.4441 -10.42038 145.458 465.3321 -6.327146 127.9337 409.7886 -6.593951 119.4333 382.0812 -6.622331 117.6231 350.199 -20.8015 117.116 350.3035 -19.88391 110.9029 353.5314 -6.734655 118.5557 350.0141 -22.46394 119.5333 349.8294 -24.17318 120.2142 349.7036 -25.34561 120.9187 349.576 -26.5433 121.6508 349.4445 -27.7725 122.4103 349.3091 -29.03167 123.1995 349.1692 -30.32358 116.4571 348.5487 -19.60675 117.116 350.3035 -19.88391 117.6231 350.199 -20.8015 110.9674 353.4841 -6.89061 111.0256 353.407 -7.051347 111.0758 353.3021 -7.211934 111.3914 352.7206 -8.168148 111.8088 352.2339 -9.252597 112.333 351.8462 -10.46878 112.9349 351.5173 -11.78062 116.4894 350.4396 -18.73466 116.4894 350.4396 -18.73466 117.4113 348.1615 -21.41338 118.5557 350.0141 -22.46394 118.3835 347.7846 -23.21102 119.5333 349.8294 -24.17318 119.3723 347.4144 -24.99953 120.2142 349.7036 -25.34561 120.9187 349.576 -26.5433 120.3769 347.0484 -26.77873 121.6508 349.4445 -27.7725 121.3966 346.6846 -28.54833 122.4103 349.3091 -29.03167 123.1995 349.1692 -30.32358 122.4307 346.3218 -30.3081 147.4998 467.1984 -12.54607 146.747 466.4441 -10.42038 148.0514 474.2868 -8.575824 145.458 465.3321 -6.327146 144.995 465.0053 -4.656908 145.458 465.3321 -6.327146 136.5414 437.3221 -6.496051 147.0757 473.3984 -5.202428 146.726 473.1499 -3.818984 147.0757 473.3984 -5.202428 145.458 465.3321 -6.327146 144.995 465.0053 -4.656908 135.5249 436.8092 -3.025954 127.9337 409.7886 -6.593951 110 229.2474 -47.73216 110 221.826 41.96307 110 229.2527 47.73582 144.5878 464.8291 -2.924179 126.697 408.9726 -3.093507 119.4333 382.0812 -6.622331 110.8337 353.5511 -6.585107 117.9326 380.7705 -3.127657 110.8337 353.5511 -6.585107 110.6931 353.0963 -6.580119 110.8337 353.5511 -6.585107 110.9029 353.5314 -6.734655 110.7504 353.5541 -6.414313 110.8108 352.8443 -6.96391 111.0758 353.3021 -7.211934 111.3914 352.7206 -8.168148 111.3602 351.7477 -8.67147 111.8088 352.2339 -9.252597 112.333 351.8462 -10.46878 112.0736 350.9663 -10.47298 112.9349 351.5173 -11.78062 115.8832 350.5798 -17.60583 113.6085 351.2409 -13.17702 112.8737 350.354 -12.30377 113.6085 351.2409 -13.17702 115.0766 350.7835 -16.07451 114.32 350.999 -14.60289 113.7236 349.8386 -14.13548 114.32 350.999 -14.60289 114.6099 349.3779 -15.9671 115.0766 350.7835 -16.07451 115.8832 350.5798 -17.60583 115.5223 348.9514 -17.79126 162.8251 503.6603 -38.99155 167.2904 511.7811 -46.03887 158.383 496.496 -31.09481 163.7564 515.7768 -41.59722 167.6005 523.8228 -47.38319 159.7894 508.5831 -34.98981 155.8186 502.3149 -27.6125 144.3892 498.092 -5.417509 143.9589 497.8401 -3.779235 140.3589 505.3188 -3.998863 140.1677 505.3716 -3.426729 140.3589 505.3188 -3.998863 143.9589 497.8401 -3.779235 140.7325 505.3944 -5.193562 122.3464 535.7144 -4.803707 140.7325 505.3944 -5.193562 140.3589 505.3188 -3.998863 140.1677 505.3716 -3.426729 146.3155 489.8796 -3.910681 143.783 497.8233 -3.092385 146.3155 489.8796 -3.910681 146.8663 490.3341 -6.069348 147.3641 481.6568 -4.389471 146.109 489.7893 -3.019197 147.3641 481.6568 -4.389471 148.098 482.3278 -7.131571 147.0992 481.4874 -3.263677 123.5104 536.151 -7.672266 123.5104 536.151 -7.672266 121.8323 538.9238 -7.712584 123.5104 536.151 -7.672266 122.3464 535.7144 -4.803707 139.995 505.459 -2.918808 121.751 535.4336 -1.634611 110 221.7832 -41.92382 110 215.4543 35.05654 139.5896 505.7034 1.230311 121.749 535.4329 1.613872 139.5608 505.7194 0.993617 139.5346 505.7366 -0.744963 139.5599 505.7198 -0.984627 140.359 505.3188 3.999053 122.3458 535.7131 4.799978 140.1869 505.3644 3.484556 110 215.3974 -34.9838 110 210.3247 27.22747 139.995 505.459 2.918806 141.0415 505.7357 6.332516 123.5104 536.151 7.67235 140.732 505.3942 5.192037 141.2709 506.3385 7.416425 123.5651 536.1705 7.775512 121.9491 538.9362 7.902199 123.5104 536.151 7.67235 123.5651 536.1705 7.775512 121.8324 538.9238 7.71264 123.6248 536.1984 7.874367 123.6248 536.1984 7.874367 141.3924 506.487 7.741588 123.6248 536.1984 7.874367 141.2709 506.3385 7.416425 123.7898 536.299 8.222576 121.9491 538.9362 7.902199 123.6248 536.1984 7.874367 123.7898 536.299 8.222576 144.8144 498.6314 6.987296 141.2709 506.3385 7.416425 141.0415 505.7357 6.332516 145.2196 499.4652 8.477823 141.3924 506.487 7.741588 141.2709 506.3385 7.416425 145.2196 499.4652 8.477823 144.3887 498.0915 5.415466 140.732 505.3942 5.192037 143.9589 497.8401 3.779438 140.359 505.3188 3.999053 143.7761 497.824 3.065602 140.359 505.3188 3.999053 140.1869 505.3644 3.484556 143.9589 497.8401 3.779438 110 206.4887 -18.50794 110 206.5183 18.59349 110 210.2755 -27.13714 143.5914 497.8851 2.363832 139.995 505.459 2.918806 143.3082 498.0431 0.787206 139.995 505.459 2.918806 139.5896 505.7034 1.230311 143.5914 497.8851 2.363832 139.5608 505.7194 0.993617 143.3096 498.0423 -0.803135 139.5346 505.7366 -0.744963 139.5599 505.7198 -0.984627 143.5914 497.8851 -2.363835 139.995 505.459 -2.918808 143.5914 497.8851 -2.363835 139.995 505.459 -2.918808 120.242 541.654 7.951237 120.3997 541.6967 8.218363 117.0266 547.5341 8.820644 113.9768 552.1536 8.809 113.6568 552.0183 8.245432 111.8506 555.1072 9.202322 113.6568 552.0183 8.245432 113.9768 552.1536 8.809 120.0919 542.8812 8.83542 120.2306 542.5894 8.769593 120.3319 542.3663 8.712802 120.4018 542.2027 8.665046 120.447 542.0875 8.626152 120.4919 541.9522 8.569451 120.5039 541.8329 8.482357 120.3997 541.6967 8.218363 119.9363 544.7519 10.16499 113.9768 552.1536 8.809 117.0266 547.5341 8.820644 115.7262 556.7609 15.18845 111.8506 555.1072 9.202322 113.9768 552.1536 8.809 117.0722 554.2337 14.38174 120.1665 549.194 13.96245 117.0722 554.2337 14.38174 119.9551 546.8261 11.85269 120.0919 542.8812 8.83542 122.5174 540.1405 9.682854 120.0919 542.8812 8.83542 120.2306 542.5894 8.769593 122.8477 542.4404 11.90196 119.9363 544.7519 10.16499 120.0919 542.8812 8.83542 122.5174 540.1405 9.682854 124.7906 537.0897 10.21605 120.3319 542.3663 8.712802 124.8934 537.3677 10.56913 124.665 536.8625 9.869955 120.4018 542.2027 8.665046 124.5153 536.6872 9.53053 120.447 542.0875 8.626152 124.3444 536.5601 9.198783 120.4919 541.9522 8.569451 120.5039 541.8329 8.482357 122.2431 539.1483 8.508049 120.5039 541.8329 8.482357 122.2431 539.1483 8.508049 123.9382 536.4362 8.566069 108.5642 557.4264 8.760399 111.1912 554.8843 8.090186 108.1904 556.2625 5.841384 111.1912 554.8843 8.090186 108.5642 557.4264 8.760399 110.4437 554.0641 5.510762 106.4591 559.7053 11.00136 105.5944 559.447 9.727533 105.6464 558.0828 6.325259 105.5944 559.447 9.727533 109.3155 557.6549 9.941182 103.3827 561.186 12.3453 102.3898 560.8727 10.95642 102.8754 559.4795 6.950337 102.3898 560.8727 10.95642 99.94689 560.4176 7.700881 109.3237 561.9395 16.96554 103.3827 561.186 12.3453 106.4591 559.7053 11.00136 106.9211 563.0407 17.96873 111.6222 560.5057 16.15767 109.3155 557.6549 9.941182 113.7706 558.7678 15.56136 98.76642 559.9996 3.924756 101.84 559.1402 3.53784 104.7435 557.7975 3.21726 107.4017 556.0061 2.971343 109.7462 553.8125 2.806405 110.9778 565.2873 23.11461 113.1941 564.2236 22.28977 115.3293 562.8956 21.65624 117.3475 561.3256 21.22474 117.4304 554.5123 15.01476 119.2147 559.5402 21.00246 120.5584 551.6173 16.25868 117.4304 554.5123 15.01476 120.5235 557.2025 20.35505 121.0911 553.7736 18.43388 120.5235 557.2025 20.35505 120.8799 557.5556 20.964 121.8433 555.9862 20.79578 120.8799 557.5556 20.964 115.9932 567.6347 27.66424 114.4536 568.3213 28.19561 117.5067 566.8298 27.23036 118.9824 565.9121 26.89781 121.7702 563.7683 26.54856 120.4074 564.8884 26.67016 123.0608 562.5605 26.53336 124.2688 561.2745 26.62497 123.3207 559.4008 24.55148 124.2688 561.2745 26.62497 122.5151 557.64 22.60541 125.1521 566.6788 30.97128 123.0608 562.5605 26.53336 124.2688 561.2745 26.62497 130.7027 552.4007 26.85662 124.2688 561.2745 26.62497 123.3207 559.4008 24.55148 125.4741 562.7508 28.57906 125.4741 562.7508 28.57906 118.6558 570.7945 31.84792 114.4536 568.3213 28.19561 115.9932 567.6347 27.66424 117.5067 566.8298 27.23036 120.9163 569.6375 31.31516 118.9824 565.9121 26.89781 123.0939 568.2579 31.02131 120.4074 564.8884 26.67016 121.7702 563.7683 26.54856 129.0329 550.8733 24.39397 122.5151 557.64 22.60541 127.4644 549.343 21.89669 121.8433 555.9862 20.79578 126.0149 547.787 19.37392 121.0911 553.7736 18.43388 124.7167 546.1666 16.84172 120.5584 551.6173 16.25868 120.1665 549.194 13.96245 123.6312 544.4129 14.33167 119.9551 546.8261 11.85269 142.049 581.8507 48.18965 151.0539 569.9171 48.35701 153.3019 572.0261 50.08963 161.0086 559.1134 50.61926 144.1758 583.6853 49.77828 140.0076 580.0281 46.53654 148.8206 567.889 46.53531 158.9805 557.1235 49.00757 138.0488 578.2212 44.82304 146.6128 565.9353 44.62865 157.0211 555.3445 47.39497 136.1766 576.4271 43.05395 144.4384 564.0509 42.64136 153.3184 552.3426 44.20326 155.1282 553.7656 45.7902 134.4013 574.637 41.23545 142.3045 562.2316 40.57782 151.587 551.0794 42.64404 132.7261 572.8475 39.37314 140.2181 560.473 38.44247 149.9168 549.932 41.09693 131.1472 571.0619 37.47154 138.1851 558.7699 36.24005 146.7421 547.9503 38.04477 148.299 548.8915 39.56027 145.2479 547.0982 36.55515 136.211 557.1171 33.97536 128.3637 566.9689 33.33068 134.3016 555.5092 31.6532 142.4579 545.6429 33.68295 143.8164 546.3327 35.0975 126.9118 564.7161 30.92742 132.4626 553.9408 29.27842 139.9369 544.47 30.98255 127.0522 564.9207 31.15779 141.1666 545.0279 32.31338 138.7673 543.97 29.69487 135.5829 542.7207 26.06097 137.653 543.5142 28.44483 133.6196 542.0175 23.71583 131.809 541.3986 21.46903 130.1947 540.8497 19.38048 127.319 539.7135 15.32565 128.7 540.3079 17.34551 126.1643 539.038 13.44349 125.351 538.2676 11.85134 124.8934 537.3677 10.56913 126.9118 564.7161 30.92742 127.0522 564.9207 31.15779 164.6562 550.2944 50.54376 161.0086 559.1134 50.61926 158.9805 557.1235 49.00757 163.2871 545.3167 48.47967 157.0211 555.3445 47.39497 161.8168 540.5763 46.21861 155.1282 553.7656 45.7902 153.3184 552.3426 44.20326 160.2526 536.0797 43.75447 151.587 551.0794 42.64404 149.9168 549.932 41.09693 148.299 548.8915 39.56027 156.8649 527.9329 38.22417 146.7421 547.9503 38.04477 145.2479 547.0982 36.55515 143.8164 546.3327 35.0975 142.4579 545.6429 33.68295 153.1313 520.8508 31.77911 141.1666 545.0279 32.31338 139.9369 544.47 30.98255 138.7673 543.97 29.69487 137.653 543.5142 28.44483 135.5829 542.7207 26.06097 149.197 514.9075 24.46695 133.6196 542.0175 23.71583 131.809 541.3986 21.46903 130.1947 540.8497 19.38048 128.7 540.3079 17.34551 145.279 510.2101 16.52748 127.319 539.7135 15.32565 126.1643 539.038 13.44349 125.351 538.2676 11.85134 124.8934 537.3677 10.56913 124.7906 537.0897 10.21605 166.4567 535.691 48.41112 161.8168 540.5763 46.21861 160.2526 536.0797 43.75447 163.2534 527.608 43.68398 156.8649 527.9329 38.22417 159.8055 520.2796 38.19189 153.1313 520.8508 31.77911 156.1932 513.8049 31.94093 149.197 514.9075 24.46695 152.5218 508.2414 24.97516 145.279 510.2101 16.52748 123.9382 536.4362 8.566069 141.5214 506.6333 8.06471 148.9106 503.5941 17.37219 141.5214 506.6333 8.06471 124.3444 536.5601 9.198783 124.5153 536.6872 9.53053 124.665 536.8625 9.869955 141.5214 506.6333 8.06471 123.9382 536.4362 8.566069 145.4697 499.8195 9.201579 145.4697 499.8195 9.201579 141.5214 506.6333 8.06471 123.9382 536.4362 8.566069 167.6018 523.8251 47.38499 163.7589 515.7813 41.60113 159.7933 508.589 34.99662 155.8235 502.3222 27.62199 151.9807 496.9989 19.56658 148.384 492.5826 10.91396 148.384 492.5826 10.91396 167.292 511.7838 46.04125 162.8284 503.6653 38.99724 158.3878 496.5032 31.10357 154.1196 490.3337 22.4594 150.1593 485.1282 13.16217 148.0937 492.1658 10.11334 150.1593 485.1282 13.16217 166.6361 501.5234 45.95058 162.4609 494.5018 39.27112 158.3599 488.1779 31.99154 154.4298 482.5668 24.18024 150.751 477.6441 15.88963 149.8186 484.6392 12.2768 150.751 477.6441 15.88963 164.0247 490.1041 44.72381 159.288 482.8614 36.91776 154.6261 476.2588 28.3422 159.0769 482.5517 36.55046 151.2676 471.7771 21.46487 150.1501 470.3294 19.02104 149.9104 470.0208 18.48189 150.1501 470.3294 19.02104 149.6714 469.7178 17.93934 150.3476 477.0892 14.9096 161.0246 466.5125 50.65669 159.288 482.8614 36.91776 159.0769 482.5517 36.55046 151.9702 455.8918 35.93915 154.6261 476.2588 28.3422 151.2676 471.7771 21.46487 144.2308 447.5961 21.21492 150.1501 470.3294 19.02104 149.9104 470.0208 18.48189 153.797 436.7776 49.4334 144.9771 429.1867 35.27295 146.7149 407.0116 48.10616 138.1092 402.451 34.52792 139.7854 377.2149 46.67034 131.3688 375.6854 33.70275 130.4744 399.0047 20.68878 123.7592 374.6646 20.33613 137.2979 423.3156 20.98192 119.4758 382.2192 6.621936 110.9731 353.4772 6.906038 111.0294 353.3995 7.063343 110.9072 353.5288 6.744768 110.8337 353.5513 6.585051 128.0145 410.0506 6.593294 136.6203 437.5771 6.495335 145.4579 465.3318 6.327086 146.9037 466.59 10.8836 147.6662 467.3745 12.99506 148.1411 467.8921 14.24089 149.6714 469.7178 17.93934 117.9271 380.7524 3.127661 110.8337 353.5513 6.585051 119.4758 382.2192 6.621936 110.6639 353.5277 6.249513 110.6912 353.0925 6.578598 110.8337 353.5513 6.585051 110.6639 353.5277 6.249513 126.6883 408.945 3.093571 128.0145 410.0506 6.593294 135.5174 436.7858 3.026023 136.6203 437.5771 6.495335 145.0268 465.0244 4.77973 145.4579 465.3318 6.327086 144.9911 465.003 4.641687 144.5878 464.8291 2.924202 148.0502 474.2854 8.571763 145.4579 465.3318 6.327086 146.9037 466.59 10.8836 145.0268 465.0244 4.77973 145.4579 465.3318 6.327086 147.0757 473.3982 5.20254 147.0757 473.3982 5.20254 149.1484 475.5234 11.81403 147.6662 467.3745 12.99506 148.1411 467.8921 14.24089 150.3476 477.0892 14.9096 149.6714 469.7178 17.93934 109.9655 352.6959 5.183135 110.152 352.6683 5.681578 110.2416 353.0938 5.583174 109.0538 351.6558 3.130626 110.2416 353.0938 5.583174 110.3533 353.246 5.741737 109.9655 352.6959 5.183135 110.4621 353.372 5.906848 108.703 351.5699 0 108.9366 351.2662 3.141521 109.0538 351.6558 3.130626 109.3153 351.8605 3.954563 109.1668 351.7215 3.542412 109.5006 352.076 4.367617 109.7188 352.3579 4.778213 117.9271 380.7524 3.127661 108.703 351.5699 0 109.0538 351.6558 3.130626 109.1651 351.7195 -3.537776 108.9366 351.2662 -3.14153 109.0538 351.6558 -3.130634 120.248 389.2991 0 109.0538 351.6558 -3.130634 109.1651 351.7195 -3.537776 109.0538 351.6558 -3.130634 117.9326 380.7705 -3.127657 110.3491 353.2406 -5.735692 110.152 352.6683 -5.681579 110.2416 353.0938 -5.583175 110.2416 353.0938 -5.583175 109.9632 352.6929 -5.179328 110.3491 353.2406 -5.735692 109.7152 352.3532 -4.771897 109.4969 352.0714 -4.360017 109.3123 351.857 -3.947366 110.6576 353.5238 -6.238432 110.5589 353.4603 -6.065168 110.4557 353.365 -5.896948 136.7897 336.0846 -54.27484 137.839 335.6145 -55.70791 135.7686 336.5455 -52.85848 134.7752 336.9975 -51.45931 133.8094 337.4405 -50.07822 132.6404 337.982 -48.37808 131.5116 338.5103 -46.70614 130.4211 339.0261 -45.0615 129.369 339.5295 -43.44611 128.3537 340.0207 -41.85977 127.3732 340.5004 -40.30125 125.513 341.4261 -37.26944 126.4263 340.9688 -38.77067 124.6325 341.8722 -35.79812 123.7842 342.3073 -34.35767 122.9678 342.7313 -32.94909 122.1814 343.1452 -31.57093 121.1775 343.6825 -29.77928 120.2241 344.2027 -28.04314 119.3162 344.7093 -26.35575 118.4502 345.2036 -24.71389 116.8458 346.1582 -21.57902 117.6268 345.686 -23.12108 116.1061 346.6198 -20.08871 115.4068 347.0751 -18.64865 114.1263 347.9689 -15.92387 114.7476 347.5234 -17.26177 113.5384 348.4207 -14.62415 112.9827 348.8746 -13.36506 112.218 349.5962 -11.54942 111.5344 350.374 -9.82049 110.977 351.3055 -8.210206 119.1202 322.2314 -39.20741 126.4263 340.9688 -38.77067 127.3732 340.5004 -40.30125 128.3537 340.0207 -41.85977 129.369 339.5295 -43.44611 130.4211 339.0261 -45.0615 131.5116 338.5103 -46.70614 132.6404 337.982 -48.37808 125.0363 320.3262 -48.45126 133.8094 337.4405 -50.07822 134.7752 336.9975 -51.45931 135.7686 336.5455 -52.85848 136.7897 336.0846 -54.27484 137.839 335.6145 -55.70791 146.4028 473.0145 -2.367131 144.5878 464.8291 -2.924179 144.2233 464.4843 -0.970817 144.5878 464.8291 -2.924179 135.5249 436.8092 -3.025954 144.2233 464.4843 -0.970817 146.4028 473.0145 -2.367131 144.5878 464.8291 -2.924179 132.0724 426.9425 0 126.697 408.9726 -3.093507 144.1773 464.4381 -0.003240883 110 204.1759 -9.373581 110 204.1852 9.428307 145.8997 489.792 -2.082171 145.8997 489.792 -2.082171 146.8463 481.4183 -2.083285 145.6995 489.8361 -0.703474 146.8463 481.4183 -2.083285 146.1647 472.8099 -0.804362 146.6606 481.3426 -0.703887 145.8997 489.7921 2.082169 145.8997 489.7921 2.082169 146.6596 481.3422 0.689913 146.8463 481.4184 2.083282 146.1011 489.7875 2.984643 146.8463 481.4184 2.083282 145.6985 489.8364 0.689507 146.1635 472.8088 0.78841 146.4028 473.0144 2.367135 146.7133 473.1427 3.765448 146.4028 473.0144 2.367135 147.0894 481.4829 3.220123 144.2242 464.4852 0.980046 144.5878 464.8291 2.924202 144.5878 464.8291 2.924202 110 203.4 0 135.5174 436.7858 3.026023 144.5878 464.8291 2.924202 144.2242 464.4852 0.980046 144.9911 465.003 4.641687 144.1773 464.4381 -0.003240883 146.3155 489.8795 3.910896 146.3155 489.8795 3.910896 147.3641 481.6567 4.389656 146.8657 490.3334 6.066706 147.3641 481.6567 4.389656 148.0971 482.3267 7.128251 148.0937 492.1658 10.11334 148.9211 483.326 9.764286 149.8186 484.6392 12.2768 147.4638 491.0961 8.141283 126.6883 408.945 3.093571 110 563.4 0 110 657.4 0 110 656.6793 -8.199214 110 564.1207 8.199214 110 656.6873 8.154454 110 566.2337 -16.07196 110 654.5388 -16.14717 110 564.1127 -8.154454 110 569.6973 -23.49881 110 651.0531 -23.5842 110 574.3664 -30.17697 110 646.3702 -30.25212 110 580.1607 -35.97861 110 640.5817 -36.02696 110 586.8952 -40.69878 110 633.8741 -40.71679 110 626.4625 -44.16893 110 594.3435 -44.17075 110 618.568 -46.28363 110 602.2671 -46.28967 110 610.4229 -46.99877 110 654.5664 16.07196 110 566.2612 16.14717 110 651.1028 23.49881 110 569.7469 23.5842 110 646.4336 30.17697 110 574.4298 30.25212 110 640.6393 35.97861 110 580.2183 36.02696 110 633.9048 40.69878 110 586.9259 40.71679 110 594.3375 44.16893 110 626.4565 44.17075 110 602.2321 46.28363 110 618.5329 46.28967 110 610.3771 46.99877 182.307 465.3532 -9.600602 181.8154 465.4443 -6.2688 182.307 465.3532 -6.2688 179.8404 452.0444 -6.2688 179.3487 452.1355 -6.2688 181.7077 464.8632 4.398 182.307 465.3532 -6.2688 179.3487 452.1355 -6.2688 179.8404 452.0444 -6.2688 182.1993 464.7721 4.398 181.7077 464.8632 4.398 181.7077 464.8632 7.7298 182.1993 464.7721 4.398 182.1993 464.7721 7.7298 181.7077 464.8632 7.7298 178.4299 447.1776 7.7298 182.1993 464.7721 7.7298 178.9215 447.0865 7.7298 174.7811 427.4909 -9.600602 173.4144 420.1165 -3.3318 171.5393 409.9994 -3.3318 174.7811 427.4909 -9.600602 173.9192 422.8406 -2.586769 173.677 421.5334 -3.14035 174.6186 423.8701 6.108942 174.2865 424.8221 4.969502 174.1269 423.9609 6.109179 174.7781 424.7311 4.969245 175.9725 431.1755 7.7298 175.2727 427.3998 7.7298 175.2727 427.3998 -9.600602 175.9725 431.1755 -9.600602 177.1988 437.7918 7.7298 176.5349 434.2096 7.7298 176.5349 434.2096 -9.600602 177.1988 437.7918 -6.2688 178.5686 445.1827 -6.2688 178.5686 445.1827 -9.600602 181.2445 459.6207 4.398 178.9215 447.0865 7.7298 178.9215 447.0865 4.398 182.1993 464.7721 4.398 182.1993 464.7721 7.7298 179.8404 452.0444 -6.2688 182.307 465.3532 -9.600602 182.307 465.3532 -6.2688 178.8856 446.893 -6.2688 178.8856 446.893 -9.600602 174.4108 422.7492 -2.586919 173.677 421.5334 -3.14035 173.9192 422.8406 -2.586769 174.1686 421.4421 -3.140402 173.906 420.0253 -3.3318 177.1988 437.7918 -6.2688 176.7072 437.8829 7.7298 177.1988 437.7918 7.7298 177.1988 437.7918 7.7298 176.0433 434.3007 7.7298 176.5349 434.2096 7.7298 174.6185 423.8698 -1.711179 173.9192 422.8406 -2.586769 174.1269 423.9612 -1.710942 174.4108 422.7492 -2.586919 174.7811 427.4909 7.7298 174.1269 423.9609 6.109179 174.2865 424.8221 4.969502 145.0012 302.6019 -49.51807 149.8266 315.2406 -43.76592 150.6033 316.326 -42.20819 143.7512 317.8309 -42.1369 150.6033 316.326 -42.20819 149.8266 315.2406 -43.76592 149.1818 301.7482 -37.55989 155.4163 323.364 -30.85339 146.5154 329.6161 -24.71984 155.4163 323.364 -30.85339 150.6033 316.326 -42.20819 143.7512 317.8309 -42.1369 149.0614 314.0002 -45.15019 143.175 315.3741 -45.01391 149.0614 314.0002 -45.15019 147.6048 311.0894 -47.38005 142.4648 312.3462 -47.24674 147.6048 311.0894 -47.38005 146.343 307.7585 -48.81966 142.0713 310.6687 -48.08299 146.343 307.7585 -48.81966 145.3559 304.1674 -49.43394 141.6576 308.905 -48.7186 145.3559 304.1674 -49.43394 140.7969 305.2351 -49.35218 145.3559 304.1674 -49.43394 145.0012 302.6019 -49.51807 140.7969 305.2351 -49.35218 137.2718 262.4734 -47.99499 140.6201 283.4799 -50.54616 140.6201 283.4799 -50.54616 152.1969 301.1326 -25.24167 141.9643 261.4628 -33.52045 138.103 262.2849 -45.79745 138.6487 262.1611 -44.2864 140.2254 261.8413 -39.57835 159.2352 330.8309 -19.22532 154.0177 300.7609 -12.68159 144.3336 260.864 -22.48724 142.0382 261.4458 -33.23557 143.5372 261.0682 -26.73712 162.6495 340.8083 -1.596364 154.6265 300.6366 -2e-6 145.7713 260.5469 -11.28538 162.5649 340.5264 -3.16919 162.3424 339.7742 -5.401347 162.0166 338.6431 -7.456562 144.713 260.7754 -20.14905 145.5661 260.5913 -13.47496 162.0166 338.6431 7.456562 154.0177 300.7609 12.68158 146.2507 260.4367 0 162.3423 339.7741 5.401597 162.5649 340.5264 3.169158 162.6495 340.8082 1.596745 162.6781 340.9027 3.83e-4 146.0799 260.4776 -6.747254 159.2358 330.8323 19.22326 152.1969 301.1326 25.24166 145.588 260.5873 13.25975 146.0796 260.4757 6.745868 155.4167 323.3647 30.85219 149.1818 301.7482 37.55988 143.6068 261.037 26.38061 145.5659 260.5923 13.47905 144.7163 260.7852 20.14185 145.3559 304.1674 49.43394 145.0012 302.6019 49.51806 140.3277 261.7811 39.22509 146.3437 307.7605 48.81906 147.6059 311.0921 47.3785 149.0624 314.0019 45.14844 149.8272 315.2416 43.76477 150.6033 316.3262 42.20796 143.5321 261.054 26.74673 142.0327 261.3942 33.21564 131.1031 263.9053 51.57476 145.0012 302.6019 49.51806 145.3559 304.1674 49.43394 140.2138 261.8069 39.5914 138.113 262.2835 45.77078 140.6203 283.4806 50.54612 140.6203 283.4806 50.54612 140.7969 305.2351 49.35218 145.3559 304.1674 49.43394 146.3437 307.7605 48.81906 140.7969 305.2351 49.35218 141.6576 308.905 48.7186 147.6059 311.0921 47.3785 142.4648 312.3462 47.24674 149.0624 314.0019 45.14844 142.0713 310.6687 48.08299 143.1749 315.374 45.01402 149.8272 315.2416 43.76477 150.6033 316.3262 42.20796 143.7515 317.8322 42.13536 150.6033 316.3262 42.20796 155.4167 323.3647 30.85219 143.7515 317.8322 42.13536 146.5154 329.6159 24.71972 159.2358 330.8323 19.22326 149.2878 341.4364 7.32731 162.0166 338.6431 7.456562 149.2878 341.4364 7.32731 162.0166 338.6431 7.456562 162.3423 339.7741 5.401597 149.6803 343.1098 3.835993 162.5649 340.5264 3.169158 162.6495 340.8082 1.596745 162.6781 340.9027 3.83e-4 149.815 343.6838 -1.08e-4 162.6495 340.8083 -1.596364 162.5649 340.5264 -3.16919 149.6803 343.1097 -3.836239 162.3424 339.7742 -5.401347 162.0166 338.6431 -7.456562 149.288 341.4372 -7.325833 162.0166 338.6431 -7.456562 159.2352 330.8309 -19.22532 149.288 341.4372 -7.325833 135.7848 262.8101 -51.65866 136.3306 253.554 -45.47358 135.7848 262.8101 -51.65866 137.2718 262.4734 -47.99499 135.7848 262.8101 -51.65866 131.1032 263.9058 -51.57474 131.0978 263.8828 -51.57598 131.1032 263.9058 -51.57474 135.7848 262.8101 -51.65866 135.7799 262.7892 -51.65979 135.7799 262.7892 -51.65979 138.103 262.2849 -45.79745 138.698 254.3178 -39.28681 138.6487 262.1611 -44.2864 140.2254 261.8413 -39.57835 142.0382 261.4458 -33.23557 141.9643 261.4628 -33.52045 140.7464 255.1684 -32.95159 143.5372 261.0682 -26.73712 142.475 256.0429 -26.49093 144.3336 260.864 -22.48724 143.903 257.018 -19.94035 144.713 260.7754 -20.14905 145.0238 258.0852 -13.32719 145.5661 260.5913 -13.47496 145.8105 259.223 -6.672296 145.7713 260.5469 -11.28538 146.0799 260.4776 -6.747254 146.2507 260.4367 0 145.8107 259.2227 6.658282 146.0796 260.4757 6.745868 145.5479 257.9764 -6.416636 145.3135 256.7742 -6.024756 145.1051 255.6315 -5.451318 144.9245 254.6225 -4.661861 144.7756 253.8214 -3.675826 144.6809 253.2503 -2.522285 144.6454 252.9145 -1.274216 144.6387 252.8061 -6.96e-4 144.6444 252.9164 1.274578 144.6812 253.2529 2.523802 144.7759 253.823 3.677192 144.9237 254.6206 4.666922 145.1039 255.6277 5.460591 145.3132 256.7729 6.027442 145.5486 257.9781 6.404082 145.0255 258.0883 13.29963 145.588 260.5873 13.25975 145.5659 260.5923 13.47905 143.9073 257.0279 19.89959 144.7163 260.7852 20.14185 142.478 256.0391 26.43447 143.6068 261.037 26.38061 143.5321 261.054 26.74673 140.7441 255.1259 32.87725 142.0327 261.3942 33.21564 138.7034 254.2994 39.20171 140.3277 261.7811 39.22509 140.2138 261.8069 39.5914 136.345 253.564 45.37801 138.113 262.2835 45.77078 135.7852 262.8117 51.65858 135.7799 262.7892 51.65979 135.7852 262.8117 51.65858 134.8289 258.531 51.70406 134.0048 254.3773 51.39474 135.7852 262.8117 51.65858 135.7799 262.7892 51.65979 135.7852 262.8117 51.65858 131.1031 263.9053 51.57476 146.5154 329.6159 24.71972 146.5154 329.6161 -24.71984 143.7512 317.8309 -42.1369 143.7515 317.8322 42.13536 143.175 315.3741 -45.01391 149.2878 341.4364 7.32731 149.288 341.4372 -7.325833 149.6803 343.1098 3.835993 149.6803 343.1097 -3.836239 143.1749 315.374 45.01402 142.4648 312.3462 -47.24674 142.4648 312.3462 47.24674 142.0713 310.6687 -48.08299 142.0713 310.6687 48.08299 141.6576 308.905 -48.7186 141.6576 308.905 48.7186 140.7969 305.2351 -49.35218 140.7969 305.2351 49.35218 131.1032 263.9058 -51.57474 131.1031 263.9053 51.57476 131.0978 263.8828 -51.57598 149.815 343.6838 -1.08e-4 131.0978 263.8828 51.57598 131.0978 263.8828 51.57598 130.0808 259.5468 -51.61579 130.0808 259.5467 51.61603 135.7799 262.7892 51.65979 131.0978 263.8828 51.57598 130.0808 259.5467 51.61603 129.108 255.3994 -51.29195 129.1125 255.4185 51.29483 134.0048 254.3773 51.39474 129.1125 255.4185 51.29483 134.8289 258.531 51.70406 128.2752 251.8487 50.72837 133.3691 250.7694 50.84247 128.2752 251.8487 50.72837 128.2649 251.8045 -50.719 127.5732 248.8558 50.04089 132.8911 247.7371 50.17081 127.5732 248.8558 50.04089 127.5584 248.7923 -50.02352 126.3733 243.7398 48.3915 132.1787 242.4829 48.54036 126.3733 243.7398 48.3915 125.6662 240.7251 -47.11708 124.9602 237.715 45.59931 131.4994 236.2356 45.7621 124.9602 237.715 45.59931 126.3486 243.6345 -48.35053 124.9146 237.5204 -45.4922 123.6845 232.2759 42.15123 131.0135 230.5512 42.30814 123.6845 232.2759 42.15123 123.642 232.0948 -42.01888 122.8036 228.5203 39.12992 130.7403 226.5796 39.25099 122.8036 228.5203 39.12992 122.769 228.3726 -38.99886 122.0469 225.294 36.00419 122.0469 225.294 36.00419 122.0227 225.1907 -35.89483 121.624 223.4912 33.99124 130.5384 223.1567 36.07633 121.624 223.4912 33.99124 121.6042 223.4064 -33.89151 121.1649 221.5337 31.53808 130.433 221.2783 34.06918 121.1649 221.5337 31.53808 121.1499 221.4697 -31.45235 120.6831 219.4796 28.58882 130.3169 219.2366 31.62102 120.6831 219.4796 28.58882 120.671 219.4279 -28.50856 120.2553 217.6555 25.54571 130.1854 217.0832 28.65757 120.2553 217.6555 25.54571 120.2479 217.6239 -25.48869 119.9242 216.244 22.80783 130.0698 215.1846 25.61627 119.9242 216.244 22.80783 119.9214 216.2319 -22.78279 119.6699 215.1598 20.38781 129.9683 212.5774 20.47811 119.6699 215.1598 20.38781 130 213.7198 22.90149 119.2691 213.4509 -15.66983 119.2638 213.4281 15.5954 119.2638 213.4281 15.5954 119.6678 215.1509 -20.36635 118.9463 212.0746 -10.19892 118.9359 212.0301 9.967663 129.9839 210.6965 15.56785 118.9359 212.0301 9.967663 118.7511 211.2422 -4.011783 118.7459 211.2203 3.711098 130.0862 209.1915 9.901047 118.7459 211.2203 3.711098 130.2005 208.3116 3.595074 118.7511 211.2422 -4.011783 130.203 208.3542 -4.154909 118.9463 212.0746 -10.19892 130.0894 209.2775 -10.32686 119.2691 213.4509 -15.66983 129.9861 210.7816 -15.82997 119.6678 215.1509 -20.36635 129.9666 212.609 -20.5483 119.9214 216.2319 -22.78279 129.9997 213.751 -22.96296 120.2479 217.6239 -25.48869 130.0728 215.2285 -25.69227 120.671 219.4279 -28.50856 130.189 217.1376 -28.73851 121.1499 221.4697 -31.45235 130.3184 219.296 -31.69608 121.6042 223.4064 -33.89151 130.4304 221.3413 -34.13855 122.0227 225.1907 -35.89483 130.5317 223.2186 -36.13655 122.769 228.3726 -38.99886 130.723 226.5567 -39.22849 123.642 232.0948 -42.01888 130.9935 230.4945 -42.26595 124.9146 237.5204 -45.4922 131.4973 236.2222 -45.75476 125.6662 240.7251 -47.11708 126.3486 243.6345 -48.35053 132.199 242.4439 -48.52818 127.5584 248.7923 -50.02352 132.9213 247.6833 -50.15948 128.2649 251.8045 -50.719 133.406 250.7684 -50.84386 129.108 255.3994 -51.29195 134.0461 254.4518 -51.40456 130.0808 259.5468 -51.61579 134.8609 258.6353 -51.70785 131.0978 263.8828 -51.57598 135.7799 262.7892 -51.65979 134.8609 258.6353 -51.70785 133.3691 250.7694 50.84247 132.8911 247.7371 50.17081 134.7605 244.9351 44.01772 132.1787 242.4829 48.54036 131.4994 236.2356 45.7621 133.3346 236.5924 41.56367 131.0135 230.5512 42.30814 132.1343 228.62 37.69954 130.7403 226.5796 39.25099 130.5384 223.1567 36.07633 130.433 221.2783 34.06918 131.194 221.5241 32.26934 130.3169 219.2366 31.62102 130.1854 217.0832 28.65757 130.5058 215.8805 25.45307 130.0698 215.1846 25.61627 130 213.7198 22.90149 129.9683 212.5774 20.47811 130.2436 211.8251 17.50713 129.9839 210.6965 15.56785 130.0862 209.1915 9.901047 130.3621 209.3755 8.868298 130.2005 208.3116 3.595074 130.4821 208.5538 0.002780914 130.203 208.3542 -4.154909 130.3684 209.359 -8.853302 130.0894 209.2775 -10.32686 129.9861 210.7816 -15.82997 130.2378 211.8031 -17.48563 129.9666 212.609 -20.5483 129.9997 213.751 -22.96296 130.0728 215.2285 -25.69227 130.5024 215.8614 -25.43057 130.189 217.1376 -28.73851 130.3184 219.296 -31.69608 131.206 221.5238 -32.22397 130.4304 221.3413 -34.13855 130.5317 223.2186 -36.13655 130.723 226.5567 -39.22849 132.151 228.6317 -37.62821 130.9935 230.4945 -42.26595 133.3372 236.5875 -41.54009 131.4973 236.2222 -45.75476 132.199 242.4439 -48.52818 134.744 244.9116 -44.10292 132.9213 247.6833 -50.15948 133.406 250.7684 -50.84386 134.0461 254.4518 -51.40456 137.3497 246.8538 37.96311 136.1605 239.6689 35.80343 135.2376 232.7741 32.47552 134.5806 226.5976 27.81373 134.1046 221.6856 21.94616 133.9563 218.1652 15.0907 134.1116 216.0427 7.635695 134.2349 215.3327 -0.01144099 134.1177 216.0329 -7.650109 133.9523 218.156 -15.09825 134.1035 221.6843 -21.95023 134.593 226.6176 -27.79408 135.2538 232.8084 -32.42861 136.1663 239.6903 -35.79309 137.3417 246.8598 -38.04285 144.5008 255.5932 -12.82294 144.06 253.1835 -12.04335 143.6984 250.8846 -10.90081 143.3974 248.8492 -9.324196 143.1496 247.2343 -7.35229 143.0144 246.0813 -5.047309 142.9992 245.3962 -2.550653 143.0097 245.1732 4.68e-4 142.9961 245.4012 2.554895 143.0147 246.0881 5.05362 143.1505 247.2395 7.358284 143.3956 248.8482 9.337038 143.6958 250.8801 10.92128 144.0598 253.1844 12.05006 144.5034 255.6001 12.79872 143.1313 253.2805 -19.20683 142.5 249.6717 -18.03688 142.0189 246.2144 -16.32853 141.6425 243.1361 -13.97363 141.3413 240.6917 -11.02077 141.2091 238.9465 -7.567609 141.248 237.9048 -3.824485 141.2889 237.5648 0.003594994 141.2428 237.9136 3.836278 141.2097 238.9586 7.58207 141.3428 240.7026 11.03446 141.6394 243.139 13.99673 142.0148 246.2128 16.36213 142.5003 249.6782 18.04897 143.1368 253.296 19.17158 141.4881 251.0563 -25.55771 140.6738 246.2563 -24.00514 140.0767 241.6443 -21.73806 139.6413 237.5103 -18.61793 139.306 234.2229 -14.69326 139.1909 231.8767 -10.09715 139.2911 230.4716 -5.109556 139.365 230.0107 -0.003621995 139.2852 230.4802 5.108242 139.1921 231.8864 10.10004 139.3069 234.2282 14.69721 139.6349 237.5022 18.63677 140.0684 241.6278 21.77377 140.6714 246.2493 24.01502 141.4929 251.0606 25.50619 139.573 248.935 -31.85196 138.5811 242.9447 -29.93968 137.8492 237.1849 -27.12327 137.3364 231.9993 -23.24808 136.9516 227.8696 -18.36167 136.8377 224.9205 -12.63092 136.9857 223.1487 -6.404463 137.0876 222.5639 -0.02342891 136.9803 223.1522 6.364987 136.8405 224.9183 12.59849 136.9512 227.8554 18.3349 137.3248 231.9618 23.24532 137.8342 237.1318 27.14798 138.5728 242.9011 29.93823 139.5736 248.9037 31.77859 174.7811 427.4909 7.7298 173.9192 422.8403 6.984919 174.1269 423.9609 6.109179 174.7811 427.4909 -9.600602 174.3874 425.3664 3.640013 174.4223 425.5547 2.199 176.0433 434.3007 7.7298 175.4809 431.2666 7.7298 176.0433 434.3007 -9.600602 178.394 446.9841 -9.600602 178.077 445.2738 -6.2688 178.077 445.2738 -9.600602 160.2247 589.1773 43.73743 170.3213 573.6862 39.02756 173.1198 570.7357 35.31607 168.1034 567.9967 35.2517 173.1198 570.7357 35.31607 170.3213 573.6862 39.02756 174.0316 569.8485 33.87501 173.2791 558.8113 22.736 174.0316 569.8485 33.87501 173.1198 570.7357 35.31607 168.1034 567.9967 35.2517 167.4424 577.2658 41.69601 163.9937 575.2901 41.60704 167.4424 577.2658 41.69601 166.2222 571.3352 38.89683 165.9793 579.3139 42.65538 162.7823 577.4401 42.56803 165.9793 579.3139 42.65538 164.5633 581.4627 43.32633 161.5275 579.667 43.24825 164.5633 581.4627 43.32633 161.9548 585.9467 43.80139 160.2445 581.9439 43.6408 161.9548 585.9467 43.80139 158.9453 584.2496 43.74131 161.9548 585.9467 43.80139 160.2247 589.1773 43.73743 158.9453 584.2496 43.74131 163.4744 590.9502 31.54599 154.3127 600.0407 43.52158 154.3127 600.0407 43.52158 176.2483 570.9912 22.73261 165.6584 592.1418 19.05017 152.032 611.5951 31.24382 148.8795 609.7938 43.3267 177.5831 571.6857 11.41045 166.7557 592.7405 6.370545 154.1504 612.8056 18.86532 178.0292 571.9179 -1.7e-4 166.7557 592.7405 -6.370545 155.2147 613.4137 6.308332 177.5831 571.6857 -11.41079 165.6584 592.1418 -19.05017 154.1505 612.8056 -18.86532 155.2147 613.4137 -6.308332 176.2483 570.9912 -22.73295 163.4744 590.9502 -31.54599 152.032 611.5951 -31.24382 164.5642 581.4612 -43.32596 160.2247 589.1773 -43.73743 154.3127 600.0407 -43.52158 165.9806 579.312 -42.65464 167.4439 577.2639 -41.6949 170.3221 573.6852 -39.0267 173.1196 570.7354 -35.31594 174.0297 569.8501 -33.87779 148.8795 609.7938 -43.3267 161.9548 585.9467 -43.80139 143.2054 612.1834 -43.17609 160.2247 589.1773 -43.73743 161.9548 585.9467 -43.80139 154.3127 600.0407 -43.52158 158.9453 584.2496 -43.74119 161.9548 585.9467 -43.80139 164.5642 581.4612 -43.32596 158.9453 584.2496 -43.74119 161.5275 579.667 -43.24825 165.9806 579.312 -42.65464 160.2445 581.9439 -43.64078 162.7823 577.4401 -42.56803 167.4439 577.2639 -41.6949 163.9937 575.2901 -41.60704 170.3221 573.6852 -39.0267 166.2222 571.3352 -38.89685 173.1196 570.7354 -35.31594 168.1034 567.9967 -35.25164 173.1196 570.7354 -35.31594 174.0297 569.8501 -33.87779 168.1034 567.9967 -35.25164 180.417 562.8212 -22.94507 180.417 562.8212 -22.94507 186.6588 554.0851 -10.34068 188.7099 550.89 1.71e-4 187.767 552.3364 -7.222344 188.4695 551.2553 -3.709324 186.6591 554.0852 10.34062 188.4695 551.2553 3.70939 187.767 552.3364 7.22222 180.4173 562.8208 22.94454 180.4173 562.8208 22.94454 148.8795 609.7938 43.3267 146.4817 614.0308 43.24172 146.4817 614.0308 43.24172 140.8398 632.4036 27.64757 144.5907 617.4699 42.99537 142.8036 620.955 42.38573 141.1256 624.468 41.40868 139.5652 627.981 40.05665 138.3137 630.9981 38.57965 142.4749 633.3811 16.67078 143.2955 633.8717 5.571019 142.475 633.3812 -16.66961 143.2955 633.8717 -5.569841 140.84 632.4038 -27.64641 138.3133 630.9993 -38.57901 148.8795 609.7938 -43.3267 139.5386 628.0433 -40.02911 141.1064 624.5096 -41.39482 142.7922 620.978 -42.38042 144.586 617.4786 -42.99449 146.4817 614.0308 -43.24172 146.4817 614.0308 -43.24172 143.2054 612.1834 43.17609 146.4817 614.0308 43.24172 144.5907 617.4699 42.99537 143.2054 612.1834 43.17609 139.3883 618.9577 42.32803 142.8036 620.955 42.38573 141.2861 615.5896 42.92958 137.5161 622.2803 41.37297 141.1256 624.468 41.40868 135.6934 625.515 40.07098 139.5652 627.981 40.05665 138.3137 630.9981 38.57965 136.9009 634.6583 36.3525 132.2665 631.5969 36.48891 136.9009 634.6583 36.3525 133.1763 646.0234 25.18455 135.7757 637.7974 34.00972 134.7811 640.767 31.35045 133.9164 643.5205 28.40144 131.6613 651.6557 14.3199 132.5559 648.2409 21.72462 132.0539 650.1234 18.09218 131.138 653.7938 5.242877 131.3714 652.8266 10.43008 131.3714 652.8266 -10.43007 131.0611 654.1171 1.68e-4 131.138 653.7939 -5.242698 132.042 650.169 -17.99273 131.6557 651.6771 -14.26027 133.8854 643.6229 -28.28104 132.537 648.3104 -21.60357 133.1506 646.113 -25.05761 132.2417 631.6409 -36.45676 138.3133 630.9993 -38.57901 139.5386 628.0433 -40.02911 134.7464 640.8743 -31.24493 135.7396 637.9019 -33.92404 136.866 634.7525 -36.28836 136.866 634.7525 -36.28836 135.6741 625.5494 -40.05495 141.1064 624.5096 -41.39482 137.5017 622.3059 -41.36413 142.7922 620.978 -42.38042 139.3796 618.9732 -42.32433 144.586 617.4786 -42.99449 141.2823 615.5965 -42.92884 146.4817 614.0308 -43.24172 143.2054 612.1834 -43.17609 135.7757 637.7974 34.00972 129.2093 637.0225 31.68661 134.7811 640.767 31.35045 133.9164 643.5205 28.40144 126.6261 641.6069 25.81874 133.1763 646.0234 25.18455 132.5559 648.2409 21.72462 124.609 645.1867 19.09125 132.0539 650.1234 18.09218 123.8348 646.5607 15.47455 131.6613 651.6557 14.3199 123.2249 647.6431 11.72591 131.3714 652.8266 10.43008 122.7855 648.423 7.879169 131.138 653.7938 5.242877 122.5201 648.8939 3.97086 131.0611 654.1171 1.68e-4 122.518 648.8977 -3.9227 131.138 653.7939 -5.242698 122.4302 649.0534 0.02361989 122.781 648.4309 -7.829839 131.3714 652.8266 -10.43007 123.218 647.6554 -11.67577 131.6557 651.6771 -14.26027 123.8256 646.5771 -15.42528 132.042 650.169 -17.99273 124.5976 645.207 -19.04384 132.537 648.3104 -21.60357 133.1506 646.113 -25.05761 126.6104 641.6349 -25.7756 133.8854 643.6229 -28.28104 134.7464 640.8743 -31.24493 129.1877 637.0608 -31.64572 135.7396 637.9019 -33.92404 173.2791 558.8113 -22.73593 186.6588 554.0851 -10.34068 178.4638 549.6099 -10.23505 186.6588 554.0851 -10.34068 187.767 552.3364 -7.222344 178.4638 549.6099 -10.23505 179.6228 547.5529 -6.483213 188.4695 551.2553 -3.709324 180.2268 546.4811 -2.221154 188.7099 550.89 1.71e-4 180.2268 546.4812 2.221496 188.4695 551.2553 3.70939 179.6228 547.553 6.483444 187.767 552.3364 7.22222 186.6591 554.0852 10.34062 178.464 549.6096 10.23453 186.6591 554.0852 10.34062 178.464 549.6096 10.23453 168.1034 567.9967 -35.25164 168.1034 567.9967 35.2517 166.2222 571.3352 38.89683 173.2791 558.8113 -22.73593 173.2791 558.8113 22.736 166.2222 571.3352 -38.89685 163.9937 575.2901 41.60704 163.9937 575.2901 -41.60704 162.7823 577.4401 42.56803 162.7823 577.4401 -42.56803 161.5275 579.667 43.24825 161.5275 579.667 -43.24825 160.2445 581.9439 43.6408 160.2445 581.9439 -43.64078 158.9453 584.2496 43.74131 158.9453 584.2496 -43.74119 143.2054 612.1834 43.17609 178.4638 549.6099 -10.23505 178.464 549.6096 10.23453 179.6228 547.5529 -6.483213 179.6228 547.553 6.483444 180.2268 546.4811 -2.221154 180.2268 546.4812 2.221496 143.2054 612.1834 -43.17609 141.2861 615.5896 42.92958 141.2823 615.5965 -42.92884 139.3883 618.9577 42.32803 139.3796 618.9732 -42.32433 137.5161 622.2803 41.37297 137.5017 622.3059 -41.36413 135.6934 625.515 40.07098 135.6741 625.5494 -40.05495 132.2665 631.5969 36.48891 132.2417 631.6409 -36.45676 129.2093 637.0225 31.68661 129.1877 637.0608 -31.64572 126.6261 641.6069 25.81874 126.6104 641.6349 -25.7756 124.609 645.1867 19.09125 124.5976 645.207 -19.04384 123.8348 646.5607 15.47455 123.8256 646.5771 -15.42528 123.2249 647.6431 11.72591 123.218 647.6554 -11.67577 122.7855 648.423 7.879169 122.781 648.4309 -7.829839 122.5201 648.8939 3.97086 122.518 648.8977 -3.9227 122.4302 649.0534 0.02361989 174.7811 427.4909 -9.600602 174.4223 425.5547 2.199 174.3874 425.3665 0.758167 178.5686 445.1827 -9.600602 178.077 445.2738 -9.600602 178.077 445.2738 -6.2688 178.5686 445.1827 -9.600602 176.5349 434.2096 -9.600602 178.077 445.2738 -9.600602 175.9725 431.1755 -9.600602 175.4809 431.2666 7.7298 175.9725 431.1755 7.7298 175.9725 431.1755 7.7298 174.7811 427.4909 7.7298 175.2727 427.3998 7.7298 176.5349 434.2096 -9.600602 176.0433 434.3007 -9.600602 178.077 445.2738 -9.600602 176.5349 434.2096 7.7298 176.0433 434.3007 7.7298 176.0433 434.3007 -9.600602 176.5349 434.2096 -9.600602 174.879 425.2753 0.757987 174.3874 425.3665 0.758167 174.4223 425.5547 2.199 174.7811 427.4909 -9.600602 174.1269 423.9612 -1.710942 173.9192 422.8406 -2.586769 178.394 446.9841 -6.2688 176.7072 437.8829 7.7298 178.077 445.2738 -6.2688 178.394 446.9841 -9.600602 178.5686 445.1827 -9.600602 178.077 445.2738 -6.2688 178.5686 445.1827 -6.2688 177.1988 437.7918 -6.2688 176.7072 437.8829 -6.2688 176.7072 437.8829 7.7298 178.5686 445.1827 -6.2688 176.7072 437.8829 -6.2688 177.1988 437.7918 -6.2688 177.1988 437.7918 7.7298 176.7072 437.8829 7.7298 176.0433 434.3007 7.7298 174.7811 427.4909 7.7298 174.2865 424.8221 4.969502 174.3874 425.3664 3.640013 181.7077 464.8632 4.398 179.3487 452.1355 -6.2688 181.8154 465.4443 -6.2688 178.394 446.9841 -6.2688 180.7529 459.7118 4.398 178.4299 447.1776 4.398 181.7077 464.8632 7.7298 181.7077 464.8632 4.398 181.8154 465.4443 -6.2688 178.5686 445.1827 -6.2688 178.077 445.2738 -6.2688 176.7072 437.8829 -6.2688 174.9139 425.4635 2.199 174.4223 425.5547 2.199 174.3874 425.3664 3.640013 174.879 425.2753 0.757987 174.7811 427.4909 -9.600602 173.677 421.5334 -3.14035 173.4144 420.1165 -3.3318 172.0309 409.9082 -3.3318 171.5393 409.9994 -3.3318 173.4144 420.1165 -3.3318 172.0309 409.9082 -3.3318 172.0309 409.9082 -9.600602 171.5393 409.9994 -3.3318 + + + + + + + + + + -0.1857989 -0.136694 -0.9730333 -0.1006511 -0.05298066 -0.9935103 -0.1030641 -0.0548129 -0.9931634 -0.0174508 0.02856689 -0.9994395 -0.110632 -0.04483264 -0.9928498 -0.1926987 -0.1247933 -0.9732903 -0.1076396 -0.05008125 -0.9929279 -0.01745086 0.02856832 -0.9994395 -0.01744973 0.02856761 -0.9994395 -0.08117955 -0.03634768 -0.9960365 -0.01745098 0.02856916 -0.9994395 -0.1240299 -0.07709145 -0.9892793 -0.1437436 -0.1146592 -0.9829502 -0.07666319 -0.03680562 -0.9963775 -0.1549742 -0.07983702 -0.9846873 -0.07013231 -0.0321058 -0.9970209 -0.01744419 0.0285713 -0.9994396 -0.2222076 -0.1725839 -0.9596034 -0.2294762 -0.2027411 -0.9519646 -0.2377715 -0.1168257 -0.96427 -0.2796159 -0.2285575 -0.9325108 -0.2748265 -0.224958 -0.9348072 -0.2614576 -0.2385988 -0.9352597 -0.2671992 -0.2177269 -0.9387224 -0.3645176 -0.3118726 -0.8774181 -0.3583244 -0.3072965 -0.8815739 -0.3512138 -0.3024747 -0.8860914 -0.3631799 -0.3109918 -0.8782851 -0.2470869 -0.2922865 -0.9238597 -0.3011981 -0.2916455 -0.9078671 -0.3096747 -0.3126046 -0.8979866 -0.2959714 -0.2820549 -0.912604 -0.3541112 -0.3036634 -0.8845303 -0.1989854 -0.1134705 -0.9734112 -0.2804391 -0.2024631 -0.9382764 -0.2920685 -0.187876 -0.9377626 -0.3888123 -0.2384145 -0.8899346 -0.3736732 -0.269085 -0.8876721 -0.03946119 0.01059007 -0.9991651 -0.389119 -0.2815085 -0.87712 -0.2176625 -0.09589111 -0.9713022 -0.1077007 -0.01931834 -0.9939957 -0.1250357 -0.031587 -0.9916493 -0.01744168 0.02856862 -0.9994397 -0.2310928 -0.09177178 -0.9685939 -0.2422942 -0.07635974 -0.9671932 -0.2403374 -0.08176052 -0.96724 -0.1301946 -0.02630746 -0.9911394 -0.1376697 -0.02310258 -0.9902088 -0.07400768 7.32447e-4 -0.9972574 -0.01747852 0.02856153 -0.9994392 -0.118659 -0.03705042 -0.9922436 -0.01745802 0.02856552 -0.9994395 -0.0174604 0.02856558 -0.9994394 -0.01745629 0.02856475 -0.9994395 -0.01745247 0.02856874 -0.9994395 -0.3191987 -0.1563185 -0.9347068 -0.3667194 -0.2312139 -0.9011421 -0.3382132 -0.153023 -0.928545 -0.3481371 -0.1362395 -0.9274909 -0.3466044 -0.1361148 -0.9280831 -0.4016284 -0.1500918 -0.9034197 -0.3577104 -0.1327261 -0.9243523 -0.0362873 0.01281803 -0.9992592 -0.4267198 -0.2185481 -0.8775802 -0.4124938 -0.251598 -0.8755269 -0.4887638 -0.2088118 -0.8470583 -0.458918 -0.1961167 -0.8665637 -0.467007 -0.196514 -0.8621409 -0.443103 -0.2298984 -0.866491 -0.4645628 -0.2018538 -0.8622276 -0.07458883 6.10384e-4 -0.9972142 -0.01743596 0.02857041 -0.9994398 -0.08313333 0.003540158 -0.9965322 -0.1325142 -0.01620566 -0.9910487 -0.07663255 0.004852473 -0.9970477 -0.01745581 0.02856737 -0.9994395 -0.4684939 -0.1963884 -0.8613623 -0.4473521 -0.1088013 -0.8877152 -0.4258387 -0.1318747 -0.8951371 -0.3629284 -0.1063882 -0.9257238 -0.5475704 -0.179146 -0.8173576 -0.5274944 -0.1739596 -0.8315575 -0.5175769 -0.1759132 -0.8373582 -0.5011562 -0.1375501 -0.8543551 -0.3067824 -0.06323647 -0.9496766 -0.2499819 -0.06149595 -0.9662957 -0.1647426 -0.01657187 -0.9861974 -0.27275 0.05728447 -0.960378 -0.1359016 0.04937988 -0.9894909 -0.1587274 0.05056935 -0.9860265 -0.01745837 0.02856856 -0.9994394 -0.2946649 0.07169008 -0.9529078 -0.158087 0.05896216 -0.9856632 -0.2964299 0.08792483 -0.9509987 -0.1592774 0.05929797 -0.9854514 -0.01745241 0.02856689 -0.9994396 -0.1446915 0.03763014 -0.9887611 -0.01746815 0.02856361 -0.9994394 -0.2486072 0.03152602 -0.9680912 -0.124792 0.03598183 -0.9915303 -0.01745241 0.02856588 -0.9994396 -0.01744866 0.02856689 -0.9994397 -0.1273242 0.02468961 -0.9915539 -0.01745116 0.02856564 -0.9994397 -0.01745223 0.02856749 -0.9994396 -0.2225776 0.01132267 -0.9748493 -0.1158187 0.02487277 -0.992959 -0.01745086 0.02856832 -0.9994395 -0.01745325 0.02856653 -0.9994395 -0.1124311 0.01553404 -0.9935382 -0.01745074 0.02856653 -0.9994397 -0.01745492 0.02856862 -0.9994395 -0.1970593 -0.004089474 -0.980383 -0.09738719 0.009064197 -0.9952054 -0.01745402 0.02856749 -0.9994395 -0.01745307 0.02856558 -0.9994395 -0.01745206 0.02856934 -0.9994395 -0.01745098 0.02856701 -0.9994396 -0.01745444 0.02856701 -0.9994395 -0.01745057 0.02856528 -0.9994397 -0.01745474 0.02856862 -0.9994394 -0.0174511 0.02856582 -0.9994397 -0.01745724 0.02856713 -0.9994394 -0.3675732 -0.03799635 -0.9292181 -0.4223501 -0.006531 -0.9064093 -0.4710976 0.0330525 -0.8814616 -0.5128142 0.08206611 -0.8545682 -0.5523971 0.110571 -0.8262152 -0.2862697 0.08438545 -0.9544259 -0.5502688 0.1394136 -0.8232668 -0.7204447 0.1012639 -0.6860796 -0.7657386 0.148234 -0.6258364 -0.5315203 0.133643 -0.8364365 -0.7582933 0.1793645 -0.6267533 -0.5240079 -0.0690335 -0.8489112 -0.6044221 -0.02529996 -0.7962625 -0.6679738 0.03170943 -0.7435089 -0.8501058 0.1591869 -0.5019759 -0.8443213 0.1666973 -0.509248 -0.7387425 0.1729205 -0.6514277 -0.8370356 0.193641 -0.5117371 -0.5789602 -0.1114277 -0.807706 -0.6950616 -0.06234949 -0.7162415 -0.6377998 -0.1225059 -0.7603972 -0.736789 -0.002716183 -0.6761173 -0.7069133 -0.06076347 -0.7046854 -0.7995813 0.07043904 -0.5964127 -0.7915818 -0.006470084 -0.611029 -0.7605327 0.01141405 -0.6491995 -0.8197848 0.07761108 -0.5673883 -0.8041936 0.09677791 -0.5864357 -0.8824949 0.1353223 -0.4504337 -0.8855069 0.1458194 -0.4411512 -0.8895164 0.1675511 -0.4250732 -0.7889429 0.1905902 -0.5841614 -0.9041542 0.2088106 -0.3726973 -0.9041947 0.2091181 -0.3724267 -0.9038752 0.2089316 -0.3733059 -0.8930137 0.1589119 -0.4210388 -0.5633583 -0.1652017 -0.8095281 -0.6438943 -0.1300728 -0.7539771 -0.6537275 -0.1153942 -0.7478801 -0.5516914 -0.1863488 -0.8129643 -0.6893315 -0.103093 -0.7170733 -0.7547349 -0.05575817 -0.6536561 -0.750342 -0.05960375 -0.6583575 -0.7652714 -0.02646023 -0.6431637 -0.7852603 -0.02191281 -0.6187778 -0.8347571 0.03418129 -0.5495566 -0.8267 0.01635819 -0.5624051 -0.8399185 0.04934948 -0.5404643 -0.8409265 0.08826154 -0.5339031 -0.8541107 0.0859726 -0.5129364 -0.2418347 0.06134372 -0.9683765 -0.1409055 0.04513734 -0.9889937 -0.1252497 0.04367256 -0.9911637 -0.01745361 0.02856761 -0.9994395 -0.1965105 0.05511695 -0.9789515 -0.1534184 0.06338769 -0.9861262 -0.1907741 0.06271648 -0.9796285 -0.1240002 0.04992967 -0.9910253 -0.0172984 0.02853763 -0.9994431 -0.01745826 0.02856749 -0.9994395 -0.1386189 0.04776275 -0.9891934 -0.01745218 0.02856564 -0.9994396 -0.253374 0.06720423 -0.9650312 -0.1380083 0.04953283 -0.9891917 -0.01745307 0.02856731 -0.9994395 -0.017452 0.02856689 -0.9994395 -0.2636532 0.07321494 -0.9618351 -0.1450873 0.05081409 -0.9881132 -0.01745724 0.02856707 -0.9994394 -0.1496953 0.05398797 -0.9872571 -0.0174542 0.02856713 -0.9994395 -0.01745164 0.02856677 -0.9994395 -0.2744587 0.07883095 -0.9583622 -0.1544554 0.05679535 -0.986366 -0.01745259 0.02856719 -0.9994396 -0.01744979 0.02856737 -0.9994397 -0.01745164 0.02856671 -0.9994396 -0.5130569 0.123816 -0.8493776 -0.494023 0.1131061 -0.8620606 -0.4744253 0.1021181 -0.8743526 -0.4542483 0.09097784 -0.8862175 -0.3148355 0.070957 -0.9464903 -0.2830333 0.09775233 -0.9541157 -0.3113913 0.08667558 -0.9463207 -0.4331551 0.08548349 -0.8972564 -0.4261366 0.1081287 -0.8981737 -0.7194043 0.1610206 -0.67567 -0.6945306 0.1475309 -0.7041746 -0.6689862 0.1304706 -0.7317342 -0.6481059 0.1169801 -0.7525121 -0.5413161 0.09900373 -0.8349702 -0.532314 0.1653524 -0.8302413 -0.5437512 0.1203961 -0.8305658 -0.6418796 0.1092587 -0.7589817 -0.6442574 0.1959018 -0.7392936 -0.6303448 0.1320873 -0.7649958 -0.7935607 0.1776829 -0.581971 -0.8126037 0.1915383 -0.550444 -0.7730752 0.163612 -0.6128507 -0.7602028 0.1503376 -0.6320527 -0.7135716 0.1304394 -0.6883322 -0.7449687 0.1471626 -0.650665 -0.6939503 0.1152718 -0.710736 -0.6945227 0.1146907 -0.7102706 -0.6880177 0.1581488 -0.7082518 -0.8145004 0.1463403 -0.5614034 -0.8211288 0.1283347 -0.5561274 -0.7775351 0.1476209 -0.611267 -0.7425705 0.2193743 -0.6328223 -0.7589659 0.1710938 -0.6282497 -0.7412953 0.222764 -0.6331331 -0.7635264 0.1536635 -0.6272282 -0.7597107 0.1717612 -0.6271665 -0.8817903 0.1964213 -0.4287943 -0.890069 0.2036562 -0.4078008 -0.8965986 0.1887013 -0.400628 -0.863238 0.1819865 -0.4708515 -0.8607045 0.1819254 -0.4754902 -0.8473014 0.1753321 -0.5013371 -0.8382415 0.1623623 -0.5205667 -0.8439085 0.1527776 -0.5142739 -0.8174526 0.1512523 -0.5557823 -0.2769011 0.1203679 -0.9533296 -0.1517129 0.07626843 -0.9854777 -0.01744592 0.02856677 -0.9994397 -0.2943588 0.1508265 -0.9437183 -0.2743394 0.141061 -0.9512306 -0.1477122 0.08572804 -0.985308 -0.1539973 0.08877885 -0.9840749 -0.0174542 0.02856689 -0.9994395 -0.5199552 0.2046005 -0.8293282 -0.6301849 0.2420149 -0.7377641 -0.7257525 0.2735458 -0.6312338 -0.7260822 0.2738792 -0.6307097 -0.6163706 0.2877067 -0.7330158 -0.6119459 0.2852044 -0.7376861 -0.5090693 0.2419605 -0.8260167 -0.7461963 0.3315309 -0.5773027 -0.7209606 0.3120307 -0.618751 -0.7328715 0.3353818 -0.5919616 -0.7154236 0.2994818 -0.6312525 -0.5433005 0.2588933 -0.7986232 -0.6227775 0.2911544 -0.7262075 -0.6492123 0.3041275 -0.6971585 -0.1579996 0.09088712 -0.9832475 -0.01745122 0.02856713 -0.9994396 -0.1224722 0.09708046 -0.9877125 -0.2805877 0.1687067 -0.9448855 -0.1527787 0.1025137 -0.9829292 -0.01745051 0.02856725 -0.9994395 -0.01745259 0.02856725 -0.9994395 -0.7436573 0.3389139 -0.5762909 -0.7408849 0.3416934 -0.5782174 -0.7416345 0.3428163 -0.5765894 -0.4125573 0.290542 -0.8633551 -0.6327255 0.3432807 -0.6941303 -0.5247094 0.2920342 -0.7996225 -0.6374598 0.3450224 -0.6889156 -0.6497923 0.3952895 -0.6492429 -0.6996994 0.3634152 -0.6151019 -0.6685521 0.3793222 -0.6396505 -0.7054749 0.3712929 -0.6036943 -0.2187021 0.1609289 -0.9624299 -0.08441472 0.1156964 -0.9896911 -0.09198588 0.1290061 -0.9873683 -0.0587489 0.08325564 -0.9947951 -0.05569761 0.07928901 -0.9952945 -0.05206584 0.08884155 -0.9946841 -0.07126259 0.1252818 -0.9895586 -0.04736548 0.07388657 -0.9961413 -0.03222846 0.04938042 -0.9982599 -0.01745158 0.02856713 -0.9994396 -0.0209974 0.1804008 -0.9833691 -0.02731418 0.0931735 -0.9952753 -0.03103828 0.07330769 -0.9968263 -0.01739585 0.1056571 -0.9942505 -0.01739567 -0.1163986 -0.9930503 -0.01745676 -0.04855543 -0.998668 -0.01739561 -0.04809731 -0.9986913 -0.1832662 0.2188818 -0.9583863 -0.1791447 0.2109451 -0.9609419 -0.09549319 0.1448115 -0.9848405 -0.3478533 0.3291453 -0.8778734 -0.2896854 0.2690546 -0.9185272 -0.1014744 0.1219219 -0.9873389 -0.3230772 0.3186824 -0.8911021 -0.2278251 0.2594735 -0.9384931 -0.2186395 0.2568496 -0.9413953 -0.4930908 0.3557565 -0.7939136 -0.1559831 0.1497877 -0.9763365 -0.5089623 0.3745574 -0.7750253 -0.4045066 0.338218 -0.8496958 -0.5402003 0.3427373 -0.7685799 -0.6072443 0.3922657 -0.6909284 -0.5325869 0.425099 -0.7318758 -0.5758436 0.3987384 -0.7137311 -0.4940761 0.3976048 -0.7731747 -0.4114026 0.4197039 -0.8090714 -0.4724434 0.3915665 -0.7896031 -0.373277 0.3708356 -0.8503795 -0.2823612 0.3824633 -0.8797693 -0.3627836 0.3545128 -0.8618056 -0.3417532 0.3549985 -0.8701614 -0.2351813 0.3105333 -0.9210098 -0.153083 0.2927377 -0.9438593 -0.2272485 0.2707083 -0.9354545 -0.1015063 0.2006931 -0.9743812 -0.08008122 0.1631533 -0.9833453 -0.08291953 0.248423 -0.965096 -0.0450772 0.06421291 -0.9969176 -0.06250274 0.07739597 -0.9950394 -0.09341782 0.09097629 -0.9914618 -0.08289098 0.0902462 -0.9924641 -0.01745307 0.02856636 -0.9994396 -0.01745259 0.02856492 -0.9994396 -0.01745432 0.02856463 -0.9994397 -0.0174514 0.02856767 -0.9994395 -0.01745307 0.02856701 -0.9994396 -0.01745313 0.02856665 -0.9994395 -0.01745349 0.02856671 -0.9994395 -0.07928794 0.3383014 -0.9376916 -0.1527193 0.3814014 -0.9117072 -0.0755341 0.4276911 -0.9007636 -0.1541215 0.4677053 -0.8703439 -0.2839537 0.4536729 -0.8447197 -0.0745877 0.5162546 -0.8531812 -0.1566852 0.5502904 -0.8201404 -0.2884045 0.5220885 -0.8026497 -0.07739657 0.6010141 -0.7954822 -0.1602841 0.6281052 -0.7614414 -0.2955837 0.5872914 -0.7534714 -0.08255523 0.680249 -0.7283173 -0.1656278 0.700325 -0.6943432 -0.3052223 0.6483799 -0.6974547 -0.08490473 0.7807454 -0.619054 -0.1642248 0.7678374 -0.6192384 -0.3170689 0.7046992 -0.6347176 -0.06998074 0.7592899 -0.6469789 -0.09012329 0.8444978 -0.5279217 -0.1702973 0.8256674 -0.5378404 -0.3307099 0.7556337 -0.5653748 -0.07114028 0.8296651 -0.5537102 -0.08594119 0.8806533 -0.4659014 -0.1770746 0.8763394 -0.4479665 -0.3457843 0.8006448 -0.4892863 -0.09476238 0.9290684 -0.357564 -0.1865358 0.9157105 -0.3559197 -0.3596068 0.8393062 -0.4077354 -0.1006823 0.902997 -0.4176834 -0.09399861 0.9609835 -0.2601442 -0.1819881 0.9379574 -0.2951546 -0.1000726 0.9536658 -0.2837375 -0.1978236 0.9512442 -0.2366437 -0.2100611 0.9475489 -0.2408851 -0.1026057 0.9710313 -0.2158017 -0.3590574 0.8636911 -0.3537166 -0.3831117 0.8747814 -0.2966194 -0.02694815 0.9876226 -0.1545172 -0.02368283 0.9768863 -0.2124435 -0.01992905 0.9639505 -0.2653343 -0.01858609 0.9842087 -0.1760338 -0.1018429 0.9713684 -0.2146422 -0.02295005 0.951604 -0.3064689 -0.01913571 0.9416172 -0.3361414 -0.03524959 0.9120645 -0.4085292 -0.02270632 0.89269 -0.4500989 -0.02008152 0.8951849 -0.4452425 -0.02392727 0.8593996 -0.5107444 -0.02017307 0.8325893 -0.5535234 -0.02270615 0.815591 -0.5781833 -0.01840311 0.7977133 -0.6027561 -0.01715153 0.7530217 -0.6577724 -0.020814 0.715794 -0.6980014 -0.01986801 0.6809768 -0.7320355 -0.01941013 0.6045839 -0.796305 -0.02014225 0.6026824 -0.797727 -0.0165416 0.5205118 -0.8536943 -0.02044767 0.4707543 -0.8820273 -0.01944047 0.4312012 -0.9020463 -0.02050852 0.3462959 -0.9379012 -0.02035611 0.3325037 -0.9428823 -0.01678562 0.249984 -0.9681044 -0.01757884 0.1575995 -0.9873467 -0.4170411 0.4688928 -0.7785989 -0.4252601 0.5158118 -0.7437016 -0.4357537 0.5608215 -0.7039873 -0.4482696 0.6034914 -0.6594336 -0.462638 0.6433107 -0.6100144 -0.478603 0.6797859 -0.5557252 -0.4961515 0.7123804 -0.4963346 -0.5152001 0.7401595 -0.4321259 -0.5205653 0.7562038 -0.3964439 -0.3752906 0.8802255 -0.2904481 -0.5444085 0.7671405 -0.3392863 -0.541298 0.4572771 -0.7056162 -0.5534998 0.4877 -0.6751197 -0.5687867 0.5165073 -0.6400797 -0.5867037 0.5433052 -0.6004984 -0.6067544 0.5676592 -0.5564281 -0.6285467 0.5892988 -0.5075984 -0.6513057 0.6084266 -0.4534511 -0.6612559 0.6173085 -0.4262288 -0.5403774 0.771257 -0.3363853 -0.6839308 0.6295765 -0.3686085 -0.6618114 0.4085316 -0.6285759 -0.6782262 0.4216216 -0.6018674 -0.6965634 0.4318729 -0.5729618 -0.7172981 0.4412804 -0.5392172 -0.7396582 0.4481104 -0.5020985 -0.7639576 0.4532717 -0.4592534 -0.7785533 0.4524826 -0.4348728 -0.6836326 0.6300407 -0.3683681 -0.7966174 0.4658176 -0.3852464 -0.720865 0.3722434 -0.584627 -0.7298964 0.3743175 -0.5719597 -0.7493164 0.3756958 -0.5453236 -0.7464181 0.3599483 -0.5597297 -0.7709673 0.3733676 -0.5159517 -0.7641691 0.3612552 -0.5343599 -0.7954531 0.3733112 -0.4773817 -0.788641 0.3444678 -0.5093008 -0.7829644 0.3656479 -0.503258 -0.8201264 0.369594 -0.4367985 -0.8044252 0.3700149 -0.4647464 -0.8238769 0.3702639 -0.4291056 -0.8372789 0.3729513 -0.3998392 -0.8275324 0.3718479 -0.4206178 -0.7995545 0.4618238 -0.3839681 -0.8446485 0.3736767 -0.3833208 -0.7627104 0.3313797 -0.5553921 -0.7653911 0.3347041 -0.5496814 -0.771652 0.3266184 -0.545778 -0.7832945 0.3227179 -0.5313218 -0.7878475 0.3230434 -0.5243466 -0.7855922 0.3385484 -0.5179092 -0.797441 0.3154484 -0.5143737 -0.7928909 0.3014084 -0.529601 -0.8122124 0.30791 -0.4954822 -0.7889462 0.3000016 -0.5362491 -0.7859377 0.2978396 -0.5418428 -0.7832462 0.2952738 -0.5471187 -0.7806517 0.2920691 -0.5525203 -0.7781414 0.2882513 -0.5580388 -0.7822868 0.2973746 -0.5473535 -0.799728 0.2987535 -0.520751 -0.8193705 0.3047919 -0.4855245 -0.8100931 0.2933779 -0.5076205 -0.8298212 0.2997305 -0.4707 -0.8034413 0.2955148 -0.5168686 -0.8226579 0.2882888 -0.4900239 -0.8414334 0.2940591 -0.4533424 -0.8163673 0.2910344 -0.498842 -0.8135119 0.2892581 -0.504508 -0.834056 0.282332 -0.4739613 -0.8530979 0.2866346 -0.4359641 -0.8280242 0.2854793 -0.4825741 -0.8256422 0.2839223 -0.4875479 -0.848244 0.2762271 -0.4518637 -0.8603706 0.2815714 -0.4248292 -0.8415122 0.280321 -0.46182 -0.8388642 0.2790415 -0.4673786 -0.8367186 0.2774209 -0.4721649 -0.8625733 0.2761101 -0.4239466 -0.8675889 0.278057 -0.4122787 -0.8746057 0.2803853 -0.3955365 -0.8598517 0.2754896 -0.4298377 -0.8499725 0.2721133 -0.4511111 -0.8500859 0.2721715 -0.4508623 -1 0 0 -0.01754868 -0.1254654 -0.9919429 -0.01742655 0.9876394 -0.1557711 -0.1062378 0.9723773 -0.2078368 -0.02884072 0.9923658 -0.1199103 -0.2136947 0.9655327 -0.1485975 -0.1125848 0.9799671 -0.1642841 -0.1099618 0.9818129 -0.1547644 -0.2185478 0.9575696 -0.187876 -0.02829122 0.9971835 -0.06946158 -0.05124163 0.9921772 -0.1138364 -0.1164895 0.9859346 -0.1198466 -0.03305184 0.9964691 -0.07718199 -0.2176041 0.9730838 -0.07587146 -0.1164304 0.9893074 -0.087834 -0.0232253 0.9986577 -0.04629796 -0.1204574 0.9913394 -0.05230903 -0.01742643 0.9994733 -0.02737569 -0.2186416 0.9750365 -0.03872919 -0.120428 0.9921123 -0.03479164 -0.01742613 0.9994242 0.02911472 -0.01742631 0.9997418 0.01458805 -0.01757872 0.9994242 0.02902317 -0.2163468 0.973454 0.07470971 -0.1153616 0.9930563 0.02304178 -0.1157893 0.9927548 0.03210604 -0.2176601 0.9752895 0.0378738 -1 -4.993e-6 0 -1 4.7112e-6 0 -1 -4.47617e-6 0 -1 -1.35659e-6 0 -1 7.126e-7 0 -1 3.18475e-7 0 -1 -1.06754e-5 0 -0.01745694 0.9973049 0.07126218 -0.02017313 0.9970287 0.07434451 -0.01925766 0.990231 0.1381 -0.01757913 0.998595 0.04999077 -0.01745206 0.9982235 0.05696737 -1 4.48083e-6 0 -0.0205391 0.9873139 0.1574465 -0.01998978 0.9755947 0.2186672 -0.01956284 0.9936178 0.1110903 -1 1.66362e-5 0 -0.01559537 0.9631932 0.2683573 -0.01992893 0.9546373 0.2971034 -1 -2.12839e-6 0 -0.02194291 0.9843196 0.1750247 -0.01699912 0.9786278 0.2049362 -0.01611405 0.9415444 0.3365035 -0.01940983 0.9273707 0.37364 -0.01696872 0.916311 0.4001078 -0.01843333 0.893927 0.4478333 -1 -4.46064e-6 0 -0.0182504 0.888229 0.4590384 -0.01855558 0.8553273 0.5177559 -0.01666349 0.8264625 0.5627453 -0.01901334 0.8103113 0.5856912 -0.0174874 0.85896 0.5117442 -0.01709097 0.7916793 0.6106979 -0.01818948 0.7598996 0.6497861 -0.01586991 0.7450022 0.6668733 -0.0180673 0.7055097 0.7084701 -0.01489305 0.6751022 0.7375738 -0.01855599 0.6453096 0.7636958 -0.01605308 0.5930498 0.8050058 -0.01712143 0.58033 0.8142015 -0.01684659 0.5135473 0.857896 -0.01644992 0.5099175 0.8600661 -0.01815891 0.4416747 0.8969916 -0.01559525 0.4232082 0.9058982 -0.01870822 0.3670544 0.9300114 -1 6.31214e-7 0 -0.01532083 0.3340068 0.9424462 -0.01867794 0.2900881 0.9568178 -0.01602274 0.2414702 0.9702759 -0.01702964 0.2105511 0.9774346 -0.01654118 0.1323295 0.9910679 -0.01678556 0.1473166 0.988947 -0.01812797 0.05154579 0.9985061 -0.01660203 0.03070163 0.9993907 -0.01586961 -0.03201395 0.9993615 -0.01641917 -0.04559534 0.9988251 -0.01553398 -0.1091653 0.9939022 -0.01568663 -0.1118515 0.9936012 -0.01751816 -0.1907774 0.981477 -0.01440495 -0.2610288 0.9652236 -0.01745676 -0.2695119 0.9628389 -0.01748764 -0.3461517 0.9380156 -0.01440513 -0.4034668 0.9148809 -0.01730436 -0.4215002 0.9066632 -1 -2.15091e-6 0 -0.01727402 -0.492554 0.8701105 -1 -2.23132e-6 0 -0.01458835 -0.536931 0.8435001 -0.01699918 -0.5625602 0.8265816 -1 2.12146e-6 0 -0.01696872 -0.6262563 0.7794327 -0.01492381 -0.6582044 0.7526913 -0.01651066 -0.6889315 0.7246385 -0.01651084 -0.7435373 0.6684907 -1 -4.45681e-6 0 -0.01535111 -0.7642921 0.6446874 -0.01586997 -0.7967054 0.6041594 -1 4.38086e-6 0 -0.01596164 -0.8413895 0.5401935 -0.01596134 -0.8529113 0.5218119 -0.01513755 -0.8839308 0.4673727 -1 2.13433e-6 0 -0.01535105 -0.9173105 0.3978766 -0.01532053 -0.921614 0.3878054 -0.0174877 -0.9472363 0.3200589 -0.01406943 -0.9699405 0.2429352 -0.01745671 -0.9701006 0.242075 -0.01745665 -0.9865471 0.1625425 -1 -2.12127e-6 0 -0.01553428 -0.9936754 0.111212 -0.01803654 -0.9964989 0.08163768 -0.01721251 -0.9996995 0.01745665 -0.01751774 -0.9997633 0.01290941 -1 2.12543e-6 0 -1 4.99288e-6 0 -0.01599186 -0.999432 -0.02966433 -1 1.06756e-5 0 -0.01635807 -0.9959225 -0.08871835 -0.02072221 -0.9979317 -0.06085431 -0.01770126 -0.9773234 -0.2110112 -0.02072232 -0.9766675 -0.2137547 -0.01770097 -0.9333008 -0.358659 -0.02142423 -0.990917 -0.132757 -0.02078342 -0.9321415 -0.3614974 -0.01770132 -0.8672136 -0.4976216 -1 -2.16613e-6 0 -0.02139377 -0.9586009 -0.2839485 -0.02078348 -0.8653382 -0.5007572 -0.01773148 -0.7806448 -0.6247234 -0.0213328 -0.9034552 -0.4281516 -0.02072221 -0.7778017 -0.6281681 -0.01779246 -0.6756578 -0.7370007 -0.02121078 -0.8266718 -0.5622845 -0.02063125 -0.6716755 -0.7405582 -0.01785379 -0.5546892 -0.831866 -0.02108901 -0.7300295 -0.6830903 -0.02056992 -0.549346 -0.8353418 -0.01785373 -0.4205546 -0.9070917 -1 -1.1609e-6 0 -0.02093631 -0.6158514 -0.7875842 -0.01733499 -0.3976985 -0.9173525 -0.01760953 -0.2763509 -0.9608954 -1 -5.9468e-7 0 -0.02081388 -0.4869596 -0.8731764 -0.01733475 -0.2686282 -0.963088 -9.15562e-5 0.9965589 -0.0828889 0 0.9965918 -0.08249235 3.05191e-5 0.9863775 -0.164498 -3.05191e-5 0.9863775 0.164498 1.22077e-4 0.9862294 0.1653838 9.15562e-5 0.9965589 0.0828889 0 0.9965918 0.08249235 -1.22077e-4 0.9862294 -0.1653838 1.22075e-4 0.94581 -0.3247207 -1.83112e-4 0.9453169 -0.3261534 1.52597e-4 0.8795385 -0.4758279 -1.83116e-4 0.8787119 -0.4773524 1.52595e-4 0.789344 -0.6139512 -1.22076e-4 0.7883949 -0.6151696 1.22077e-4 0.6773124 -0.7356956 -3.05193e-5 0.6766127 -0.736339 6.10393e-5 0.5465461 -0.8374291 3.05191e-5 0.5464754 -0.8374752 9.1557e-5 0.4008364 -0.9161497 -1.22077e-4 0.2458016 -0.9693202 1.83112e-4 0.2443017 -0.9696993 0 0.4016 -0.9158153 -1.83117e-4 0.08334851 -0.9965204 2.13631e-4 0.08142387 -0.9966796 -2.13631e-4 -0.08142387 -0.9966796 1.83117e-4 -0.08334851 -0.9965204 -1.83112e-4 -0.2443017 -0.9696993 1.22077e-4 -0.2458016 -0.9693202 -9.1557e-5 -0.4008364 -0.9161497 0 -0.4016 -0.9158153 -3.05191e-5 -0.5464754 -0.8374752 -6.10378e-5 -0.5465321 -0.8374381 6.10386e-5 -0.6766127 -0.736339 -1.22077e-4 -0.6773124 -0.7356956 1.22076e-4 -0.7883949 -0.6151696 -1.52595e-4 -0.789344 -0.6139512 1.83116e-4 -0.8787119 -0.4773524 -1.52597e-4 -0.8795385 -0.4758279 1.83112e-4 -0.9453169 -0.3261534 -1.22075e-4 -0.94581 -0.3247207 1.22077e-4 -0.9862294 -0.1653838 -3.05193e-5 -0.9863824 -0.1644682 9.15562e-5 -0.9965589 -0.0828889 -9.15562e-5 -0.9965589 0.0828889 0 -0.9965943 0.08246201 3.05193e-5 -0.9863824 0.1644682 0 -0.9965943 -0.08246201 -1.22077e-4 -0.9862294 0.1653838 1.22075e-4 -0.94581 0.3247207 -1.83112e-4 -0.9453169 0.3261534 1.52597e-4 -0.8795385 0.4758279 -1.83116e-4 -0.8787119 0.4773524 1.52595e-4 -0.789344 0.6139512 -1.22076e-4 -0.7883949 0.6151696 1.22077e-4 -0.6773124 0.7356956 -6.10386e-5 -0.6766127 0.736339 6.10378e-5 -0.5465321 0.8374381 3.05191e-5 -0.5464754 0.8374752 9.1557e-5 -0.4008364 0.9161497 -1.22077e-4 -0.2458016 0.9693202 1.83112e-4 -0.2443017 0.9696993 0 -0.4016 0.9158153 -1.83117e-4 -0.08334851 0.9965204 2.13631e-4 -0.08142387 0.9966796 -2.13631e-4 0.08142387 0.9966796 1.83117e-4 0.08334851 0.9965204 -1.83112e-4 0.2443017 0.9696993 1.22077e-4 0.2458016 0.9693202 -9.1557e-5 0.4008364 0.9161497 0 0.4016 0.9158153 -3.05191e-5 0.5464754 0.8374752 -6.10393e-5 0.5465461 0.8374291 3.05193e-5 0.6766127 0.736339 -1.22077e-4 0.6773124 0.7356956 1.22076e-4 0.7883949 0.6151696 -1.52595e-4 0.789344 0.6139512 1.83116e-4 0.8787119 0.4773524 -1.52597e-4 0.8795385 0.4758279 1.83112e-4 0.9453169 0.3261534 -1.22075e-4 0.94581 0.3247207 -0.1155764 0.9911128 0.0658605 -0.2116469 0.9660075 0.1484428 -0.1105706 0.9905573 0.08105862 -0.1194221 0.9837912 0.1337662 -1 -1.13172e-5 0 -0.2140918 0.9581182 0.1901953 -0.1190248 0.9780181 0.1712126 -0.2062157 0.9480978 0.2420448 -0.1105107 0.9724391 0.2053039 -0.1095938 0.9705655 0.214457 -0.1958693 0.952582 0.2328581 -0.1080972 0.9686024 0.2238851 -0.1774379 0.9377294 0.2986292 -0.0921691 0.9607867 0.2615222 -0.09958511 0.9537343 0.2836787 -0.1862571 0.9159954 0.355332 -0.07171911 0.9287781 0.3636313 -0.0944882 0.9080454 0.4080756 -0.1812518 0.8765643 0.4458508 -0.08630853 0.8788948 0.4691426 -0.1699636 0.8266842 0.5363819 -0.08993935 0.841255 0.5331051 -0.08145558 0.8200497 0.566466 -0.1637037 0.7688645 0.6181007 -0.08090633 0.7750649 0.6266807 -0.08066153 0.7469206 0.6600027 -0.1648982 0.7000315 0.6948127 -0.08462935 0.673342 0.7344717 -0.1600134 0.6281513 0.7614603 -0.07931983 0.5940293 0.8005234 -0.1564715 0.5503513 0.8201404 -0.07452809 0.5096724 0.8571346 -0.1541522 0.4679197 0.8702232 -0.07300132 0.4208564 0.9041851 -0.1527488 0.3821315 0.9113965 -0.07605403 0.3306155 0.9406961 -0.1526582 0.2935971 0.9436611 -0.08090686 0.2408284 0.9671896 -0.1022704 0.2017329 0.9740866 -0.08725363 0.1555855 0.9839614 -0.1057495 0.1313247 0.985683 -0.106727 0.1318446 0.9855082 -0.09817975 0.1273559 0.986986 -0.0976597 0.1271408 0.9870653 -0.09701949 0.1268669 0.9871637 -0.09442561 0.1259517 0.9875323 -0.09109884 0.1250663 0.9879572 -0.08820086 0.1248546 0.988247 -0.08566719 0.1254642 0.9883926 -0.08435451 0.1266233 0.9883577 -0.08365261 0.1280273 0.9882365 -0.08340972 0.1297078 0.9880378 -0.01745051 0.02856117 0.9994397 -0.0174517 0.02856773 0.9994396 -1 -2.72149e-6 0 -0.02630746 0.0420553 0.998769 -0.02227908 0.03576862 0.9991118 -0.02179032 0.03497433 0.9991506 -0.03390675 0.05026507 0.9981603 -0.01416075 0.02743643 0.9995233 0.2371934 -0.09650093 0.9666576 0.1044355 -0.06939989 0.9921073 0.1182301 -0.1468567 0.9820666 0.1205814 -0.003112912 0.9926986 0.1201229 -0.003448605 0.9927532 0.256089 -0.03460907 0.9660335 0.2457124 -0.2914306 0.9244964 0.1175609 -0.2855093 0.9511383 0.2479649 -0.1658084 0.9544743 0.2424479 -0.4123508 0.878172 0.1152696 -0.4232351 0.8986573 0.2366188 -0.5272573 0.8160952 0.1167041 -0.5551072 0.8235511 0.2262355 -0.6357057 0.7380351 0.1210102 -0.6750936 0.7277399 0.2127791 -0.7349609 0.6438615 0.1294918 -0.7780494 0.6147122 0.1978549 -0.8209009 0.5357006 0.1416099 -0.8602193 0.4898666 0.1828706 -0.8904565 0.4167081 0.1523237 -0.9208703 0.3588809 0.1679165 -0.942707 0.2882841 0.1615976 -0.9616201 0.2217503 0.1539692 -0.9766138 0.1500628 0.2266989 -0.97165 0.06711238 0.1341309 -0.9898223 0.04754853 0.2034117 -0.9790927 -0.001159727 0.2824856 -0.955281 -0.08740693 0.1117613 -0.9875404 -0.1107847 0.2071936 -0.9685516 -0.1377628 0.2038682 -0.9565633 -0.2083851 0.2172033 -0.936962 -0.2737243 0.09833335 -0.9529976 -0.2865768 0.2024306 -0.9176058 -0.3420841 0.2221484 -0.8896314 -0.3990066 0.1138677 -0.8935765 -0.4342295 0.1963322 -0.8611698 -0.4688716 0.2256327 -0.824675 -0.5186532 0.1389539 -0.8114751 -0.5676267 0.1856824 -0.7853658 -0.5905274 0.2303902 -0.7413139 -0.6303762 0.1753661 -0.7087892 -0.6832748 0.1739601 -0.6901639 -0.7024327 0.2369497 -0.6421508 -0.7290385 0.208779 -0.5929801 -0.7776798 0.1597667 -0.5788531 -0.7996273 0.2439744 -0.5325382 -0.810481 0.2384453 -0.4691999 -0.8502913 0.1388917 -0.4438065 -0.8852937 0.2349379 -0.4066398 -0.8828638 0.1200309 -0.3039075 -0.94511 0.2438473 -0.2850176 -0.9269863 0.1182631 -0.1540625 -0.9809581 0.2489135 -0.1603776 -0.9551551 0.1059938 -0.07281923 -0.9916968 0.2558458 -0.03460919 -0.966098 0.1209157 -0.00350964 -0.9926567 0.1205213 -0.003082454 -0.992706 0.255599 -0.03500556 -0.966149 0.2365847 -0.09851592 -0.9666036 -0.4012382 0.8972083 0.184459 -0.4124662 0.9062049 0.09308338 -0.4154561 0.9083697 0.04754871 -0.5734577 0.7910297 0.2131162 -0.5893005 0.8006783 0.1078863 -0.7229449 0.6504918 0.2328329 -0.7414634 0.6605876 0.1177124 -0.5936349 0.8029071 0.05420261 -0.8416324 0.4828468 0.2418964 -0.8625767 0.4909085 0.1223532 -0.7470188 0.6621449 0.05939036 -0.9030147 0.386409 0.1877567 -0.9109618 0.398273 0.1073659 -0.8682025 0.4923619 0.0616787 -0.8879623 0.3835679 0.2537689 -0.9471277 0.3046715 0.1006212 -0.946608 0.3040913 0.1070606 -0.9363067 0.301105 0.1807363 -0.9146715 0.3993791 0.06222939 -0.9523701 0.3049439 -7.01933e-4 -0.936032 0.3008914 0.1825064 -0.9204347 0.2952752 0.2561494 -0.8724375 0.3835111 0.302939 -0.9206441 0.2935038 0.25743 -0.9087954 0.2913651 0.2986592 -0.9273991 0.2979018 0.2262418 -0.711767 0.6409016 0.2874596 -0.8267316 0.4764335 0.2992091 -0.5654544 0.7810705 0.2649347 -0.3981234 0.8873162 0.2327396 -0.8380255 0.3676642 0.403158 -0.8435536 0.372244 0.3871068 -0.797869 0.4633152 0.3856738 -0.8881981 0.2854131 0.3600605 -0.8862449 0.2843772 0.3656496 -0.8961604 0.288069 0.3375098 -0.8807229 0.2825161 0.380147 -0.8953729 0.2876437 0.3399536 -0.8932752 0.2870664 0.345908 -0.9134506 0.2910041 0.2844728 -0.9047169 0.2898122 0.3122439 -0.8742921 0.2802911 0.3962957 -0.7960307 0.4681025 0.3836866 -0.6836326 0.6300407 0.3683681 -0.8342751 0.365621 0.4126818 -0.6839146 0.6295896 0.3686162 -0.5404101 0.77126 0.3363256 -0.5444014 0.7671609 0.3392513 -0.3752906 0.8802255 0.2904481 -0.3831083 0.8747735 0.2966472 -0.4150028 0.9085624 -0.04782384 -0.4124982 0.9060862 -0.09409081 -0.594093 0.8025413 -0.0545994 -0.7416914 0.6603257 -0.1177452 -0.7470403 0.6621369 -0.05920654 -0.589779 0.8002683 -0.1083118 -0.8626613 0.490874 -0.1218944 -0.8683672 0.4921246 -0.06125229 -0.9141498 0.4004765 -0.06283956 -0.9112592 0.3952482 -0.1156965 -0.9471098 0.3047366 -0.100592 -0.9462152 0.3035433 -0.1119747 -0.952055 0.3059272 -6.10389e-5 -0.3969619 0.8884415 -0.2304192 -0.5746472 0.7901743 -0.2130855 -0.5676862 0.7800076 -0.2632884 -0.400869 0.8975988 -0.183359 -0.7233383 0.6503056 -0.2321299 -0.7118607 0.6409341 -0.2871553 -0.842415 0.4816809 -0.2414966 -0.8269496 0.475612 -0.2999127 -0.8829243 0.3887247 -0.2633208 -0.870446 0.3850032 -0.3067513 -0.8974184 0.2874608 -0.334674 -0.9081324 0.2907269 -0.3012865 -0.919207 0.2946626 -0.2612136 -0.8761284 0.2809031 -0.3917811 -0.8822219 0.2829446 -0.3763337 -0.8888791 0.2852991 -0.3584668 -0.8853752 0.2840464 -0.368006 -0.8875237 0.2848035 -0.3621997 -0.8960433 0.2876433 -0.3381831 -0.8813315 0.2825461 -0.3787119 -0.9016852 0.3891788 -0.1884245 -0.9273397 0.2979939 -0.2263643 -0.9348666 0.3003097 -0.189311 -0.9044941 0.2881307 -0.3144381 -0.9129759 0.2925246 -0.2844371 -0.9205705 0.2957276 -0.2551376 -0.9359747 0.3011062 -0.1824461 -1 -2.6267e-6 0 -0.866234 0.2774525 -0.4155225 -1 2.1815e-6 0 -0.8705095 0.2790098 -0.4054219 -0.8953165 0.2874925 -0.34023 -0.8858782 0.2700941 -0.3771857 -0.8850294 0.2707368 -0.3787141 -0.8862708 0.2707642 -0.3757801 -0.8952174 0.2702163 -0.3543575 -0.8948158 0.2694213 -0.3559731 -0.9011373 0.2727797 -0.3369613 -0.8889071 0.2712256 -0.3691623 -0.8540805 0.2646017 -0.4478086 -0.8550885 0.2689662 -0.4432616 -0.8591523 0.2755293 -0.4312089 0.2284051 -0.5638715 -0.7936499 -0.8512378 0.2707957 -0.4495153 -0.8497413 0.2744576 -0.4501252 -0.8492 0.2757725 -0.450343 -0.8517864 0.2694221 -0.4493013 -0.8561015 0.2691512 -0.4411894 -0.8578092 0.2697916 -0.4374653 -0.8637196 0.2762279 -0.4215291 -1 -2.47598e-6 0 -0.8603097 0.2703403 -0.4321844 -0.8578834 0.2627668 -0.4415765 -0.8667826 0.2811756 -0.4118598 -0.8709693 0.2726014 -0.40878 -0.8762041 0.2843466 -0.3891188 -0.8726004 0.2698494 -0.407124 -0.8786231 0.2693337 -0.3943107 -0.8629591 0.2664931 -0.4292821 -0.8666071 0.2686955 -0.42047 -0.8778861 0.269546 -0.3958041 -0.8829531 0.2703397 -0.3838104 -0.8827776 0.2698232 -0.3845767 -0.8927496 0.2869727 0.3473398 -0.8998594 0.2687828 0.3435244 -0.900077 0.2735145 0.3391922 -0.8949229 0.2686935 0.3562539 -0.8860031 0.271804 0.375661 -0.8931806 0.2627109 0.3649814 -0.8891555 0.2664048 0.3720634 -0.8993686 0.260725 0.3509396 -0.9081231 0.2724735 -0.3179163 -0.9093526 0.2761995 -0.3111136 -0.8962888 0.271438 -0.3506965 -0.8999179 0.2715288 -0.3412039 -0.9169799 0.2754663 -0.288559 -0.9178561 0.278485 -0.2828187 -0.9249852 0.2782769 -0.2587749 -0.925526 0.2804411 -0.2544693 -0.9309078 0.2801604 -0.234352 -0.9323823 0.2816282 -0.2266027 -0.935173 0.2807167 -0.2159852 -0.9468243 0.285445 -0.1484754 -0.9479981 0.2805967 -0.1502172 -0.9043498 0.4225101 -0.06030625 -0.9347789 0.2785811 -0.2204111 -0.9411852 0.3145321 -0.1234506 -0.952002 0.3054622 -0.01962351 -0.9524328 0.3041815 -0.01858597 -0.897628 0.4242156 0.1196044 -0.9445281 0.3113839 0.1044355 -0.9334599 0.2843168 0.21867 -0.936089 0.2787331 0.2145814 -0.9323037 0.2814185 0.2271857 -0.9546343 0.281141 0.09814906 -0.9320504 0.2807748 0.2290146 -0.9255477 0.2803164 0.2545279 -0.9347362 0.2833079 0.2144876 -0.9248506 0.2782731 0.2592597 -0.9178476 0.2783299 0.2829992 -0.9168181 0.2754635 0.289075 -0.9093617 0.2760404 0.3112283 -0.9080135 0.2724773 0.3182259 -0.8625407 0.2763536 0.4238541 -0.8684271 0.2782751 0.4103627 -0.8608964 0.2758359 0.4275183 -0.8551858 0.2818472 0.4349938 -0.8491896 0.2801029 0.4476823 -0.8638564 0.2768124 0.4208648 -0.8573109 0.2639593 0.441977 -0.8607724 0.275988 0.42767 -0.8555088 0.2695439 0.4420983 -0.8446761 0.2810501 0.4555581 -0.8539601 0.2659145 0.4472601 -0.8485877 0.2744596 0.4522953 -0.8510169 0.2714953 0.4495115 -0.834513 0.2396356 0.4961482 -0.8726205 0.2796829 0.4003885 -0.8670305 0.2777891 0.4136317 -1 2.75483e-6 0 -0.7639247 0.453545 0.4590384 -0.8222247 0.367088 0.4349632 -0.82375 0.3678812 0.4313922 -0.7775431 0.4541594 0.4349322 -0.8793954 0.2820633 0.3835414 -0.8807776 0.2702455 0.3888422 -0.8811779 0.2697278 0.3882945 -0.8893094 0.2700676 0.3690425 -0.8870485 0.2702804 0.3742908 -0.8758084 0.2696368 0.4003198 -0.8728284 0.2714408 0.4055742 -0.8680807 0.2710692 0.4158816 -1 -2.5334e-6 0 -0.8550543 0.2775409 0.4380105 -0.8578608 0.2692393 0.4377046 -0.8637818 0.2758925 0.4216212 -0.8590825 0.2693006 0.4352636 -0.8619542 0.2706444 0.4287034 -0.5722367 0.1889754 -0.7980185 -1 1.68781e-6 0 -0.8445571 0.2809596 0.4558344 -0.8534311 0.2638055 0.4495131 -0.8485877 0.2711635 0.454279 -0.8422943 0.2805918 0.4602267 -0.8464581 0.2709826 0.4583417 -0.8394929 0.2833406 0.4636484 -0.8496856 0.261977 0.4576052 -0.8428147 0.2719554 0.4644392 -0.8430261 0.2896252 0.4532375 -0.8333473 0.2871517 0.4723095 -0.8455758 0.2603016 0.4660952 -0.8389754 0.2723237 0.4711263 -0.8300395 0.2864562 0.4785156 -0.8412687 0.2585913 0.4747606 -0.8350929 0.2725656 0.4778368 -0.8264601 0.289322 0.4829664 -0.8371661 0.2569393 0.4828407 -0.8313958 0.2727779 0.4841212 -0.8320194 0.2957633 0.4693271 -0.8196276 0.2923753 0.4926738 -0.8270807 0.2729977 0.4913347 -0.8154101 0.2949064 0.4981333 -0.832642 0.2551152 0.4915524 -0.8223748 0.2732704 0.4990221 -0.8214249 0.3005838 0.4846758 -0.8084829 0.2976228 0.5077167 -0.8279573 0.2537677 0.5000888 -0.8176558 0.2737523 0.5064571 -0.8048835 0.2999429 0.5120516 -0.8236778 0.2519345 0.5080196 -0.8135764 0.2743051 0.5126892 -0.8038132 0.3086096 0.508571 -0.7988418 0.3029037 0.5197126 -0.8189637 0.2498337 0.5166057 -0.8099118 0.2744264 0.5183948 -0.7952806 0.3022054 0.5255481 -0.8062556 0.27452 0.5240142 -0.7918605 0.305104 0.5290261 -0.8142182 0.24812 0.5248669 -0.8021577 0.2746392 0.5302041 -0.7802832 0.3185284 0.5382359 -0.7838914 0.3109624 0.5374166 -0.8093494 0.2463237 0.5331775 -0.7977979 0.2748849 0.5366161 -0.7789376 0.3121183 0.5439104 -0.8044959 0.2443091 0.5413867 -0.7932566 0.2751922 0.5431513 -0.774055 0.3125457 0.5505944 -0.7995775 0.2425376 0.5494101 -0.7889808 0.27513 0.549375 -0.7692947 0.3121798 0.5574312 -0.7842007 0.2749204 0.5562805 -0.7646577 0.3108987 0.5644825 -0.7942544 0.2408856 0.5577939 -0.7791821 0.2748546 0.5633208 -0.7603006 0.3141062 0.5685775 -0.7893816 0.2388745 0.5655226 -0.7739726 0.2747664 0.5704997 -0.7504383 0.3249692 0.5755324 -0.7505887 0.3198715 0.5781859 -0.7840394 0.2367377 0.5737923 -0.7685338 0.2746726 0.5778501 -0.7447268 0.3204199 0.5854172 -0.7786461 0.2350007 0.5817947 -0.7631285 0.2747628 0.5849277 -0.7399021 0.3200525 0.591702 -0.7734414 0.23289 0.5895343 -0.7582807 0.2749172 0.5911269 -0.7356089 0.3189887 0.5976002 -0.7679917 0.2306661 0.5974795 -0.7540342 0.2746714 0.5966475 -0.7316688 0.3208795 0.6014126 -0.7493674 0.2742452 0.6026924 -0.732586 0.3279912 0.5964392 -0.7236539 0.3253101 0.608686 -0.7623679 0.2288019 0.605347 -0.7444632 0.274035 0.6088344 -0.717958 0.3263085 0.6148651 -0.756685 0.2267857 0.6131853 -0.7393978 0.2739132 0.6150305 -0.7124666 0.3264925 0.6211231 -0.7509027 0.2248679 0.6209505 -0.734167 0.2738172 0.6213074 -0.7071542 0.3257896 0.6275303 -0.7453708 0.2228513 0.6282991 -0.7292008 0.2733626 0.627327 -0.704454 0.3251866 0.6308711 -0.726291 0.2730534 0.6308276 -0.6925522 0.3214941 0.6457656 -0.6119108 0.2880406 0.7366125 -0.9119791 0.4087456 -0.03494465 -0.7414689 0.2232494 0.6327587 -0.5324285 0.1656552 0.8301074 -0.6431307 0.197398 0.7398765 -0.6300593 0.241983 0.7378819 -0.5198876 0.2045674 0.8293787 -0.539921 0.2565777 0.8016566 -0.507837 0.2428401 0.8265169 -0.7436093 0.3389503 0.5763315 -0.7408527 0.3416621 0.5782771 -0.8513525 0.388077 0.3529804 -0.7416208 0.3428241 0.5766025 -0.7629294 0.3302528 0.5557623 -0.7862103 0.3377582 0.517487 -0.7738448 0.3240224 0.5442184 -0.7825735 0.3199939 0.534025 -0.7881765 0.3222472 0.5243421 -0.717715 0.4399007 0.5397894 -0.7661904 0.377617 0.5199596 -0.7806202 0.3734635 0.5011559 -0.7590847 0.3734689 0.5332087 -0.7401152 0.4478352 0.5016705 -0.7924625 0.3756307 0.4805254 -0.803893 0.3728164 0.4634264 -0.7359712 0.3404115 0.5852063 -0.64973 0.394892 0.6495469 -0.7091768 0.351094 0.611393 -0.7054415 0.371261 0.603753 -0.7147637 0.3574123 0.6011401 -0.6873597 0.3379727 0.6428928 -0.7314617 0.3505474 0.5848764 -0.7025839 0.3560987 0.6160923 -0.661807 0.4084983 0.6286022 -0.7207549 0.3722496 0.5847588 -0.67893 0.4193032 0.6026931 -0.7260442 0.373429 0.5774173 -0.7391492 0.3732827 0.5606412 -0.6971773 0.4302271 0.5734531 -0.7446793 0.3760936 0.5513679 -0.7589239 0.1710913 0.6283012 -0.684579 0.1475609 0.713847 -0.76182 0.1725249 0.6243922 -0.7982993 0.1434112 0.5849373 -0.7718685 0.1222916 0.62391 -0.7695874 0.1216519 0.6268463 -0.6377036 0.1424037 0.7570042 -0.6484168 0.1169812 0.7522441 -0.6944408 0.1149364 0.7103109 -0.6413411 0.1102066 0.7592998 -0.6928497 0.1149358 0.7118632 -0.7655256 0.1748778 0.6191837 -0.7694296 0.1780513 0.6134134 -0.7734743 0.1812525 0.6073592 -0.7779742 0.1847044 0.6005334 -0.7825682 0.1880885 0.5934725 -0.7913296 0.19343 0.5799849 -0.7890195 0.1912654 0.5838372 -0.7864534 0.1906239 0.5874977 -0.7950184 0.1969387 0.5737255 -0.7987171 0.2002362 0.5674123 -0.8057066 0.2048753 0.5557545 -0.802967 0.2024661 0.5605815 -0.8090932 0.2085373 0.5494363 -0.8126751 0.2121415 0.5427295 -0.817822 0.2161062 0.5333529 -0.8157636 0.2139437 0.537362 -0.8212592 0.2200401 0.5264177 -0.8249116 0.2236469 0.5191367 -0.8283872 0.2270336 0.5120845 -0.8346773 0.2323448 0.4993293 -0.8322458 0.2296313 0.5046152 -0.8372684 0.2353959 0.4935287 -0.8407738 0.2385687 0.485988 -0.8394025 0.2375316 0.4888579 -0.8454076 0.2437249 0.4752728 -0.843537 0.2413811 0.4797714 -0.8481284 0.2461983 0.4691105 -0.8524357 0.2507164 0.4587972 -0.850863 0.2490025 0.4626339 -0.8568734 0.2557467 0.4476177 -0.8567127 0.2507482 0.4507424 -0.8588743 0.2574609 0.4427741 -0.8601778 0.2600523 0.4387105 -0.851547 0.208904 0.4808606 -0.8658113 0.2464765 0.435454 -0.8636991 0.2415611 0.4423483 -0.8665233 0.2483934 0.4329412 -0.8568543 0.2386593 0.456993 -0.8386914 0.2348128 0.4913856 -0.7706431 0.4376468 0.463222 -0.6828937 0.5833101 0.4397791 -0.7493141 0.4799187 0.4562966 -0.6544627 0.6215626 0.4305098 -0.7003512 0.5592006 0.4436249 -0.7476027 0.4846782 0.4540673 -0.2946022 0.9176828 0.2665855 -0.3223399 0.9051275 0.2772026 -0.1634921 0.966212 0.1992608 -0.09161931 0.9829085 0.1596776 -0.03494435 0.9912295 0.1274477 0.02371317 0.9952524 0.09439498 0.05966514 0.9954779 0.07391768 -0.8245753 0.2095467 0.5255149 0.2159842 0.9760341 -0.02661269 0.2035321 0.978871 -0.01965433 0.2421377 0.9692531 -0.04379475 0.2429642 0.9690183 -0.04440557 -0.8046746 0.1887015 0.5629304 -0.8416867 0.1810089 0.5087231 -0.7973024 0.1869273 0.5739052 -0.7923631 0.1889732 0.5800429 -0.8018373 0.1661478 0.5739791 -0.7961847 0.146309 0.5870977 -0.8196024 0.1514379 0.5525563 -0.7934575 0.1412714 0.5920031 -0.7892075 0.1350189 0.5991007 -0.7847367 0.1299806 0.6060475 -0.7804915 0.1264705 0.6122405 -0.7763258 0.1239704 0.6180208 -0.2004786 0.05090546 0.9783747 -0.1545791 0.06610429 0.9857664 -0.1240305 0.04989904 0.991023 -0.01743859 0.02856618 0.9994398 -0.1352893 0.04504555 0.9897816 -0.195779 0.05270618 0.9792307 -0.1249457 0.04294055 0.991234 -0.01744496 0.02856737 0.9994397 -0.3052517 0.073673 0.9494177 -0.2813218 0.09918588 0.9544738 -0.1517722 0.07629805 0.9854663 -0.01744091 0.02856731 0.9994397 -0.01745808 0.02856564 0.9994395 -0.4261366 0.1081287 0.8981737 -0.2769011 0.1203679 0.9533296 -0.5357753 0.1294345 0.8343811 -0.4540929 0.09091621 0.8863036 -0.5426015 0.09860765 0.8341823 -0.4322414 0.0842936 0.8978096 -0.2415622 0.06131374 0.9684464 -0.3164787 0.06952154 0.9460487 -0.1432878 0.08438569 0.9860769 -0.1475304 0.08594244 0.9853166 -0.2743968 0.1412422 0.9511873 -0.0174542 0.02856689 0.9994395 -0.1579639 0.09030431 0.983307 -0.2947242 0.1507039 0.943624 -1 -2.10538e-6 0 -1 -2.3159e-7 0 -0.2859024 0.0842936 0.9545442 -0.1578748 0.05887115 0.9857027 -0.1591582 0.0593295 0.9854688 -0.01746165 0.02856814 0.9994394 -0.2959118 0.08832186 0.9511233 -0.1510382 0.04950171 0.9872878 -0.2945994 0.07721292 0.9524965 -0.1602843 0.05438435 0.9855716 -0.01743447 0.02856355 0.99944 -0.1544256 0.05679565 0.9863707 -0.01744991 0.02856761 0.9994395 -0.01745039 0.02856683 0.9994396 -0.2741255 0.07877063 0.9584626 -0.1496658 0.05395781 0.9872633 -0.01744824 0.02856469 0.9994397 -0.2633472 0.07315367 0.9619235 -0.1436516 0.05090522 0.9883183 -0.01745426 0.02856785 0.9994395 -0.0174551 0.02856767 0.9994395 -0.2530962 0.06711184 0.9651105 -0.1373955 0.0491352 0.9892968 -0.01744991 0.02856636 0.9994396 -0.1386189 0.04776275 0.9891934 -0.01745355 0.02856779 0.9994395 -0.01745343 0.02856707 0.9994396 -0.01745331 0.02856749 0.9994395 -0.01744705 0.0285663 0.9994397 -0.4742358 0.1020557 0.8744629 -0.4938247 0.1130111 0.8621866 -0.5128164 0.1237254 0.8495361 -0.5312482 0.1335521 0.8366236 -0.5497133 0.1405718 0.8234409 -0.2785789 0.06131297 0.9584543 -0.5515812 0.1204915 0.8253727 -0.7390435 0.1727975 0.6511188 -0.757024 0.1819848 0.6275318 -0.5194342 0.08957338 0.8498028 -0.7620368 0.1545498 0.62882 -0.669314 0.1303775 0.7314509 -0.694804 0.1475611 0.7038987 -0.7196851 0.161022 0.6753705 -0.817629 0.1899489 0.5435092 -0.8368579 0.1966331 0.5108859 -0.8376964 0.1988033 0.5086668 -0.7228784 0.1101744 0.6821352 -0.8439115 0.1673967 0.5096979 -0.7135117 0.1304396 0.6883943 -0.7467451 0.1462177 0.6488393 -0.7730752 0.163612 0.6128507 -0.7631361 0.1519557 0.6281185 -0.79351 0.1776852 0.5820396 -0.8334234 -0.04773229 0.5505697 -0.9044716 0.2075316 0.3726413 -0.9041506 0.2089928 0.3726043 -0.8355888 0.1582732 0.5260617 -0.882476 0.1353241 0.4504702 -0.8895049 0.1675489 0.4250982 -0.8855069 0.1458194 0.4411512 -0.8929873 0.1589737 0.4210713 -0.8140535 0.1428576 0.5629464 -0.8311891 0.1631248 0.5315215 -0.838089 0.1656584 0.5197733 -0.847306 0.1753026 0.5013398 -0.8618474 0.1794256 0.4743686 -0.8625752 0.1789973 0.4732062 -0.877 0.1945905 0.439324 -0.8852038 0.1986787 0.4206435 -0.8901774 0.2036225 0.4075809 -0.9070053 0.2070739 0.3666903 -0.1585761 -0.01901322 0.9871637 -0.08978664 0.003601193 0.9959546 -0.07687801 0.003662288 0.9970339 -0.01745402 0.02856689 0.9994395 -0.1324847 -0.01937979 0.9909956 -0.2400049 -0.07779407 0.9676496 -0.1306222 -0.01986795 0.9912332 -0.08606392 0.006805717 0.9962664 -0.1301032 -0.02670425 0.9911409 -0.01742267 0.02857017 0.99944 -0.01745265 0.02856612 0.9994395 -0.1865018 -0.009613454 0.9824077 -0.1039786 0.01031541 0.9945261 -0.01745671 0.02856594 0.9994395 -0.01745408 0.02856886 0.9994395 -0.2143052 0.002319395 0.9767641 -0.1158817 0.01812845 0.9930976 -0.0174483 0.02856767 0.9994396 -0.0174551 0.02856642 0.9994395 -0.01745301 0.02856498 0.9994397 -0.2360362 0.01937973 0.9715511 -0.1244245 0.02093577 0.9920082 -0.01744991 0.02856701 0.9994397 -0.01744997 0.0285682 0.9994396 -0.01744836 0.02856695 0.9994396 -0.0174517 0.02856916 0.9994395 -0.1273875 0.02719265 0.9914802 -0.0174492 0.02856564 0.9994397 -0.01745223 0.02856588 0.9994397 -0.01745104 0.02856886 0.9994395 -0.2565739 0.03802675 0.9657763 -0.1392571 0.03427255 0.989663 -0.01745283 0.02856594 0.9994395 -0.01745277 0.02856659 0.9994396 -0.1444178 0.03927844 0.988737 -0.01745092 0.02856761 0.9994395 -0.01745367 0.02856683 0.9994395 -0.01745647 0.02856814 0.9994394 -0.4850381 0.04565638 0.8733005 -0.4451807 0.008850455 0.8953971 -0.400658 -0.02142453 0.9159772 -0.3518886 -0.04620635 0.9349007 -0.2985689 -0.06683695 0.952045 -0.2480303 -0.06799697 0.966363 -0.2433295 -0.08295112 0.9663901 -0.432908 -0.1152082 0.8940458 -0.3595418 -0.1160935 0.9258791 -0.351453 -0.1368457 0.9261502 -0.6843973 0.04855632 0.7274907 -0.6326107 -0.00250256 0.7744659 -0.5750424 -0.04678589 0.8167848 -0.5054231 -0.08371323 0.8588012 -0.4917564 -0.1430436 0.8589029 -0.414325 -0.1407533 0.8991793 -0.4059976 -0.1658416 0.8987005 -0.4033074 -0.1636729 0.900308 -0.3528035 -0.1316909 0.926384 -0.8208089 0.09708094 0.5628927 -0.7672845 0.02594131 0.6407821 -0.8206278 0.09247279 0.5639317 -0.7679465 0.04977625 0.638577 -0.7216881 -0.02630752 0.6917183 -0.7286129 0.004699885 0.6849096 -0.6545081 -0.07474076 0.7523517 -0.672518 -0.04184162 0.738897 -0.5822214 -0.1232074 0.8036407 -0.5820879 -0.09259444 0.8078366 -0.5275844 -0.1739896 0.831494 -0.5014525 -0.1377003 0.8541569 -0.5176125 -0.175915 0.8373358 -0.4589744 -0.1960232 0.866555 -0.4677936 -0.1965722 0.861701 -0.04236024 0.01379454 0.9990072 -0.4629451 -0.1963602 0.8643637 -0.8541063 0.08566695 0.5129948 -0.8347571 0.03418129 0.5495566 -0.8409171 0.08783328 0.5339887 -0.8398969 0.0493195 0.5405005 -0.8265792 0.01614457 0.562589 -0.7852323 -0.02200442 0.6188103 -0.7547362 -0.05572777 0.6536571 -0.7652708 -0.02649068 0.6431632 -0.7503122 -0.05963432 0.6583886 -0.6893315 -0.103093 0.7170733 -0.6364127 -0.1350466 0.7594348 -0.6537103 -0.1154217 0.747891 -0.5669311 -0.1674302 0.8065707 -0.5514874 -0.2025274 0.8092246 -0.5614633 -0.1916306 0.8050073 -0.1304696 -0.02713155 0.9910811 -0.01748967 0.02855849 0.9994391 -0.1218934 -0.02911525 0.9921162 -0.2339907 -0.0879563 0.9682521 -0.1290328 -0.03006082 0.9911846 -0.01745659 0.02856594 0.9994395 -0.2165327 -0.08691829 0.9723985 -0.3370255 -0.1457911 0.9301391 -0.3247539 -0.1672447 0.9308943 -0.3958974 -0.244033 0.8852757 -0.4277309 -0.2171463 0.8774359 -0.4020351 -0.1980418 0.8939504 -0.4325527 -0.2223039 0.8737729 -0.4558403 -0.1959661 0.8682206 -0.185036 -0.1171925 0.975719 -0.1095035 -0.04266607 0.9930703 -0.1074572 -0.05154645 0.9928726 -0.01745152 0.02856701 0.9994395 -0.1918141 -0.1249462 0.9734454 -0.1914772 -0.142555 0.9710894 -0.1865335 -0.136482 0.9729224 -0.1031547 -0.05481237 0.9931541 -0.103947 -0.0557273 0.9930205 -0.01745378 0.02856713 0.9994395 -0.01745313 0.02856588 0.9994395 -0.2128088 -0.1101124 0.9708697 -0.1162773 -0.03500527 0.9925997 -0.01744902 0.02856719 0.9994397 -0.01745533 0.02856439 0.9994395 -0.01746094 0.02856653 0.9994395 -0.3020498 -0.1753031 0.9370352 -0.3090668 -0.1948643 0.9308629 -0.2808983 -0.2023724 0.9381586 -0.2711914 -0.2212624 0.9367488 -0.2675028 -0.2163217 0.9389608 -0.2744588 -0.2250483 0.9348935 -0.03952217 0.01052904 0.9991633 -0.37365 -0.2690597 0.8876895 -0.3877801 -0.2508698 0.8869561 -0.3787752 -0.273331 0.8842057 -0.3617169 -0.309315 0.8794801 -0.3533539 -0.3038819 0.8847581 -0.1218628 -0.07092642 0.9900097 -0.3641514 -0.3122998 0.8774181 -0.1056859 -0.05795478 0.9927093 -0.01745146 0.02856606 0.9994396 -0.08228051 -0.05221879 0.9952403 -0.1816501 -0.1486284 0.9720663 -0.1019027 -0.06180083 0.9928728 -0.01745164 0.02856659 0.9994396 -0.0174542 0.02856624 0.9994396 -0.1373682 -0.1285175 0.9821473 -0.2574622 -0.2326499 0.9378632 -0.210275 -0.2094815 0.9549356 -0.2459843 -0.2952727 0.9232041 -0.3025678 -0.3029341 0.9037056 -0.2757753 -0.2872506 0.9172977 -0.2580059 -0.3286874 0.908514 -0.3170631 -0.3228312 0.8917685 -0.3696475 -0.3151404 0.8740981 -0.0426352 -0.03177034 0.9985855 -0.03546321 -0.01699912 0.9992265 -0.03344833 -0.00979644 0.9993925 -0.02557462 0.008331537 0.9996382 -0.02649044 -7.93493e-4 0.9996488 -0.03726369 -0.03375399 0.9987353 -0.02499496 0.004486262 0.9996775 -0.01745343 0.02857106 0.9994395 -0.01986783 -0.04815894 0.9986422 -0.01767069 -0.007507741 0.9998157 -0.01751798 0.04074311 0.9990161 -0.0184642 0.06070309 0.9979851 -0.01721298 0.09528183 0.9953016 -0.01742625 0.0674467 0.9975708 -0.0751065 -0.09030479 0.9930781 -0.05997061 -0.05841416 0.9964895 -0.03549402 -0.01205515 0.9992973 -0.1178351 -0.1437765 0.9825698 -0.09241122 -0.09674489 0.9910099 -0.04788374 -0.02948099 0.9984178 -0.07892203 -0.1019638 0.9916526 -0.1865654 -0.2042973 0.9609662 -0.06308192 -0.04248189 0.9971038 -0.1349545 -0.1640084 0.977184 -0.2153707 -0.2574256 0.9419913 -0.1321464 -0.262248 0.9559097 -0.1769192 -0.2389035 0.9547904 -0.119452 -0.2124744 0.9698382 -0.1557078 -0.2095738 0.9653154 -0.07913655 -0.1474692 0.9858957 -0.06613457 -0.1144461 0.9912257 -0.06442534 -0.09274685 0.9936034 -0.06952273 -0.1685575 0.9832371 -0.0415672 -0.04544317 0.9981018 -0.01745218 0.02856713 0.9994396 -0.01745289 0.02856463 0.9994396 -0.01745325 0.02856773 0.9994395 -0.01745116 0.02856618 0.9994396 -0.07083499 -0.2226985 0.9723107 -0.07364267 -0.28218 0.9565309 -0.13822 -0.3160842 0.9386087 -0.07791507 -0.3447124 0.9354692 -0.1457299 -0.3705966 0.91729 -0.08301264 -0.4084711 0.9089886 -0.1540907 -0.4251304 0.8919194 -0.2725706 -0.3619015 0.8914777 -0.08356183 -0.467922 0.8798105 -0.160959 -0.4789401 0.8629651 -0.2888358 -0.3957453 0.8717567 -0.08749735 -0.534384 0.840701 -0.1706634 -0.5297218 0.8308243 -0.3074229 -0.4295315 0.8491137 -0.08850449 -0.4993792 0.8618511 -0.09494554 -0.5951877 0.797958 -0.1824734 -0.5789462 0.7946854 -0.3251217 -0.4623058 0.8249662 -0.09430468 -0.562105 0.8216719 -0.09461075 -0.6717975 0.7346679 -0.1954459 -0.6091052 0.7686299 -0.3446183 -0.4961137 0.7969375 -0.08325582 -0.6711437 0.7366375 -0.100133 -0.6274107 0.7722237 -0.1086795 -0.7148253 0.6908066 -0.2084467 -0.6494197 0.731303 -0.1245793 -0.6897034 0.7132947 -0.2678982 -0.5849936 0.765515 -0.2264503 -0.6360142 0.7377033 -0.2943552 -0.6021999 0.7420987 -0.0736429 -0.711007 0.6993181 -0.02060037 -0.7730801 0.6339739 -0.02642941 -0.6908274 0.7225366 -0.02050906 -0.6586707 0.7521518 -0.01822 -0.7422003 0.6699305 -0.06055039 -0.7496169 0.6590964 -0.01858639 -0.6547663 0.755603 -0.01840305 -0.6222864 0.7825733 -0.02163785 -0.5861142 0.8099395 -0.02673482 -0.5495904 0.8350064 -0.02096676 -0.5219117 0.8527418 -0.01950174 -0.5172092 0.8556368 -0.01849466 -0.4749103 0.8798399 -0.01806735 -0.4149698 0.9096559 -0.01959311 -0.3621985 0.9318951 -0.01760965 -0.3461509 0.9380136 -0.02139359 -0.2793992 0.9599367 -0.02185171 -0.2211421 0.9749968 -0.01956248 -0.1997453 0.9796526 -0.01837271 -0.1562293 0.98755 -0.02005112 -0.102514 0.9945296 -0.01739597 -0.04635876 0.9987733 -0.3348833 -0.3483726 0.8754941 -0.3575944 -0.3731288 0.8560965 -0.3810355 -0.4036809 0.8317775 -0.3722119 -0.3813067 0.8462054 -0.4054214 -0.434415 0.8043116 -0.3919304 -0.413935 0.8216134 -0.3665958 -0.5131486 0.7760709 -0.4262385 -0.4543167 0.7822512 -0.337756 -0.5680845 0.7504673 -0.3764542 -0.5476974 0.7472013 -0.4333734 -0.4836386 0.7604482 -0.4443936 -0.4922176 0.7484894 -0.4550396 -0.4826899 0.7482976 -0.3844218 -0.3278084 0.8629958 -0.3906713 -0.3301525 0.8592877 -0.4044396 -0.3423637 0.8480659 -0.4135676 -0.346486 0.8419675 -0.4234616 -0.3565623 0.8327926 -0.4296174 -0.358691 0.8287157 -0.4430814 -0.369499 0.8167922 -0.4434956 -0.3681758 0.8171648 -0.4566925 -0.3774336 0.8055905 -0.4618154 -0.3808787 0.8010355 -0.4736895 -0.3875946 0.7908152 -0.4819042 -0.3913831 0.7839564 -0.4904565 -0.3989575 0.7747809 -0.4703278 -0.429524 0.7709091 -0.5053044 -0.3994947 0.7648997 -0.5128426 -0.3989759 0.7601386 -0.5194483 -0.4384791 0.7334232 -0.4820207 -0.4474729 0.7532756 -0.5397715 -0.386471 0.7478549 -0.5368043 -0.3848791 0.7508058 -0.5393655 -0.3846943 0.7490628 -0.5314309 -0.3801167 0.7570288 -0.5520972 -0.3915953 0.7360991 -0.499535 -0.4500637 0.7402077 -1 2.19083e-6 0 -1 -5.77189e-7 0 -0.01825022 0.1488708 0.9886882 -0.01623612 0.1873258 0.9821637 -0.0174874 0.2364618 0.9714835 -0.01504582 0.3166955 0.948408 -0.01736557 0.3210651 0.9468979 -1 -6.07999e-7 0 -0.01773136 0.4040689 0.9145568 -0.01556479 0.4616034 0.8869498 -0.01590049 0.4847677 0.8744984 -1 1.10983e-6 0 -0.01608383 0.593241 0.8048642 -0.0159614 0.5580407 0.8296601 -1 -1.7964e-6 0 -0.01699888 0.6312181 0.775419 -1 1.4947e-6 0 -0.01510709 0.7113466 0.7026791 -0.016999 0.6962268 0.7176206 -1 1.24768e-6 0 -0.01764035 0.7578638 0.6521743 -1 -2.14143e-6 0 -0.01464933 0.811695 0.5838979 -0.01745682 0.8124139 0.5828199 -1 4.72699e-6 0 -0.01776242 0.8608679 0.5085185 -0.01525944 0.8923428 0.4511002 -0.01623612 0.9032132 0.4288851 -1 -4.71161e-6 0 -0.01550346 0.9510541 0.3086355 -0.01626694 0.9367685 0.3495715 -1 4.22423e-6 0 -0.01721286 0.9646547 0.2629545 -1 -2.51945e-6 0 -0.01467949 0.9875254 0.1567747 -0.01715165 0.9839331 0.1777122 -0.01763993 0.9958951 0.08877968 -0.01593106 0.9998727 -0.00100708 -0.01803648 0.9996382 -0.01995915 -0.01693797 0.9875907 -0.1561345 -0.01916623 0.9852008 -0.1703295 -0.0159918 0.9513324 -0.3077517 -0.02005118 0.9416424 -0.3360174 -1 -4.83442e-6 0 -1 5.0734e-6 0 -1 2.23485e-6 0 -0.01528996 0.8923733 -0.4510391 -0.02063053 0.8705117 -0.4917151 -1 -2.56727e-6 0 -0.0149241 0.8120375 -0.5834145 -0.02087485 0.7739273 -0.6329303 -1 -4.80171e-6 0 -1 6.48668e-7 0 -0.01486289 0.7119556 -0.7020673 -0.0207833 0.6547206 -0.7555853 -1 -2.38651e-6 0 -0.01510685 0.5942031 -0.8041732 -0.02035588 0.5163446 -0.856139 -1 1.29886e-6 0 -0.01559537 0.461361 -0.8870754 -0.01971548 0.3627837 -0.9316649 -1 2.35459e-6 0 -0.01629728 0.3165153 -0.9484474 -0.0184946 0.1981304 -0.9800013 -1 -1.32132e-6 0 -1 -4.21426e-7 0 -0.01736551 0.1141121 -0.9933162 -0.02346938 0.07028609 -0.9972508 -0.02221751 0.09128105 -0.9955773 -0.01748728 0.1870807 -0.9821889 -1 7.60086e-7 0 -0.02050882 -0.04449683 -0.998799 -0.01913571 -0.05945193 -0.9980478 -0.01742655 0.001922667 -0.9998463 -0.01986783 -0.1455452 -0.9891521 -0.01995944 -0.147987 -0.9887879 -0.02713167 -0.1032163 -0.9942888 -0.01745229 0.02856969 -0.9994395 -0.04675531 -0.03619569 -0.9982504 -0.04355061 -0.04159736 -0.998185 -0.04742705 -0.03680628 -0.9981964 -0.0242623 0.008484184 -0.9996697 -0.02795505 9.76598e-4 -0.9996088 -0.02539151 0.008850395 -0.9996384 -0.02035582 0.02093571 -0.9995736 0.2255661 0.2086891 -0.9516139 0.1006203 0.1247912 -0.9870678 0.1709386 0.2008475 -0.9645933 -0.01745569 0.02856999 -0.9994394 -0.01745182 0.02856683 -0.9994395 -0.01745182 0.02856427 -0.9994396 -0.01745104 0.02856141 -0.9994398 -0.0174542 0.02857804 -0.9994392 -0.01745122 0.02855986 -0.9994398 -0.01745253 0.02856987 -0.9994395 0.2412256 0.1697796 -0.9555025 0.08847516 0.0863083 -0.9923322 0.1143856 0.1002858 -0.9883616 0.231611 0.2974107 -0.9262306 0.106207 0.2612754 -0.9594036 0.2250527 0.4100025 -0.8838831 0.1083421 0.3858505 -0.9161776 0.2251443 0.5296704 -0.817777 0.1091984 0.5068968 -0.8550622 0.1101152 0.6187575 -0.7778264 0.2231254 0.6453578 -0.7305672 0.1242432 0.7190908 -0.6837192 0.218764 0.74898 -0.6254369 0.145455 0.807907 -0.5710772 0.2124738 0.8364667 -0.5051518 0.1663909 0.8811823 -0.4425291 0.2064302 0.9050397 -0.3718735 0.1823212 0.9356857 -0.3020783 0.2018863 0.9525129 -0.2279499 0.1914467 0.9694721 -0.1532062 0.1994448 0.9768983 -0.07675647 0.1942846 0.9809452 0 0.1995642 0.9768548 0.0769996 0.1915397 0.9694486 0.1532379 0.2022513 0.9523847 0.2281621 0.1825659 0.9356278 0.3021098 0.2069786 0.9048523 0.3720244 0.1667581 0.8810349 0.4426843 0.2132111 0.8362722 0.5051633 0.1461241 0.8076199 0.5713126 0.2197372 0.7489072 0.6251829 0.1251296 0.7186106 0.6840626 0.2241007 0.6441941 0.7312952 0.1159128 0.6148142 0.7801075 0.1111521 0.5094932 0.8532654 0.2251428 0.5315592 0.816551 0.1084664 0.3849733 0.9165319 0.2270982 0.4106446 0.8830614 0.1061779 0.2607907 0.9595388 0.234053 0.2970144 0.9257439 0.2761951 0.2150049 0.936744 0.1065108 0.1677926 0.9800516 0.1917228 0.1390157 0.971554 0.1128292 0.1011404 0.9884535 0.08865827 0.08505702 0.9924238 0.2413107 0.1706601 0.9553242 0.2060628 0.2224514 0.9529185 -0.01736569 -0.7751702 0.6315138 -0.04971516 -0.7829606 0.6200816 0.0696749 -0.8055799 0.5883761 -0.01721292 -0.8129153 0.5821275 -0.03671449 -0.7865089 0.6164867 -0.02087521 -0.8709297 0.4909642 -0.02157711 -0.8617736 0.506834 -0.07501709 -0.8586987 0.5069606 -0.07278805 -0.8325006 0.5492221 -0.05862611 -0.8660861 0.4964454 -0.07935082 -0.8310477 0.5505119 -0.02221816 -0.9409156 0.3379117 -0.0367757 -0.8791995 0.4750326 -0.08157747 -0.9068131 0.4135639 0.0272839 -0.9001859 0.4346504 -0.02292013 -0.9095726 0.4149125 -0.0635401 -0.9125732 0.4039468 -0.0180673 -0.9322683 0.3613162 -0.07681679 -0.9283326 0.3637276 -0.006592094 -0.9339477 0.357349 -0.01998972 -0.952366 0.3043017 -0.07175135 -0.9293801 0.3620834 -0.02105808 -0.9855192 0.1682512 -0.03076374 -0.9609398 0.2750425 -0.1038879 -0.9489082 0.2979606 -0.0896033 -0.9469999 0.3084845 -0.08640074 -0.9472652 0.308583 -0.1111191 -0.9494414 0.2936218 -0.02475106 -0.9688025 0.2465953 -0.09173917 -0.9487044 0.3025624 -0.02850508 -0.9818081 0.1877246 -0.1033388 -0.9754925 0.1942561 -0.106635 -0.9662767 0.2343894 -0.07464975 -0.9779854 0.1948646 -0.1270197 -0.9648244 0.2301735 -0.02035629 -0.9961785 0.084935 -0.0594511 -0.9828051 0.1748131 -0.1458513 -0.9852514 0.0894823 -0.04269665 -0.9847089 0.1688944 -0.03650045 -0.9923189 0.1181993 -0.08453744 -0.9901261 0.1118214 -0.02444547 -0.9972296 0.07025408 -0.2012146 -0.9774762 0.06366348 -0.07483166 -0.9937173 0.08322429 -0.01742655 -0.9989607 0.04211676 -0.1139888 -0.9921455 0.05151623 -0.0209667 -0.9840622 -0.1765843 -0.03756839 -0.9979889 -0.05105757 -0.01736527 -0.9958945 -0.08884066 -0.03961312 -0.997714 -0.05475032 -0.1713364 -0.9819649 -0.07993054 -0.1073343 -0.9931403 -0.04638844 -0.09497648 -0.9931941 -0.06741744 -0.2053329 -0.9772239 -0.05359166 -1 4.83423e-6 0 -1 -5.07351e-6 0 -1 -2.23489e-6 0 -1 2.56717e-6 0 -1 4.80173e-6 0 -1 -6.4866e-7 0 -1 2.38651e-6 0 -1 -1.29886e-6 0 -1 -2.35459e-6 0 -1 1.32132e-6 0 -1 4.21426e-7 0 -0.02743673 -0.9757607 -0.2171137 -0.02215683 -0.9375461 -0.3471545 -0.02743649 -0.9951307 -0.09466969 -0.02026444 -0.9909457 -0.1327263 -0.01751774 -0.9854215 -0.1692267 -0.01306241 -0.889589 -0.4565752 -0.02279788 -0.8606445 -0.5086958 -1 2.51941e-6 0 -0.03085452 -0.9683009 -0.2478738 -0.02551376 -0.9627187 -0.2692987 -0.015473 -0.9461437 -0.3233771 -0.0172435 -0.8163666 -0.5772767 -0.02227872 -0.7574156 -0.652553 -0.01889133 -0.6952261 -0.7185428 -0.02020341 -0.6295421 -0.7767038 -0.01785355 -0.7751214 -0.63156 -0.0170297 -0.7430832 -0.6689824 -1 2.40989e-6 0 -0.02365213 -0.6115692 -0.7908375 -0.01858592 -0.4835392 -0.8751255 -1 -1.24767e-6 0 -0.01797586 -0.6545784 -0.7557805 -0.02304202 -0.466762 -0.8840827 -0.01992905 -0.3221923 -0.9464645 -1 -2.26398e-6 0 -1 -1.24441e-6 0 -0.02438467 -0.5789762 -0.8149798 -0.02005106 -0.5438517 -0.8389418 -0.01782321 -0.5078102 -0.8612845 -0.01852512 -0.2643271 -0.9642552 -1 2.75889e-7 0 -0.02514731 -0.4348599 -0.900147 -0.02017343 -0.3906506 -0.920318 -0.01748722 -0.3298159 -0.9438833 -0.01907455 -0.2054561 -0.9784804 -9.15567e-5 -0.9961675 0.08746713 0 -0.9962048 0.08704048 3.05193e-5 -0.9848282 0.1735329 -3.05193e-5 -0.9848282 -0.1735329 1.22076e-4 -0.9846667 -0.1744469 9.15567e-5 -0.9961675 -0.08746713 0 -0.9962048 -0.08704048 -1.22076e-4 -0.9846667 0.1744469 1.22076e-4 -0.9397124 0.341966 -1.83116e-4 -0.939143 0.3435264 1.83116e-4 -0.8662018 0.4996943 -2.13633e-4 -0.8651824 0.5014573 2.13632e-4 -0.7664799 0.6422683 -1.83113e-4 -0.7651985 0.6437946 1.83116e-4 -0.6431964 0.7657012 -1.22077e-4 -0.6420347 0.7666756 1.22077e-4 -0.5001205 0.8659558 0 -0.4994679 0.8663325 6.1038e-5 -0.341721 0.9398014 -3.05189e-5 -0.1737748 0.9847854 9.1556e-5 -0.1731324 0.9848986 0 -0.3417847 0.9397783 -9.15583e-5 -4.27272e-4 1 9.15583e-5 4.27272e-4 1 -9.1556e-5 0.1731324 0.9848986 3.05189e-5 0.1737748 0.9847854 -6.1038e-5 0.341721 0.9398014 0 0.3417847 0.9397783 0 0.4994812 0.8663249 -1.22077e-4 0.5001205 0.8659558 1.22077e-4 0.6420347 0.7666756 -1.83116e-4 0.6431964 0.7657012 1.83113e-4 0.7651985 0.6437946 -2.13632e-4 0.7664799 0.6422683 2.13633e-4 0.8651824 0.5014573 -1.83116e-4 0.8662018 0.4996943 1.83116e-4 0.939143 0.3435264 -1.22076e-4 0.9397124 0.341966 1.22076e-4 0.9846667 0.1744469 -3.05193e-5 0.9848282 0.1735329 9.15567e-5 0.9961675 0.08746713 -9.15567e-5 0.9961675 -0.08746713 0 0.9962048 -0.08704048 3.05193e-5 0.9848282 -0.1735329 0 0.9962048 0.08704048 -1.22076e-4 0.9846667 -0.1744469 1.22076e-4 0.9397124 -0.341966 -1.83116e-4 0.939143 -0.3435264 1.83116e-4 0.8662018 -0.4996943 -2.13633e-4 0.8651824 -0.5014573 2.13632e-4 0.7664799 -0.6422683 -1.83113e-4 0.7651985 -0.6437946 1.83116e-4 0.6431964 -0.7657012 -1.22077e-4 0.6420347 -0.7666756 1.22077e-4 0.5001205 -0.8659558 0 0.4994812 -0.8663249 6.1038e-5 0.341721 -0.9398014 -3.05189e-5 0.1737748 -0.9847854 9.1556e-5 0.1731324 -0.9848986 0 0.3417847 -0.9397783 -9.15583e-5 4.27272e-4 -1 9.15583e-5 -4.27272e-4 -1 -9.1556e-5 -0.1731324 -0.9848986 3.05189e-5 -0.1737748 -0.9847854 -6.1038e-5 -0.341721 -0.9398014 0 -0.3417847 -0.9397783 0 -0.4994679 -0.8663325 -1.22077e-4 -0.5001205 -0.8659558 1.22077e-4 -0.6420347 -0.7666756 -1.83116e-4 -0.6431964 -0.7657012 1.83113e-4 -0.7651985 -0.6437946 -2.13632e-4 -0.7664799 -0.6422683 2.13633e-4 -0.8651824 -0.5014573 -1.83116e-4 -0.8662018 -0.4996943 1.83116e-4 -0.939143 -0.3435264 -1.22076e-4 -0.9397124 -0.341966 -0.1689218 -0.9725745 -0.1598882 -0.08853608 -0.9908655 -0.1017203 -0.09546279 -0.9839265 -0.1509155 -0.1573852 -0.9607613 -0.2284024 -0.0927155 -0.9771448 -0.1912906 -0.09665256 -0.9690588 -0.2271198 -0.1924506 -0.9412869 -0.2773841 -0.1087076 -0.9572193 -0.2681679 -0.1834193 -0.9223155 -0.3401345 -0.09912645 -0.9484159 -0.3011333 -0.09720194 -0.9447358 -0.313091 -0.1681004 -0.9289779 -0.3297613 -0.09454858 -0.9417322 -0.322802 -0.06909435 -0.8853172 -0.4598254 -0.07245266 -0.9225359 -0.3790491 -0.07895416 -0.8845491 -0.4597164 -0.06607443 -0.9259881 -0.3717259 -0.07724493 -0.8396535 -0.5376016 -0.08383756 -0.8353544 -0.543281 -0.1024538 -0.7165665 -0.6899535 -0.05874824 -0.7900043 -0.6102803 -0.07962554 -0.7523686 -0.6539124 -0.04901325 -0.7999606 -0.5980477 -0.06689816 -0.7286164 -0.6816473 -0.1199096 -0.6885724 -0.7151851 -0.07544207 -0.7026919 -0.7074833 -0.1209475 -0.6617473 -0.7399069 -0.04986846 -0.6635808 -0.7464407 -0.09778308 -0.6358038 -0.7656318 -0.1818003 -0.581047 -0.7933051 -0.09464067 -0.591161 -0.8009819 -0.1740521 -0.619086 -0.7657927 -0.1709071 -0.5292629 -0.8310666 -0.09189438 -0.5537469 -0.8275989 -0.08694988 -0.5272234 -0.8452665 -0.1614143 -0.4785358 -0.8631042 -0.08240157 -0.4870849 -0.8694587 -0.08102852 -0.4628849 -0.8827072 -0.1523838 -0.4256552 -0.8919624 -0.07553493 -0.4209204 -0.9039472 -0.07761079 -0.3916553 -0.916833 -0.1457874 -0.3702518 -0.9174201 -0.07812881 -0.3311929 -0.9403229 -0.1378231 -0.315809 -0.9387596 -0.07355177 -0.2708597 -0.9598048 -0.1313232 -0.2628601 -0.9558551 -0.0702247 -0.2139092 -0.9743262 -0.1236006 -0.2087477 -0.9701275 -0.06881988 -0.1618411 -0.9844142 -0.07825052 -0.1459721 -0.9861891 -0.06482309 -0.1083132 -0.9920012 -0.06338775 -0.08810806 -0.9940921 -0.04019385 -0.03802698 -0.9984681 -0.0406515 -0.03241133 -0.9986476 -0.6842456 -0.6343159 -0.3597936 -0.6504917 -0.6440216 -0.4026126 -0.7124089 -0.5681753 -0.4118866 -0.6702342 -0.5494693 -0.4988684 -0.6764005 -0.5561848 -0.4828467 -0.6092561 -0.6269268 -0.4855615 -0.7316123 -0.5679669 -0.3770372 -0.7841563 -0.5164433 -0.3440717 -0.7697028 -0.5072958 -0.3875676 -0.755687 -0.5000883 -0.4229052 -0.7631645 -0.5006073 -0.4086223 -0.7211903 -0.4727976 -0.5063073 -0.7321231 -0.4787229 -0.4845826 -0.727068 -0.4767768 -0.4940204 -0.5727028 -0.7451393 -0.3417295 -0.5170297 -0.7713175 -0.3711467 -0.6137235 -0.618973 -0.4901182 -0.4781125 -0.7552566 -0.4483258 -0.665777 -0.5450124 -0.5096101 -0.4454905 -0.8380911 -0.3148678 -0.3662275 -0.8707364 -0.3281703 -0.4859381 -0.7453269 -0.4564559 -0.3325335 -0.8538566 -0.400438 -0.3067464 -0.9095575 -0.2803779 -0.3459324 -0.845711 -0.4063295 -0.3208773 -0.9281452 -0.1886382 -0.4637072 -0.8600586 -0.2127791 -0.5947182 -0.7698957 -0.2314539 -0.7109755 -0.6595507 -0.2439401 -0.7525428 -0.5724489 -0.3255485 -0.792035 -0.5194373 -0.3207265 -0.7653233 -0.5950276 -0.2454027 -0.8091601 -0.5313423 -0.2508692 -0.3272547 -0.9401667 -0.09482234 -0.4758549 -0.8728177 -0.108404 -0.6123933 -0.7816208 -0.1185051 -0.7338956 -0.6670585 -0.1281807 -0.7788148 -0.6001259 -0.1824732 -0.8207126 -0.5437542 -0.1753917 -0.8223965 -0.5397902 -0.179696 -0.7796517 -0.6164944 -0.1099008 -0.8310895 -0.5459213 -0.106114 -0.3917723 -0.9177673 -0.06494438 -0.5616664 -0.8243104 -0.07101702 -0.7137684 -0.6968001 -0.07074201 -0.7764455 -0.6270527 -0.06274795 -0.8349127 -0.5503826 -3.05192e-5 -0.8359283 -0.5487401 0.01040709 -0.7481198 -0.6489626 0.1384356 -0.7100636 -0.6978558 0.09384703 -0.7805848 -0.6181626 0.09253364 -0.823194 -0.5404338 0.1740204 -0.8243286 -0.5409561 0.16688 -0.7772563 -0.6063808 0.1678541 -0.3330261 -0.9408782 0.06198459 -0.3900322 -0.917186 0.08151608 -0.4821361 -0.8732652 0.07037633 -0.5606437 -0.8230811 0.09064298 -0.6188945 -0.7816216 0.07770133 -0.7643855 -0.5002108 -0.4068218 -0.7332035 -0.4792802 -0.4823932 -0.8106504 -0.5169948 -0.2748862 -0.8004472 -0.5032551 -0.3256051 -0.7688359 -0.491906 -0.4085585 -0.7314013 -0.4783026 -0.4860851 -0.7344546 -0.4716501 -0.4879781 -0.7342345 -0.47247 -0.4875161 0.7599297 0.4060589 0.5075659 -0.7364855 -0.4716718 -0.4848865 -0.7707744 -0.4912142 -0.4057285 -0.7365682 -0.4717162 -0.4847177 -0.7858969 -0.5154979 0.3415086 -0.790355 -0.5184597 0.3264026 -0.7435648 -0.5853849 0.3231656 -0.7430887 -0.5856997 0.3236898 -0.7634955 -0.4997802 0.4090165 -0.7637842 -0.5012239 0.4067045 -0.7187466 -0.5730502 0.3937221 -0.7153808 -0.5748072 0.3972744 -0.7641654 -0.5008473 0.4064521 -0.7311839 -0.4785137 0.4862046 -0.728204 -0.476995 0.4921329 -0.7604766 -0.4990189 0.4155185 -0.7260785 -0.4751509 0.497033 -0.7235496 -0.473353 0.5024073 -0.7280694 -0.4769257 0.492399 -0.6669731 -0.5502361 0.5023815 -0.6789903 -0.5491008 0.4872995 -0.6827456 -0.5486746 0.4825089 -0.6651138 -0.5503906 0.5046722 -0.7330466 -0.479308 0.482604 -0.7689124 -0.4750385 0.4279162 -0.7693218 -0.490409 0.4094423 -0.8021596 -0.5018838 0.3235006 -0.7365573 -0.4717092 0.484741 -0.7341746 -0.4725623 0.4875168 -0.7366433 -0.4717667 0.4845542 -0.7344194 -0.4717082 0.4879751 0.7611185 0.4023652 -0.5087246 -0.8041436 -0.512535 0.3010998 -0.8376837 -0.5207751 0.1645581 -0.7747631 -0.4896212 0.4000166 -0.8380494 -0.5360342 0.101689 -0.8495815 -0.5274559 -0.001220703 -0.8379633 -0.5359767 -0.1026968 -0.8374076 -0.52053 -0.1667246 -0.6946158 -0.4564443 -0.5560284 -0.6468797 -0.4254648 -0.6328715 -0.69499 -0.4560528 -0.5558821 -0.6716924 -0.4568998 -0.5831569 -0.6928892 -0.4554763 -0.5589687 -0.6934207 -0.455434 -0.5583439 -0.7097252 -0.4381649 -0.5516355 -0.7194552 -0.4596773 -0.5206544 -0.7122647 -0.4492474 -0.5393105 -0.6892456 -0.4565061 -0.5626214 -0.7051187 -0.4389595 -0.5568863 -0.7017252 -0.450309 -0.5520902 -0.6949885 -0.4497343 -0.5610082 -0.643499 -0.3597002 -0.6756663 -0.713783 -0.4678899 -0.5211459 -0.6926967 -0.4559279 -0.558839 -0.7108177 -0.4661164 -0.5267577 -0.7047598 -0.4627084 -0.5377868 -0.7025198 -0.4613882 -0.5418366 -0.7007582 -0.4603561 -0.5449866 -0.6986554 -0.4590152 -0.548804 -0.696214 -0.4575199 -0.553138 -0.63928 -0.523247 -0.5635015 -0.6643137 -0.457759 -0.5908843 -0.6370533 -0.53277 -0.5570631 -0.7262942 -0.4754575 -0.4964241 -0.7184044 -0.4707061 -0.5121824 -0.7866577 -0.4858319 -0.3809686 -0.7275612 -0.4660677 -0.5034239 -0.7267867 -0.4603837 -0.5097334 -0.7373213 -0.4630423 -0.4918833 -0.7208908 -0.4526892 -0.5247753 -0.7421062 -0.4655407 -0.4822347 -0.8455225 -0.5300499 0.06433355 -0.7147064 -0.4579456 -0.5286594 -0.7222005 -0.4572654 -0.5189749 -0.656163 -0.4190592 -0.6275665 -0.7144996 -0.448031 -0.5373625 -0.7246239 -0.4577006 -0.5151993 -0.7097762 -0.4436826 -0.5471414 -0.7120442 -0.4459165 -0.5423573 -0.7233355 -0.4583678 -0.5164153 -0.7122915 -0.4462237 -0.5417798 -0.7216579 -0.4589788 -0.5182166 -0.7101863 -0.4441792 -0.5462055 -0.7189118 -0.4585825 -0.5223677 -0.6775885 -0.4590096 -0.5746166 -0.6969765 -0.4383533 -0.5675123 -0.6859679 -0.4488685 -0.5726826 -0.665798 -0.4590331 -0.5882192 -0.686994 -0.4336211 -0.5831056 -0.6754194 -0.4471971 -0.5863645 -0.6561405 -0.4569087 -0.6005948 -0.6755946 -0.4280261 -0.6003047 -0.6636385 -0.4447247 -0.6015015 -0.6478577 -0.4544892 -0.6113265 -0.6408466 -0.4549223 -0.6183537 -0.6630939 -0.4224183 -0.6179558 -0.6538158 -0.440333 -0.6153308 -0.6302635 -0.4460157 -0.6354824 -0.6257989 -0.4525712 -0.6352599 -0.6416703 -0.4352676 -0.6315073 -0.6287575 -0.4306876 -0.6474353 -0.6495152 -0.4156751 -0.6366665 -0.6300675 -0.4312048 -0.6458154 -0.6614171 -0.3815234 -0.6457301 -0.6361206 -0.4074675 -0.6552258 -0.6179215 -0.4265664 -0.6604653 -0.6648243 -0.3763594 -0.6452616 -0.6221314 -0.3987317 -0.6737697 -0.6041061 -0.4201641 -0.6771396 -0.6142873 -0.5085694 -0.603331 -0.5831362 -0.4869997 -0.650218 -0.6092879 -0.4543413 -0.6498787 -0.607638 -0.3891202 -0.6923594 -0.5899736 -0.4127465 -0.6939537 -0.5465373 -0.4648069 -0.6966 -0.5612806 -0.4371281 -0.7027682 -0.5499871 -0.4672494 -0.6922371 -0.5771849 -0.4958809 -0.6488142 -0.6175894 -0.5079944 -0.6004375 -0.4323679 -0.2666172 -0.8613787 -0.4093286 -0.2971691 -0.8626359 -0.4616276 -0.2433875 -0.8530314 -0.4517837 -0.2811173 -0.8466786 -0.4290677 -0.3120271 -0.8476675 -0.4791884 -0.256151 -0.8395029 -0.4708581 -0.2952782 -0.8313264 -0.4483847 -0.3261258 -0.8322218 -0.495655 -0.2680767 -0.826112 -0.4895556 -0.3089441 -0.8154072 -0.4672731 -0.3394604 -0.816347 -0.5249005 -0.2901464 -0.8001841 -0.5079274 -0.3220668 -0.7989259 -0.4856792 -0.3520365 -0.8001164 -0.5107995 -0.2793115 -0.8130614 -0.5382641 -0.3003988 -0.7874214 -0.5257803 -0.3348843 -0.7819257 -0.5035685 -0.3637595 -0.783644 -0.5630143 -0.3182825 -0.7627 -0.5429046 -0.3469414 -0.7647787 -0.5209978 -0.3747485 -0.7668931 -0.5514547 -0.3097106 -0.7745819 -0.5740337 -0.3274089 -0.7505257 -0.5598744 -0.3585394 -0.7469875 -0.5376653 -0.3847311 -0.7502654 -0.5944196 -0.3423628 -0.7276353 -0.5762042 -0.369375 -0.7290753 -0.5522128 -0.3925368 -0.7355107 -0.5850877 -0.3353473 -0.7383866 -0.603423 -0.3501452 -0.7164351 -0.5926562 -0.3794782 -0.7104611 -0.5638735 -0.3980929 -0.7235805 -0.6198999 -0.3627477 -0.6958004 -0.6121535 -0.3567996 -0.7056643 -0.5725705 -0.4027922 -0.714088 -0.5793167 -0.4067913 -0.7063378 -0.6286104 -0.3702322 -0.6839423 -0.6401642 -0.3795939 -0.6679059 -0.6526855 -0.3893346 -0.6499388 -0.6742644 -0.4054193 -0.6172542 -0.6642959 -0.3978878 -0.6327689 -0.6833918 -0.413142 -0.6019048 -0.6920531 -0.4201882 -0.5869451 -0.7000895 -0.4261149 -0.5729753 -0.7100681 -0.4325537 -0.5556085 -0.7067242 -0.4308341 -0.5611799 -0.7128028 -0.4349269 -0.5502279 -0.7381969 -0.4309607 -0.518978 -0.7129313 -0.4307802 -0.5533152 -0.7068769 -0.4286673 -0.562645 -0.7158365 -0.4320045 -0.5485893 -0.6989569 -0.4265401 -0.5740407 -0.7007158 -0.4142341 -0.5808678 -0.7259319 -0.4140552 -0.5491641 -0.6923953 -0.3977298 -0.6019966 -0.6814584 -0.3929319 -0.6174296 -0.668983 -0.3891821 -0.6332449 -0.6658427 -0.3758469 -0.6445096 -0.6927207 -0.3753839 -0.6158127 -0.6520712 -0.3573787 -0.6686431 -0.6378256 -0.3524689 -0.684795 -0.6264936 -0.3499611 -0.6964432 -0.6160026 -0.3485004 -0.7064619 -0.6190177 -0.3340614 -0.7107885 -0.6573852 -0.3367192 -0.6741402 -0.6079391 -0.3174589 -0.7277568 -0.595938 -0.313915 -0.7391316 -0.5822438 -0.3113256 -0.7510451 -0.5816419 -0.297169 -0.7572209 -0.6126981 -0.3018323 -0.7304097 -0.5673137 -0.2810781 -0.774048 -0.5512951 -0.2767156 -0.7870848 -0.5464105 -0.2638664 -0.7948649 -0.5670415 -0.2690548 -0.7785072 -0.5300347 -0.2482773 -0.8108154 -0.5170807 -0.2380164 -0.8221775 -0.5353928 -0.2448835 -0.8083233 -0.5022201 -0.2244974 -0.8350905 -0.5080794 -0.2271525 -0.8308172 -0.4812954 -0.2135157 -0.8501563 -0.384662 -0.3274693 -0.8630174 -0.3850028 -0.327199 -0.8629679 -0.4041618 -0.3423305 -0.8482118 -0.3700467 -0.3178586 -0.8729441 -0.414144 -0.347887 -0.8411061 -0.4234493 -0.356491 -0.8328295 -0.3974784 -0.3369899 -0.8534922 -0.4318721 -0.3594509 -0.8272132 -0.4424672 -0.3693737 -0.8171817 -0.4510388 -0.3715981 -0.8114671 -0.4616593 -0.3806316 -0.801243 -0.4708822 -0.3845126 -0.79399 -0.4833673 -0.389642 -0.783923 -0.4886428 -0.3986722 -0.7760726 -0.5106173 -0.3959261 -0.7632251 -0.5181244 -0.3940333 -0.7591344 -0.47168 -0.4911515 -0.7323172 -0.4954796 -0.4470762 -0.7447301 -0.5143447 -0.4211382 -0.7470557 -0.344139 -0.4967066 -0.7967754 -0.4190626 -0.449582 -0.7888363 -0.461153 -0.4577654 -0.7601243 -0.4536982 -0.4678591 -0.7584628 -0.4532405 -0.4879408 -0.7459806 -0.5022211 -0.4498809 -0.7384993 -0.5183054 -0.4675521 -0.716069 -0.584782 -0.3976982 -0.7070122 -0.2611824 -0.3275005 -0.9080349 -0.3153263 -0.3234139 -0.8921731 -0.3279543 -0.3393073 -0.8816556 -0.2755889 -0.3617448 -0.890613 -0.3420923 -0.3572605 -0.8691018 -0.2909991 -0.3951912 -0.8712884 -0.352163 -0.3714817 -0.8590592 -0.3673649 -0.390865 -0.8439595 -0.3082088 -0.4296734 -0.8487569 -0.3841535 -0.4106752 -0.8269051 -0.3250608 -0.4629468 -0.8246307 -0.4017859 -0.4305961 -0.8081802 -0.273149 -0.2873405 -0.9180551 -0.1966062 -0.1949582 -0.9609045 -0.1941637 -0.2549581 -0.9472576 -0.1217387 -0.1060522 -0.9868803 -0.1666325 -0.1789621 -0.9696424 -0.1725578 -0.2068008 -0.9630459 -0.09918671 -0.09466993 -0.9905552 -0.1394432 -0.1714276 -0.9752786 -0.3484975 -0.5223953 -0.7782369 -0.3764257 -0.5476698 -0.7472359 -0.2857213 -0.5686347 -0.7713741 -0.337729 -0.5680903 -0.7504749 -0.2943273 -0.6022052 -0.7421053 -0.1659047 -0.2124471 -0.962986 -0.1232373 -0.1452723 -0.9816866 -0.1548528 -0.2092374 -0.9655259 -0.08157813 -0.07672554 -0.9937093 -0.1026359 -0.1215577 -0.9872637 -0.06705069 -0.06216758 -0.995811 -0.08853441 -0.1056859 -0.9904506 -0.05310231 -0.04596096 -0.9975309 -0.06802725 -0.07574862 -0.9948037 -0.2264258 -0.6360005 -0.7377227 -0.2084175 -0.6494238 -0.7313076 -0.04208594 -0.02841335 -0.99871 -0.05325639 -0.05148625 -0.9972528 -0.03244125 -0.01010161 -0.9994227 -0.03994989 -0.02575838 -0.9988697 -0.06253325 -0.02749752 -0.997664 -0.01743537 0.0285719 -0.9994398 -0.05401808 -0.02462857 -0.9982362 -0.01748436 0.02855932 -0.9994392 -0.04471087 -0.0179454 -0.9988388 -0.01745754 0.02858161 -0.9994391 -0.03839254 -0.009827017 -0.9992144 -0.0335403 -0.002227842 -0.999435 -0.02896219 0.002349913 -0.9995778 -0.02584916 0.007873773 -0.9996349 -0.02368235 0.01306188 -0.9996343 0.1926053 0.1348329 -0.9719688 0.1148756 0.09235215 -0.9890777 0.08926838 0.08264571 -0.9925729 0.2494644 0.1496664 -0.9567484 0.1220149 0.09122127 -0.9883275 0.116187 0.0917716 -0.9889786 0.244458 0.1551285 -0.9571706 0.191294 0.139442 -0.9715774 0.1004076 0.08905452 -0.9909529 0.1203674 -0.002746701 -0.9927257 0.2565422 -0.03253316 -0.9659854 0.1204879 -0.002014219 -0.9927128 0.1257393 -0.002960324 -0.9920589 0.2582837 -0.03119057 -0.9655655 0.1295841 -0.002288877 -0.9915658 0.2607241 -0.02887099 -0.9649816 0.1317798 -0.001190185 -0.9912784 0.2638397 -0.02667391 -0.9641978 0.1324216 2.13632e-4 -0.9911935 0.2675934 -0.02450698 -0.9632203 0.1320575 0.001922667 -0.9912402 0.1294601 0.002349913 -0.9915819 0.2753098 -0.01620543 -0.961219 0.1297372 0.004272639 -0.9915393 0.1352888 0.006439387 -0.9907853 0.2716206 -0.02353024 -0.9621168 0.2780301 -0.004455804 -0.9605621 0.1346198 0.01574784 -0.9907723 0.1341292 0.02032536 -0.9907555 0.2815381 0.02542233 -0.9592133 0.1391983 0.03662312 -0.9895871 0.2795228 0.06988829 -0.9575921 0.1285174 0.04934996 -0.9904786 0.1346807 0.06402903 -0.9888182 0.2673767 0.1124013 -0.9570139 0.1251908 0.07822138 -0.9890443 0.124001 0.08228075 -0.9888648 0.2552341 0.1393517 -0.9567846 0.6819731 0.3614342 -0.6358287 0.7716958 0.4067227 -0.4889401 0.7580175 0.3962066 -0.5181022 0.8288423 0.4340755 -0.3529859 0.8367233 0.428311 -0.3412388 0.01812809 -0.02963364 0.9993965 0.7030475 0.3137406 -0.6381936 0.692824 0.3388279 -0.636546 0.7706136 0.369925 -0.5189511 0.8292168 0.4316078 -0.3551257 0.05237007 -0.01309251 0.998542 0.8508144 0.3994354 -0.3414183 0.8685263 0.3661434 -0.3340674 0.8797163 0.3723955 -0.2956702 0.7762968 0.3572626 -0.5193523 0.8309462 0.4285506 -0.3547856 0.8437933 0.4276037 -0.3242964 0.851229 0.4327864 -0.2968254 0.8650285 0.40639 -0.294233 0.8369805 0.4268372 -0.3424524 0.7130591 0.3833563 -0.5870133 0.7585856 0.4122536 -0.5045742 0.5676695 0.3183527 -0.7592121 0.7081143 0.3991345 -0.5824653 0.7649427 0.424863 -0.4841015 0.7263908 0.4047169 -0.5554825 0.4842763 0.2692086 -0.8324682 0.3904656 0.2329853 -0.8906484 0.564814 0.3298182 -0.7564424 0.3888487 0.2407987 -0.8892765 0.4923006 0.2546498 -0.8323423 0.5010419 0.2361614 -0.8325773 0.6739172 0.3947002 -0.6245377 0.7481588 0.4304492 -0.5049477 0.6573025 0.4454042 -0.6079216 0.7389237 0.4466136 -0.504508 0.6564015 0.4169498 -0.6287208 0.7221803 0.4208013 -0.5489827 0.8315815 0.4724645 -0.2919752 0.8135193 0.4623656 -0.3527102 0.8506146 0.4790067 -0.216812 0.731867 0.4424589 -0.5182672 0.478782 0.2961258 -0.8264849 0.4616676 0.3844229 -0.7994262 0.453274 0.3307996 -0.8277164 0.8205713 0.4453675 -0.3582046 0.8203105 0.4550803 -0.3463994 0.8220686 0.4426218 -0.3581748 0.828742 0.4716092 -0.301283 0.8298432 0.4718243 -0.2978963 0.8315758 0.4720035 -0.2927362 0.8136433 0.4824483 -0.3243891 0.8113289 0.4635904 -0.3561314 0.8160275 0.4518701 -0.360434 0.8239641 0.4394801 -0.3576879 0.7585833 -0.0940904 -0.644747 0.8444745 -0.09635001 -0.5268582 0.8426308 -0.1094718 -0.527247 0.9304199 -0.1144484 -0.3481673 0.9196919 -0.1248229 -0.3722715 0.9309697 -0.1043159 -0.3498766 0.838521 -0.1343464 -0.528047 0.7539535 -0.1166149 -0.6464944 0.8384261 -0.134468 -0.5281669 0.9242511 -0.1536349 -0.3495088 0.9158508 -0.1507343 -0.3721511 0.9161151 -0.1485963 -0.3723606 0.7616309 -0.0661956 -0.6446213 0.84674 -0.06210541 -0.5283694 0.9347673 -0.07794559 -0.3466046 0.765713 0.01263469 -0.6430585 0.8502236 -0.02050864 -0.5260222 0.950708 -0.08713269 -0.2975941 0.94362 -0.02139383 -0.3303387 0.8479477 0.03842377 -0.5286855 0.9409081 0.02475106 -0.3377564 0.7582696 0.1287892 -0.6390938 0.8411446 0.1353839 -0.5235905 0.9542225 0.008789598 -0.2989689 0.9274299 0.142496 -0.3457872 0.8173432 0.2315821 -0.5275604 0.9433964 0.1458797 -0.2978633 0.9031712 0.2752179 -0.3294497 0.01852518 -0.02652126 0.9994767 0.7298737 0.2414091 -0.6395359 0.804636 0.2866659 -0.5199843 0.9130595 0.2796736 -0.2968252 0.7873632 0.3257918 -0.5233727 0.522092 0.1838477 -0.8328385 0.5423533 0.1037646 -0.8337182 0.5482757 0.02075296 -0.8360402 0.5437571 -0.03650069 -0.8384486 0.5404058 -0.05710166 -0.8394647 0.747631 -0.1202154 -0.6531433 0.5363398 -0.0734896 -0.8407967 0.8240712 -0.1322383 -0.5508356 0.5313017 -0.07547295 -0.8438142 0.01818907 -0.02969461 0.9993936 0.9194598 -0.1574499 -0.3602822 0.8114448 -0.1381299 -0.567871 0.7410019 -0.1264708 -0.6594856 0.8326599 -0.1392903 -0.5359811 0.8030894 -0.1448759 -0.5779778 0.7343549 -0.1326063 -0.6656866 0.5257582 -0.08011347 -0.8468531 0.8261752 -0.1460631 -0.5441508 0.7992725 -0.152597 -0.5812725 0.7276455 -0.13865 -0.6717948 0.5202 -0.08466029 -0.8498381 0.8196323 -0.1527197 -0.5521592 0.8070594 -0.1633712 -0.5674197 0.7218451 -0.1419152 -0.6773478 0.5145848 -0.08908563 -0.8527991 0.7985029 -0.1613852 -0.5799553 0.8130127 -0.159282 -0.5600354 0.7201961 -0.1475611 -0.6778963 0.7204122 -0.1478974 -0.6775934 0.8052783 -0.1693202 -0.5682055 0.5095135 -0.09079378 -0.8556592 0.5086035 -0.09485381 -0.8557601 0.897926 -0.1778029 -0.4026353 0.8821045 -0.1830863 -0.4340175 0.01742643 -0.02954256 0.9994117 0.8873242 -0.1837884 -0.4229394 0.8806083 -0.1900141 -0.4340782 0.8806964 -0.1884874 -0.4345648 0.8857261 -0.1901341 -0.4234834 0.8045249 -0.1684677 -0.5695247 0.9080628 -0.1739584 -0.3809994 0.01767051 -0.0295729 0.9994065 0.9030077 -0.1721904 -0.3936086 0.9009448 -0.1659306 -0.4009557 0.8928588 -0.1825026 -0.4116989 0.897324 -0.1759734 -0.4047755 0.9090614 -0.1659969 -0.3821684 0.01782298 -0.02963382 0.9994019 0.9210604 -0.1675182 -0.3515472 0.9251108 -0.1774047 -0.3357048 0.01812803 -0.02969461 0.9993947 0.9361102 -0.1598587 -0.3132779 0.508449 -0.09488403 -0.8558485 0.9714447 -0.1870499 0.1459715 0.9672726 -0.1887912 0.1695336 0.9778575 -0.1901025 0.08749777 -0.1870489 -0.7975094 -0.5735778 0.9806527 -0.1891845 0.05029457 0.9808248 -0.1900123 0.04333716 -0.2101542 -0.9090101 -0.3599112 -0.2087808 -0.893842 -0.3968087 -0.1957513 -0.8525592 -0.4845868 -0.2016408 -0.8597279 -0.4692643 0.95252 -0.1837532 0.2427765 0.9480502 -0.1855875 0.258376 -0.1870524 -0.7975086 -0.573578 0.9285751 -0.1823518 0.3232586 -0.1870551 -0.7975091 -0.5735762 0.9250068 -0.1775302 0.3359249 0.9165928 -0.1763113 0.3588485 -0.165444 -0.7341063 -0.6585715 -0.1739881 -0.7417614 -0.6477022 -0.1633055 -0.69076 -0.7044019 -0.1870636 -0.7975091 -0.5735735 0.907956 -0.1739003 0.3812804 0.9118555 -0.1750281 0.3713282 -0.1445702 -0.6541217 -0.7424448 -0.1201542 -0.5734563 -0.810377 0.903196 -0.1723135 0.3931225 -0.107276 -0.5111407 -0.8527761 0.9051309 -0.1768267 0.386614 0.897114 -0.1780799 0.4043194 0.9009392 -0.1659352 0.4009668 -0.09888076 -0.4762147 -0.8737519 -0.09372478 -0.3863134 -0.9175935 0.727707 -0.1395046 0.6715512 0.8123924 -0.1611722 0.5603948 0.759099 -0.1398685 0.6357717 0.8973302 -0.1760051 0.4047477 0.8940204 -0.1813432 0.4096856 0.8866196 -0.1843068 0.4241894 0.8918249 -0.1843039 0.4131351 0.887375 -0.1836948 0.4228734 0.8818613 -0.1830255 0.4345368 0.7218815 -0.1417027 0.6773533 0.8066822 -0.1630333 0.568053 0.8189234 -0.1531151 0.5531006 0.9081375 -0.167674 0.3836298 0.7347754 -0.1329102 0.6651617 0.8258458 -0.147224 0.544338 0.9431395 -0.1713356 0.2848371 0.9210699 -0.1681609 0.3512151 0.9569201 -0.1819537 0.2262671 0.9522793 -0.1731638 0.2513531 0.9491842 -0.1749067 0.2616429 0.9547276 -0.178689 0.2378349 0.9708929 -0.1903149 0.1454218 0.9074588 -0.2248046 0.3549386 0.9579618 -0.1925445 0.2126871 0.9662902 -0.1862264 0.1777727 0.9820275 -0.1845211 -0.03967541 0.9805502 -0.1898597 -0.04974621 0.9822459 -0.1875987 0 0.9849753 -0.1699612 -0.03061068 0.9833883 -0.1814974 -0.002533078 0.9819881 -0.187724 0.02142453 0.9685748 -0.2105796 0.13236 0.9801414 -0.1873853 0.06488293 0.9778575 -0.1901025 -0.08749777 0.9710201 -0.1886984 -0.1466738 0.9796696 -0.1891891 -0.06674569 0.9481376 -0.1853121 -0.2582528 0.9523901 -0.1843375 -0.2428433 0.9649847 -0.1887303 -0.1821687 0.9672501 -0.1879687 -0.1705726 0.9753079 -0.1893422 -0.1136847 0.9714316 -0.184398 -0.1493923 0.9285751 -0.1823518 -0.3232586 0.9431445 -0.171306 -0.2848386 0.9618797 -0.1872059 -0.1993526 0.959424 -0.1829611 -0.2145481 0.9571315 -0.1806104 -0.2264497 0.9546954 -0.1786582 -0.2379871 0.9491767 -0.1749053 -0.2616713 0.9522867 -0.1731652 -0.2513245 0.9123166 -0.1780807 -0.3687354 0.917986 -0.1801241 -0.3533509 -0.09726566 -0.475555 0.8742923 -0.1163372 -0.5005066 0.8578805 -0.1325739 -0.57525 0.8071628 -0.09375321 -0.3864269 0.9175427 -0.1471329 -0.6562843 0.740029 -0.158974 -0.6954695 0.7007493 -0.166086 -0.7402762 0.6514651 -0.1870628 -0.7975059 0.5735782 -0.1710283 -0.7291594 0.6626281 -0.1870648 -0.7975039 0.5735803 -0.1870675 -0.7975042 0.573579 -0.1979489 -0.8593656 0.4714944 -0.1993832 -0.8501483 0.4873337 -0.2109487 -0.8938463 0.3956509 -0.1870494 -0.7975121 0.573574 -0.2086605 -0.909811 0.3587544 -0.2267855 -0.9527982 0.2018516 -0.2208061 -0.9676708 0.1218935 -0.232095 -0.9726932 1.83112e-4 -0.2208061 -0.9676708 -0.1218935 -0.2267862 -0.9528625 -0.2015471 -0.05411005 -0.2656978 -0.9625367 -0.04657268 -0.2183364 -0.9747617 -0.02380514 -0.1485685 -0.9886155 -0.01195234 -0.05095368 -0.9986296 -0.03766059 -0.1606833 -0.9862874 -0.01194959 -0.05095332 -0.9986296 0.890513 -0.1920558 0.4124333 0.8911596 -0.1902869 0.4118561 0.8854964 -0.1913886 0.4233988 -0.007416009 -0.03103756 -0.9994907 -0.008575737 -0.03866726 -0.9992154 -0.009582817 -0.04092532 -0.9991163 -0.01195025 -0.0509532 -0.9986295 0.8850439 -0.1917865 0.4241643 0.8806059 -0.1896778 0.4342296 0.8901137 -0.1931845 0.4127678 0.8802531 -0.1907728 0.4344654 0.7203446 -0.147835 0.6776788 0.8036328 -0.1709688 0.5700385 0.8054017 -0.1688322 0.568176 0.9121718 -0.1609302 0.3768873 0.7410616 -0.1270809 0.6593013 0.8008587 -0.1340715 0.5836524 0.9360716 -0.1594911 0.3135803 0.9193451 -0.1565303 0.3609751 0.9499592 -0.1651983 0.2651169 0.984302 -0.1744471 0.02679574 0.9780938 -0.1767337 0.1099894 0.9781532 -0.1769165 0.1091652 0.9840431 -0.173651 0.03878915 0.9773409 -0.1705707 0.1253415 0.9870132 -0.1602244 0.01153612 0.9787864 -0.1733194 0.1092593 0.978597 -0.1698697 0.1161559 0.9843562 -0.176155 0.00350964 0.9904168 -0.1378563 0.00839281 0.9821779 -0.1555272 0.1055364 0.9953722 -0.09607332 0.002014219 0.9860034 -0.135107 0.09769088 0.9988617 -0.04770141 -3.05192e-5 0.9897131 -0.1114568 0.08969646 0.9999898 -0.001648008 0.004211604 0.9926844 -0.08807718 0.08258378 0.9991381 0.03906458 0.0140388 0.9945929 -0.06799691 0.07849556 0.9974176 0.06619542 0.02786368 0.995543 -0.0543245 0.07709199 0.9973035 0.06625694 0.03155672 0.9963464 -0.05938953 0.06137323 0.9975068 -0.05755841 0.04083412 0.9977951 0.06286954 0.02127188 0.9982853 -0.05853593 -9.15578e-5 0.9977925 0.06286936 -0.02139389 0.9975154 -0.05725371 -0.0410481 0.9980753 0.06201535 3.05194e-5 0.9963982 -0.05914664 -0.06076413 0.9977504 0.06204462 -0.02539157 0.9955397 -0.05438536 -0.07709175 0.9945736 -0.06820923 -0.0785551 0.9973275 0.06601238 -0.03131234 0.9991332 0.03903388 -0.01446598 0.9926841 -0.08813822 -0.08252274 0.9999986 -0.00125128 -0.001220762 0.9896943 -0.1116988 -0.08960318 0.9988442 -0.04797524 0.002929747 0.9859488 -0.1355046 -0.09769147 0.9953914 -0.09589207 9.76622e-4 0.9821238 -0.1558287 -0.1055948 0.9905609 -0.1370311 -0.003418147 0.9772233 -0.1728299 -0.1231448 0.9790358 -0.1702684 -0.111793 0.9844115 -0.1758488 -0.003357052 0.9781486 -0.1769213 -0.1091986 0.978086 -0.1767379 -0.110053 0.9864435 -0.1640105 -0.005462944 0.9498007 -0.1650195 -0.2657952 0.9842725 -0.1746915 -0.02627694 0.9773133 -0.1705713 -0.1255556 0.9500965 -0.1618133 -0.2667082 0.8325645 -0.1382216 0.5364059 0.9297146 -0.1495759 0.3365382 0.7481809 -0.1199409 0.6525639 0.8383966 -0.1345292 0.5281981 0.9501273 -0.1617829 0.2666167 0.9446538 -0.1551279 0.2890757 0.9172307 -0.1550692 0.366935 0.9237944 -0.1551916 0.350028 0.9837 -0.171122 0.05524003 0.9775839 -0.1673355 0.127783 0.9502172 -0.159219 0.2678371 0.9834421 -0.1688917 0.06570726 0.9759145 -0.1663604 0.141121 0.7539752 -0.1171935 0.6463647 0.8385287 -0.1337983 0.5281739 0.9306387 -0.1050455 0.3505384 0.919731 -0.1252514 0.3720308 0.9305461 -0.1146588 0.3477607 0.758463 -0.09421271 0.6448705 0.8425909 -0.1098063 0.5272412 0.8439284 -0.09711337 0.5275926 0.9507008 -0.08700996 0.2976529 0.9491431 -0.1272645 0.2879779 0.9346328 -0.07871007 0.3467944 0.9601017 -0.1514055 0.2351195 0.9667221 -0.1534193 0.2047219 0.9747975 -0.09250211 0.2030103 0.9707788 -0.1306823 0.2012727 0.9569169 -0.1523193 0.2472022 0.9539908 -0.1555549 0.2563284 0.9791544 -0.1520172 0.1347126 0.9831358 -0.1528081 0.1004682 0.990303 -0.09402823 0.1022683 0.9860157 -0.1325451 0.1010187 0.9759209 -0.1507661 0.157633 0.9713339 -0.1562582 0.1791476 0.9675211 -0.1577234 0.197551 0.9882357 -0.1527476 0.00766021 0.9863303 -0.1633049 0.02200388 0.9955782 -0.09393626 3.96742e-4 0.9907602 -0.1333363 0.02481168 0.9893401 -0.1401745 0.03946125 0.9834741 -0.1584851 0.0875284 0.9876116 -0.147867 -0.05252408 0.985612 -0.1690143 -0.001831114 0.9910727 -0.1333068 -0.002075254 0.9865624 -0.16166 -0.02368283 0.9907872 -0.1323288 -0.02880954 0.9843456 -0.1545507 -0.0847221 0.9824056 -0.1539376 -0.1057482 0.9903476 -0.09375494 -0.1020867 0.9855723 -0.1326649 -0.1051065 0.9684382 -0.1540308 -0.1959643 0.9664137 -0.1551889 -0.2048433 0.9748245 -0.09247416 -0.2028939 0.9702494 -0.1304062 -0.2039867 0.9668515 -0.1136538 -0.2286506 0.9751124 -0.142951 -0.169472 0.9791042 -0.1560426 -0.1304068 0.9501486 -0.1589125 -0.2682622 0.9442703 -0.154947 -0.2904226 0.9488293 -0.1270497 -0.2891045 0.9257582 -0.144293 -0.3495016 0.9587887 -0.1556169 -0.2377134 0.9624688 -0.1568967 -0.2214438 0.9646091 -0.1574772 -0.2114956 0.9836969 -0.171091 -0.05539244 0.9779145 -0.1670905 -0.1255544 0.9758387 -0.1667547 -0.1411799 0.9812951 -0.1790526 -0.07071155 0.9754853 -0.168527 -0.1415175 0.9741452 -0.1701755 -0.1485984 0.9833641 -0.1693214 -0.06576919 0.9784982 -0.1942836 -0.06924748 0.9737834 -0.1791795 -0.1401452 0.9727825 -0.1820133 -0.1434072 0.9728776 -0.2218105 -0.06564587 0.9719625 -0.1935501 -0.1335197 0.9666002 -0.2499512 -0.05664336 0.9705292 -0.2076501 -0.1222889 0.9586668 -0.2795552 -0.05298119 0.9685963 -0.2223038 -0.1113655 0.9505661 -0.3059903 -0.05286008 0.9664596 -0.2363121 -0.1005616 0.9443079 -0.3243522 -0.05548286 0.9643448 -0.2471137 -0.0947315 0.9447283 -0.3236888 -0.0520966 0.9669341 -0.2419242 -0.08069229 0.9616912 -0.2662192 -0.06540268 0.9474605 -0.3177021 -0.03720253 0.9588726 -0.2819944 -0.03228896 0.9512336 -0.3081766 -0.01348918 0.9577389 -0.2876391 -3.05187e-5 0.9511626 -0.3083969 0.01345896 0.958801 -0.2822445 0.03222858 0.9473825 -0.3179203 0.03732514 0.9593903 -0.2742423 0.06604272 0.9670156 -0.2430509 0.07620519 0.9452211 -0.3219099 0.05413991 0.9643616 -0.2470492 0.09473013 0.9664557 -0.2362501 0.1007443 0.9454889 -0.3217043 0.05057048 0.9509499 -0.3045213 0.05441582 0.9686329 -0.222054 0.1115458 0.9589941 -0.2780879 0.0547508 0.9705581 -0.2074971 0.1223192 0.9669365 -0.2481507 0.05877977 0.9722827 -0.192546 0.1326367 0.973576 -0.2188798 0.06512683 0.9736945 -0.1800651 0.1396268 0.9784557 -0.1946169 0.06891089 0.9737859 -0.168132 0.1532079 0.9749509 -0.1706301 0.142675 0.9819717 -0.1767951 0.06689709 0.9840311 -0.1736848 -0.03894251 0.8918648 -0.1843059 -0.4130479 0.8909118 -0.1905914 -0.4122512 0.8913307 -0.1894299 -0.4118811 0.8905798 -0.1914772 -0.4125581 0.8852773 -0.1901056 -0.4244338 0.8804773 -0.1900732 -0.4343179 0.01181066 0.05096608 -0.9986306 -0.01195275 -0.05095309 0.9986296 -0.00564599 -0.02578854 0.9996516 -0.008942008 -0.04071229 0.999131 -0.008942127 -0.03821003 0.9992298 -0.007172048 -0.03140449 0.9994811 -0.01194918 -0.0509532 0.9986295 -0.02679556 -0.1551276 0.987531 -0.03201407 -0.1365405 0.9901171 -0.05398815 -0.2215683 0.9736493 -0.01195156 -0.05095332 0.9986295 -0.05139458 -0.2699131 0.9615121 0.9735788 -0.2283517 0 0.9735921 -0.2282952 0 0.9735898 -0.2283045 0 0.973578 -0.2283551 0 0.9735836 -0.2283306 0 0.9735713 -0.2283836 0 0.97358 -0.2283465 2.96893e-6 0.9735864 -0.2283189 0 0.9735763 -0.2283619 0 0.9735792 -0.2283499 3.31267e-7 0.9735792 -0.2283496 0 0.9735767 -0.2283605 0 0.9735784 -0.2283533 0 0.9735777 -0.2283562 0 0.973577 -0.2283592 0 0.97358 -0.2283467 0 0.9735795 -0.2283487 0 0.9735794 -0.228349 0 -0.005646049 -0.02539205 -0.9996617 0.9735796 -0.2283484 0 0.009796619 0.03732478 -0.9992552 -0.003601253 0.02804726 -0.9996002 7.01936e-4 -0.005615472 -0.999984 -0.002716183 -0.01422184 -0.9998952 0.9735771 -0.2283586 0 0.02594101 0.1418822 -0.9895436 -0.01522922 0.07773309 -0.9968579 0.973584 -0.2283295 0 0.973581 -0.2283421 -1.31755e-7 0.0430926 0.1690745 -0.9846608 0.9735811 -0.2283416 0 0.973577 -0.2283591 2.40253e-7 0.9735782 -0.2283543 -1.36042e-7 0.05273652 0.2352696 -0.9704985 0.06329691 0.2523331 -0.965568 0.9735801 -0.2283458 -1.33996e-7 0.9735759 -0.2283638 0 0.07031691 0.3124586 -0.9473252 0.08258521 0.3335456 -0.9391097 0.9735758 -0.2283644 -1.39432e-7 0.9735838 -0.2283304 -8.45532e-7 0.08771246 0.3880835 -0.9174409 0.1011716 0.4122246 -0.9054476 0.9735795 -0.2283486 0 0.9735755 -0.2283651 1.67319e-7 0.1047424 0.4609643 -0.8812157 0.1186912 0.4872782 -0.8651431 0.97358 -0.2283465 -8.00053e-7 0.9735785 -0.228353 -3.75225e-7 0.1208558 0.5303924 -0.8390935 0.1351386 0.5586218 -0.8183394 0.973577 -0.2283592 2.66204e-7 0.9735799 -0.2283467 7.45863e-7 0.1362397 0.5959572 -0.7913746 0.1507642 0.6258851 -0.7652047 0.973585 -0.2283251 -1.99034e-7 0.9735776 -0.2283565 0 0.1509497 0.6576051 -0.7380852 0.1653519 0.6881728 -0.7064538 0.9735738 -0.2283726 5.71773e-7 0.9735815 -0.2283402 -2.95637e-7 0.1647102 0.7151484 -0.6792888 0.1785374 0.74531 -0.6423686 0.9735803 -0.228345 1.33734e-7 0.9735764 -0.2283619 5.54478e-7 0.1771931 0.7679792 -0.615476 0.190351 0.797051 -0.5731284 0.9735813 -0.2283411 -1.64132e-7 0.9735811 -0.2283418 8.39474e-7 0.1884855 0.815499 -0.5472062 0.2007858 0.8426657 -0.4995994 0.9735825 -0.2283356 6.23368e-7 0.9735712 -0.2283837 7.00275e-7 0.1985269 0.8572825 -0.4750303 0.2096953 0.8818433 -0.4223509 0.9735831 -0.2283332 3.98986e-7 0.207164 0.8930209 -0.3994957 0.2170562 0.9143095 -0.3419428 0.9735711 -0.2283846 4.90415e-7 0.9735866 -0.2283179 -1.2582e-6 0.2143394 0.9223342 -0.3214939 0.2226996 0.9398736 -0.258926 0.9735746 -0.2283694 -8.43599e-7 0.9735758 -0.2283642 -2.59599e-6 0.2200127 0.9452092 -0.2411929 0.2267234 0.9582873 -0.1740176 0.973579 -0.2283509 -2.10059e-6 0.9735701 -0.228389 7.12184e-7 0.2241616 0.9614075 -0.1595224 0.2289227 0.969496 -0.08758944 0.9735968 -0.2282749 1.26692e-6 0.9735634 -0.2284174 -3.20571e-6 0.2269103 0.970816 -0.07764083 0.2291346 0.9733947 -3.96743e-4 0.973563 -0.228419 -2.49865e-6 0.227736 0.9701518 0.08331805 0.2281628 0.9698144 0.08603411 0.2284698 0.9735451 0.003418147 0.2247733 0.9604674 0.1642539 0.2262358 0.9586563 0.1726142 0.2203801 0.9442681 0.2445209 0.2224541 0.9402341 0.2578258 0.21461 0.9216758 0.3231969 0.2170537 0.9145737 0.341237 0.2074103 0.8930301 0.3993472 0.2098777 0.8819321 0.4220749 0.1988319 0.858258 0.4731375 0.201062 0.8424891 0.4997863 0.1890332 0.8177198 0.5436918 0.190563 0.7965865 0.5737035 0.1780171 0.7715808 0.6107152 0.1786301 0.7445209 0.6432574 0.1658732 0.720076 0.6737779 0.1652595 0.6871319 0.707488 0.152442 0.6636647 0.7323323 0.1503996 0.6245796 0.7663422 0.1379783 0.6026365 0.7859971 0.1344671 0.5571264 0.8194686 0.1227483 0.5372297 0.8344563 0.1177728 0.4858013 0.8660986 0.1065719 0.4673966 0.8776007 0.1001315 0.4107803 0.9062192 0.08942174 0.3937 0.9148793 0.08148509 0.3322274 0.939673 0.07165801 0.3169068 0.9457459 0.06232017 0.2512951 0.9659022 0.0536828 0.2382919 0.9697089 0.04232949 0.1684024 0.9848091 0.03549385 0.158517 0.9867182 0.02105814 0.08374434 0.9962648 0.005340814 0.01907438 0.9998039 0.003936946 0.01516813 0.9998772 0.01867765 0.07791531 0.996785 -0.003357052 -0.01452696 0.9998889 -0.001159667 -0.005707025 0.9999831 0.8025327 -0.4318466 -0.4116429 0.8902764 -0.1928815 -0.4125589 0.8867395 -0.196514 -0.4184201 0.8798166 -0.2083567 -0.4272122 0.8845648 -0.1944065 -0.4239709 0.8811773 -0.2049661 -0.4260463 0.877411 -0.2188568 -0.4269096 0.8776449 -0.2227607 -0.4244021 0.8740733 -0.2387831 -0.4230588 0.8731077 -0.244768 -0.4216297 0.8716432 -0.2599059 -0.4155565 0.868683 -0.2745555 -0.4123215 0.8687185 -0.2812615 -0.407701 0.872488 -0.2526699 -0.4182376 0.8711749 -0.2581022 -0.4176574 0.8670027 -0.2909135 -0.4045687 0.8658888 -0.303879 -0.3973591 0.8627663 -0.3204892 -0.3910511 0.8626617 -0.3275038 -0.3854296 0.8666282 -0.2960074 -0.4016655 0.8654203 -0.3017694 -0.3999788 0.8599891 -0.3405592 -0.3800505 0.8586012 -0.3535668 -0.3712069 0.8543236 -0.368275 -0.3667491 0.8513702 -0.3857962 -0.3554294 0.85813 -0.3518828 -0.3738869 0.844506 -0.4142111 -0.3394688 0.8465771 -0.4162844 -0.3316847 0.8388152 -0.450064 -0.3063194 0.8327641 -0.470568 -0.2916674 0.8306066 -0.4858328 -0.2721384 0.8227975 -0.5146452 -0.2411321 0.8260583 -0.5063716 -0.2474176 0.8197249 -0.5299111 -0.2173603 0.8132524 -0.5488317 -0.1934019 0.8136436 -0.5507811 -0.1860759 0.8088733 -0.5678044 -0.1527166 0.8048624 -0.5764234 -0.1411836 0.80397 -0.5846888 -0.1084961 0.7992863 -0.5964891 -0.0730924 0.798318 -0.599944 -0.05249279 0.7981199 -0.6024887 -0.003479242 0.7980695 -0.6025654 -4.88303e-4 0.8003286 -0.5972861 0.05218738 0.7987117 -0.5970425 0.07483243 0.8039532 -0.5852869 0.1053504 0.8055008 -0.5756281 0.1407864 0.8078104 -0.5696088 0.1516189 0.8120987 -0.5538105 0.1838201 0.8134675 -0.5492295 0.1913574 0.8196615 -0.5301843 0.2169324 0.8223683 -0.5222128 0.2258415 0.8261262 -0.5058264 0.2483048 0.8293216 -0.5070111 0.2348737 0.8325823 -0.4824405 0.2721358 0.8364933 -0.4611715 0.2959725 0.8412813 -0.4467342 0.304425 0.8346856 -0.4994563 0.2320419 0.8318932 -0.4887959 0.26274 0.8433069 -0.4292527 0.3233816 0.8483467 -0.4123471 0.3320811 0.8497435 -0.3974809 0.3463308 0.8543203 -0.3804202 0.3541433 0.8552311 -0.3669287 0.3659827 0.8593817 -0.3500213 0.3727579 0.8600473 -0.3381166 0.382094 0.86348 -0.3231984 0.3872277 0.8637106 -0.3126644 0.3952786 0.8665258 -0.2990251 0.3996462 0.8666408 -0.2891753 0.406585 0.8691411 -0.276753 0.4098801 0.8691318 -0.2691812 0.4149114 0.8716062 -0.2566384 0.4176593 0.8717865 -0.2510831 0.4206489 0.8746188 -0.2383548 0.4221718 0.8748795 -0.2353073 0.4233396 0.8785764 -0.2193084 0.4242729 0.8786672 -0.2179958 0.4247609 0.8773615 -0.196329 0.4378262 0.8758873 -0.1919932 0.4426741 0.8816554 -0.2077104 0.423722 0.8817221 -0.2136629 0.4206117 0.8794734 -0.1928817 0.435113 0.8764203 -0.2075306 0.4345326 0.8046717 -0.1707554 0.5686355 0.7091052 -0.2182707 0.6704683 0.7963932 -0.2240094 0.5617631 0.7996215 -0.1969679 0.5672823 0.707535 -0.1827816 0.682631 0.7203714 -0.1481394 0.6775838 0.7076511 -0.1814372 -0.6828694 0.7990889 -0.1945915 -0.5688507 0.7995676 -0.2202252 -0.5587421 0.8049182 -0.1702981 -0.5684235 0.7097552 -0.2177242 -0.6699581 0.7978936 -0.261763 -0.5429974 0.7044765 -0.2845617 -0.6501827 0.7940663 -0.2770183 -0.5410357 0.7864485 -0.2909087 -0.5448587 0.771612 -0.3084556 -0.5563004 0.6976035 -0.3594223 -0.6198105 0.7825112 -0.340197 -0.5214809 0.7773908 -0.3463345 -0.5250868 0.7549654 -0.37057 -0.5410224 0.7673346 -0.3726652 -0.5218412 0.6868394 -0.4348101 -0.5824019 0.7508345 -0.4265675 -0.5042695 0.7204612 -0.4539391 -0.5242853 0.7374064 -0.4470766 -0.5063145 0.6879004 -0.5065254 -0.5198317 0.7232443 -0.5177584 -0.4569947 0.6772288 -0.5802377 -0.4524218 0.7034007 -0.5921286 -0.3932061 0.6632823 -0.6473205 -0.3755435 0.6903766 -0.6493282 -0.3189875 0.6431621 -0.7044752 -0.3000955 0.6702657 -0.6993812 -0.2482138 0.6248525 -0.749646 -0.2181521 0.6540673 -0.7378743 -0.1665459 0.6052255 -0.7869061 -0.120337 0.6581208 -0.7495265 -0.07132387 0.5911889 -0.8065329 7.01943e-4 0.6791691 -0.7339812 9.76607e-4 0.6585463 -0.7490972 0.07190352 0.6051125 -0.7869179 0.1208271 0.6539056 -0.7381693 0.1658722 0.6251353 -0.7495337 0.2177276 0.6697156 -0.6999297 0.2481524 0.6422887 -0.7053731 0.2998568 0.6885074 -0.6539295 0.3135822 0.6745367 -0.6623595 0.3260067 0.6771584 -0.6589689 0.3274397 0.6434435 -0.6605955 0.3867741 0.7370161 -0.5848457 0.3387668 0.6967349 -0.5948601 0.4008766 0.659221 -0.5913456 0.4644761 0.7439677 -0.5156837 0.42495 0.7221158 -0.5140051 0.4629769 0.6745787 -0.5124881 0.5313189 0.7471704 -0.4424059 0.4959976 0.7499839 -0.4289197 0.5035397 0.6876725 -0.4326184 0.5830506 0.7497128 -0.370019 0.54865 0.7732104 -0.3509737 0.5281697 0.6971243 -0.3571686 0.6216498 0.7531252 -0.3025685 0.5841702 0.7881208 -0.2856571 0.5452206 0.7030621 -0.2878535 0.6502646 0.7519073 -0.2410424 0.6136237 0.4976513 -0.1986516 -0.8443226 0.4911481 -0.1456384 -0.858815 0.4934602 -0.3017709 -0.8157399 0.4876723 -0.4025532 -0.7746784 0.4798521 -0.5011545 -0.7201292 0.4698227 -0.5967548 -0.6505002 0.4589521 -0.6859867 -0.5646107 0.4477814 -0.7627727 -0.4665508 0.4348348 -0.8241354 -0.3629321 0.4216547 -0.8708684 -0.2525778 0.4100832 -0.9026593 -0.1305295 0.4056625 -0.9140226 7.62983e-4 0.4106077 -0.9023054 0.1313248 0.4222308 -0.8706165 0.252484 0.4355753 -0.8238757 0.3626335 0.4478349 -0.7628208 0.4664209 0.4592003 -0.6859926 0.5644019 0.4701796 -0.5966208 0.6503652 0.4802882 -0.5002786 0.7204476 0.4880296 -0.4012641 0.7751221 0.4933518 -0.3014741 0.8159151 0.4971896 -0.1999623 0.8442854 0.4914804 -0.1452711 0.8586869 0.5082901 -0.09527957 0.8558989 0.5081716 -0.09531074 0.8559659 0.2561466 -0.03454756 0.9660204 0.1211602 -0.002868771 0.9926288 -0.01745283 0.02857196 0.9994394 -0.01745283 0.02856838 0.9994395 0.258312 -0.03122079 0.965557 0.1216188 -0.002105772 0.9925746 0.2565435 -0.0323807 0.9659902 -0.01745241 0.02856707 0.9994395 0.1268356 -0.003357052 0.9919182 -0.01745188 0.0285564 0.9994399 -0.01745146 0.02858328 0.9994391 -0.0174539 0.02856111 0.9994397 -0.01745229 0.02855962 0.9994398 -0.01744985 0.02857011 0.9994395 -0.01745343 0.02856755 0.9994395 -0.01745259 0.02857053 0.9994395 -0.01745182 0.02856516 0.9994396 -0.01745408 0.02856552 0.9994396 -0.01745247 0.0285719 0.9994394 -0.01745152 0.02856242 0.9994397 -0.01745086 0.02856928 0.9994395 -0.01745188 0.02856212 0.9994397 -0.01745134 0.02857202 0.9994395 -0.01745355 0.02856165 0.9994397 -0.01745182 0.02857017 0.9994395 -0.0174508 0.02856606 0.9994397 -0.01745659 0.02856743 0.9994395 -0.0174573 0.02856612 0.9994395 -0.01744854 0.0285691 0.9994396 -0.01745319 0.02856773 0.9994395 0.5145624 -0.089087 0.8528125 0.5095551 -0.09067368 0.8556472 0.1926987 0.1341932 0.9720388 0.09924656 0.08981633 0.9910011 0.0900923 0.08176058 0.9925718 0.2437531 0.155554 0.9572813 0.1150556 0.09402823 0.9888989 0.2495217 0.1496642 0.9567339 0.1161265 0.09180247 0.9889828 0.1220447 0.09125119 0.988321 0.2552626 0.1393507 0.9567772 0.1230823 0.08249229 0.9889619 0.1254319 0.07852464 0.9889898 0.2674434 0.112068 0.9570344 0.1428269 0.06262409 0.9877645 0.1297662 0.05307227 0.9901233 0.2789753 0.07031601 0.9577205 0.1393508 0.03689771 0.9895554 0.2815383 0.02539181 0.959214 0.1333359 0.0209968 0.9908486 0.1349231 0.01590019 0.9907285 0.2779655 -0.004608333 0.9605801 0.1396853 0.003875911 0.9901884 0.1316274 0.006195306 0.99128 0.2716487 -0.02356058 0.9621081 0.1294301 0.002441465 0.9915856 0.1315357 0.001922667 0.9913096 0.2747301 -0.01510679 0.9614028 0.2675934 -0.02450698 0.9632203 0.1324216 2.13632e-4 0.9911935 0.2638681 -0.02667367 0.9641899 0.1317798 -0.001190185 0.9912784 0.2607524 -0.02890127 0.964973 0.1295841 -0.002288877 0.9915658 -0.01903629 0.02872794 0.999406 -0.0173425 0.02854955 0.999442 -0.01736378 0.02855932 0.9994414 -0.01738238 0.02854555 0.9994414 -0.0174753 0.02855539 0.9994395 -0.01744377 0.02854222 0.9994404 -0.01743459 0.02857643 0.9994397 -0.01745218 0.02858817 0.999439 -0.01740789 0.02856123 0.9994406 -0.01747435 0.02855336 0.9994396 -0.01745837 0.02857249 0.9994393 -0.01745027 0.02856975 0.9994395 -0.01744621 0.0285741 0.9994394 -0.01746523 0.0285657 0.9994394 -0.01745122 0.02856713 0.9994396 -0.02661281 0.04171985 0.9987749 -0.0215767 0.03506594 0.9991521 -1 7.80549e-6 0 -0.03131252 0.04834216 0.9983399 -0.02392679 0.03839278 0.9989763 -0.03622657 0.05490452 0.9978343 -0.0263071 0.04165798 0.9987856 -0.04132324 0.06149655 0.9972516 -0.0289011 0.04498445 0.9985696 -0.04657208 0.06796592 0.9966001 -0.03161746 0.04834175 0.9983304 -0.05197435 0.07437551 0.995875 -0.03445619 0.05163854 0.9980713 -0.05795633 0.08066278 0.9950551 -0.0375995 0.0542019 0.9978219 -0.03991895 0.05749797 0.9975473 -0.06372332 0.08719229 0.9941514 -0.04290938 0.0607323 0.9972314 -0.06976741 0.09326738 0.9931938 -0.04599183 0.06387591 0.9968975 -0.0759918 0.09915554 0.9921661 -0.0494402 0.06701898 0.9965261 -0.08237206 0.1049565 0.9910596 -0.05288946 0.07004112 0.996141 -0.08893245 0.1105399 0.9898849 -0.05642932 0.07294005 0.9957387 -0.09567749 0.1159422 0.9886371 -0.05994015 0.07565766 0.9953307 -0.1025761 0.1210099 0.9873372 -0.06341862 0.07815933 0.9949218 -0.1096237 0.1258597 0.9859727 -0.0669291 0.08047974 0.9945067 -0.1168284 0.130379 0.984557 -0.07037687 0.08258444 0.9940961 -0.1241531 0.1345908 0.9830928 -0.0738244 0.08450585 0.9936845 -0.1316577 0.1384938 0.9815731 -0.07724404 0.08621668 0.9932774 -0.1393203 0.1420671 0.9800035 -0.08081328 0.08771049 0.9928626 -0.1473168 0.1453025 0.9783583 -0.08508783 0.08926904 0.9923665 -0.1554935 0.1483521 0.9766338 -0.08951115 0.09060978 0.9918557 -0.1638871 0.1510996 0.9748385 -0.09405964 0.09186226 0.9913194 -0.1725228 0.1535096 0.9729701 -0.09869784 0.09299081 0.990763 -0.1813458 0.1555875 0.9710336 -0.1034285 0.09399813 0.9901853 -0.1903468 0.1572643 0.9690387 -0.1081581 0.09485203 0.9895984 -0.1994727 0.1585161 0.9669971 -0.1128305 0.09549546 0.9890146 -0.2086597 0.1593102 0.9649256 -0.1174059 0.0958901 0.9884437 -0.2179079 0.1596465 0.9628235 -0.1219523 0.09595048 0.9878872 -0.227248 0.1594642 0.9606922 -0.1265329 0.0957694 0.9873287 -0.2366771 0.1588224 0.9585194 -0.1311694 0.095371 0.9867619 -0.2462297 0.1577237 0.9562919 -0.135873 0.09482419 0.986178 -0.2558403 0.1561654 0.9540221 -0.1407213 0.09408885 0.9855683 -0.265609 0.1541222 0.9516818 -0.1456368 0.09317457 0.9849409 -0.2756214 0.1507662 0.9493695 -0.1499092 0.09024459 0.9845727 -0.1518936 0.09412091 0.9839054 -0.2892283 0.1590649 0.943952 0.6727439 0.3955647 0.6252554 0.7215083 0.4120419 0.5564596 0.7476182 0.4333969 0.5032239 0.8134261 0.4614796 0.3540828 0.8137713 0.4689927 0.3432525 0.8144899 0.4590356 0.3548134 0.7359094 0.4472588 0.5083277 0.6542465 0.4173236 0.630716 0.7415198 0.4442648 0.5027697 0.8146916 0.471376 0.337761 0.7623718 0.4292232 0.4843106 0.8005763 0.3917733 0.4534218 0.8234184 0.4563899 0.3371803 0.7990252 0.4237602 0.4265984 0.8160275 0.4518701 0.360434 0.7070697 0.401389 0.582185 0.7413953 0.4051077 0.534996 0.8288463 0.4294387 0.3586032 0.8235578 0.4459756 0.3505118 0.5647554 0.3299111 0.7564457 0.7126326 0.3852183 0.586312 0.7693527 0.4101139 0.489799 0.7133279 0.3877784 0.5837734 0.478782 0.2961258 0.8264849 0.3887835 0.2408266 0.8892975 0.5677219 0.3182868 0.7592005 0.3904969 0.2329248 0.8906505 0.4611498 0.384088 0.7998859 0.4495741 0.3356165 0.8277951 0.6561385 0.4452489 0.6092911 0.6820163 0.3605253 0.6362982 0.759291 0.3948899 0.517242 0.7036653 0.3110887 0.6388106 0.7664834 0.3698592 0.5250785 0.6928613 0.3387396 0.6365522 0.8508183 0.4344429 0.2955799 0.8378534 0.4392375 0.3241482 0.8366813 0.4283967 0.3412341 0.8798375 0.3723035 0.2954257 0.8649683 0.4064515 0.2943248 0.8484039 0.4080725 0.3371763 0.8510473 0.4016885 0.3381788 0.7444267 0.3681542 0.5570382 0.4842763 0.2692086 0.8324682 0.5010985 0.2360677 0.8325698 0.4923439 0.2545953 0.8323333 0.8299062 0.4341954 0.3503289 0.7341015 0.4706929 -0.4894315 0.6519544 0.4939252 -0.5753203 0.7305017 0.4770112 -0.4887 0.7258946 0.5028922 -0.4692297 0.6509802 0.542453 -0.5310082 0.7000607 0.5045515 -0.5053145 0.8155249 0.4900718 -0.3078132 0.8549051 0.4594672 -0.2408884 0.7333461 0.510037 -0.4495174 0.8131195 0.4883661 -0.3167574 0.8116108 0.4840732 -0.3270493 0.7528748 0.4339201 -0.4948667 0.8055505 0.4724349 -0.3576223 0.7243509 0.5371745 -0.4321568 0.6531748 0.58942 -0.4753386 0.736238 0.5402151 -0.4075799 0.8182859 0.4959401 -0.2906056 0.7236391 0.5722032 -0.3859144 0.8179687 0.4943763 -0.2941415 0.8255665 0.4978241 -0.2657279 0.6577791 0.6331501 -0.4079799 0.7422862 0.5693649 -0.35332 0.8260625 0.504543 -0.2511118 0.7246546 0.6063305 -0.327474 0.8223132 0.5017991 -0.2683261 0.8290165 0.5097274 -0.2300212 0.6633313 0.6716325 -0.3300023 0.7496436 0.595491 -0.2888339 0.8320133 0.5089985 -0.220623 0.8336412 0.5138575 -0.2024666 0.7265523 0.636977 -0.2576474 0.8361066 0.5180345 -0.1804606 0.6685268 0.7029221 -0.2428426 0.757853 0.6162133 -0.2143363 0.8388798 0.5165061 -0.1717618 0.8415889 0.5196756 -0.1471925 0.7286139 0.6614108 -0.1779265 0.8423461 0.5242384 -0.125009 0.6724404 0.7250869 -0.1485698 0.7652879 0.6300289 -0.1319019 0.8443766 0.5227341 -0.1173771 0.8481958 0.5224314 -0.08734655 0.730042 0.677336 -0.0908547 0.8466933 0.5280427 -0.06543308 0.6742345 0.7368297 -0.04989916 0.7694224 0.6371821 -0.04458868 0.8475241 0.5273755 -0.05981802 0.8530865 0.5211662 -0.02508628 0.7304521 0.6829639 0 0.8487133 0.5288398 -0.003784358 0.6757256 0.735238 0.05310338 0.7648783 0.6418544 0.0546298 0.8483385 0.5294448 -0.003204464 0.8483098 0.5286219 0.03048861 0.6730032 0.7242444 0.1501225 0.6780158 0.7304174 0.08237147 0.8485834 0.5258135 0.05853557 0.8457504 0.5297232 0.06402945 0.7596839 0.6343721 0.143013 0.8458813 0.5256391 0.09049057 0.668432 0.7026746 0.2438181 0.6912992 0.7002414 0.1782343 0.8447723 0.5223672 0.1161562 0.8424298 0.5241114 0.1249774 0.7517982 0.6195911 0.2256249 0.8412044 0.520202 0.1475304 0.6627953 0.6717681 0.3308025 0.7006967 0.6634629 0.262376 0.8387284 0.5169341 0.1712126 0.8369905 0.5164773 0.1808266 0.7438687 0.5974388 0.2995434 0.8347628 0.5130288 0.1999316 0.6569629 0.6334629 0.4088088 0.7071952 0.6232974 0.3337295 0.8321027 0.5096687 0.2187302 0.8291527 0.509614 0.229781 0.7373188 0.5698282 0.3628455 0.8248994 0.5009092 0.2619755 0.8254482 0.5055783 0.2510495 0.6522008 0.589758 0.4762561 0.7122219 0.582394 0.3918639 0.8220595 0.5001757 0.2721073 0.7326388 0.5394841 0.4149667 0.8182808 0.4941669 0.2936252 0.818207 0.4959783 0.2907627 0.6498697 0.5426872 0.5321277 0.7177279 0.5424848 0.4365514 0.8137348 0.4879723 0.3157827 0.8151434 0.4908745 0.3075443 0.7299931 0.5083613 0.4568141 0.814726 0.4841356 0.319115 0.6507571 0.4939809 0.5766264 0.7168711 0.5097051 0.4757065 0.8134853 0.4820789 0.3253331 0.7327378 0.4979224 0.4638628 0.8198921 0.4767673 0.31697 0.7528488 0.4338921 0.4949306 0.8116078 0.484285 0.3267428 0.8057069 0.4725593 0.3571051 0.7309577 0.4774069 0.4876307 0.818037 0.4753978 0.3237478 0.7344389 0.4704193 0.4891885 0.8159758 0.4732696 0.3319632 0.4546782 0.4710366 0.7559049 0.4524795 0.5557875 0.6973971 0.4534347 0.6364322 0.6239801 0.4567236 0.7102487 0.5356774 0.4612373 0.7741205 0.4335868 0.4657273 0.8252468 0.3194779 0.4693257 0.8610408 0.1958118 0.471302 0.8794912 0.06610375 0.4712808 0.879539 -0.06561672 0.4692946 0.8611618 -0.1953537 0.4656279 0.8254466 -0.3191064 0.4611452 0.7743638 -0.4332506 0.4567215 0.7104591 -0.5354003 0.4535234 0.6366419 -0.6237015 0.45266 0.5560284 -0.6970878 0.4550704 0.4713066 -0.7555006 -0.03372377 0.06174045 -0.9975224 -0.0340597 0.06045901 -0.9975895 -0.0765711 0.1351972 -0.9878557 0.008564651 -0.01520496 -0.9998478 0.008567392 -0.0152046 -0.9998477 -0.07663297 0.1394714 -0.9872564 -0.09775245 0.2963703 -0.9500575 0.825004 0.4119221 0.3868961 -0.1564732 0.3161205 -0.9357265 0.008564233 -0.01520639 -0.9998478 0.008567571 -0.01520448 -0.9998477 0.8346608 0.4235715 0.3520352 -0.1613861 0.2888043 -0.9436878 -0.2432686 0.4304429 -0.8692177 0.8444565 0.4330624 0.3151987 -0.2403697 0.4287957 -0.8708367 -0.30596 0.5422131 -0.7825557 0.8535317 0.4312369 0.2924354 -0.3097702 0.5563657 -0.771038 -0.3323226 0.6326307 -0.6995286 0.87421 0.4410572 0.2030413 0.8633063 0.3904365 0.3197838 -0.3385215 0.6388632 -0.6908379 0.8718783 0.4438742 0.206891 -0.3746001 0.6648193 -0.6462896 -0.3449902 0.6122783 -0.711405 0.8845275 0.4408141 0.1526247 -0.3746069 0.6648148 -0.6462903 0.9026639 0.3812448 0.1996255 0.8969882 0.4193025 0.1399913 0.8867328 0.4163722 0.2008463 -0.3746489 0.6648461 -0.6462336 0.9189282 0.3795652 0.1072438 0.9002509 0.420522 0.1127374 0.1798202 -0.29909 -0.9371285 0.2241008 -0.377367 -0.8985394 0.1650153 -0.2934386 -0.9416283 0.2619473 -0.4460397 -0.8558226 0.2619168 -0.4648702 -0.8457514 0.09351032 -0.1645892 -0.9819198 0.09189283 -0.1629412 -0.9823473 0.05157643 -0.08935856 -0.9946633 0.05096727 -0.09045934 -0.9945952 0.1805521 -0.3040636 0.9353857 0.2628023 -0.3752052 0.8889072 0.2646647 -0.4472931 0.8543311 0.1636433 -0.291335 0.9425204 0.252299 -0.4441708 0.8596845 0.3184058 -0.567869 0.7590406 0.320854 -0.566141 0.7593004 0.3779526 -0.6733501 0.6354144 0.3796929 -0.6711845 0.636667 0.4261938 -0.7585121 0.4929688 0.4272422 -0.7566999 0.4948428 0.4620007 -0.82106 0.3352847 0.4620054 -0.8196645 0.3386758 0.4837607 -0.8586593 0.1693513 0.4835401 -0.8582195 0.1721871 0.4909304 -0.8711985 7.62978e-4 0.4912043 -0.8710445 3.05191e-4 0.4837655 -0.8592171 -0.1664842 0.4842576 -0.8578199 -0.1721621 0.462603 -0.8224189 -0.3310977 0.4623096 -0.8192659 -0.3392244 0.428065 -0.7606652 -0.4880051 0.4267529 -0.7566372 -0.4953606 0.3809756 -0.6763134 -0.6304425 0.3785272 -0.671418 -0.6371147 0.3219761 -0.5715 -0.7547974 0.3194789 -0.566596 -0.7595408 0.008562207 -0.01520544 0.9998478 0.00856769 -0.01520377 0.9998478 0.05148601 -0.08813971 0.9947767 0.04959309 -0.08801633 0.9948838 0.09036755 -0.1617216 0.9826902 0.008567154 -0.01520478 0.9998477 0.09485399 -0.164499 0.981806 -0.07608437 0.1384046 0.987449 -0.137946 0.2475703 0.9589995 -0.07644933 0.1358998 0.9877686 -0.1604401 0.2908187 0.9432303 -0.1818333 0.3224047 0.9289736 -0.03411984 0.06183081 0.9975033 0.008566975 -0.01520472 0.9998478 -0.03497493 0.06207597 0.9974585 0.8565784 0.4376432 -0.2733897 0.8747709 0.4403916 -0.2020674 0.8867449 0.4162864 -0.2009711 0.8501654 0.4361153 -0.2949958 0.8718912 0.4438652 -0.2068563 0.8845167 0.4408239 -0.1526586 0.9026367 0.3812767 -0.1996873 0.8970035 0.4192792 -0.1399632 -0.3746043 0.6648185 0.646288 -0.374612 0.6648193 0.6462827 0.9189499 0.3794701 -0.1073954 0.9002807 0.4204911 -0.1126152 -0.3746041 0.6648212 0.6462853 -0.337696 0.6239974 0.7046905 -0.3598506 0.6386425 0.680179 -0.3435832 0.6161791 0.7087128 -0.374597 0.6648193 0.6462913 -0.3052799 0.5552597 0.773622 -0.3062024 0.5430949 0.7818492 -0.2405802 0.4285153 0.8709167 -0.2436656 0.4319999 0.8683336 0.8712071 0.4909156 0 0.8712143 0.490903 0 0.8712147 0.4909023 0 0.871214 0.4909034 0 0.8712081 0.4909139 0 0.8712188 0.490895 0 0.8712168 0.4908984 0 0.8712113 0.4909083 0 0.8712162 0.4908995 0 0.8712185 0.4908955 0 0.8712072 0.4909156 0 0.8712292 0.4908765 0 0.8712139 0.4909036 0 -0.3746551 0.6648185 -0.6462584 -0.3746031 0.6648166 -0.6462906 0.871212 0.4909071 0 0.8712141 0.4909032 7.59137e-7 0.8712095 0.4909116 -7.86805e-7 0.8712157 0.4909006 -8.83656e-7 0.8712074 0.4909153 1.29108e-6 0.8712079 0.4909142 -1.06524e-6 0.8712232 0.4908873 -6.18919e-7 0.8712255 0.4908831 -2.09802e-6 0.8712078 0.4909145 -9.91202e-7 0.8712105 0.4909099 -1.02851e-6 0.8712185 0.4908956 6.74547e-7 0.8712157 0.4909005 -8.96872e-7 0.8712109 0.490909 -7.58771e-7 0.8711984 0.4909314 -2.13673e-6 0.8712189 0.4908947 -9.05684e-7 0.8712091 0.4909121 -9.33743e-6 0.8712221 0.4908891 0 0.8712135 0.4909043 0 -0.3745992 0.6648121 0.6462973 -0.4379529 0.7773588 0.4515646 -0.4092343 0.726117 0.5525228 -0.4091094 0.7260509 0.5527021 0.9047306 0.4156969 -0.09305191 0.9197869 0.3868 -0.06616556 -0.4384025 0.7779242 0.4501523 0.8712147 0.4909022 0 0.8712151 0.4909016 0 0.9047199 0.415706 0.09311497 0.9254182 0.3738539 0.06192237 -0.409174 0.7260574 -0.5526459 -0.4091722 0.7261762 -0.5524909 -0.4383473 0.7779344 -0.4501887 0.9278852 0.3728266 -0.005432426 0.9747127 0.1854938 0.1246086 -0.4774682 0.8474489 -0.2320657 -0.477602 0.8476222 -0.2311558 -0.437988 0.7773364 -0.4515692 0.9195773 0.3925698 -0.01632779 -0.4908712 0.8712323 -3.05192e-5 0.9605036 0.2757114 -0.03763025 -0.4908712 0.8712323 0 -0.4776256 0.8476099 0.2311524 -0.4774413 0.8474553 0.232098 0.9370573 0.2859941 -0.2003271 0.9517332 0.2898689 -0.1008956 0.9566662 0.2911871 0 0.9517304 0.2898681 0.1009258 0.9370656 0.2859662 0.2003288 0.8591725 0.3800843 0.3425764 0.8707196 0.3524995 0.3429164 0.9130759 0.2796787 0.2967695 0.7312031 0.2413742 0.6380288 0.7081108 0.3150821 0.6319038 0.7787905 0.33443 0.5306995 0.8872185 0.3077843 0.3436747 0.8026866 0.2553545 0.5389698 0.9682279 0.1486905 -0.2010617 0.9834211 0.1504293 -0.1012628 0.9885282 0.1510366 0 0.9834135 0.1504586 0.1012925 0.9682279 0.1486905 0.2010617 0.9051319 0.2494926 0.3442236 0.9434006 0.1458498 0.2978646 0.7585917 0.1278765 0.6388944 0.6943059 0.2275187 0.6827698 0.927924 0.1682196 0.3326549 0.8290601 0.1386802 0.5416892 0.9793859 0.008423209 -0.2018223 0.9947887 0.008209526 -0.1016274 0.9999671 0.008118152 -3.05194e-5 0.9947825 0.008209466 0.1016877 0.9793859 0.008423209 0.2018223 0.9542428 0.008758962 0.2989047 0.9396332 0.1152415 0.322194 0.7650552 0.01303166 0.6438329 0.7016659 0.1140806 0.703314 0.9408522 0.02304214 0.3380329 0.8475868 0.03750842 0.5293297 0.9433797 -0.02295041 0.3309199 0.8488054 -0.02313369 0.5281991 0.7613645 -0.0659216 0.6449639 0.8464584 -0.06244289 0.5287809 0.8711717 0.4909787 0 0.871193 0.4909409 0 0.8712924 0.4907643 0 0.5221318 0.1836678 0.8328533 0.5423885 0.1035214 0.8337254 0.548277 0.02063095 0.8360423 0.5437565 -0.0365312 0.8384477 0.5403704 -0.05710113 0.8394876 0.5363121 -0.07364255 0.840801 0.5312798 -0.0754742 0.8438279 0.5201777 -0.0846616 0.8498516 0.5257582 -0.08011347 0.8468531 -0.03711074 0.05746674 0.9976575 -0.04660296 0.07089632 0.9963945 -0.05667436 0.08417224 0.9948383 -0.06702071 0.09714341 0.9930112 -0.07739591 0.1099596 0.9909182 -0.08841454 0.1227489 0.9884916 -0.09973704 0.135292 0.9857732 -0.1113935 0.1475276 0.9827651 -0.1234501 0.1600425 0.9793603 -0.1366626 0.1715454 0.9756514 -0.1483819 0.1822577 0.9719903 -0.1613564 0.1930356 0.9678333 -0.1747826 0.2041419 0.9632119 -0.1896479 0.2138499 0.9582808 -0.2024303 0.2226641 0.953647 -0.216841 0.2314904 0.948363 -0.2315171 0.2397572 0.9428236 -0.2465957 0.2474197 0.9370028 -0.2619435 0.2544053 0.9309477 -0.2776286 0.2607517 0.9246248 -0.2935917 0.2663689 0.9180694 -0.3098571 0.2712814 0.9112601 -0.3263446 0.2754381 0.9042307 -0.3431008 0.2787961 0.8969697 -0.360071 0.2813302 0.8894956 -0.3772515 0.2830379 0.8817999 -0.3946151 0.2838909 0.8738907 -0.4121273 0.2838259 0.8657909 -0.429744 0.282854 0.8575043 -0.44747 0.2809887 0.8490088 -0.4652442 0.2781882 0.8403328 -0.4830369 0.274434 0.8314815 -0.5008197 0.269698 0.8224614 -0.5172353 0.2598689 0.815436 -1 1.90909e-6 0 -0.5360696 0.2706747 0.7996029 -0.03592056 0.05441492 0.9978722 -0.06131184 0.08761888 0.9942655 -0.03988796 0.06131207 0.9973213 -0.06433463 0.09299224 0.9935862 -0.07727479 0.1093811 0.9909917 -0.1000713 0.1377926 0.9853929 -0.112891 0.153848 0.9816244 -0.1290646 0.1718217 0.9766369 -0.1434377 0.187293 0.9717752 -0.1588837 0.2035335 0.9660902 -0.1624251 0.2037485 0.9654557 -0.1920581 0.2340832 0.9530576 -0.2094236 0.2490376 0.9455803 -0.2259656 0.2631382 0.9379221 -0.2265107 0.256999 0.9394915 -0.2639326 0.2886229 0.9203459 -0.2807425 0.2990843 0.9119936 -0.3000678 0.3099561 0.9021566 -0.3201497 0.3203328 0.8915666 -0.3405364 0.3299767 0.8804262 -0.3604252 0.3384214 0.8692322 -0.3808252 0.3459717 0.8574823 -0.4020966 0.3527768 0.8449065 -0.4233287 0.3582623 0.8321304 -0.4468582 0.3615883 0.8182736 -0.4675325 0.3641009 0.8055085 -0.4876095 0.3641888 0.7934756 -0.5094612 0.3644632 0.7794972 -0.534423 0.3658956 0.7619137 -0.5535671 0.362422 0.7498092 -0.5758995 0.3603721 0.7338064 -0.5945448 0.354145 0.721871 -0.616008 0.3481068 0.7066513 -0.6379525 0.3408436 0.6905378 -0.6642874 0.3281151 0.6716121 -1 -1.83053e-6 0 0.152567 -0.1478365 0.9771735 -0.02499473 0.05273622 0.9982957 -1 9.5817e-7 0 -1 1.98151e-6 0 -1 -2.35653e-6 0 -0.1025142 0.1440508 0.984246 -0.1246086 0.1684948 0.9777947 -0.1184753 0.160256 0.9799396 -0.1418826 0.1874779 0.9719678 -0.1601046 0.2064635 0.9652665 -0.1541524 0.2003585 0.9675194 -0.1717327 0.2186715 0.9605679 -1 -2.25043e-6 0 -1 -3.29204e-7 0 -0.2261183 0.2671059 0.9367631 -0.2101845 0.2546203 0.9439232 -0.2410073 0.2786371 0.929665 -0.2506865 0.2856923 0.924952 -0.2986966 0.3236312 0.8977991 -1 3.11803e-6 0 -1 1.93436e-6 0 -0.3086132 0.3258262 0.8936416 -0.2882215 0.3132166 0.9048888 -0.3309783 0.3387301 0.8807471 -0.3520443 0.3494196 0.8683149 -0.3743774 0.3597283 0.8546562 -0.3969873 0.3689712 0.8403936 -0.4153097 0.374261 0.829124 -0.4332801 0.378071 0.8181264 -0.4295253 0.3849369 0.8169037 -0.4488751 0.3799019 0.8088176 -0.4705443 0.384114 0.7943831 -0.5104033 0.3945524 0.764079 -0.4859374 0.3909595 0.7816749 -0.5353138 0.3977009 0.7451666 -0.5558789 0.3954389 0.7311819 -0.5341275 0.3959032 0.7469728 -0.5777233 0.3921072 0.7158825 -0.6039213 0.3927564 0.6935573 -0.6281803 0.3897019 0.6734405 -0.6479558 0.3840246 0.657783 -0.6737164 0.3775559 0.6352619 -0.655655 0.3871731 0.6482387 -0.6946704 0.3688204 0.6175797 -0.2259937 0.2710704 0.9356536 -0.2267897 0.2713176 0.9353893 -0.2278544 0.271527 0.9350698 -0.2290158 0.2716816 0.9347411 -0.2301464 0.2716527 0.9344719 -0.2312749 0.2714383 0.9342554 -0.2323745 0.271012 0.9341064 -0.2332577 0.2702775 0.934099 -0.2360069 0.3090704 0.9212906 -0.2823635 0.3823748 0.879807 -0.3403798 0.3551205 0.8706497 -0.3449018 0.3555837 0.8686789 -0.3512451 0.3557314 0.8660728 -0.3581191 0.3550671 0.8635267 -0.3642176 0.3534138 0.8616521 -0.3689473 0.3510325 0.8606126 -0.3712048 0.3708691 0.8512716 -0.4111841 0.41976 0.8091534 -0.4464042 0.3954372 0.8027158 -0.4522611 0.3950991 0.7995979 -0.4621189 0.3937869 0.7945931 -0.4721669 0.3912903 0.7899053 -0.4810111 0.3876532 0.7863545 -0.4884049 0.3829903 0.7840786 -0.4933668 0.3959508 0.7744755 -0.532405 0.4250084 0.7320607 -0.5541076 0.4052346 0.7271518 -0.5659214 0.4021847 0.7197087 -0.5814337 0.3963308 0.7105327 -0.5940877 0.3894562 0.703835 -0.6041565 0.3820384 0.6993151 -0.611025 0.3867393 0.6907107 -0.6547048 0.3857668 0.6500353 -0.6681779 0.3795313 0.6399175 -0.6860147 0.3690404 0.6270512 -0.5413202 0.4573617 0.7055444 -0.553498 0.4877899 0.6750564 -0.5687931 0.5166047 0.6399953 -0.5867057 0.5433681 0.6004394 -0.606754 0.5677198 0.5563666 -0.6285451 0.5893278 0.5075666 -0.6516774 0.6077296 0.4538516 -0.6624563 0.6163108 0.4258081 -0.3561629 0.8616884 0.3614428 -0.3615345 0.8401725 0.4042313 -0.345781 0.8006677 0.4892511 -0.3306789 0.7556936 0.5653129 -0.3170394 0.7047931 0.6346281 -0.3052181 0.6485235 0.697323 -0.2955513 0.5874707 0.7533444 -0.2883797 0.5223124 0.8025129 -0.2840116 0.4538815 0.8445882 -0.5208452 0.7535256 0.4011478 -0.4961557 0.712417 0.4962778 -0.5175449 0.7396638 0.4301684 -0.478631 0.6798434 0.5556306 -0.4626457 0.6433824 0.609933 -0.4483304 0.6036132 0.6592807 -0.4357898 0.5610119 0.7038132 -0.4252865 0.5160204 0.7435419 -0.4170489 0.4691151 0.7784608 0.984158 -0.1441735 -0.103186 0.9821923 -0.1722796 -0.07495456 0.9794777 -0.1734091 -0.102727 0.9879547 -0.1117599 -0.1070294 0.9944928 0.0233165 -0.1021777 0.9928684 -0.04907423 -0.1086469 0.9919172 0.09329551 -0.08600151 0.9864808 0.1519869 -0.06128305 0.9772704 0.207924 -0.04135286 0.9801145 0.1970911 -0.02304172 0.9807517 0.1952592 2.74669e-4 0.9789782 0.2039563 -0.001892149 0.9549465 0.2793424 -0.1002251 0.9507908 0.297042 -0.08810847 0.9478614 0.3115692 -0.06695884 0.9410474 0.3363783 -0.03576803 0.9408183 0.3369635 -0.03628742 0.9449974 0.3266778 -0.01617515 0.9479511 0.3112635 -0.06711131 0.9633929 -0.1526255 -0.2204081 0.9695402 -0.1301347 -0.2075014 0.973639 -0.09350937 -0.2080461 0.9680591 -0.1747206 -0.1798173 0.9692776 -0.1740793 -0.1737741 0.9634088 -0.1763111 -0.2018864 0.9618762 -0.1778663 -0.2077447 0.9690436 -0.1046501 -0.2236137 0.9786081 -0.01123118 -0.2054268 0.9634436 -0.1501566 -0.2218776 0.9728956 -0.02188235 -0.2302074 0.9775034 0.0780074 -0.1959645 0.9692131 -0.07867717 -0.2333155 0.9734199 0.08517992 -0.2125989 0.9704843 0.1695959 -0.1714576 0.97166 0.0116887 -0.236094 0.9671133 0.1832354 -0.1763992 0.959531 0.2489775 -0.1315692 0.9810776 0.1936152 -6.10389e-5 0.9807575 0.1952298 -1.83114e-4 0.9789648 0.2040209 0.001892149 0.979092 0.2004207 0.03479206 0.9458764 0.3243868 0.009552419 0.9480248 0.3175851 0.01971554 0.9431017 0.3318038 0.021577 0.969088 0.2426306 0.04471117 0.9486353 0.3088566 0.06854659 0.9477267 0.3119923 0.06689691 0.9506105 0.2975007 0.0885055 0.9321023 0.3621655 0.004638791 0.9471184 0.3208434 -0.005157649 0.9477787 0.3189273 0.001098692 0.9439322 0.3295171 -0.0202648 0.9476753 0.3192285 0.002197325 0.9856466 0.1567158 0.06277787 0.9911538 0.09341752 0.09427207 0.9796379 0.1776831 0.09348046 0.9936462 0.02163815 0.1104492 0.985282 0.1106931 0.1302559 0.9920903 -0.05169963 0.1143862 0.9860857 0.04049813 0.1612296 0.9800947 -0.1387404 0.142006 0.9817382 -0.03466963 0.1870515 0.9877013 -0.1146311 0.1063297 0.9817501 -0.1602576 0.1023927 0.9796282 -0.1728289 0.102269 0.9665011 -0.1451476 0.2116786 0.969063 -0.1304678 0.2095114 0.9658357 -0.1514354 0.2103066 0.9821757 -0.1723736 0.07495564 0.9645099 -0.1702632 0.2018195 0.9636161 -0.1682223 0.2077143 0.968354 -0.1771048 0.1758534 0.9642441 -0.1645883 0.2077115 0.9544923 0.2780617 0.1078248 0.9569794 0.2628283 0.1229299 0.9403318 0.3370863 0.04635888 0.9426101 0.3290559 0.05664324 0.9620465 0.2283422 0.1494204 0.9632787 0.2230651 0.1494527 0.9678084 0.1745973 0.1812809 0.9688397 0.1799426 0.1702069 0.971748 0.1198167 0.2033465 0.973385 0.1344988 0.1855578 0.9740135 0.065921 0.2166848 0.9766542 0.08759093 0.1961488 0.9746733 0.01419115 0.2231827 0.9783933 0.04052984 0.2027409 0.9739598 -0.03314381 0.2242857 0.9784663 -0.005310237 0.2063382 0.9721897 -0.07513827 0.2218136 0.9768905 -0.04938012 0.2079581 0.9695273 -0.1123709 0.2176919 0.9737338 -0.09161752 0.2084436 0.9838367 -0.1714245 0.05175995 0.9847795 -0.170783 0.03228884 0.9852209 -0.170938 0.01095634 0.9817755 -0.1893417 0.01632779 0.9779015 -0.1728616 0.1175911 0.9782731 -0.1707873 0.1175307 0.979365 -0.1791484 0.09354168 0.9751488 -0.1869605 0.1188722 0.9784947 -0.1872635 0.08649033 0.9790055 -0.1841853 0.08731639 0.9766537 -0.1964233 0.08698046 0.9795522 -0.181255 0.08731609 0.9730564 -0.1753351 0.1497291 0.974121 -0.1747546 0.14335 0.9679511 -0.1789653 0.1761881 0.9763042 -0.2160748 0.01190239 0.9658947 -0.2586177 0.01281791 0.960779 -0.2484883 0.123115 0.9398728 -0.3395884 0.03631794 0.9418489 -0.3133392 0.1214048 0.9555184 -0.2946301 0.01333677 0.9238095 -0.3822197 0.02200418 0.9407871 -0.3387945 0.01174992 0.908579 -0.4177126 6.40897e-4 0.9255411 -0.3786457 0.001190185 0.9137102 -0.4061477 -0.01333677 0.9099156 -0.4144747 -0.01626646 0.9123004 -0.4089833 -0.02099692 0.8865693 -0.4604361 0.04464888 0.8832334 -0.4675277 0.0362876 0.8764177 -0.4809508 0.02404904 0.8702192 -0.4925769 0.009308278 0.8705696 -0.4919748 0.008331775 0.8703445 -0.4924261 0.004120051 0.8735171 -0.4865657 0.01489329 0.9747678 -0.2058487 0.08633744 0.9711083 -0.2221158 0.08725321 0.9773762 -0.1932473 0.08597248 0.9697427 -0.225963 0.09241163 0.9643045 -0.250743 0.0851171 0.9576199 -0.2758597 0.08285862 0.9641801 -0.24531 0.1008951 0.9490749 -0.3040592 0.08249241 0.9569656 -0.270188 0.1059022 0.9393889 -0.3330588 0.08136487 0.9479058 -0.2995491 0.1083748 0.9287517 -0.36229 0.07852518 0.9370607 -0.3324759 0.1066645 0.9174531 -0.3910666 0.07312279 0.9245459 -0.3679689 0.099065 0.9058309 -0.4186885 0.06457793 0.9105526 -0.4047206 0.08423411 0.8942593 -0.4444745 0.05237007 0.8955202 -0.440756 0.06146532 0.9113518 -0.4115762 -0.006561517 0.9112838 -0.4117257 0.006622493 0.9099116 -0.4144868 0.01617538 0.9123231 -0.4089325 0.02099746 0.9154003 -0.4024599 0.00827074 0.8704376 -0.4922744 -0.002075254 0.8711488 -0.4909978 -0.004577875 0.8709182 -0.491385 -0.006500482 0.9256249 -0.3784414 8.85064e-4 0.8802279 -0.4733796 -0.03332668 0.8816071 -0.4707581 -0.03399831 0.8972437 -0.43823 -0.05392801 0.8682332 -0.4961463 -0.003143429 0.8703387 -0.492453 8.52607e-4 0.8703853 -0.4923709 5.7987e-4 0.8702362 -0.492617 0.004211664 0.8703821 -0.4923768 4.40669e-6 0.8704062 -0.4923343 1.51006e-4 0.8704165 -0.4923156 -8.3146e-4 0.8703978 -0.4923493 -3.50202e-5 0.8701968 -0.4927044 -3.26912e-4 0.9407864 -0.3388552 -0.009918749 0.9673371 -0.2532179 -0.01181089 0.9555276 -0.2945719 -0.0139473 0.976424 -0.2156776 -0.00891149 0.9798873 -0.1934931 -0.04880052 0.9835757 -0.1801859 -0.01059019 0.9853037 -0.1704482 -0.01113939 0.9753596 -0.2028298 -0.08679628 0.9770193 -0.1953245 -0.08533239 0.9788769 -0.1860153 -0.08484369 0.9846683 -0.1712121 -0.03338789 0.9804166 -0.1732857 -0.09357064 0.9813683 -0.1711504 -0.08731478 0.9779614 -0.1751809 -0.1135929 0.9772815 -0.1931246 -0.08731502 0.9185512 -0.3842607 -0.09277677 0.9176355 -0.3902553 -0.07513946 0.8939495 -0.444701 -0.05563718 0.8828588 -0.4682253 -0.03640937 0.9373024 -0.3331464 -0.102361 0.939347 -0.3314983 -0.08795601 0.957197 -0.2709169 -0.1018723 0.9567947 -0.2762256 -0.09079337 0.9512931 -0.2898955 -0.1048921 0.9663866 -0.2399104 -0.09241175 0.9698791 -0.2267598 -0.08896428 0.9718174 -0.2190656 -0.08707076 0.9838445 -0.1714258 -0.05160778 0.9770214 -0.1762142 -0.1199074 0.974121 -0.1747546 -0.14335 0.973052 -0.1753343 -0.149759 0.9777779 -0.1808574 -0.1060241 0.9811778 -0.181617 -0.06561529 0.9779702 -0.1810061 -0.103977 0.9817463 -0.1817732 -0.05597245 0.9825213 -0.1819529 -0.03930813 0.9800639 -0.1937055 -0.04419183 0.9791935 -0.1925731 -0.06399774 0.9810649 -0.1890044 -0.04229933 0.9800226 -0.1940391 -0.04364198 0.974944 -0.1803699 -0.130196 0.9725703 -0.1798162 -0.1475579 0.9713108 -0.1794846 -0.1560152 0.9791535 -0.1723124 -0.1075503 0.9731025 -0.1695032 -0.1560138 0.9765868 -0.1638886 -0.1393511 0.9815353 -0.1566867 -0.1097173 0.9807258 -0.1321775 -0.1438967 0.9805076 -0.118596 -0.1566529 0.985655 -0.1268692 -0.1113043 0.9846815 -0.08679747 -0.1512241 0.9896767 -0.09177124 -0.1100828 0.9858248 -0.04205513 -0.1624221 0.9875948 -0.01580882 -0.1562267 0.9931496 -0.03128194 -0.1125846 0.9870851 0.07443648 -0.1418536 0.9961335 0.0145269 -0.08664286 0.9837057 0.1596171 -0.08273845 0.9481151 0.3111146 -0.06546407 0.9970492 0.05804675 -0.0502339 0.9750515 0.2151284 -0.05472052 0.9941465 0.1000403 -0.04080349 0.9992439 -0.03888082 0 0.995797 0.09158682 -4.27263e-4 0.9753038 0.2208678 -1.22077e-4 0.999105 0.04171961 -0.006988823 0.982877 -0.1757306 -0.0554232 0.9847531 -0.1651988 -0.05450671 0.9876204 -0.1458495 -0.05774164 0.9908183 -0.1223797 -0.05746656 0.9941197 -0.09662252 -0.04889112 0.9972252 -0.06921613 -0.02740567 0.9986874 -0.04727458 -0.01971554 0.9998701 -0.01608359 0.001129209 0.998896 -0.04696911 -9.76617e-4 0.998967 -0.04544222 3.05187e-5 0.983259 -0.1822137 1.9895e-6 0.9831807 -0.1821699 -0.01303172 0.9832549 -0.1822356 4.63548e-6 0.9832536 -0.1822428 1.79172e-6 0.9830405 -0.1833839 -0.001324057 0.9832575 -0.1822218 2.38776e-5 0.9832695 -0.1821568 1.60455e-4 0.9832555 -0.182233 1.02839e-5 0.9832533 -0.1822443 0 0.9832524 -0.1822494 -3.19083e-5 0.983251 -0.1822566 -5.29431e-5 0.9832562 -0.1822288 3.36319e-5 0.9832552 -0.1822345 -4.32061e-6 0.9832545 -0.1822377 1.81656e-5 0.9832586 -0.1822162 1.43604e-6 0.9832577 -0.1822203 1.34262e-6 0.9832522 -0.1822499 -1.74619e-6 0.9832496 -0.1822646 -1.87917e-6 0.9832558 -0.1822311 -6.14508e-7 0.9832561 -0.1822291 0 0.9832471 -0.1822781 5.43932e-7 0.9832636 -0.1821889 3.45851e-7 0.9832737 -0.1821346 2.16835e-6 0.9832568 -0.1822261 2.55019e-6 0.9831852 -0.1826112 5.76192e-7 0.9832276 -0.1823829 1.06254e-6 0.9828634 -0.1838768 -0.01300108 0.983255 -0.1822351 3.13647e-7 0.9832552 -0.1822342 3.13542e-7 0.9832556 -0.1822322 0 0.9975791 -0.06549406 0.02337765 0.9970499 -0.07089519 0.02942013 0.9986235 -0.0508452 0.01287913 0.9988572 -0.04626679 0.01199394 0.98325 -0.1822623 -6.85447e-7 0.9765301 -0.2102788 -0.04660314 0.9832577 -0.1822204 -9.56237e-7 0.9832581 -0.1822187 -1.25748e-6 0.9760794 -0.212288 -0.0469377 0.9706602 -0.2350581 -0.05066168 0.98325 -0.1822618 -1.07982e-6 0.9799757 -0.1959341 -0.03546345 0.9832611 -0.1822022 -6.67354e-7 0.969668 -0.2391819 -0.05035728 0.9620814 -0.2687199 -0.04678565 0.9832579 -0.1822197 0 0.9832535 -0.1822434 -9.11217e-7 0.9750491 -0.2172947 -0.04541212 0.9832427 -0.1823019 0 0.959609 -0.2776924 -0.04513758 0.9507272 -0.3083332 -0.03238064 0.9832543 -0.1822393 -5.25949e-7 0.9666574 -0.2511405 -0.05002051 0.9832575 -0.1822217 -1.0809e-6 0.950895 -0.3079719 -0.03085517 0.9612569 -0.2743963 -0.02630734 0.9832847 -0.182075 0 0.9823933 -0.1868249 -6.22683e-7 0.9641059 -0.2655182 1.22077e-4 0.9641059 -0.2655182 0 0.9624661 -0.2714022 -1.22075e-4 0.9641315 -0.2654253 0 0.9637946 -0.2651504 -0.02819967 0.9641315 -0.2654253 1.22077e-4 0.9308338 -0.3623843 0.04718255 0.964094 -0.2653014 0.0117498 0.9511757 -0.3074147 0.02758884 0.9572577 -0.2864814 0.03982722 0.9618338 -0.2697261 0.0460835 0.9188792 -0.3913202 0.050296 0.9555505 -0.2947832 -0.005127191 0.9497738 -0.3121457 0.02224814 0.9673633 -0.2485779 0.0491662 0.9705069 -0.2357294 0.05047851 0.9607314 -0.2742418 0.04226851 0.974881 -0.217939 0.04593163 0.9764932 -0.210369 0.04696905 0.9697573 -0.2392729 0.04815977 0.9794223 -0.1981307 0.03842365 0.9801313 -0.1937068 0.04266613 0.9759764 -0.2127804 0.0468471 0.9818397 -0.1867787 0.0332356 0.9819125 -0.1886063 0.01660221 0.9798666 -0.1947708 0.043886 0.983255 -0.1822352 -3.33047e-6 0.9817487 -0.1818346 0.05572843 0.983201 -0.1820155 0.01364195 0.981747 -0.1818343 0.05575883 0.9832559 -0.18223 0 0.9832557 -0.1822315 2.13838e-5 0.9832541 -0.1822401 -2.47659e-5 0.9832508 -0.1822575 -1.07868e-4 0.9832558 -0.1822306 1.70432e-5 0.9832513 -0.1822553 -2.73369e-5 0.9832551 -0.1822349 -2.53271e-6 0.9832562 -0.1822284 0 0.9832027 -0.1820158 0.01351994 0.9818766 -0.1890325 0.01361131 0.9830451 -0.1749039 0.05505609 0.9830383 -0.1747196 0.05575764 0.9847208 -0.1653205 0.05472022 0.9859707 -0.1588197 0.05136311 0.9876319 -0.1456376 0.05807799 0.9836899 -0.172402 0.05130249 0.9886044 -0.1415475 0.05124151 0.9908464 -0.1221085 0.05755978 0.9917104 -0.1188404 0.04886066 0.9941416 -0.09641104 0.04886168 0.9949285 -0.09213769 0.04034644 0.9832558 -0.1822306 0 0.9832544 -0.1822385 -5.54869e-6 0.9832583 -0.1822177 0 0.9832555 -0.1822327 0 0.9832513 -0.1822552 0 0.9832456 -0.1822862 -1.06376e-5 0.9832537 -0.1822422 -2.40558e-6 0.9832541 -0.18224 0 0.9832548 -0.1822365 0 0.9832553 -0.1822339 0 0.9832786 -0.1821077 0 0.9832931 -0.1820298 0 0.9832428 -0.1823011 0 0.983232 -0.182359 0 0.9832158 -0.1824463 0 0.9832504 -0.1822597 0 0.9832922 -0.1820345 0 0.9832858 -0.1820693 0 0.983257 -0.1822248 0 0.9832523 -0.1822496 0 0.9832495 -0.1822652 0 0.9832221 -0.1824124 0 0.9832614 -0.1822007 0 0.9832662 -0.1821746 0 0.9833667 -0.1816314 0 0.9807547 0.1952292 0.00238043 0.9745861 0.2239161 0.006592035 0.97518 0.2213252 0.006256401 0.9828909 0.178688 0.04467958 0.9787806 0.2026168 0.03058022 0.9744725 0.2236129 0.02002048 0.9904508 0.1378525 -0.002014219 0.990653 0.1363902 -0.002105772 0.9851173 0.1545168 0.0752899 0.933157 0.3594254 0.005615532 0.9835062 0.1623612 0.07971566 0.9884057 0.1072118 0.107517 0.9882621 0.08676511 0.1257377 0.9873566 0.0769999 0.1385571 0.9892023 0.0307933 0.1432852 0.9878356 0.01635807 0.1546392 0.9875193 -0.01739609 0.1565344 0.9860524 -0.04068237 0.1613867 0.9856811 -0.04825097 0.161569 0.9847032 -0.08633887 0.1513448 0.9818034 -0.09793615 0.1626979 0.9804838 -0.1137138 0.1603773 0.9799406 -0.1330026 0.1484148 0.9765151 -0.1438664 0.1603771 0.9771636 -0.1688932 0.1289436 0.9746385 -0.1642556 0.1519868 0.9741927 -0.1630928 0.1560429 0.971331 -0.1794827 0.1558915 0.9712969 -0.1794821 0.1561045 0.9725511 -0.1798183 0.1476817 0.9749324 -0.1803678 0.130286 0.9779658 -0.1810109 0.1040103 0.9812068 -0.1816473 0.06509637 0.9812126 -0.1816484 0.06500518 0.9802548 -0.1867486 0.06500643 0.9054453 -0.4244618 -0.00100708 0.9050627 -0.4252781 0 0.9053589 -0.4246473 0 0.8748413 -0.4839476 0.02114999 0.9235128 -0.383566 0.001098692 0.9067685 -0.4216286 -6.40912e-4 0.9051437 -0.4251044 -0.001098692 0.9048393 -0.4247691 -0.02893239 0.9094161 -0.4158874 -1.83116e-4 0.9146202 -0.4043141 3.35708e-4 0.8658531 -0.5002971 -0.00112915 -0.157662 -0.739266 -0.6546974 -0.1926056 -0.7202186 -0.6664746 -0.2630761 -0.6836929 -0.6807019 -0.1148444 -0.7562093 -0.6441726 -0.3053174 -0.6536369 -0.6924883 -0.3731904 -0.6108444 -0.6982823 -0.2286499 -0.7026439 -0.6738032 -0.3806376 -0.6040089 -0.7002059 -0.4301076 -0.5652773 -0.7038957 -0.4457082 -0.5524658 -0.7043619 -0.4782014 -0.5199513 -0.7077954 -0.1935532 -0.8388524 -0.5087866 -0.1644713 -0.8074327 -0.5665702 -0.2025864 -0.7905997 -0.5778504 -0.2512322 -0.8099124 -0.5300229 -0.279282 -0.7446097 -0.6062657 -0.3466672 -0.7005676 -0.6237203 -0.3626013 -0.7417442 -0.5642126 -0.4196411 -0.6491771 -0.6344057 -0.4674406 -0.6570903 -0.5913813 -0.4874251 -0.5912521 -0.6425247 -0.5158948 -0.6102293 -0.6012262 -0.5181803 -0.5618529 -0.6448338 -0.2200461 -0.864406 -0.4520865 -0.294541 -0.8245071 -0.4831497 -0.4399575 -0.7218282 -0.5342298 -0.5112578 -0.6583604 -0.5524283 -0.7392993 -0.4513803 -0.4996924 -0.7191495 -0.4333391 -0.543177 -0.7128715 -0.4298959 -0.5540792 -0.7178304 -0.4325416 -0.5455523 -0.745871 -0.4483343 -0.4926185 -0.7425659 -0.4464978 -0.4992352 -0.7427421 -0.4465852 -0.4988949 -0.7224829 -0.4350523 -0.5373529 -0.7207133 -0.4341676 -0.5404359 -0.7186654 -0.4332196 -0.5439126 -0.7177872 -0.432827 -0.5453828 -0.8213604 -0.299728 -0.4853147 -0.7815566 -0.3689421 -0.5030419 -0.7674354 -0.3517641 -0.5360084 -0.7464414 -0.4486644 -0.4914525 -0.8339306 -0.3227075 -0.4476826 -0.7918823 -0.3794456 -0.4784804 -0.7891631 -0.3763006 -0.4854064 -0.7772373 -0.2626193 -0.5717808 -0.7327884 -0.3164196 -0.6024118 -0.8076658 -0.2883169 -0.5143436 -0.7445738 -0.2364313 -0.6242677 -0.6934384 -0.2818496 -0.6631018 -0.7096056 -0.2104614 -0.672433 -0.6510149 -0.2482164 -0.7173342 -0.6731492 -0.1852174 -0.7159363 -0.6067847 -0.2212954 -0.7634402 -0.6163591 -0.1953513 -0.7628496 -0.5862655 -0.2051166 -0.7837219 -0.5803518 -0.1966652 -0.7902624 -0.7493628 -0.4502769 -0.4854958 -0.7946673 -0.3828064 -0.4711298 -0.7494103 -0.4503176 -0.4853847 -0.7915712 -0.4729529 -0.3869503 -0.7129832 -0.4354441 -0.5495848 -0.7770438 -0.4656891 -0.4234814 -0.8384249 -0.3141957 -0.4453369 -0.8285616 -0.4099623 -0.3813354 -0.8197566 -0.4089016 -0.4009971 -0.8461224 -0.335043 -0.4145157 -0.7314574 -0.4445449 -0.517059 -0.7419549 -0.4588578 -0.4888277 -0.7124146 -0.4359393 -0.5499293 -0.7281665 -0.4463793 -0.5201146 -0.7426486 -0.4594936 -0.4871743 -0.9402721 0.1339191 -0.3129764 -0.9404221 0.1207954 -0.3178281 -0.9329707 0.2064316 -0.2948761 -0.9252043 0.1234175 -0.3588386 -0.9326249 0.1992879 -0.3008241 -0.934223 0.135963 -0.3297599 -0.9323829 0.2072538 -0.2961554 -0.9136461 0.2606319 -0.3119648 -0.9278601 0.266825 -0.2605382 -0.9269527 0.2668884 -0.2636839 -0.921451 0.2502838 -0.29713 -0.9294629 0.1933392 -0.3141954 -0.9297215 -0.0160228 -0.3679149 -0.927794 -0.0285052 -0.3720027 -0.903522 -0.01672452 -0.4282153 -0.9191228 -0.01083439 -0.3938225 -0.8954554 -0.1667553 -0.4127378 -0.8921075 -0.1775913 -0.4154582 -0.86584 -0.154429 -0.4758915 -0.8813169 -0.158214 -0.4452516 -0.8636898 -0.3275917 -0.3830449 -0.9034007 -0.1857097 -0.386496 -0.9154433 -0.1775586 -0.36116 -0.9365084 -0.02749764 -0.3495655 -0.9491068 0.1337642 -0.2851379 -0.9436596 0.1243665 -0.3066588 -0.9449656 -0.0205394 -0.3265247 -0.9325561 0.2070753 -0.2957347 -0.9390213 0.207471 -0.2742169 -0.9361014 0.2036821 -0.2867541 -0.9287138 0.2666112 -0.2576997 -0.9313184 0.2652713 -0.249554 -0.901443 0.2287712 -0.3675111 -0.8968641 0.2164413 -0.3857306 -0.8802922 0.2052102 -0.4277553 -0.9113944 0.203685 -0.3575932 -0.9096987 0.2063432 -0.3603758 -0.9101116 0.218456 -0.3520994 -0.8853722 0.2186115 -0.4102743 -0.860889 0.1921191 -0.4711267 -0.8670181 0.2070112 -0.4532396 -0.83311 0.1750269 -0.5246841 -0.7949895 0.1507943 -0.5875824 -0.8011949 0.1670325 -0.574619 -0.8460873 0.1954762 -0.4959086 -0.7919762 0.150155 -0.5918 -0.7881495 0.1496645 -0.59701 -0.7840847 0.1495108 -0.6023768 -0.7798028 0.1497285 -0.6078562 -0.7752634 0.1503709 -0.6134781 -0.7704581 0.1514669 -0.6192352 -0.768481 0.1519871 -0.6215601 -0.7767103 0.2339286 -0.5848064 -0.7885935 0.1923644 -0.5840517 -0.7865194 0.1907166 -0.5873793 -0.7926523 0.1889461 -0.5796567 -0.7914977 0.1947156 -0.5793249 -0.7721976 0.2322819 -0.5914017 -0.7836764 0.1885486 -0.5918622 -0.7676292 0.2307587 -0.5979096 -0.7803414 0.1858304 -0.597105 -0.7629938 0.2292643 -0.6043826 -0.7768969 0.1829931 -0.6024491 -0.758468 0.2275526 -0.6106932 -0.7734501 0.1808267 -0.6075168 -0.7693873 0.1784759 -0.613343 -0.753763 0.2255674 -0.6172202 -0.7654476 0.175698 -0.6190479 -0.7490236 0.223825 -0.6235913 -0.7630643 0.1739883 -0.6224637 -0.7459593 0.2248071 -0.6269025 -0.8977598 0.1107856 -0.426326 -0.9044263 0.1659005 -0.3930523 -0.9086797 0.170633 -0.3810326 -0.8788114 0.07529181 -0.4711918 -0.9143877 0.1754247 -0.3648579 -0.9213204 0.23561 -0.3092839 -0.9123592 0.1168869 -0.3923496 -0.9234926 0.1862305 -0.3353798 -0.8991892 0.2518145 -0.3578384 -0.8824044 0.241316 -0.4038923 -0.8184387 0.1844287 -0.5441914 -0.8252747 0.2018246 -0.527436 -0.8628717 0.2307562 -0.449671 -0.8145523 0.1839991 -0.5501356 -0.810556 0.1840299 -0.5559964 -0.8063626 0.1845225 -0.5618994 -0.801972 0.185493 -0.5678321 -0.7974401 0.1869615 -0.5737028 -0.8023431 0.2435412 -0.5449158 -0.8150041 0.2139672 -0.538504 -0.8120449 0.2110682 -0.5440896 -0.8148679 0.2271253 -0.5332959 -0.80645 0.2450113 -0.5381522 -0.8175519 0.2164431 -0.5336305 -0.7983575 0.2417748 -0.5515164 -0.8089522 0.2086624 -0.5495967 -0.8054684 0.2061281 -0.5556365 -0.7941923 0.2398172 -0.5583425 -0.8020681 0.2033476 -0.5615484 -0.7900188 0.2385072 -0.5647875 -0.798606 0.2004832 -0.5674812 -0.7855079 0.2371051 -0.571628 -0.7951137 0.197611 -0.5733621 -0.7811152 0.2355492 -0.5782523 -0.9139279 0.2758325 -0.2977453 -0.9340745 0.262802 -0.2417436 -0.9378596 0.2581632 -0.231886 -0.9312704 0.2699444 -0.2446743 -0.8982703 0.2652115 -0.3503904 -0.8793812 0.2543473 -0.4024876 -0.8414475 0.2204714 -0.4933139 -0.8481923 0.2322213 -0.4760705 -0.8596468 0.2574942 -0.441253 -0.8381458 0.2200732 -0.4990787 -0.8345811 0.2201052 -0.5050031 -0.8314784 0.2205047 -0.5099229 -0.8285012 0.2211717 -0.5144599 -0.8253361 0.2221507 -0.5191044 -0.8220069 0.2234623 -0.5238028 -0.8184295 0.2251695 -0.5286511 -0.8335363 0.2555055 -0.4898308 -0.8393584 0.237955 -0.4887279 -0.8373361 0.2359776 -0.4931359 -0.6387841 0.6200457 -0.45552 -0.8008228 0.3718149 -0.4695068 -0.8221837 0.3236547 -0.468254 -0.8211009 0.326072 -0.4684768 -0.8113876 0.3495077 -0.4685027 -0.791422 0.3947344 -0.466729 -0.7705488 0.4380726 -0.4629763 -0.6596495 0.61445 -0.4327977 -0.8411118 0.2394849 -0.4849516 -0.8298414 0.2539178 -0.4968793 -0.8345116 0.2333483 -0.4991383 -0.8261905 0.2525785 -0.5036005 -0.8317738 0.2300852 -0.5051864 -0.8223053 0.2511718 -0.5106142 -0.8296001 0.2280385 -0.5096686 -0.8273147 0.2258421 -0.5143402 -0.8184061 0.2495869 -0.5176077 -0.8249384 0.2233407 -0.519226 -0.8145228 0.2480893 -0.5244087 -0.8226425 0.2212635 -0.5237384 -0.8200721 0.2189728 -0.5287086 -0.8105677 0.2464755 -0.5312531 -0.9415696 0.2096039 -0.2636529 -0.9455711 0.2124429 -0.2465022 -0.956808 0.1376722 -0.2560563 -0.9480411 0.2158606 -0.2337142 -0.9342639 0.2982674 -0.1954165 -0.9332231 0.2982664 -0.2003295 -0.9277982 0.2963766 -0.2266086 -0.9603378 0.1467958 -0.2370707 -0.9670636 0.1427996 -0.2107049 -0.9662468 0.1352623 -0.2192519 -0.9500489 0.223855 -0.2174766 -0.9517369 0.2246203 -0.2091471 -0.9275019 0.2952405 -0.2292889 -0.9221688 0.288895 -0.2571855 -1 -1.72177e-6 0 -0.9348829 0.298413 -0.1922075 -0.921916 0.2872137 -0.2599603 -0.9158303 0.2814207 -0.2864564 -0.8629399 0.2595381 -0.4335605 -0.9154712 0.2792772 -0.2896841 -0.8661553 0.278576 -0.4149342 -0.8622296 0.261794 -0.4336174 -0.8650332 0.2786393 -0.4172265 -0.8597275 0.2577046 -0.4409728 -0.859479 0.2585884 -0.44094 -0.8594567 0.2566681 -0.4421039 -0.8548172 0.2615815 -0.448177 -0.8567911 0.2544065 -0.4485381 -0.8550159 0.2540083 -0.4521366 -0.8510549 0.2623725 -0.4548258 -0.8528081 0.2514507 -0.4577019 -0.6874773 0.576967 -0.4410036 -0.7486349 0.4809819 -0.4562919 -0.847699 0.2609689 -0.4618458 -0.8503059 0.2490092 -0.4636534 -0.6978303 0.5635136 -0.4421373 -0.7462915 0.4853809 -0.4554718 -0.8441259 0.2598696 -0.4689555 -0.8478527 0.2466253 -0.4693846 -0.8407183 0.2581942 -0.4759503 -0.8456419 0.2444939 -0.4744604 -0.8432195 0.2420185 -0.4800085 -0.8372741 0.2569138 -0.4826671 -0.8549771 -0.006866872 -0.5186203 -0.822272 -0.03076308 -0.5682628 -0.8796129 -0.01297044 -0.4755134 -0.7768736 -0.1063299 -0.6206138 -0.7299777 -0.1230821 -0.6722972 -0.8075697 -0.1228094 -0.5768442 -0.8374717 -0.1389224 -0.528528 -0.8854793 -0.3372048 -0.3197174 -0.8939963 -0.3435841 -0.2876121 -0.8580822 -0.4207704 -0.2943592 -0.8724278 -0.4290723 -0.2340228 -0.8692461 -0.425803 -0.251203 -0.9060038 -0.3480146 -0.2409214 -0.8490433 -0.4168918 -0.3245408 -0.8193007 -0.4908785 -0.296285 -0.8110501 -0.4859586 -0.3256408 -0.8269408 -0.4970007 -0.2629815 -0.8370937 -0.5015604 -0.2184293 -0.9429278 -0.1825671 -0.2784896 -0.9092357 -0.3500276 -0.2253251 -0.9516196 -0.1919963 -0.2399115 -0.9342503 -0.1828093 -0.306198 -0.9650748 -0.01785361 -0.2613655 -0.9553842 -0.1891907 -0.2268213 -0.9720857 -0.02923703 -0.2327976 -0.9582756 -0.02288943 -0.2849282 -0.9747787 -0.02377432 -0.221904 -0.7708308 -0.4642015 -0.4362761 -0.7465559 -0.4587922 -0.481834 -0.7846775 -0.4805848 -0.3915605 -0.845311 -0.5071011 -0.1682198 -0.8534026 -0.5113763 -0.1009873 -1 -1.37105e-6 0 -0.8539188 -0.5104896 0.1011091 -0.8533553 -0.5116286 0.1001039 -0.8586187 -0.5109169 0.04168879 -0.8573862 -0.5141326 -0.02359157 -0.8532801 -0.5133903 -0.09134328 -0.8275995 -0.4958516 0.2630788 -0.8197121 -0.4907469 0.2953637 -0.8373616 -0.4996641 0.2217236 -1 2.38131e-6 0 -0.8447044 -0.5066761 0.1724932 -0.7902141 -0.4744886 0.3878434 -0.7716795 -0.4627636 0.4363034 -0.8105888 -0.4873604 0.3246933 -0.7764543 -0.4661899 0.4240116 -0.7334639 -0.4415188 0.5168093 -0.7431659 -0.456868 0.4888519 -0.7463406 -0.4581808 0.4827486 -0.7276784 -0.4489431 0.5185888 -0.7437901 -0.4572122 0.4875791 -0.7138761 -0.4303521 0.5524292 -0.7086271 -0.439325 0.5521243 -0.7464302 -0.4486576 0.4914757 -0.7494854 -0.4503687 0.4852214 -0.7493131 -0.4502531 0.4855946 -0.7391586 -0.4608487 0.4911854 -0.7758015 -0.4937418 0.3928754 -0.7435514 -0.4600234 0.4852937 -0.7459102 -0.4483518 0.4925431 -0.8630228 -0.329272 0.3831079 -0.8222513 -0.4005659 0.4042893 -0.8322722 -0.4056373 0.3778644 -0.8436061 -0.3371434 0.4179272 -0.7907763 -0.3807543 0.4792694 -0.7940556 -0.3833245 0.4717394 -0.8387928 -0.3138606 0.44488 -0.8854725 -0.3376295 0.3192877 -0.8499999 -0.416195 0.3229273 -0.8940333 -0.3432815 0.2878583 -0.8576075 -0.421464 0.2947501 -0.9094721 -0.349689 0.224896 -0.8684213 -0.4272676 0.251569 -0.8716756 -0.4295965 0.2358569 -0.906477 -0.3474594 0.2399408 -1 -6.93821e-6 0 -0.9094371 -0.359667 0.2087197 -0.8738512 -0.4313864 0.2242538 -0.929486 -0.3630843 0.06500542 -0.8870128 -0.4381656 0.1456686 -0.8914512 -0.4391791 0.1115191 -0.9272747 -0.3505472 0.1314476 -0.8970047 -0.4399571 0.04266506 -0.9290142 -0.3643115 -0.06488448 -0.8975469 -0.4401517 -0.02600258 -0.8941269 -0.4370073 -0.09778416 -0.9262005 -0.3526203 -0.1334609 -0.890128 -0.4330699 -0.141854 -0.909308 -0.3597068 -0.2092134 -0.8741623 -0.4314199 -0.2229735 -1 3.50228e-6 0 -0.7333435 -0.4605333 0.5001165 -0.7240344 -0.4586405 0.5151924 -0.7108297 -0.4666737 0.5262477 -0.714266 -0.4702363 0.5183647 -0.7137834 -0.4697518 0.5194676 -0.5635403 -0.676401 0.4742406 -0.6651065 -0.5465697 0.5088173 -0.6984784 -0.4563745 0.5512262 -0.6995888 -0.4572368 0.5490992 -0.7016705 -0.4588585 0.5450757 -0.7022875 -0.4593206 0.5438905 -0.703161 -0.4600149 0.5421726 -0.7060039 -0.4620934 0.5366827 -0.7111255 -0.4657825 0.5266376 -0.7131757 -0.4672814 0.5225214 -0.692443 -0.4543346 0.5604488 -0.6887541 -0.4591591 0.5610623 -0.6938317 -0.4565116 0.5569515 -0.5831951 -0.5701938 0.5785866 -0.5802085 -0.6004125 0.5503299 -0.6388532 -0.5298089 0.5578254 -0.6389819 -0.520964 0.5659494 -0.6807458 -0.4555701 0.573621 -0.6747624 -0.4658544 0.5724295 -0.6898553 -0.4502187 0.566924 -0.6932528 -0.4549252 0.5589665 -0.5579911 -0.2233734 0.7992185 -0.7059218 -0.457491 0.5407184 -0.7072793 -0.4558023 0.5403706 -0.697623 -0.4379905 0.566998 -0.6936488 -0.4525137 0.5604309 -0.6954016 -0.4500609 0.5602338 -0.7053363 -0.4368562 0.5582628 -0.7082864 -0.4421297 0.5503197 -0.7195336 -0.4589865 0.5211552 -0.7056666 -0.4381957 0.5567936 -0.7103373 -0.4442393 0.5459603 -0.7220509 -0.45919 0.5174815 -0.7125646 -0.4463447 0.5413208 -0.7232496 -0.4579136 0.5169383 -0.7158929 -0.4439653 0.5388805 -0.7231365 -0.4561492 0.5186538 -0.7223587 -0.4553768 0.5204132 -0.6358104 -0.3837507 0.6696869 -0.718546 -0.4605055 0.5211778 -0.7400016 -0.4732019 0.4779934 -0.7307196 -0.4580616 0.5061903 -0.4793604 -0.752352 0.4518629 -0.5512145 -0.6923676 0.465607 -0.5812628 -0.7543659 0.3050668 -0.6055029 -0.6997769 0.3790496 -0.5240772 -0.7740303 0.3552751 -0.6388627 -0.7020989 0.3145024 -0.3446513 -0.8479099 0.4028205 -0.329455 -0.8546605 0.4012668 -0.4525104 -0.8463626 0.2809001 -0.3717885 -0.873529 0.3141982 -0.4892593 -0.743884 0.4552605 -0.2552961 -0.8907437 0.3760314 -0.2504422 -0.8904647 0.379936 -0.3122767 -0.9167176 0.2492231 -0.2650325 -0.9202587 0.2878918 -0.2393925 -0.9433786 0.2296263 -0.259352 -0.8321667 0.4901381 -0.2270042 -0.8717901 0.4341096 -0.3040921 -0.8302715 0.4670944 -0.2001779 -0.8616593 0.4663392 -0.3762146 -0.7605475 0.5291787 -0.4489161 -0.7272568 0.5192033 -0.4847984 -0.6730107 0.5585939 -0.243511 -0.9527419 0.1816185 -0.3160878 -0.9290363 0.1923018 -0.4601621 -0.8611178 0.2161645 -0.5922514 -0.7709096 0.2343858 -0.6571046 -0.7145719 0.2400014 -0.1825048 -0.8169379 0.5470872 -0.2414361 -0.7853465 0.5700346 -0.3489563 -0.7182689 0.6019298 -0.4489049 -0.6398016 0.6238096 -0.6177162 -0.5142243 0.5949792 -0.5430321 -0.5479763 0.6362689 -0.6599183 -0.4535469 0.5990018 -0.6615949 -0.4603514 0.5919196 -0.5995322 -0.5071181 0.619187 -0.6527721 -0.4498509 0.6095266 -0.6368537 -0.4531864 0.6237303 -0.5774537 -0.4968525 0.647831 -0.6269914 -0.4538241 0.6331868 -0.6271122 -0.4462849 0.6384044 -0.1926982 -0.7809559 0.5941173 -0.1548269 -0.7979705 0.5824702 -0.2692117 -0.7397292 0.6167055 -0.3423323 -0.6907989 0.6368717 -0.4790577 -0.5831277 0.6560988 -0.4098421 -0.6405671 0.6493871 -0.5422395 -0.519533 0.6603499 -0.5695608 -0.4878897 0.6614865 -0.6588431 -0.3849965 0.6462998 -0.6623547 -0.3795958 0.645905 -0.6268958 -0.4341668 0.6469164 -0.4755576 -0.5244501 0.7062558 -0.5192866 -0.4904763 0.6998389 -0.5499879 -0.4669755 0.6924213 -0.6171233 -0.3953117 0.6803584 -0.6046251 -0.4207441 0.6763157 -0.6172274 -0.4277926 0.6603211 -0.5908534 -0.4120104 0.6936424 -0.5435279 -0.4686627 0.6963713 -0.1918753 -0.7232178 0.6634303 -0.1148746 -0.7562066 0.6441704 -0.1543664 -0.7386881 0.6561335 -0.2290472 -0.6998682 0.6765515 -0.2650301 -0.6838473 0.6797882 -0.3052898 -0.6536431 0.6924948 -0.3729753 -0.6120933 0.6973029 -0.3785918 -0.6039158 0.7013944 -0.4458524 -0.5505326 0.7057829 -0.6321279 -0.4041443 0.6611217 -0.6301938 -0.4323369 0.6449346 -0.64627 -0.4130439 0.6416617 -0.6425296 -0.4362474 0.6299555 -0.6599395 -0.421099 0.6222182 -0.6554069 -0.4400916 0.6138088 -0.6739569 -0.427636 0.6024198 -0.6672791 -0.4451884 0.5971147 -0.6753882 -0.4482038 0.5856314 -0.6862199 -0.4325154 0.5848357 -0.6860842 -0.4494034 0.5721234 -0.4094778 -0.2969836 0.8626289 -0.4342566 -0.2682936 0.8599069 -0.4220499 -0.2629534 0.8675997 -0.4513129 -0.2356361 0.860693 -0.3997347 -0.2896535 0.8696626 -0.4293189 -0.3117269 0.8476507 -0.4546154 -0.2836463 0.8443162 -0.4618214 -0.2432711 0.8529597 -0.4487223 -0.3257303 0.8321948 -0.4745502 -0.2983602 0.8281204 -0.4794865 -0.2559337 0.839399 -0.4677029 -0.3390045 0.8162904 -0.494225 -0.3125758 0.8111955 -0.5106744 -0.279554 0.8130567 -0.4955958 -0.2678946 0.8262066 -0.486205 -0.3514922 0.8000363 -0.5134003 -0.3263763 0.7936615 -0.5249285 -0.2903587 0.8000887 -0.5041151 -0.3632082 0.7835483 -0.5319524 -0.3395584 0.7757105 -0.5385466 -0.3003421 0.7872498 -0.5148538 -0.3701332 0.7732573 -0.5550128 -0.3391847 0.759549 -0.5628967 -0.318987 0.7624924 -0.5510612 -0.3097125 0.7748612 -0.5742871 -0.3275667 0.750263 -0.5770581 -0.3560072 0.7350258 -0.5657168 -0.398773 0.7217651 -0.5849037 -0.3747473 0.7193415 -0.5943698 -0.3431322 0.7273133 -0.5845962 -0.3354065 0.7387489 -0.5786459 -0.4065781 0.7070101 -0.601146 -0.3854634 0.7000297 -0.6119669 -0.356645 0.7059044 -0.5710352 -0.4021753 0.7156633 -0.6035601 -0.3501845 0.7163004 -0.6203649 -0.3628739 0.6953201 -0.6401004 -0.3796533 0.6679335 -0.6286754 -0.3693799 0.6843433 -0.6525636 -0.3894873 0.6499695 -0.663952 -0.3982797 0.6328831 -0.6743168 -0.4059939 0.6168191 -0.6921222 -0.4199794 0.5870129 -0.6835702 -0.4129865 0.601809 -0.7001142 -0.4260808 0.5729705 -0.7075285 -0.4305356 0.5603951 -0.7105544 -0.4310876 0.5561259 -0.5099141 -0.4732301 0.71836 -0.5050612 -0.4690181 0.7245243 -0.4871533 -0.2144304 0.8465822 -0.4777849 -0.2049089 0.8542447 -0.4856281 -0.2113484 0.8482317 -0.5082045 -0.2281914 0.8304559 -0.5022488 -0.2245577 0.835057 -0.5318924 -0.2461085 0.8102599 -0.517057 -0.2354864 0.8229207 -0.5331626 -0.2465305 0.8092963 -0.5613944 -0.271862 0.7816185 -0.5462695 -0.2565474 0.7973539 -0.5596315 -0.2670739 0.7845279 -0.5707638 -0.279034 0.7722493 -0.6038777 -0.307478 0.7353836 -0.5811479 -0.2870642 0.7614862 -0.5931386 -0.294265 0.7493963 -0.6034798 -0.3025944 0.7377322 -0.6121052 -0.3145676 0.7255168 -0.6469448 -0.3457209 0.6796614 -0.618435 -0.3218829 0.7168889 -0.6277524 -0.3268622 0.7064618 -0.6360206 -0.3323848 0.6964182 -0.6452124 -0.339987 0.6841857 -0.6560993 -0.3543266 0.6663232 -0.6858311 -0.3844524 0.6179255 -0.6660799 -0.3647035 0.6506373 -0.6778393 -0.3732237 0.6334334 -0.6876291 -0.3827113 0.6170076 -0.6955654 -0.395286 0.5999484 -0.7195873 -0.4227248 0.5509064 -0.702187 -0.4035561 0.58658 -0.7105505 -0.4099353 0.5719013 -0.7173005 -0.4163474 0.5586905 -0.7220259 -0.4216243 0.5485541 -0.7242833 -0.424462 0.5433651 -0.6244265 -0.1949577 0.7563618 -0.5946055 -0.2173271 0.7740888 -0.6069687 -0.2214178 0.7632583 -0.6731677 -0.185192 0.7159254 -0.6512493 -0.2484263 0.7170487 -0.7095955 -0.2104279 0.6724539 -0.6936419 -0.2820896 0.6627869 -0.7445514 -0.2364033 0.624305 -0.7329024 -0.3166429 0.6021556 -0.7771971 -0.262555 0.5718652 -0.7675026 -0.3509123 0.5364705 -0.7254608 -0.4263162 0.5403342 -0.7352663 -0.4424355 0.5134534 -0.8072019 -0.289566 0.5143703 -0.7829753 -0.3682471 0.5013422 -0.7244135 -0.4244667 0.543188 -0.7260892 -0.4269676 0.5389742 -0.7252345 -0.4257163 0.5411105 -0.7427421 -0.4465852 0.4988949 -0.7425772 -0.4465046 0.4992123 -0.8199617 -0.3014695 0.4865995 -0.8347589 -0.322465 0.4463115 -0.7885568 -0.3788967 0.4843713 -0.716095 -0.4359012 0.5451588 -0.7299634 -0.1230848 0.6723122 -0.7768468 -0.1063304 0.6206473 -0.8075449 -0.1228103 0.5768788 -0.8374165 -0.1388928 0.5286232 -0.8664698 -0.1564412 0.4740847 -0.8787435 -0.1580291 0.450374 -0.8922229 -0.17759 0.415211 -0.8222478 -0.03076332 0.5682977 -0.8549637 -0.006866753 0.5186426 -0.8795807 -0.01293992 0.4755736 -0.9047717 -0.01770108 0.425529 -0.9164804 -0.008942008 0.3999798 -0.895495 -0.1669096 0.4125893 -0.9278274 -0.02859687 0.3719123 -0.8788376 0.075383 0.4711285 -0.8977512 0.110754 0.4263525 -0.9122578 0.1168286 0.3926026 -0.9262603 0.1243966 0.3557633 -0.9326565 0.1387387 0.3330218 -0.9297714 -0.01602262 0.3677884 -0.9401387 0.1225949 0.3179778 -0.9043872 0.165874 0.3931534 -0.9111286 0.1776233 0.3718799 -0.9234471 0.186136 0.3355576 -0.9133199 0.179728 0.3654378 -0.9305669 0.1997799 0.3068115 -0.9303295 0.2062448 0.3032329 -0.9327208 0.2039583 0.2973768 -0.9325677 0.2040802 0.2977734 -0.9336616 0.2033773 0.2948116 -0.9408403 0.1352602 0.3106836 -0.8938239 0.2183668 0.3916565 -0.9129689 0.2012712 0.3549333 -0.9100854 0.2183655 0.3522232 -0.9013935 0.2287131 0.3676684 -0.9212856 0.2355478 0.309435 -0.9214056 0.250227 0.2973182 -0.9136418 0.2605391 0.3120549 -0.9270021 0.2668023 0.2635977 -0.9280706 0.2667108 0.2599049 -0.8801414 0.2050275 0.4281529 -0.885322 0.2185456 0.4104178 -0.8607712 0.1919674 0.4714038 -0.8669659 0.2069523 0.4533663 -0.8408339 0.1883338 0.5074729 -0.8502032 0.2099414 0.4827828 -0.8824044 0.241316 0.4038923 -0.8687099 0.2431802 0.4315167 -0.8991833 0.2517518 0.3578971 -0.879453 0.2543809 0.4023095 -0.8663905 0.2483074 0.4332563 -0.8665075 0.2484891 0.432918 -0.8663148 0.2479981 0.4335847 -0.8679391 0.2529137 0.4274536 -0.8983899 0.2652107 0.3500843 -0.9139807 0.275891 0.2975289 -0.9310212 0.2702788 0.2452529 -0.9373532 0.2587686 0.2332549 -0.9336398 0.263166 0.2430235 -0.9312171 0.2652772 0.2499258 -0.9288148 0.2665223 0.2574276 -0.9154775 0.279096 0.2898386 -0.8690243 0.2785761 0.4088916 -0.9157939 0.2815409 0.2864545 -0.868022 0.2637149 0.4207047 -0.8720892 0.2787633 0.4021834 -0.9219883 0.287034 0.2599024 -0.9221951 0.2891378 0.2568181 -0.9276641 0.2950604 0.2288641 -0.92787 0.2966449 0.2259628 -0.9336386 0.2983542 0.1982517 -0.9331258 0.2983255 0.2006945 -0.9348319 0.2983552 0.1925452 -0.9348878 0.2984756 0.1920864 -0.9567988 0.1374572 0.2562063 -0.9478687 0.2155884 0.234663 -0.9451484 0.2120472 0.2484566 -0.9510253 0.2218173 0.2152861 -0.9499155 0.2212654 0.2206856 -0.9658104 0.1361461 0.2206232 -0.9603378 0.1467958 0.2370707 -0.949134 0.1337028 0.2850759 -0.9409369 0.2096667 0.2658526 -0.93884 0.2076849 0.2746752 -0.943619 0.1244567 0.3067471 -0.9360917 0.2037171 0.2867605 -0.8968436 0.2699137 0.3504545 -0.9091261 0.3291153 0.2552902 -0.8575368 0.4997873 0.1218338 -0.701366 0.7081108 -0.08163934 -0.8805046 0.4438993 0.1663287 -0.9015746 0.2966184 0.31493 -0.9521614 0.2891978 0.09875935 -0.8873434 0.4262605 0.1758511 -0.8863729 0.4286745 0.1748757 -0.8845446 0.433559 0.1720685 -0.8810363 0.442624 0.166911 -0.9521147 0.2917963 0.09128361 -0.9563618 0.2921852 -2.74668e-4 -0.9518439 0.2902715 0.0986697 -0.9344949 0.2870321 -0.2105513 -0.955035 0.2964933 0 -0.9516389 0.2911499 -0.09805709 -0.9325904 0.2845656 -0.2220308 -0.9349845 0.2851403 -0.2109483 -0.9525795 0.2910965 -0.08862906 -0.8901945 0.2719597 -0.3655022 -0.895671 0.2795844 -0.3458411 -0.9036441 0.2801361 -0.3239617 -0.8892484 0.2792845 -0.3622672 -0.9117867 0.2809888 -0.2994833 -0.9194481 0.2820268 -0.2740002 -0.9264045 0.2832164 -0.2481195 -0.8721072 0.2787593 -0.4021471 -0.8786491 0.2789154 -0.3875334 -0.8842977 0.2790688 -0.3743501 -0.7329161 0.2739089 -0.6227422 -0.7309035 0.2740011 -0.625063 -0.737513 0.2740267 -0.6172391 -0.7420089 0.2741218 -0.6117842 -0.7465911 0.274215 -0.6061418 -0.7515888 0.2743343 -0.5998793 -0.7566276 0.2745491 -0.5934119 -0.7615093 0.2747012 -0.5870629 -0.766251 0.2747969 -0.580815 -0.7708225 0.2748556 -0.5747063 -0.7752604 0.27486 -0.5687033 -0.7831885 0.2758342 -0.5572535 -0.7795756 0.2755554 -0.5624334 -0.7872872 0.2755017 -0.5516138 -0.7912425 0.2751922 -0.5460813 -0.7950586 0.274918 -0.5406497 -0.798964 0.2746429 -0.5350028 -0.8033248 0.2743365 -0.5285915 -0.8076697 0.2741878 -0.5220066 -0.8118723 0.273971 -0.5155612 -0.8158595 0.2737843 -0.5093286 -0.8228583 0.2738792 -0.49789 -0.8196903 0.2740033 -0.5030209 -0.8264063 0.2733935 -0.4922486 -0.8297874 0.2729945 -0.4867512 -0.8354893 0.2729012 -0.4769515 -0.8330612 0.2736687 -0.4807437 -0.8384212 0.2722916 -0.4721307 -0.8415435 0.2718062 -0.4668256 -0.8452289 0.271102 -0.4605345 -0.8487106 0.2706754 -0.4543405 -0.8516456 0.2684797 -0.4501315 -0.759889 0.3212109 -0.5651481 -0.7628709 0.3106602 -0.5670258 -0.7610902 0.3096793 -0.5699478 -0.7575393 0.307325 -0.5759215 -0.7541293 0.3041848 -0.5820316 -0.750887 0.3002144 -0.5882518 -0.7478253 0.2953395 -0.5945856 -0.7418655 0.3114199 -0.5938464 -0.7545909 0.3267402 -0.5690638 -0.7291926 0.3160862 -0.6069331 -0.7255941 0.3133407 -0.6126425 -0.7223647 0.310047 -0.6181102 -0.7193208 0.3060218 -0.6236413 -0.718199 0.3043946 -0.625727 -0.9684357 0.1450578 -0.2027086 -0.9533514 0.2250773 -0.2011505 -0.9493612 0.3042156 -0.0785259 -0.9442134 0.3058363 -0.1221697 -0.9483022 0.3056223 -0.08554613 -0.9700545 0.2291995 -0.08038771 -0.9815379 0.1372462 -0.1332176 -0.9645383 0.2234332 -0.1405118 -0.9530801 0.3027186 0 -0.9506231 0.2986033 -0.08456963 -0.9524365 0.304732 -0.001800596 -0.9575169 -0.1937374 -0.2136055 -0.971713 -0.19325 -0.1357511 -0.9771617 -0.0243237 -0.2111008 -0.9778124 -0.1982237 -0.06775313 -0.990356 -0.02813887 -0.1356589 -0.9869469 0.1473447 -0.065005 -0.9973734 -0.02545315 -0.06781405 -0.9717932 -0.1933393 0.1350476 -0.9575708 -0.1940106 0.2131156 -0.9974422 -0.02542203 0.06680536 -0.9904486 -0.02810841 0.1349876 -0.9555038 -0.1892818 0.2262408 -0.9772427 -0.02426242 0.2107324 -0.9778674 -0.1982836 0.06677609 -0.9869787 0.1475585 0.06402844 -0.9816084 0.1373653 0.1325739 -0.9671659 0.1436817 0.2096324 -0.9685283 0.145882 0.2016712 -0.9750096 -0.02313309 0.220955 -0.9705431 0.2262088 0.08292084 -0.9644906 0.2234293 0.140845 -0.9538956 0.2236112 0.2002033 -1 -1.66357e-5 0 -0.9482597 0.3043367 0.09045869 -0.9441748 0.3058336 0.1224738 -0.9484313 0.3066524 0.08026432 -0.9529143 0.2229153 0.2055802 -1 9.90256e-6 0 -0.9729452 0.2310287 -0.001892149 -0.9517481 -0.1919671 0.2394248 -0.9429118 -0.182564 0.2785459 -0.9720696 -0.02801668 0.2330147 -0.9342678 -0.1828127 0.3061427 -0.9650671 -0.01785349 0.261394 -0.9582947 -0.02288919 0.2848638 -0.9036104 -0.1815277 0.3879896 -0.9451099 -0.02212619 0.3260031 -0.9349916 -0.0298174 0.3534144 -0.9167363 -0.1758822 0.3586924 -0.9506231 0.2986033 0.08456963 -1 1.61726e-7 0 -1 1.6658e-7 0 -1 0 0 -1 2.54066e-7 0 -1 -2.24845e-7 0 -1 2.92521e-7 0 -1 -1.36813e-7 0 -1 -4.41155e-7 0 -1 -1.6658e-7 0 -1 -2.54066e-7 0 -1 2.24845e-7 0 -1 -2.92521e-7 0 -1 1.36814e-7 0 -1 4.41158e-7 0 0.9832548 -0.1822363 -9.4625e-6 0.983258 -0.1822192 3.19412e-5 0.983258 -0.182219 -1.10751e-5 0.9832547 -0.1822367 1.83435e-5 0.9831181 -0.1829722 3.9593e-5 0.9832497 -0.182264 0 0.9832543 -0.1822392 0 0.9832716 -0.1821454 -1.01062e-5 0.983255 -0.1822357 -2.51467e-6 0.9832538 -0.1822417 -1.00265e-5 0.9832543 -0.1822392 0 0.9832494 -0.1822658 1.63385e-5 0.983254 -0.1822412 -1.69096e-6 0.9832562 -0.1822288 -3.59093e-6 0.9832735 -0.1821355 0 0.9832568 -0.1822255 -1.31172e-5 0.1444185 0.7796832 -0.6092925 0.1445986 0.7796362 -0.6093101 0.1443254 0.7797055 -0.6092861 0.1446618 0.7796173 -0.6093192 0.1822032 0.9832609 0 0 0 -1 0 0 1 0.1760017 0.9493777 0.260203 0.1806448 0.9747005 0.1316305 0.1760058 0.9494003 0.2601176 0.1683464 0.9077153 0.3843339 -0.1822575 -0.9832509 0 -0.1822574 -0.9832509 0 -0.1158675 -0.6252685 0.7717603 -0.1821985 -0.9832618 0 -0.1158663 -0.6253216 0.7717176 -0.1821985 -0.9832618 0 0.1821985 0.9832618 0 1.33344e-6 0 -1 0.1682211 0.9077286 -0.3843571 0.1682191 0.907718 -0.3843832 0.02401858 0.1294623 -0.9912935 -5.09773e-7 0 -1 0.1823897 0.9832264 0 0.1682191 0.907718 0.3843832 0.0912519 0.4927603 0.8653672 0.1109969 0.5991452 0.792909 0.09122228 0.4926432 0.865437 0.111029 0.5991236 0.7929209 0.04745739 0.2559037 0.9655367 0.04745775 0.2558752 0.9655442 0.02401858 0.1294623 0.9912935 0.02398806 0.1294624 0.9912942 -0.1821931 -0.9832628 0 -4.11683e-7 0 1 -0.1822133 -0.983259 0 -0.1822032 -0.9832609 0 -0.1822032 -0.9832609 0 -2.25469e-6 0 1 0.9832542 -0.1822397 0 0.9832621 -0.1821972 0 0.9832548 -0.1822361 0 0.9832508 -0.1822577 0 0.9832563 -0.1822282 0 0.9832549 -0.1822355 -1.78037e-6 0.9832597 -0.1822097 -2.98898e-6 0.9832251 -0.1823967 -3.99059e-5 0.9833023 -0.1819797 2.31409e-5 0.9832543 -0.182239 0 0.9832597 -0.18221 0 0.9832549 -0.1822355 0 0.9832543 -0.182239 0 0.9832639 -0.1821873 1.84291e-5 0.9832403 -0.1823142 -1.04875e-5 0.9832769 -0.1821172 3.2275e-5 0.9832453 -0.1822877 5.5766e-6 0.983264 -0.182187 1.87899e-5 0.9832529 -0.1822465 -5.59519e-6 0.9832413 -0.182309 -3.84332e-6 0.9832328 -0.1823549 1.19655e-5 0.9832534 -0.1822436 -2.82461e-5 0.9832896 -0.1820484 1.94164e-5 0.9832119 -0.1824672 -3.19445e-5 0.9842619 -0.1767151 5.66395e-4 0.9832549 -0.1822356 -8.91171e-6 0.9832532 -0.1822454 -7.15504e-6 0.9832515 -0.1822538 4.97499e-6 0.9832755 -0.1821244 3.14485e-6 0.9832243 -0.1824008 0 0.9832357 -0.1823391 0 0.9832536 -0.182243 -1.49637e-5 0.9833603 -0.1816661 2.43129e-5 0.9832623 -0.1821956 -3.30704e-5 0.9832381 -0.1823264 -1.93405e-5 0.9832462 -0.1822828 -1.40921e-5 0.182374 0.9832293 0 1.48298e-6 0 -1 -1.17019e-6 0 -1 0.182384 0.9832274 0 -0.01931846 -0.1042219 0.9943664 -0.01931852 -0.1041918 0.9943696 -0.03619557 -0.1953831 0.9800589 -0.03619515 -0.1954417 0.9800472 -0.07001066 -0.3778868 0.923201 -0.07001101 -0.3779497 0.9231752 -0.1014764 -0.5477593 0.8304591 -0.1015076 -0.5477929 0.8304332 -0.128821 -0.6953463 0.7070351 -0.1288209 -0.6953155 0.7070654 -0.1513121 -0.8165302 0.5571205 -0.1513431 -0.8165023 0.5571528 -0.1683154 -0.9076826 0.3844245 -0.1683127 -0.9076986 0.3843879 -0.178599 -0.9636474 0.1987112 -0.1785642 -0.9636548 0.1987065 -0.1821985 -0.9832618 0 -0.182169 -0.9832673 0 -0.1785367 -0.9636404 -0.1988013 -0.1786001 -0.9636533 -0.198682 -0.1683101 -0.9077147 -0.3843512 -0.168314 -0.907736 -0.3842992 -0.1513433 -0.8165643 -0.5570619 -0.1512835 -0.8165099 -0.5571579 -0.1288209 -0.6953155 -0.7070654 -0.1288236 -0.6952691 -0.7071107 -0.1014764 -0.5477593 -0.8304591 -0.07001185 -0.3779236 -0.9231859 -0.07000988 -0.3779129 -0.9231904 -0.03619515 -0.1954417 -0.9800472 -0.03619539 -0.1954124 -0.9800531 -0.01931846 -0.1042219 -0.9943664 0.1821985 0.9832618 0 0.1158466 0.625301 -0.7717372 1.1976e-6 0 1 0.1822116 0.9832593 0 0.1158748 0.6253089 -0.7717266 0.1821984 0.9832618 0 -2.14743e-6 0 1 0.1443569 0.7796491 0.6093508 0.1445679 0.779666 0.6092791 0.1442944 0.7796416 0.6093754 0.1446304 0.7796736 0.6092545 0.9832539 -0.1822413 0 0.9832539 -0.1822412 0 0.9832555 -0.1822322 0 0.9832586 -0.1822158 0 0.9832551 -0.1822351 -2.43708e-6 0.9832557 -0.1822314 0 0.9832556 -0.1822317 0 0.9832552 -0.1822344 0 0.9832553 -0.1822341 -4.19588e-5 0.9832545 -0.182238 8.73729e-6 0.9832554 -0.1822334 0 0.983254 -0.1822409 -4.19588e-5 0.9832537 -0.1822422 1.09216e-5 0.9832546 -0.1822374 0 0.06998068 0.3779506 -0.9231772 0.05014348 0.2706772 -0.9613634 0.04739546 0.2558684 -0.9655491 0.02392709 0.1294626 -0.9912956 0.1821981 0.983262 0 -1.57064e-6 0 1 0.111029 0.5991236 -0.7929209 0.1110887 0.5990855 -0.7929414 0.1109989 0.5991257 -0.7929236 0.1111208 0.5990639 -0.7929532 2.73469e-6 0 -1 0.1821931 0.9832628 0 4.96733e-7 0 1 -2.73475e-6 0 -1 -0.1822133 -0.983259 0 -0.1821931 -0.9832628 0 0.1807326 0.9746804 -0.1316583 1.26879e-7 0 1 2.09429e-6 0 1 0.1823511 0.9831094 -0.01562571 0.1823509 0.9831084 0.01568675 0.180766 0.9746656 0.1317214 0.1807621 0.974675 -0.1316576 0.1823758 0.983229 0 0.920825 -0.1931865 -0.338763 0.9251446 -0.2089922 -0.3169064 0.9337101 -0.190441 -0.3031796 0.1430726 0.7451803 -0.6513345 0.1626047 0.7696868 -0.617367 0.1528716 0.7401866 -0.6547933 0.9374333 -0.1938591 -0.2892016 0.9562622 -0.1892198 -0.2230657 0.17115 0.8032995 -0.5704539 0.1704944 0.8033187 -0.5706231 0.9221649 -0.2020669 -0.3298198 0.1281809 0.6562556 -0.7435712 0.1334311 0.6421602 -0.7548686 0.9176452 -0.1941313 -0.3467568 0.09921616 0.5023068 -0.8589785 0.104436 0.4844894 -0.8685408 0.9119929 -0.1879041 -0.3646385 0.07529121 0.3765478 -0.9233325 0.05246186 0.265819 -0.9625944 0.9085737 -0.1857371 -0.3741599 0.04004144 0.2469629 -0.9681974 0.01971513 0.1642829 -0.9862163 -0.005070149 0.05481058 -0.9984839 0.0210278 0.165293 -0.9860203 0.9102829 -0.1867137 -0.3694905 0.9117949 -0.1895554 -0.3642785 -0.005050063 0.05484026 -0.9984824 0.9608651 -0.1976726 -0.1940713 0.9439436 -0.1938 -0.2672304 0.9166498 -0.1831773 -0.3552457 0.9226481 -0.1882712 -0.3365627 0.932924 -0.1940132 -0.3033345 0.9724887 -0.1922393 -0.1315675 0.975051 -0.1997162 -0.09689778 0.9645406 -0.1978521 -0.1746885 0.9498014 -0.1936165 -0.245744 0.9570438 -0.1989836 -0.2108859 0.9796743 -0.200116 -0.01385581 0.979604 -0.2009381 -1.22077e-4 0.9764474 -0.2002945 -0.08020323 0.9784532 -0.2054873 -0.02011227 0.9786929 -0.2025566 -0.03363221 0.9782805 -0.1981891 -0.06073242 0.96889 -0.1976417 -0.1489637 0.9727825 -0.2024303 -0.1127665 0.9783946 -0.1973696 0.06155782 0.9747855 -0.2007862 0.09735643 0.9795584 -0.2011486 0.002166807 0.9794692 -0.1981889 0.03689718 0.9801405 -0.196907 0.02349942 0.980484 -0.1962677 0.01141411 0.9805924 -0.1960574 0 0.9785532 -0.1998367 -0.0499897 0.9724887 -0.1922393 0.1315675 0.9606944 -0.1984686 0.1941043 0.9757243 -0.1977023 0.09421223 0.9785472 -0.2000554 0.04922795 0.9562622 -0.1892198 0.2230657 0.9374012 -0.1944691 0.288896 0.9609866 -0.1952614 0.1959023 0.9747055 -0.1924203 0.113682 0.9681071 -0.198773 0.1525056 0.9216878 -0.1932798 0.336355 0.9220641 -0.1904677 0.3369274 0.9363078 -0.1906248 0.2949405 0.9199057 -0.1987707 0.3380292 0.9191211 -0.201031 0.338826 0.9209378 -0.1986474 0.3352804 0.9239063 -0.1954447 0.3289355 0.9346815 -0.187449 0.3020486 0.9577502 -0.190256 0.2156784 0.9474344 -0.195139 0.2535526 -0.004399001 0.05465167 0.9984958 0.9309868 -0.185709 0.3142862 0.9171215 -0.1901018 0.3503562 0.9119912 -0.189796 0.3636612 -0.004728496 0.05476689 0.9984881 0.01980674 0.1646191 0.9861584 0.020509 0.1631567 0.986387 0.04693889 0.2745836 0.9604169 -0.005053579 0.0548802 0.9984802 0.05325549 0.2546804 0.9655577 0.1001633 0.482322 0.8702488 0.09921616 0.5023068 0.8589785 0.1334325 0.6422584 0.7547847 0.09036672 0.3622605 0.927686 0.133248 0.6585494 0.7406468 0.1356265 0.7542775 0.6423948 0.1394399 0.7649815 0.6287766 0.1705672 0.8035146 0.5703254 0.1547315 0.7357838 0.659303 0.1701379 0.8028295 0.5714175 0.1709749 0.8032246 0.5706118 0.1701804 0.8019894 0.5725834 0.1705984 0.8020887 0.5723198 0.1776235 0.8763068 0.4478128 0.1812868 0.8491485 0.4960665 0.1912946 0.8894835 0.4150007 0.1949266 0.9347752 0.2969831 0.2027364 0.9456254 0.2543438 0.1928492 0.9744089 0.1154837 0.2005738 0.9796437 0.00827074 0.2077461 0.9781801 0.002288937 0.2017927 0.9711807 -0.1268376 0.1987996 0.9472432 -0.251414 0.1963884 0.9327763 -0.3022581 0.182291 0.8890541 -0.4199438 0.1680076 0.8577698 -0.485803 0.1701666 0.8019881 -0.5725892 0.1880275 0.877299 -0.4415793 0.1701563 0.8028271 -0.5714154 0.1706125 0.8020963 -0.572305 0.9033672 -0.1906226 -0.3841753 0.9117834 -0.2115266 -0.3520053 0.9041327 -0.1994737 -0.3778283 0.9048408 -0.2014894 -0.3750536 -0.00468868 0.05483663 -0.9984843 -0.00505191 0.05488091 -0.9984802 -0.004965484 0.05502337 -0.9984728 -0.00502777 0.05521333 -0.998462 0.9083709 -0.1944067 -0.3702273 0.914241 -0.2032291 -0.350516 0.9300452 -0.2109494 -0.3008593 0.9164959 -0.2109192 -0.3399244 0.931708 -0.202309 -0.3016477 0.942556 -0.2135431 -0.2568804 -0.1014443 -0.9943309 -0.03186154 0.9438153 -0.2135449 -0.2522131 0.9547998 -0.2105229 -0.2098515 0.9547024 -0.2188534 -0.20161 0.9598877 -0.2180897 -0.1762174 0.9632073 -0.2226354 -0.1505497 0.9651075 -0.2163808 -0.1474686 0.9699084 -0.2201063 -0.1040713 0.9693874 -0.2215097 -0.1059328 0.9751228 -0.2155885 -0.05154711 0.9508625 -0.2953667 -0.09284001 0.9759588 -0.2124714 -0.04858583 0.9788013 -0.2048121 0 0.9752954 -0.2144569 0.05298095 0.9754955 -0.2134841 0.05322605 0.9757444 -0.2121356 -0.05404859 0.9768797 -0.2063993 -0.05572748 0.9769858 -0.2070433 -0.05130302 0.9762699 -0.2130831 -0.03863692 0.9760189 -0.2157673 -0.02884018 0.9767947 -0.2122604 -0.0285964 0.9775884 -0.2093917 -0.02182114 0.9780408 -0.2084139 0 0.9780001 -0.2075636 0.02081435 0.9773939 -0.2096944 0.02700906 0.9765954 -0.2133556 0.02722257 0.9767952 -0.2111313 0.03598201 0.9774764 -0.2054263 0.04837328 0.9772824 -0.2049662 0.05392718 0.9759789 -0.211194 0.05350041 0.9698622 -0.2204689 0.1037339 0.9719613 -0.217324 0.08978617 0.9691364 -0.217266 0.1164917 0.9627689 -0.222823 0.1530554 0.9638651 -0.2167796 0.1548251 0.9543654 -0.2209588 0.2009077 0.9577253 -0.2142148 0.1920272 0.9528251 -0.2121967 0.2170186 0.9443162 -0.2149142 0.2491564 0.9444343 -0.2069783 0.2553507 0.9295153 -0.2112826 0.3022596 0.934583 -0.2038058 0.2915784 0.9266318 -0.2026187 0.3167004 0.9112641 -0.2119843 0.3530732 0.9135786 -0.2014914 0.3532357 0.9066748 -0.1918764 0.3756651 0.9059026 -0.1952621 0.3757834 0.9065327 -0.1920858 0.375901 0.9054811 -0.2044191 0.3719098 0.9023233 -0.2091158 0.3769395 -0.005046784 0.0549224 0.9984779 -0.005063593 0.05475866 0.9984869 -0.9735789 0.2283508 1.01985e-6 -0.9735839 0.22833 -1.43509e-7 -0.9735777 0.2283558 -2.39351e-7 -0.9735789 0.2283513 -1.37211e-6 -0.9735766 0.2283608 -4.63094e-6 -0.9735778 0.2283558 0 -0.9735799 0.2283467 1.01682e-6 -0.9735788 0.2283516 -8.71944e-7 -0.9735763 0.2283625 -8.05515e-7 -0.9735721 0.22838 0 -0.9735822 0.2283368 0 -0.9735717 0.2283818 0 -0.9735746 0.2283689 0 -0.9735843 0.2283277 0 -0.9735772 0.2283589 0 -0.9735788 0.2283512 0 -0.9735827 0.228335 0 -0.9735791 0.2283504 2.23019e-7 -0.9735168 0.2286157 2.4786e-7 -0.9735514 0.2284685 -1.68646e-6 -0.9733479 0.2293338 0 -0.004975974 0.05531716 0.9984565 -0.9735809 0.2283428 2.65502e-7 -0.01525938 0.01330614 0.9997951 -0.01489335 0.01272648 0.9998082 -0.02481216 -0.02819985 0.9992944 -0.9735785 0.2283524 0 -0.9735791 0.2283504 2.10474e-7 -0.0423606 -0.1060237 0.993461 -0.04361122 -0.1070901 0.9932925 -0.9735753 0.2283663 2.08185e-7 -0.024293 -0.02697867 0.9993408 -0.9735783 0.2283537 2.43399e-7 -0.05865758 -0.1754235 0.9827441 -0.05996954 -0.1765515 0.9824629 -0.973576 0.2283636 -4.8933e-7 -0.07510769 -0.2474189 0.9659931 -0.07654303 -0.2481239 0.9656996 -0.9735817 0.2283388 -4.70963e-7 -0.9735823 0.2283364 -1.0449e-6 -0.09757065 -0.3433133 0.9341393 -0.09891122 -0.3425728 0.93427 -0.97358 0.2283464 -9.77884e-7 -0.9735797 0.228348 0 -0.1241836 -0.4549839 0.8817983 -0.124883 -0.4528689 0.8827877 -0.9735789 0.2283511 0 -0.9735758 0.2283641 0 -0.9735814 0.2283406 -4.80392e-7 -0.1477748 -0.5551778 0.8184989 -0.1478348 -0.5527325 0.8201413 -0.9735808 0.2283429 -4.57509e-7 -0.9735767 0.2283604 2.8246e-7 -0.1661464 -0.6333645 0.7558075 -0.1658096 -0.6308274 0.758 -0.9735769 0.2283598 2.39579e-7 -0.9735797 0.2283479 -4.7235e-7 -0.1793306 -0.6885736 0.7026429 -0.9735828 0.2283347 -5.41933e-7 -0.9735731 0.2283759 -4.59169e-7 -0.1797566 -0.690827 0.7003183 -0.189435 -0.7309135 0.6556522 -0.9735786 0.2283523 -4.377e-7 -0.9735797 0.2283478 -1.2317e-6 -0.1897705 -0.7324386 0.6538508 -0.1984378 -0.768634 0.6081318 -0.9735822 0.2283372 -1.17885e-6 -0.9735761 0.2283629 -3.44943e-7 -0.1987134 -0.7701022 0.6061812 -0.2074674 -0.8067058 0.553338 -0.9735766 0.2283608 -2.88842e-7 -0.9735826 0.2283352 -4.28555e-7 -0.2076527 -0.8082404 0.5510244 -0.2154372 -0.8410265 0.4962474 -0.9735783 0.2283536 -4.65299e-7 -0.9735724 0.2283791 0 -0.2155593 -0.8422164 0.4941719 -0.2217499 -0.8686275 0.4430726 -0.9735838 0.2283305 0 -0.9735757 0.2283647 -7.51801e-7 -0.2279163 -0.8959783 0.3811524 -0.2278222 -0.8951445 0.3831624 -0.9735823 0.2283368 -7.78671e-7 -0.2218744 -0.8693389 0.4416126 -0.9735899 0.2283041 1.91683e-6 -0.2350584 -0.9251267 0.2981414 -0.9735819 0.2283381 2.14294e-7 -0.9735661 0.2284057 2.6199e-7 -0.9735847 0.2283263 1.56688e-6 -0.2349048 -0.9264352 0.2941728 -0.2414991 -0.9516527 0.18983 -0.9735761 0.228363 1.7312e-6 -0.9735531 0.2284614 -6.97322e-6 -0.2409824 -0.9526375 0.1854978 -0.2453436 -0.9672747 0.0647006 -0.9735839 0.2283296 1.34959e-6 -0.2445502 -0.9677021 0.06122142 -0.245249 -0.9669268 -0.07004058 -0.2443356 -0.9670575 -0.07141458 -0.2413427 -0.9508744 -0.1938859 -0.2406412 -0.9511204 -0.1935506 -0.2351171 -0.9246294 -0.299634 -0.2344773 -0.9249693 -0.299086 -0.2280706 -0.895039 -0.3832612 -0.2274914 -0.8951335 -0.3833845 -0.2219951 -0.868906 -0.4424031 -0.2215092 -0.8687631 -0.442927 -0.2157104 -0.8415699 -0.4952062 -0.2150984 -0.8414413 -0.4956907 -0.2079874 -0.8076564 -0.5517541 -0.2071025 -0.8073825 -0.5524871 -0.1991684 -0.7698472 -0.6063557 -0.1979778 -0.7691441 -0.6076366 -0.1902307 -0.7324481 -0.6537066 -0.1889749 -0.731423 -0.6552166 -0.1804919 -0.6906548 -0.700299 -0.1792416 -0.6901093 -0.7011574 -0.1671214 -0.6334806 -0.7554951 -0.165687 -0.6336026 -0.7557087 -0.1493911 -0.5560584 -0.8176072 -0.1473183 -0.556007 -0.8180181 -0.1288523 -0.4694778 -0.8734917 -0.1202136 -0.4572026 -0.8812007 -0.08981859 -0.3931815 -0.9150634 -0.08945244 -0.3383383 -0.9367633 -0.09735643 -0.3435553 -0.9340726 -0.07703119 -0.2492832 -0.9653621 -0.07507818 -0.2479717 -0.9658537 -0.06033581 -0.1774368 -0.9822809 -0.05838245 -0.1753914 -0.9827662 -0.04419136 -0.1076402 -0.9932074 -0.04181087 -0.1048935 -0.9936042 -0.02569723 -0.02850502 -0.9992633 -0.02359086 -0.0256356 -0.999393 -0.01568686 0.01385575 -0.999781 -0.01443523 0.0147404 -0.9997872 0.9055267 -0.1982814 -0.375108 0.8995134 -0.221567 0.3765419 0.8975862 -0.2289515 0.3767231 0.9066057 -0.2397595 0.3472484 0.8929597 -0.2512031 0.3735238 0.8894633 -0.2743407 0.3655028 0.9015267 -0.2742729 0.3347002 0.8863188 -0.3048294 0.3485945 0.8935109 -0.3204517 0.3145615 0.8769238 -0.3434387 0.336236 0.8947668 -0.3454487 0.282945 0.8732786 -0.3753871 0.3105947 0.8811732 -0.3797166 0.2816898 0.8715394 -0.4102708 0.2685087 0.8837437 -0.4013576 0.2406436 0.8686361 -0.4379498 0.2316708 0.8463574 -0.4727113 0.2454046 0.8775519 -0.4374026 0.1964222 0.8785902 -0.4371893 0.1922107 0.8480431 -0.4948419 0.1896171 0.8887132 -0.4378865 0.1358095 0.8584173 -0.4933145 0.140572 0.8397594 -0.5329219 0.103917 0.9168474 -0.3964399 0.04718214 0.7744529 -0.6326307 -0.001098632 0.9218842 -0.3847517 -0.04577833 0.8310241 -0.5459795 -0.1063271 0.8703259 -0.4725646 -0.1386197 0.8802596 -0.4518643 -0.1447821 0.8483452 -0.4939245 -0.1906541 0.8793662 -0.4355171 -0.1924576 0.9212853 -0.3520398 -0.1652313 0.8495942 -0.4716441 -0.2360967 0.8659067 -0.443971 -0.2304242 0.8998345 -0.3715434 -0.2285904 0.874441 -0.4081965 -0.2621613 0.8792859 -0.3831673 -0.2829121 0.865233 -0.391537 -0.3131625 0.894558 -0.3328155 -0.2983284 0.8784781 -0.344506 -0.3310468 0.8910945 -0.3227387 -0.3190459 0.8857232 -0.3063195 -0.348802 0.9005224 -0.2754029 -0.3364713 0.889178 -0.2770842 -0.364125 0.892834 -0.2538572 -0.3720269 0.9065504 -0.2408902 -0.3466097 0.8980875 -0.229382 -0.3752636 0.9001187 -0.220383 -0.3757895 0.9017598 -0.2081125 -0.3788386 0.9279451 -0.2304221 0.2929566 0.9249997 -0.2516595 0.284681 0.919077 -0.2817811 0.2754942 0.9115299 -0.3291848 0.2464765 0.9053775 -0.3734613 0.2020359 0.9024575 -0.4009023 0.1576325 0.9023916 -0.4203409 0.09488415 0.9032838 -0.4290423 0.001007139 0.9028878 -0.4194595 -0.09406095 0.9032787 -0.399253 -0.1571131 0.9066723 -0.3717576 -0.1993531 0.9132788 -0.3271018 -0.2427475 0.9205687 -0.2793079 -0.2730211 0.9257652 -0.2502868 -0.2833999 0.9284162 -0.2302348 -0.2916083 0.9703918 -0.2179078 -0.1041929 0.9723196 -0.2084784 -0.1055058 0.9730607 -0.2086569 -0.09805679 0.9727395 -0.2187008 -0.07712209 0.9728584 -0.2236747 -0.05929863 0.9742116 -0.2189465 -0.05453824 0.9756431 -0.2158634 -0.03903424 0.9764099 -0.2159253 0 0.9758117 -0.2152804 0.03802651 0.9745713 -0.2177243 0.05298137 0.9733315 -0.2219622 0.0579549 0.9731639 -0.2174794 0.07519912 0.9734032 -0.2077122 0.09665364 0.9726229 -0.2070741 0.105475 0.9706271 -0.2169597 0.1039783 0.9636089 -0.2222703 -0.1485058 0.9657483 -0.2125049 -0.148903 0.9671239 -0.2126274 -0.1395034 0.9675895 -0.2259051 -0.112861 0.9681257 -0.2342948 -0.08853578 0.9695982 -0.2320382 -0.0777021 0.9712462 -0.2321908 -0.05261522 0.9719439 -0.2352112 0.00100708 0.9704773 -0.2351498 0.05365258 0.9684443 -0.2364344 0.07883179 0.9668148 -0.2384153 0.09180146 0.9662013 -0.229564 0.1172845 0.9659348 -0.2152523 0.1436542 0.9651391 -0.2128714 0.1522908 0.9633355 -0.2214771 0.1514357 0.9551617 -0.2247439 -0.1927597 0.9563573 -0.2209302 -0.1912348 0.9570049 -0.2250447 -0.1830205 0.9573534 -0.2447631 -0.153511 0.9577483 -0.2605715 -0.1217404 0.9590596 -0.2642946 -0.1017503 0.9611461 -0.2681431 -0.06555557 0.9624734 -0.2713737 0.001190185 0.9612064 -0.2677461 0.06628799 0.9592574 -0.2638103 0.1011415 0.9579491 -0.2598744 0.1216511 0.957535 -0.2443965 0.1529614 0.9572008 -0.2253224 0.1816496 0.956526 -0.2200418 0.191415 0.9552705 -0.2229096 0.194344 0.9438047 -0.2259943 -0.2411623 0.94409 -0.2323144 -0.2339318 0.9431766 -0.245011 -0.2244714 0.9415726 -0.2749763 -0.1944977 0.94018 -0.3025081 -0.1566865 0.9403281 -0.3157825 -0.1267464 0.9420021 -0.326188 -0.07895284 0.943284 -0.3319866 6.10382e-4 0.942072 -0.326008 0.07886207 0.9405556 -0.3154717 0.1258285 0.9403367 -0.3020516 0.1566261 0.9414798 -0.2752506 0.1945584 0.9429423 -0.2458602 0.2245275 0.944251 -0.2320342 0.2335602 0.9447376 -0.225045 0.2383817 0.8399428 0.4587916 0.2898386 0.842691 0.4686499 0.2650271 0.8436197 0.4799799 0.2406767 0.3237529 -0.6075555 0.7253004 0.3223702 -0.607477 0.7259816 0.2851111 -0.5409237 0.7912733 0.8579251 0.4578185 0.2331666 0.361351 -0.6744302 0.6438707 0.3601706 -0.6747763 0.6441694 0.8394799 0.4587444 0.2912512 0.1998385 -0.3913149 0.8982969 0.2025232 -0.3925337 0.8971632 0.2822453 -0.5363517 0.7954021 0.8365995 0.4545568 0.3057439 0.1368469 -0.2793399 0.9503905 0.1377032 -0.2779396 0.9506774 0.8352554 0.4531522 0.3114506 0.08398973 -0.186047 0.9789445 0.08652061 -0.1640992 0.9826422 0.8363226 0.4539758 0.3073607 0.04452717 -0.08145517 0.995682 0.03961306 -0.05694764 0.997591 -0.02389585 0.006992638 0.9996901 0.003479123 -0.04156678 0.9991298 0.8510202 0.4656272 0.2428085 0.8363956 0.4688283 0.2839765 -0.02373063 0.00694859 0.9996943 0.873207 0.4551285 0.174263 0.8673793 0.4754853 0.1468572 0.8438508 0.4796979 0.2404288 0.8334555 0.472319 0.2868217 0.8842043 0.4586741 0.08832275 0.8757099 0.4803373 0.04907441 0.8598545 0.4894707 0.1451504 0.8873855 0.4610278 6.1039e-4 0.8757099 0.4803373 -0.04907441 0.867716 0.4947129 0.04825049 0.8837593 0.4595658 -0.0881409 0.8673793 0.4754853 -0.1468572 0.8598545 0.4894707 -0.1451504 0.867716 0.4947129 -0.04825049 0.8726353 0.4558957 -0.1751191 0.8507034 0.4665837 -0.2420815 0.8436955 0.4798489 -0.2406722 0.8386911 0.4592796 -0.2926767 0.8392267 0.4594413 -0.2908819 0.8363956 0.4688283 -0.2839765 0.8376141 0.4606343 -0.2936304 0.8389744 0.4594979 -0.2915199 0.8442544 0.4565071 -0.2807772 0.8502943 0.4550102 -0.2645096 0.8605177 0.4538806 -0.2313045 0.8331832 0.4732053 -0.2861511 0.8364418 0.4540048 -0.3069934 -0.02253079 0.007731318 -0.9997163 -0.02315592 0.007261037 -0.9997056 0.04599171 -0.05578821 -0.9973828 0.02978676 -0.08817011 -0.99566 0.08099895 -0.1608687 -0.9836465 -0.02382802 0.006796479 -0.999693 0.08402001 -0.1860466 -0.9789419 0.1377336 -0.278031 -0.9506462 0.06775224 -0.04355061 -0.9967513 0.1368769 -0.2793387 -0.9503866 0.202527 -0.3926327 -0.8971191 0.1998385 -0.3913149 -0.8982969 0.2853849 -0.5400675 -0.7917593 0.2813532 -0.5362162 -0.7958095 0.3237195 -0.6075807 -0.7252941 0.3603646 -0.6751503 -0.6436689 0.3231638 -0.6089116 -0.7244253 0.879471 0.4500357 -0.1549153 0.3603271 -0.6746178 -0.6442478 0.8864472 0.4569875 -0.07330596 0.8890838 0.4577261 0.004120051 0.8876132 0.4583031 -0.04583942 0.8904747 0.4543624 -0.02468961 0.8877125 0.4535461 0.07913631 0.8853228 0.4645892 0.0189827 0.8878997 0.4580345 0.0428797 0.8790208 0.4524201 0.1504608 0.3601698 -0.6747222 0.6442265 -0.02300351 0.007163882 0.9997097 0.8306981 0.4767686 0.2874589 -0.02224326 0.007457494 0.9997249 0.8415328 0.4972776 0.2110393 0.8306785 0.4766529 0.2877069 0.8307147 0.4766256 0.2876479 0.8305516 0.4780845 0.285691 0.8305885 0.4807434 0.2810847 0.8343912 0.485131 0.2616094 0.8525219 0.5068926 0.1275395 0.858249 0.5115252 0.0418412 0.8520562 0.5074677 -0.1283623 0.8584827 0.5111404 -0.0417506 0.8395574 0.4998158 -0.2129031 0.8342117 0.4879103 -0.2569716 -0.02367949 0.006785273 -0.9996966 0.8383296 0.4768307 -0.2642651 0.8341881 0.4769579 -0.2768419 0.8312318 0.4766246 -0.2861517 0.8303107 0.4764077 -0.2891712 0.8378045 0.4793639 -0.261331 -0.02375245 0.006609201 -0.999696 -0.04608321 0.04617476 0.9978699 -0.04599189 0.04614448 0.9978755 -0.06885069 0.08673483 0.9938495 -0.02385044 0.006787776 0.9996925 -0.112769 0.1641025 0.9799764 -0.1135617 0.1670312 0.9793898 -0.06857705 0.08572894 0.9939556 -0.1563167 0.2412197 0.9577986 -0.1576308 0.2464411 0.9562528 -0.2137877 0.3219786 0.9222932 -0.2017294 0.3220957 0.9249647 -0.2538257 0.3849044 0.8873676 0.8378947 0.4831437 0.2539777 -0.2950013 0.4496741 0.8430703 -0.2842608 0.4676234 0.8369733 0.8434055 0.506379 0.1795765 0.8346083 0.4924576 0.2468087 0.8336514 0.5012407 0.2319123 0.8363497 0.5066807 0.2092705 0.8511373 0.5151259 0.1010475 0.8452652 0.5101317 0.1590365 0.8465085 0.5156509 0.1323919 0.8547253 0.517944 0.03433424 0.8526023 0.5172012 0.07464885 0.8520732 0.5181596 -0.07404023 0.8561865 0.5166601 0.002685666 0.8527384 0.5209942 -0.03744709 0.8483452 0.5122666 -0.1337661 0.8503273 0.5162636 -0.1020563 0.8388307 0.5018335 -0.2110124 0.8528525 0.5010299 -0.1470098 0.8432116 0.5067998 -0.1792995 -0.2891739 0.4561471 -0.8416106 -0.2738189 0.3595474 -0.8920477 -0.2223653 0.3294889 -0.9176005 0.8981463 0.4203089 -0.1291263 0.888176 0.4336504 -0.1519562 0.8780984 0.4453666 -0.1749055 -0.2995789 0.4727768 -0.8286946 -0.210554 0.3338222 -0.9188198 -0.1580588 0.2474495 -0.9559217 -0.1566566 0.241745 -0.9576107 -0.1138348 0.1676393 -0.9792542 -0.1130133 0.1644691 -0.9798867 -0.068973 0.08694875 -0.9938223 -0.06863689 0.0858801 -0.9939385 -0.04611355 0.04623562 -0.9978656 -0.04608434 0.04629796 -0.9978641 -0.3287491 0.5274268 0.7834189 -0.3647295 0.5761634 0.7314427 -0.3579571 0.5971039 0.7178676 -0.392721 0.6469765 0.6535992 -0.4227553 0.6829946 0.5956479 -0.4189375 0.7037429 0.573792 -0.4448485 0.7428994 0.5002104 -0.4595344 0.7614347 0.4572148 -0.4591058 0.7859398 0.4141505 -0.4762167 0.8033487 0.3575593 -0.4761586 0.8161107 0.3274697 -0.490381 0.8283496 0.270857 -0.4883409 0.8411452 0.2323747 -0.4996276 0.8469345 0.1818631 -0.4977651 0.8591103 0.1189936 -0.5047497 0.8585231 0.090366 -0.5021908 0.864757 3.0519e-5 -0.5048758 0.8585606 -0.0892986 -0.4977404 0.8591202 -0.1190255 -0.5060287 0.8625164 6.10372e-4 -0.4997285 0.8471029 -0.1807983 -0.4884594 0.8411695 -0.2320373 -0.4905978 0.828599 -0.269699 -0.4764919 0.8164423 -0.3261557 -0.4765331 0.8036726 -0.3564079 -0.4596228 0.7867608 -0.4120125 -0.4576715 0.7619517 -0.4582209 -0.4504035 0.7388412 -0.5012487 -0.427545 0.7053318 -0.5654312 -0.4185705 0.6861016 -0.5950324 -0.4006868 0.64011 -0.6555222 -0.3702552 0.6006424 -0.7086182 -0.3595518 0.5807276 -0.7303959 -0.3397105 0.5157459 -0.7865133 0.3597165 -0.6739679 -0.6452684 0.3601983 -0.6747648 -0.644166 0.3927218 -0.7464706 -0.5371695 0.394093 -0.7347471 -0.5521209 0.4246707 -0.7847328 -0.4514968 0.3597252 -0.6739656 -0.645266 0.4240397 -0.8073968 -0.4102448 0.4673154 -0.8531132 -0.2319791 0.4597992 -0.8768412 -0.1404789 0.4817149 -0.8763281 0 0.4597731 -0.8768498 0.1405108 0.4673154 -0.8531132 0.2319791 0.426239 -0.8049587 0.4127492 0.4201803 -0.7855492 0.4542697 0.3890284 -0.7416781 0.5464161 0.3597223 -0.6739715 0.6452614 0.4003551 -0.7457141 0.5325657 0.3597182 -0.6739715 0.6452636 -0.871208 -0.4909142 0 -0.8712142 -0.4909031 0 -0.8712136 -0.4909044 0 -0.8712097 -0.490911 0 -0.8712106 -0.4909096 0 -0.871226 -0.4908824 0 -0.8712123 -0.4909067 0 -0.8712115 -0.490908 0 -0.8712291 -0.4908766 0 -0.8712153 -0.4909012 0 -0.8712034 -0.4909222 0 -0.87121 -0.4909105 0 -0.8712097 -0.4909111 0 -0.8712008 -0.4909268 0 -0.8712141 -0.4909033 0 -0.8712119 -0.4909073 2.25845e-6 -0.8712123 -0.4909065 0 -0.8712295 -0.4908761 0 -0.8712142 -0.4909031 0 -0.8711815 -0.4909611 1.11684e-5 -0.8712024 -0.4909242 3.8259e-6 -0.871214 -0.4909033 0 -0.8712242 -0.4908855 -1.45167e-6 -0.8712118 -0.4909073 0 -0.8712118 -0.4909075 0 -0.8712124 -0.4909063 0 -0.8712138 -0.4909038 0 -0.8712098 -0.4909109 0 -0.8712131 -0.4909049 0 -0.8712133 -0.4909049 -7.94838e-7 -0.8712126 -0.490906 0 -0.8712206 -0.4908917 -8.73162e-7 -0.8712089 -0.4909126 6.19321e-7 -0.8712133 -0.4909048 -5.37712e-7 -0.8712199 -0.4908928 -1.80131e-6 -0.8712096 -0.4909114 7.33154e-7 -0.8712128 -0.4909056 -1.55985e-6 -0.8712151 -0.4909015 0 -0.8712214 -0.4908903 0 -0.8712164 -0.4908994 -1.01624e-6 -0.8712064 -0.490917 2.10339e-6 -0.8712162 -0.4908996 -1.5928e-6 -0.8711967 -0.4909342 0 -0.8712289 -0.4908771 0 -0.8712335 -0.4908687 0 -0.8712029 -0.4909234 0 -0.8711075 -0.4910925 -1.06852e-5 + + + + + + + + + + 0.312631 0.136698 0.323985 0.137749 0.311605 0.1366209 0.307214 0.137432 0.311605 0.1366209 0.323985 0.137749 0.298191 0.135299 0.312631 0.136698 0.311605 0.1366209 0.294212 0.135592 0.298191 0.135299 0.311605 0.1366209 0.307214 0.137432 0.294212 0.135592 0.311605 0.1366209 0.312631 0.136698 0.336114 0.138861 0.323985 0.137749 0.307214 0.137432 0.323985 0.137749 0.336114 0.138861 0.312631 0.136698 0.336895 0.138879 0.336114 0.138861 0.340058 0.139149 0.336114 0.138861 0.336895 0.138879 0.340058 0.139149 0.339521 0.139158 0.336114 0.138861 0.307214 0.137432 0.336114 0.138861 0.339521 0.139158 0.312631 0.136698 0.337187 0.138953 0.336895 0.138879 0.340463 0.139644 0.336895 0.138879 0.337187 0.138953 0.340058 0.139149 0.336895 0.138879 0.340463 0.139644 0.326007 0.138384 0.338188 0.139526 0.337187 0.138953 0.340463 0.139644 0.337187 0.138953 0.338188 0.139526 0.313591 0.137234 0.326007 0.138384 0.337187 0.138953 0.312631 0.136698 0.313591 0.137234 0.337187 0.138953 0.316413 0.139415 0.338188 0.139526 0.326007 0.138384 0.336292 0.140258 0.338188 0.139526 0.316413 0.139415 0.341617 0.140718 0.338188 0.139526 0.336292 0.140258 0.341617 0.140718 0.340463 0.139644 0.338188 0.139526 0.316413 0.139415 0.326007 0.138384 0.313591 0.137234 0.299192 0.135369 0.313591 0.137234 0.312631 0.136698 0.300289 0.135912 0.313591 0.137234 0.299192 0.135369 0.293944 0.135215 0.313591 0.137234 0.300289 0.135912 0.316413 0.139415 0.313591 0.137234 0.293944 0.135215 0.299192 0.135369 0.312631 0.136698 0.298191 0.135299 0.286465 0.133897 0.27897 0.132984 0.27276 0.1321099 0.253855 0.129788 0.27276 0.1321099 0.27897 0.132984 0.274319 0.132254 0.286465 0.133897 0.27276 0.1321099 0.26686 0.131162 0.274319 0.132254 0.27276 0.1321099 0.266073 0.1310189 0.27276 0.1321099 0.269028 0.131564 0.253855 0.129788 0.269028 0.131564 0.27276 0.1321099 0.266073 0.1310189 0.26686 0.131162 0.27276 0.1321099 0.286465 0.133897 0.285274 0.133805 0.27897 0.132984 0.281001 0.133707 0.27897 0.132984 0.285274 0.133805 0.281001 0.133707 0.253855 0.129788 0.27897 0.132984 0.299192 0.135369 0.298191 0.135299 0.285274 0.133805 0.281001 0.133707 0.285274 0.133805 0.298191 0.135299 0.286465 0.133897 0.299192 0.135369 0.285274 0.133805 0.294212 0.135592 0.281001 0.133707 0.298191 0.135299 0.300289 0.135912 0.299192 0.135369 0.286465 0.133897 0.287727 0.1344839 0.286465 0.133897 0.274319 0.132254 0.293944 0.135215 0.300289 0.135912 0.286465 0.133897 0.287727 0.1344839 0.293944 0.135215 0.286465 0.133897 0.287727 0.1344839 0.274319 0.132254 0.275771 0.1329219 0.272067 0.132389 0.275771 0.1329219 0.274319 0.132254 0.268336 0.131853 0.272067 0.132389 0.274319 0.132254 0.267619 0.131442 0.268336 0.131853 0.274319 0.132254 0.26686 0.131162 0.267619 0.131442 0.274319 0.132254 0.287727 0.1344839 0.275771 0.1329219 0.293944 0.135215 0.296597 0.137521 0.293944 0.135215 0.275771 0.1329219 0.267842 0.134246 0.275771 0.1329219 0.272067 0.132389 0.27819 0.135239 0.296597 0.137521 0.275771 0.1329219 0.267842 0.134246 0.27819 0.135239 0.275771 0.1329219 0.316413 0.139415 0.293944 0.135215 0.296597 0.137521 0.266073 0.1310189 0.269028 0.131564 0.265274 0.131013 0.253855 0.129788 0.265274 0.131013 0.269028 0.131564 0.256094 0.1294929 0.266073 0.1310189 0.265274 0.131013 0.253855 0.129788 0.256094 0.1294929 0.265274 0.131013 0.267842 0.134246 0.272067 0.132389 0.268336 0.131853 0.257811 0.129966 0.268336 0.131853 0.267619 0.131442 0.260133 0.13082 0.268336 0.131853 0.257811 0.129966 0.267842 0.134246 0.268336 0.131853 0.260133 0.13082 0.256781 0.129507 0.267619 0.131442 0.26686 0.131162 0.257811 0.129966 0.267619 0.131442 0.256781 0.129507 0.255693 0.129253 0.26686 0.131162 0.266073 0.1310189 0.256781 0.129507 0.26686 0.131162 0.255693 0.129253 0.255693 0.129253 0.266073 0.1310189 0.256094 0.1294929 0.229008 0.120976 0.225125 0.119643 0.22336 0.118185 0.211212 0.111828 0.22336 0.118185 0.225125 0.119643 0.226042 0.1186079 0.229008 0.120976 0.22336 0.118185 0.218323 0.1128489 0.226042 0.1186079 0.22336 0.118185 0.211212 0.111828 0.218323 0.1128489 0.22336 0.118185 0.229008 0.120976 0.227302 0.121013 0.225125 0.119643 0.211212 0.111828 0.225125 0.119643 0.227302 0.121013 0.2336159 0.123224 0.229894 0.1223 0.227302 0.121013 0.224607 0.122168 0.227302 0.121013 0.229894 0.1223 0.229008 0.120976 0.2336159 0.123224 0.227302 0.121013 0.224607 0.122168 0.211212 0.111828 0.227302 0.121013 0.2336159 0.123224 0.232896 0.123509 0.229894 0.1223 0.225874 0.123079 0.229894 0.1223 0.232896 0.123509 0.225874 0.123079 0.224607 0.122168 0.229894 0.1223 0.239647 0.125351 0.236187 0.124654 0.232896 0.123509 0.227407 0.123946 0.232896 0.123509 0.236187 0.124654 0.2336159 0.123224 0.239647 0.125351 0.232896 0.123509 0.227407 0.123946 0.225874 0.123079 0.232896 0.123509 0.239647 0.125351 0.239766 0.125743 0.236187 0.124654 0.22916 0.124772 0.236187 0.124654 0.239766 0.125743 0.22916 0.124772 0.227407 0.123946 0.236187 0.124654 0.24699 0.12736 0.247571 0.1277379 0.239766 0.125743 0.233767 0.126272 0.239766 0.125743 0.247571 0.1277379 0.239647 0.125351 0.24699 0.12736 0.239766 0.125743 0.231253 0.125553 0.22916 0.124772 0.239766 0.125743 0.233767 0.126272 0.231253 0.125553 0.239766 0.125743 0.255693 0.129253 0.256094 0.1294929 0.247571 0.1277379 0.244586 0.1283749 0.247571 0.1277379 0.256094 0.1294929 0.24699 0.12736 0.255693 0.129253 0.247571 0.1277379 0.236779 0.126968 0.233767 0.126272 0.247571 0.1277379 0.240449 0.127671 0.236779 0.126968 0.247571 0.1277379 0.244586 0.1283749 0.240449 0.127671 0.247571 0.1277379 0.249041 0.1290799 0.256094 0.1294929 0.253855 0.129788 0.249041 0.1290799 0.244586 0.1283749 0.256094 0.1294929 0.256781 0.129507 0.255693 0.129253 0.24699 0.12736 0.248364 0.127749 0.24699 0.12736 0.239647 0.125351 0.248364 0.127749 0.256781 0.129507 0.24699 0.12736 0.2413 0.125897 0.239647 0.125351 0.2336159 0.123224 0.2413 0.125897 0.248364 0.127749 0.239647 0.125351 0.235543 0.123952 0.2336159 0.123224 0.229008 0.120976 0.235543 0.123952 0.2413 0.125897 0.2336159 0.123224 0.231202 0.121911 0.229008 0.120976 0.226042 0.1186079 0.231202 0.121911 0.235543 0.123952 0.229008 0.120976 0.231202 0.121911 0.226042 0.1186079 0.228489 0.1197749 0.219853 0.112112 0.228489 0.1197749 0.226042 0.1186079 0.219853 0.112112 0.226042 0.1186079 0.218323 0.1128489 0.233062 0.123405 0.231202 0.121911 0.228489 0.1197749 0.233062 0.123405 0.228489 0.1197749 0.230484 0.1216 0.222337 0.113238 0.230484 0.1216 0.228489 0.1197749 0.222337 0.113238 0.228489 0.1197749 0.219853 0.112112 0.257811 0.129966 0.256781 0.129507 0.248364 0.127749 0.249637 0.1284199 0.248364 0.127749 0.2413 0.125897 0.249637 0.1284199 0.257811 0.129966 0.248364 0.127749 0.242793 0.1268129 0.2413 0.125897 0.235543 0.123952 0.242793 0.1268129 0.249637 0.1284199 0.2413 0.125897 0.237233 0.125142 0.235543 0.123952 0.231202 0.121911 0.237233 0.125142 0.242793 0.1268129 0.235543 0.123952 0.233062 0.123405 0.237233 0.125142 0.231202 0.121911 0.233174 0.1247439 0.233062 0.123405 0.230484 0.1216 0.233174 0.1247439 0.230484 0.1216 0.231867 0.12392 0.2244009 0.115009 0.231867 0.12392 0.230484 0.1216 0.2244009 0.115009 0.230484 0.1216 0.222337 0.113238 0.256995 0.130347 0.257811 0.129966 0.249637 0.1284199 0.256995 0.130347 0.260133 0.13082 0.257811 0.129966 0.247573 0.128756 0.249637 0.1284199 0.242793 0.1268129 0.25256 0.129653 0.256995 0.130347 0.249637 0.1284199 0.247573 0.128756 0.25256 0.129653 0.249637 0.1284199 0.242583 0.127728 0.242793 0.1268129 0.237233 0.125142 0.245691 0.128389 0.247573 0.128756 0.242793 0.1268129 0.242583 0.127728 0.245691 0.128389 0.242793 0.1268129 0.237201 0.126313 0.237233 0.125142 0.233062 0.123405 0.240199 0.127147 0.242583 0.127728 0.237233 0.125142 0.23974 0.127029 0.240199 0.127147 0.237233 0.125142 0.237201 0.126313 0.23974 0.127029 0.237233 0.125142 0.2349849 0.125548 0.237201 0.126313 0.233062 0.123405 0.234953 0.125535 0.2349849 0.125548 0.233062 0.123405 0.233174 0.1247439 0.234953 0.125535 0.233062 0.123405 0.2377949 0.135298 0.233174 0.1247439 0.231867 0.12392 0.231576 0.123588 0.231867 0.12392 0.2244009 0.115009 0.235647 0.135783 0.231867 0.12392 0.231576 0.123588 0.2377949 0.135298 0.231867 0.12392 0.235647 0.135783 0.267842 0.134246 0.260133 0.13082 0.256995 0.130347 0.257303 0.135936 0.256995 0.130347 0.25256 0.129653 0.267842 0.134246 0.256995 0.130347 0.267639 0.1370429 0.257303 0.135936 0.267639 0.1370429 0.256995 0.130347 0.257303 0.135936 0.25256 0.129653 0.247573 0.128756 0.248914 0.136081 0.247573 0.128756 0.245691 0.128389 0.257303 0.135936 0.247573 0.128756 0.248914 0.136081 0.248914 0.136081 0.245691 0.128389 0.242583 0.127728 0.248914 0.136081 0.242583 0.127728 0.240199 0.127147 0.242647 0.1367239 0.240199 0.127147 0.23974 0.127029 0.248914 0.136081 0.240199 0.127147 0.242647 0.1367239 0.242647 0.1367239 0.23974 0.127029 0.237201 0.126313 0.242647 0.1367239 0.237201 0.126313 0.2349849 0.125548 0.242647 0.1367239 0.2349849 0.125548 0.234953 0.125535 0.2377949 0.135298 0.234953 0.125535 0.233174 0.1247439 0.242647 0.1367239 0.234953 0.125535 0.2377949 0.135298 0.178865 0.07804697 0.171033 0.07421499 0.159538 0.06657397 0.158903 0.06760597 0.159538 0.06657397 0.171033 0.07421499 0.1622959 0.06682097 0.178865 0.07804697 0.159538 0.06657397 0.156321 0.06374698 0.1622959 0.06682097 0.159538 0.06657397 0.134935 0.04589688 0.156321 0.06374698 0.159538 0.06657397 0.158903 0.06760597 0.134935 0.04589688 0.159538 0.06657397 0.178865 0.07804697 0.181343 0.08149999 0.171033 0.07421499 0.158903 0.06760597 0.171033 0.07421499 0.181343 0.08149999 0.192371 0.08802396 0.190567 0.08843296 0.181343 0.08149999 0.178961 0.08517599 0.181343 0.08149999 0.190567 0.08843296 0.178865 0.07804697 0.192371 0.08802396 0.181343 0.08149999 0.178961 0.08517599 0.158903 0.06760597 0.181343 0.08149999 0.203401 0.09692996 0.198795 0.095025 0.190567 0.08843296 0.178961 0.08517599 0.190567 0.08843296 0.198795 0.095025 0.192371 0.08802396 0.203401 0.09692996 0.190567 0.08843296 0.203401 0.09692996 0.206113 0.101284 0.198795 0.095025 0.196161 0.09967195 0.198795 0.095025 0.206113 0.101284 0.196161 0.09967195 0.178961 0.08517599 0.198795 0.095025 0.212435 0.104916 0.212597 0.107221 0.206113 0.101284 0.196161 0.09967195 0.206113 0.101284 0.212597 0.107221 0.203401 0.09692996 0.212435 0.104916 0.206113 0.101284 0.219853 0.112112 0.218323 0.1128489 0.212597 0.107221 0.211212 0.111828 0.212597 0.107221 0.218323 0.1128489 0.212435 0.104916 0.219853 0.112112 0.212597 0.107221 0.211212 0.111828 0.196161 0.09967195 0.212597 0.107221 0.222337 0.113238 0.219853 0.112112 0.212435 0.104916 0.214954 0.1059949 0.212435 0.104916 0.203401 0.09692996 0.214954 0.1059949 0.222337 0.113238 0.212435 0.104916 0.205953 0.09795898 0.203401 0.09692996 0.192371 0.08802396 0.205953 0.09795898 0.214954 0.1059949 0.203401 0.09692996 0.1949509 0.08899796 0.192371 0.08802396 0.178865 0.07804697 0.1949509 0.08899796 0.205953 0.09795898 0.192371 0.08802396 0.18147 0.07896 0.178865 0.07804697 0.1622959 0.06682097 0.18147 0.07896 0.1949509 0.08899796 0.178865 0.07804697 0.18147 0.07896 0.1622959 0.06682097 0.163195 0.06703799 0.160089 0.06429696 0.163195 0.06703799 0.1622959 0.06682097 0.160089 0.06429696 0.1622959 0.06682097 0.156321 0.06374698 0.16492 0.067667 0.18147 0.07896 0.163195 0.06703799 0.160089 0.06429696 0.16492 0.067667 0.163195 0.06703799 0.2244009 0.115009 0.222337 0.113238 0.214954 0.1059949 0.217084 0.107708 0.214954 0.1059949 0.205953 0.09795898 0.217084 0.107708 0.2244009 0.115009 0.214954 0.1059949 0.208145 0.09960699 0.205953 0.09795898 0.1949509 0.08899796 0.208145 0.09960699 0.217084 0.107708 0.205953 0.09795898 0.1972039 0.09057396 0.1949509 0.08899796 0.18147 0.07896 0.1972039 0.09057396 0.208145 0.09960699 0.1949509 0.08899796 0.183776 0.08045697 0.18147 0.07896 0.16492 0.067667 0.183776 0.08045697 0.1972039 0.09057396 0.18147 0.07896 0.183776 0.08045697 0.16492 0.067667 0.166528 0.06854999 0.163527 0.06586998 0.166528 0.06854999 0.16492 0.067667 0.163527 0.06586998 0.16492 0.067667 0.160089 0.06429696 0.167275 0.06907796 0.183776 0.08045697 0.166528 0.06854999 0.166356 0.06834197 0.167275 0.06907796 0.166528 0.06854999 0.166356 0.06834197 0.166528 0.06854999 0.163527 0.06586998 0.221475 0.112702 0.2244009 0.115009 0.217084 0.107708 0.226996 0.118487 0.231576 0.123588 0.2244009 0.115009 0.221475 0.112702 0.226996 0.118487 0.2244009 0.115009 0.215179 0.106597 0.217084 0.107708 0.208145 0.09960699 0.215179 0.106597 0.221475 0.112702 0.217084 0.107708 0.208033 0.100176 0.208145 0.09960699 0.1972039 0.09057396 0.208033 0.100176 0.215179 0.106597 0.208145 0.09960699 0.190837 0.08630698 0.1972039 0.09057396 0.183776 0.08045697 0.199949 0.09341996 0.208033 0.100176 0.1972039 0.09057396 0.190837 0.08630698 0.199949 0.09341996 0.1972039 0.09057396 0.180629 0.07883 0.183776 0.08045697 0.167275 0.06907796 0.180629 0.07883 0.190837 0.08630698 0.183776 0.08045697 0.180629 0.07883 0.167275 0.06907796 0.169251 0.07098197 0.166356 0.06834197 0.169251 0.07098197 0.167275 0.06907796 0.20376 0.106599 0.180629 0.07883 0.169251 0.07098197 0.169881 0.07252097 0.169251 0.07098197 0.166356 0.06834197 0.172489 0.07489299 0.20376 0.106599 0.169251 0.07098197 0.169881 0.07252097 0.172489 0.07489299 0.169251 0.07098197 0.226303 0.119837 0.231576 0.123588 0.226996 0.118487 0.235647 0.135783 0.231576 0.123588 0.226303 0.119837 0.226303 0.119837 0.226996 0.118487 0.221475 0.112702 0.226303 0.119837 0.221475 0.112702 0.215179 0.106597 0.220103 0.115765 0.215179 0.106597 0.208033 0.100176 0.220103 0.115765 0.226303 0.119837 0.215179 0.106597 0.212686 0.111371 0.208033 0.100176 0.199949 0.09341996 0.212686 0.111371 0.220103 0.115765 0.208033 0.100176 0.212686 0.111371 0.199949 0.09341996 0.190837 0.08630698 0.20376 0.106599 0.190837 0.08630698 0.180629 0.07883 0.20376 0.106599 0.212686 0.111371 0.190837 0.08630698 0.159209 0.06148689 0.156321 0.06374698 0.155346 0.06083196 0.134935 0.04589688 0.155346 0.06083196 0.156321 0.06374698 0.162226 0.03692597 0.159209 0.06148689 0.155346 0.06083196 0.162226 0.03692597 0.155346 0.06083196 0.156268 0.04923188 0.134935 0.04589688 0.156268 0.04923188 0.155346 0.06083196 0.159209 0.06148689 0.160089 0.06429696 0.156321 0.06374698 0.162733 0.06317496 0.163527 0.06586998 0.160089 0.06429696 0.159209 0.06148689 0.162733 0.06317496 0.160089 0.06429696 0.165625 0.06575697 0.166356 0.06834197 0.163527 0.06586998 0.162733 0.06317496 0.165625 0.06575697 0.163527 0.06586998 0.168875 0.06966996 0.166356 0.06834197 0.165625 0.06575697 0.168875 0.06966996 0.169881 0.07252097 0.166356 0.06834197 0.167174 0.05686098 0.165625 0.06575697 0.162733 0.06317496 0.186426 0.08204197 0.165625 0.06575697 0.167174 0.05686098 0.186426 0.08204197 0.168875 0.06966996 0.165625 0.06575697 0.166496 0.03914499 0.162733 0.06317496 0.159209 0.06148689 0.16752 0.05494797 0.167174 0.05686098 0.162733 0.06317496 0.169868 0.04250997 0.16752 0.05494797 0.162733 0.06317496 0.166496 0.03914499 0.169868 0.04250997 0.162733 0.06317496 0.162226 0.03692597 0.166496 0.03914499 0.159209 0.06148689 0.162226 0.03692597 0.156268 0.04923188 0.157471 0.03606289 0.134935 0.04589688 0.157471 0.03606289 0.156268 0.04923188 0.160441 0.03025895 0.162226 0.03692597 0.157471 0.03606289 0.105418 0.01844096 0.160441 0.03025895 0.157471 0.03606289 0.134935 0.04589688 0.105418 0.01844096 0.157471 0.03606289 0.179396 0.06071794 0.167174 0.05686098 0.16752 0.05494797 0.186426 0.08204197 0.167174 0.05686098 0.179396 0.06071794 0.179396 0.06071794 0.16752 0.05494797 0.169868 0.04250997 0.167962 0.032637 0.169868 0.04250997 0.166496 0.03914499 0.170036 0.03886598 0.169868 0.04250997 0.167962 0.032637 0.178704 0.05500888 0.169868 0.04250997 0.170036 0.03886598 0.179396 0.06071794 0.169868 0.04250997 0.178704 0.05500888 0.164332 0.03099495 0.166496 0.03914499 0.162226 0.03692597 0.164332 0.03099495 0.167962 0.032637 0.166496 0.03914499 0.160441 0.03025895 0.164332 0.03099495 0.162226 0.03692597 0.197331 0.01375591 0.1936179 0.01482099 0.207411 0.009556949 0.1927019 0.01457798 0.207411 0.009556949 0.1936179 0.01482099 0.204725 0.01278793 0.197331 0.01375591 0.207411 0.009556949 0.194979 0.01332396 0.207411 0.009556949 0.1927019 0.01457798 0.103559 0.01667797 0.207411 0.009556949 0.194979 0.01332396 0.292295 0.01569592 0.204725 0.01278793 0.207411 0.009556949 0.292295 0.01569592 0.207411 0.009556949 0.283415 0.005760908 0.09471297 0.01186388 0.283415 0.005760908 0.207411 0.009556949 0.103559 0.01667797 0.09471297 0.01186388 0.207411 0.009556949 0.189051 0.01804792 0.182124 0.0204119 0.1936179 0.01482099 0.1927019 0.01457798 0.1936179 0.01482099 0.182124 0.0204119 0.192443 0.01616996 0.189051 0.01804792 0.1936179 0.01482099 0.197331 0.01375591 0.192443 0.01616996 0.1936179 0.01482099 0.176306 0.02761989 0.173381 0.02635997 0.182124 0.0204119 0.180259 0.01979088 0.182124 0.0204119 0.173381 0.02635997 0.17717 0.02671897 0.176306 0.02761989 0.182124 0.0204119 0.182303 0.02238392 0.17717 0.02671897 0.182124 0.0204119 0.1826519 0.02213299 0.182303 0.02238392 0.182124 0.0204119 0.189051 0.01804792 0.1826519 0.02213299 0.182124 0.0204119 0.180259 0.01979088 0.1927019 0.01457798 0.182124 0.0204119 0.171168 0.03492099 0.167962 0.032637 0.173381 0.02635997 0.170584 0.02525997 0.173381 0.02635997 0.167962 0.032637 0.172284 0.03273797 0.171168 0.03492099 0.173381 0.02635997 0.173529 0.03089797 0.172284 0.03273797 0.173381 0.02635997 0.176306 0.02761989 0.173529 0.03089797 0.173381 0.02635997 0.170584 0.02525997 0.180259 0.01979088 0.173381 0.02635997 0.170251 0.03777092 0.170036 0.03886598 0.167962 0.032637 0.171168 0.03492099 0.170251 0.03777092 0.167962 0.032637 0.164332 0.03099495 0.170584 0.02525997 0.167962 0.032637 0.178704 0.05500888 0.170036 0.03886598 0.170251 0.03777092 0.17879 0.04752898 0.170251 0.03777092 0.171168 0.03492099 0.178704 0.05500888 0.170251 0.03777092 0.17879 0.04752898 0.17879 0.04752898 0.171168 0.03492099 0.172284 0.03273797 0.180754 0.04013293 0.172284 0.03273797 0.173529 0.03089797 0.17879 0.04752898 0.172284 0.03273797 0.180754 0.04013293 0.180754 0.04013293 0.173529 0.03089797 0.176306 0.02761989 0.185123 0.03366088 0.176306 0.02761989 0.17717 0.02671897 0.180754 0.04013293 0.176306 0.02761989 0.185123 0.03366088 0.185123 0.03366088 0.17717 0.02671897 0.182303 0.02238392 0.185123 0.03366088 0.182303 0.02238392 0.1826519 0.02213299 0.191695 0.02521795 0.1826519 0.02213299 0.189051 0.01804792 0.185123 0.03366088 0.1826519 0.02213299 0.191695 0.02521795 0.191695 0.02521795 0.189051 0.01804792 0.192443 0.01616996 0.202787 0.01642888 0.192443 0.01616996 0.197331 0.01375591 0.200999 0.02475899 0.191695 0.02521795 0.192443 0.01616996 0.202787 0.01642888 0.200999 0.02475899 0.192443 0.01616996 0.204725 0.01278793 0.202787 0.01642888 0.197331 0.01375591 0.184489 0.01698398 0.1927019 0.01457798 0.180259 0.01979088 0.184489 0.01698398 0.194979 0.01332396 0.1927019 0.01457798 0.175804 0.02055096 0.180259 0.01979088 0.170584 0.02525997 0.175804 0.02055096 0.184489 0.01698398 0.180259 0.01979088 0.1639029 0.027188 0.170584 0.02525997 0.164332 0.03099495 0.168925 0.02397096 0.175804 0.02055096 0.170584 0.02525997 0.1639029 0.027188 0.168925 0.02397096 0.170584 0.02525997 0.160441 0.03025895 0.1639029 0.027188 0.164332 0.03099495 0.105418 0.01844096 0.194979 0.01332396 0.184489 0.01698398 0.104487 0.01756298 0.103559 0.01667797 0.194979 0.01332396 0.105418 0.01844096 0.104487 0.01756298 0.194979 0.01332396 0.105418 0.01844096 0.184489 0.01698398 0.175804 0.02055096 0.105418 0.01844096 0.175804 0.02055096 0.168925 0.02397096 0.105418 0.01844096 0.168925 0.02397096 0.1639029 0.027188 0.105418 0.01844096 0.1639029 0.027188 0.160441 0.03025895 0.2017379 0.034361 0.1937 0.03635096 0.191695 0.02521795 0.185123 0.03366088 0.191695 0.02521795 0.1937 0.03635096 0.200999 0.02475899 0.2017379 0.034361 0.191695 0.02521795 0.204758 0.04518991 0.198291 0.04933691 0.1937 0.03635096 0.1900939 0.04718798 0.1937 0.03635096 0.198291 0.04933691 0.2017379 0.034361 0.204758 0.04518991 0.1937 0.03635096 0.1900939 0.04718798 0.185123 0.03366088 0.1937 0.03635096 0.209877 0.05730789 0.205192 0.06394499 0.198291 0.04933691 0.197272 0.062442 0.198291 0.04933691 0.205192 0.06394499 0.204758 0.04518991 0.209877 0.05730789 0.198291 0.04933691 0.197272 0.062442 0.1900939 0.04718798 0.198291 0.04933691 0.216978 0.07082998 0.213966 0.07990497 0.205192 0.06394499 0.206218 0.07912498 0.205192 0.06394499 0.213966 0.07990497 0.209877 0.05730789 0.216978 0.07082998 0.205192 0.06394499 0.206218 0.07912498 0.197272 0.062442 0.205192 0.06394499 0.225933 0.08586698 0.2241269 0.09696 0.213966 0.07990497 0.216446 0.09695196 0.213966 0.07990497 0.2241269 0.09696 0.216978 0.07082998 0.225933 0.08586698 0.213966 0.07990497 0.216446 0.09695196 0.206218 0.07912498 0.213966 0.07990497 0.242631 0.111773 0.235203 0.1148959 0.2241269 0.09696 0.227484 0.11568 0.2241269 0.09696 0.235203 0.1148959 0.236759 0.102785 0.242631 0.111773 0.2241269 0.09696 0.225933 0.08586698 0.236759 0.102785 0.2241269 0.09696 0.227484 0.11568 0.216446 0.09695196 0.2241269 0.09696 0.254964 0.13041 0.246784 0.133549 0.235203 0.1148959 0.238924 0.135125 0.235203 0.1148959 0.246784 0.133549 0.24865 0.120882 0.254964 0.13041 0.235203 0.1148959 0.242631 0.111773 0.24865 0.120882 0.235203 0.1148959 0.238924 0.135125 0.227484 0.11568 0.235203 0.1148959 0.261659 0.140609 0.258538 0.152803 0.246784 0.133549 0.25044 0.155151 0.246784 0.133549 0.258538 0.152803 0.254964 0.13041 0.261659 0.140609 0.246784 0.133549 0.25044 0.155151 0.238924 0.135125 0.246784 0.133549 0.275991 0.162976 0.270169 0.17255 0.258538 0.152803 0.261741 0.175635 0.258538 0.152803 0.270169 0.17255 0.268676 0.15141 0.275991 0.162976 0.258538 0.152803 0.261659 0.140609 0.268676 0.15141 0.258538 0.152803 0.261741 0.175635 0.25044 0.155151 0.258538 0.152803 0.291417 0.188354 0.28144 0.192698 0.270169 0.17255 0.261741 0.175635 0.270169 0.17255 0.28144 0.192698 0.283578 0.175301 0.291417 0.188354 0.270169 0.17255 0.275991 0.162976 0.283578 0.175301 0.270169 0.17255 0.283562 0.196858 0.28144 0.192698 0.291417 0.188354 0.272602 0.19647 0.261741 0.175635 0.28144 0.192698 0.283562 0.196858 0.272602 0.19647 0.28144 0.192698 0.331011 0.193936 0.291417 0.188354 0.283578 0.175301 0.331011 0.193936 0.292634 0.190518 0.291417 0.188354 0.283562 0.196858 0.291417 0.188354 0.292634 0.190518 0.329543 0.166254 0.283578 0.175301 0.275991 0.162976 0.329543 0.166254 0.331011 0.193936 0.283578 0.175301 0.329543 0.166254 0.275991 0.162976 0.268676 0.15141 0.329543 0.166254 0.268676 0.15141 0.261659 0.140609 0.3271 0.139321 0.261659 0.140609 0.254964 0.13041 0.3271 0.139321 0.329543 0.166254 0.261659 0.140609 0.3271 0.139321 0.254964 0.13041 0.24865 0.120882 0.323682 0.113506 0.24865 0.120882 0.242631 0.111773 0.323682 0.113506 0.3271 0.139321 0.24865 0.120882 0.323682 0.113506 0.242631 0.111773 0.236759 0.102785 0.31929 0.08919399 0.236759 0.102785 0.225933 0.08586698 0.31929 0.08919399 0.323682 0.113506 0.236759 0.102785 0.31929 0.08919399 0.225933 0.08586698 0.216978 0.07082998 0.313931 0.06679499 0.216978 0.07082998 0.209877 0.05730789 0.313931 0.06679499 0.31929 0.08919399 0.216978 0.07082998 0.307621 0.04675096 0.209877 0.05730789 0.204758 0.04518991 0.307621 0.04675096 0.313931 0.06679499 0.209877 0.05730789 0.307621 0.04675096 0.204758 0.04518991 0.2017379 0.034361 0.300391 0.02954399 0.2017379 0.034361 0.200999 0.02475899 0.300391 0.02954399 0.307621 0.04675096 0.2017379 0.034361 0.292295 0.01569592 0.200999 0.02475899 0.202787 0.01642888 0.292295 0.01569592 0.300391 0.02954399 0.200999 0.02475899 0.292295 0.01569592 0.202787 0.01642888 0.204725 0.01278793 0.180754 0.04013293 0.185123 0.03366088 0.1900939 0.04718798 0.187104 0.05429589 0.1900939 0.04718798 0.197272 0.062442 0.187104 0.05429589 0.180754 0.04013293 0.1900939 0.04718798 0.195015 0.06980198 0.197272 0.062442 0.206218 0.07912498 0.195015 0.06980198 0.187104 0.05429589 0.197272 0.062442 0.204114 0.08640795 0.206218 0.07912498 0.216446 0.09695196 0.204114 0.08640795 0.195015 0.06980198 0.206218 0.07912498 0.214019 0.103893 0.216446 0.09695196 0.227484 0.11568 0.214019 0.103893 0.204114 0.08640795 0.216446 0.09695196 0.224385 0.122079 0.227484 0.11568 0.238924 0.135125 0.224385 0.122079 0.214019 0.103893 0.227484 0.11568 0.234923 0.140833 0.238924 0.135125 0.25044 0.155151 0.234923 0.140833 0.224385 0.122079 0.238924 0.135125 0.245393 0.16005 0.25044 0.155151 0.261741 0.175635 0.245393 0.16005 0.234923 0.140833 0.25044 0.155151 0.255582 0.1796309 0.261741 0.175635 0.272602 0.19647 0.255582 0.1796309 0.245393 0.16005 0.261741 0.175635 0.265325 0.19949 0.255582 0.1796309 0.272602 0.19647 0.27436 0.200125 0.265325 0.19949 0.272602 0.19647 0.27436 0.200125 0.272602 0.19647 0.283562 0.196858 0.17879 0.04752898 0.180754 0.04013293 0.187104 0.05429589 0.186985 0.06387799 0.187104 0.05429589 0.195015 0.06980198 0.186985 0.06387799 0.17879 0.04752898 0.187104 0.05429589 0.1964499 0.08144497 0.195015 0.06980198 0.204114 0.08640795 0.1964499 0.08144497 0.186985 0.06387799 0.195015 0.06980198 0.206772 0.09998196 0.204114 0.08640795 0.214019 0.103893 0.206772 0.09998196 0.1964499 0.08144497 0.204114 0.08640795 0.217571 0.11929 0.214019 0.103893 0.224385 0.122079 0.217571 0.11929 0.206772 0.09998196 0.214019 0.103893 0.228525 0.139218 0.224385 0.122079 0.234923 0.140833 0.228525 0.139218 0.217571 0.11929 0.224385 0.122079 0.2393749 0.1596519 0.234923 0.140833 0.245393 0.16005 0.2393749 0.1596519 0.228525 0.139218 0.234923 0.140833 0.249891 0.18049 0.245393 0.16005 0.255582 0.1796309 0.249891 0.18049 0.2393749 0.1596519 0.245393 0.16005 0.249891 0.18049 0.255582 0.1796309 0.265325 0.19949 0.259891 0.201642 0.249891 0.18049 0.265325 0.19949 0.266771 0.202735 0.259891 0.201642 0.265325 0.19949 0.266771 0.202735 0.265325 0.19949 0.27436 0.200125 0.178704 0.05500888 0.17879 0.04752898 0.186985 0.06387799 0.188668 0.07370996 0.186985 0.06387799 0.1964499 0.08144497 0.188668 0.07370996 0.178704 0.05500888 0.186985 0.06387799 0.1996459 0.09351998 0.1964499 0.08144497 0.206772 0.09998196 0.1996459 0.09351998 0.188668 0.07370996 0.1964499 0.08144497 0.211193 0.114205 0.206772 0.09998196 0.217571 0.11929 0.211193 0.114205 0.1996459 0.09351998 0.206772 0.09998196 0.222929 0.1355929 0.217571 0.11929 0.228525 0.139218 0.222929 0.1355929 0.211193 0.114205 0.217571 0.11929 0.234555 0.1575649 0.228525 0.139218 0.2393749 0.1596519 0.234555 0.1575649 0.222929 0.1355929 0.228525 0.139218 0.245806 0.1800169 0.2393749 0.1596519 0.249891 0.18049 0.245806 0.1800169 0.234555 0.1575649 0.2393749 0.1596519 0.245806 0.1800169 0.249891 0.18049 0.259891 0.201642 0.256474 0.2028599 0.245806 0.1800169 0.259891 0.201642 0.261117 0.204578 0.256474 0.2028599 0.259891 0.201642 0.261117 0.204578 0.259891 0.201642 0.266771 0.202735 0.179396 0.06071794 0.178704 0.05500888 0.188668 0.07370996 0.190423 0.08065098 0.188668 0.07370996 0.1996459 0.09351998 0.190423 0.08065098 0.179396 0.06071794 0.188668 0.07370996 0.196375 0.09120696 0.1996459 0.09351998 0.211193 0.114205 0.196375 0.09120696 0.190423 0.08065098 0.1996459 0.09351998 0.208956 0.113497 0.211193 0.114205 0.222929 0.1355929 0.20257 0.102162 0.196375 0.09120696 0.211193 0.114205 0.208956 0.113497 0.20257 0.102162 0.211193 0.114205 0.2212859 0.135763 0.222929 0.1355929 0.234555 0.1575649 0.215505 0.12524 0.208956 0.113497 0.222929 0.1355929 0.2212859 0.135763 0.215505 0.12524 0.222929 0.1355929 0.235556 0.1626729 0.234555 0.1575649 0.245806 0.1800169 0.222164 0.137376 0.2212859 0.135763 0.234555 0.1575649 0.228853 0.149837 0.222164 0.137376 0.234555 0.1575649 0.235556 0.1626729 0.228853 0.149837 0.234555 0.1575649 0.248731 0.189283 0.245806 0.1800169 0.256474 0.2028599 0.242192 0.175814 0.235556 0.1626729 0.245806 0.1800169 0.248731 0.189283 0.242192 0.175814 0.245806 0.1800169 0.255133 0.203131 0.248731 0.189283 0.256474 0.2028599 0.255724 0.204443 0.255133 0.203131 0.256474 0.2028599 0.257587 0.205596 0.256474 0.2028599 0.261117 0.204578 0.256262 0.205772 0.256474 0.2028599 0.257587 0.205596 0.255724 0.204443 0.256474 0.2028599 0.256262 0.205772 0.186426 0.08204197 0.179396 0.06071794 0.190423 0.08065098 0.186426 0.08204197 0.190423 0.08065098 0.196375 0.09120696 0.186426 0.08204197 0.196375 0.09120696 0.20257 0.102162 0.2044849 0.108388 0.20257 0.102162 0.208956 0.113497 0.186426 0.08204197 0.20257 0.102162 0.2044849 0.108388 0.2044849 0.108388 0.208956 0.113497 0.215505 0.12524 0.2044849 0.108388 0.215505 0.12524 0.2212859 0.135763 0.219601 0.140487 0.2212859 0.135763 0.222164 0.137376 0.216511 0.135565 0.2212859 0.135763 0.219601 0.140487 0.2140949 0.13178 0.2212859 0.135763 0.216511 0.135565 0.211591 0.1279129 0.2212859 0.135763 0.2140949 0.13178 0.208992 0.12396 0.2212859 0.135763 0.211591 0.1279129 0.206297 0.119925 0.2212859 0.135763 0.208992 0.12396 0.2035059 0.11581 0.2212859 0.135763 0.206297 0.119925 0.2044849 0.108388 0.2212859 0.135763 0.2035059 0.11581 0.222541 0.145258 0.222164 0.137376 0.228853 0.149837 0.219601 0.140487 0.222164 0.137376 0.222541 0.145258 0.228034 0.154409 0.228853 0.149837 0.235556 0.1626729 0.225349 0.149896 0.228853 0.149837 0.228034 0.154409 0.222541 0.145258 0.228853 0.149837 0.225349 0.149896 0.235357 0.167123 0.235556 0.1626729 0.242192 0.175814 0.233036 0.163027 0.235556 0.1626729 0.235357 0.167123 0.230596 0.158788 0.235556 0.1626729 0.233036 0.163027 0.228034 0.154409 0.235556 0.1626729 0.230596 0.158788 0.241654 0.178567 0.242192 0.175814 0.248731 0.189283 0.239661 0.174892 0.242192 0.175814 0.241654 0.178567 0.2375659 0.171081 0.242192 0.175814 0.239661 0.174892 0.235357 0.167123 0.242192 0.175814 0.2375659 0.171081 0.25039 0.195321 0.248731 0.189283 0.255133 0.203131 0.247974 0.190578 0.248731 0.189283 0.25039 0.195321 0.245387 0.185593 0.248731 0.189283 0.247974 0.190578 0.243562 0.182137 0.248731 0.189283 0.245387 0.185593 0.241654 0.178567 0.248731 0.189283 0.243562 0.182137 0.254669 0.203925 0.255133 0.203131 0.255724 0.204443 0.254669 0.203925 0.254626 0.2038249 0.255133 0.203131 0.252599 0.199742 0.255133 0.203131 0.254626 0.2038249 0.25039 0.195321 0.255133 0.203131 0.252599 0.199742 0.273902 3.42e-4 0.292295 0.01569592 0.283415 0.005760908 0.09471297 0.01186388 0.273902 3.42e-4 0.283415 0.005760908 0.331011 0.193936 0.293952 0.193083 0.292634 0.190518 0.283562 0.196858 0.292634 0.190518 0.293952 0.193083 0.331011 0.193936 0.297333 0.2013249 0.293952 0.193083 0.286677 0.205031 0.293952 0.193083 0.297333 0.2013249 0.286677 0.205031 0.283562 0.196858 0.293952 0.193083 0.3315 0.222023 0.297698 0.202439 0.297333 0.2013249 0.286677 0.205031 0.297333 0.2013249 0.297698 0.202439 0.331011 0.193936 0.3315 0.222023 0.297333 0.2013249 0.3315 0.222023 0.2999 0.211465 0.297698 0.202439 0.288591 0.21345 0.297698 0.202439 0.2999 0.211465 0.288591 0.21345 0.286677 0.205031 0.297698 0.202439 0.3315 0.222023 0.300005 0.2121109 0.2999 0.211465 0.288591 0.21345 0.2999 0.211465 0.300005 0.2121109 0.3315 0.222023 0.300779 0.222023 0.300005 0.2121109 0.289273 0.222023 0.300005 0.2121109 0.300779 0.222023 0.288591 0.21345 0.300005 0.2121109 0.289273 0.222023 0.331483 0.227324 0.300779 0.222023 0.3315 0.222023 0.300559 0.227309 0.300779 0.222023 0.331483 0.227324 0.288588 0.230619 0.300779 0.222023 0.300559 0.227309 0.289273 0.222023 0.300779 0.222023 0.288588 0.230619 0.329525 0.222023 0.3315 0.222023 0.331011 0.193936 0.328976 0.251012 0.331483 0.227324 0.3315 0.222023 0.329525 0.222023 0.328976 0.251012 0.3315 0.222023 0.328983 0.193203 0.331011 0.193936 0.329543 0.166254 0.328983 0.193203 0.329525 0.222023 0.331011 0.193936 0.327353 0.1647689 0.329543 0.166254 0.3271 0.139321 0.327353 0.1647689 0.328983 0.193203 0.329543 0.166254 0.324634 0.137216 0.3271 0.139321 0.323682 0.113506 0.324634 0.137216 0.327353 0.1647689 0.3271 0.139321 0.320856 0.111151 0.323682 0.113506 0.31929 0.08919399 0.320856 0.111151 0.324634 0.137216 0.323682 0.113506 0.315974 0.08675396 0.31929 0.08919399 0.313931 0.06679499 0.315974 0.08675396 0.320856 0.111151 0.31929 0.08919399 0.303027 0.04549199 0.313931 0.06679499 0.307621 0.04675096 0.310013 0.06464898 0.315974 0.08675396 0.313931 0.06679499 0.303027 0.04549199 0.310013 0.06464898 0.313931 0.06679499 0.29509 0.02988499 0.307621 0.04675096 0.300391 0.02954399 0.29509 0.02988499 0.303027 0.04549199 0.307621 0.04675096 0.286306 0.01843392 0.300391 0.02954399 0.292295 0.01569592 0.286306 0.01843392 0.29509 0.02988499 0.300391 0.02954399 0.273902 3.42e-4 0.263948 0 0.292295 0.01569592 0.286306 0.01843392 0.292295 0.01569592 0.263948 0 0.328976 0.251012 0.331431 0.232622 0.331483 0.227324 0.300559 0.227309 0.331483 0.227324 0.331431 0.232622 0.328976 0.251012 0.331101 0.247395 0.331431 0.232622 0.2999 0.232567 0.331431 0.232622 0.331101 0.247395 0.3 0.23195 0.300559 0.227309 0.331431 0.232622 0.2999 0.232567 0.3 0.23195 0.331431 0.232622 0.328976 0.251012 0.330505 0.261983 0.331101 0.247395 0.293953 0.250962 0.331101 0.247395 0.330505 0.261983 0.297692 0.2416689 0.2999 0.232567 0.331101 0.247395 0.224198 0.193901 0.224207 0.249981 0.224965 0.222023 0.293953 0.250962 0.297692 0.2416689 0.331101 0.247395 0.327332 0.279546 0.329635 0.276478 0.330505 0.261983 0.283381 0.269035 0.330505 0.261983 0.329635 0.276478 0.328976 0.251012 0.327332 0.279546 0.330505 0.261983 0.292882 0.253064 0.293953 0.250962 0.330505 0.261983 0.291417 0.255692 0.292882 0.253064 0.330505 0.261983 0.283381 0.269035 0.291417 0.255692 0.330505 0.261983 0.327332 0.279546 0.328495 0.290818 0.329635 0.276478 0.275616 0.281633 0.329635 0.276478 0.328495 0.290818 0.275616 0.281633 0.283381 0.269035 0.329635 0.276478 0.324598 0.307123 0.327084 0.30487 0.328495 0.290818 0.268146 0.29346 0.328495 0.290818 0.327084 0.30487 0.327332 0.279546 0.324598 0.307123 0.328495 0.290818 0.268146 0.29346 0.275616 0.281633 0.328495 0.290818 0.324598 0.307123 0.325399 0.318655 0.327084 0.30487 0.261011 0.304437 0.327084 0.30487 0.325399 0.318655 0.261011 0.304437 0.268146 0.29346 0.327084 0.30487 0.320813 0.333143 0.323458 0.33198 0.325399 0.318655 0.247663 0.32469 0.325399 0.318655 0.323458 0.33198 0.324598 0.307123 0.320813 0.333143 0.325399 0.318655 0.254195 0.314784 0.261011 0.304437 0.325399 0.318655 0.247663 0.32469 0.254195 0.314784 0.325399 0.318655 0.31594 0.357435 0.321246 0.344899 0.323458 0.33198 0.241447 0.334073 0.323458 0.33198 0.321246 0.344899 0.320813 0.333143 0.31594 0.357435 0.323458 0.33198 0.241447 0.334073 0.247663 0.32469 0.323458 0.33198 0.31594 0.357435 0.318761 0.357353 0.321246 0.344899 0.235572 0.343052 0.321246 0.344899 0.318761 0.357353 0.235572 0.343052 0.241447 0.334073 0.321246 0.344899 0.310008 0.379411 0.315988 0.369368 0.318761 0.357353 0.22486 0.35992 0.318761 0.357353 0.315988 0.369368 0.31594 0.357435 0.310008 0.379411 0.318761 0.357353 0.22486 0.35992 0.235572 0.343052 0.318761 0.357353 0.310008 0.379411 0.312956 0.380731 0.315988 0.369368 0.216 0.374962 0.315988 0.369368 0.312956 0.380731 0.216 0.374962 0.22486 0.35992 0.315988 0.369368 0.303065 0.398465 0.309645 0.391459 0.312956 0.380731 0.216 0.374962 0.312956 0.380731 0.309645 0.391459 0.310008 0.379411 0.303065 0.398465 0.312956 0.380731 0.303065 0.398465 0.306089 0.401393 0.309645 0.391459 0.2091259 0.388325 0.309645 0.391459 0.306089 0.401393 0.2091259 0.388325 0.216 0.374962 0.309645 0.391459 0.295172 0.414028 0.30227 0.410519 0.306089 0.401393 0.204291 0.400194 0.306089 0.401393 0.30227 0.410519 0.303065 0.398465 0.295172 0.414028 0.306089 0.401393 0.204291 0.400194 0.2091259 0.388325 0.306089 0.401393 0.286418 0.4255 0.298222 0.418716 0.30227 0.410519 0.20156 0.410679 0.30227 0.410519 0.298222 0.418716 0.295172 0.414028 0.286418 0.4255 0.30227 0.410519 0.20156 0.410679 0.204291 0.400194 0.30227 0.410519 0.264424 0.444149 0.293935 0.425939 0.298222 0.418716 0.201037 0.419924 0.298222 0.418716 0.293935 0.425939 0.276936 0.432239 0.264424 0.444149 0.298222 0.418716 0.286418 0.4255 0.276936 0.432239 0.298222 0.418716 0.201037 0.419924 0.20156 0.410679 0.298222 0.418716 0.269679 0.444504 0.289443 0.432094 0.293935 0.425939 0.201037 0.419924 0.293935 0.425939 0.289443 0.432094 0.264424 0.444149 0.269679 0.444504 0.293935 0.425939 0.274843 0.44339 0.284745 0.437107 0.289443 0.432094 0.2029049 0.42791 0.289443 0.432094 0.284745 0.437107 0.269679 0.444504 0.274843 0.44339 0.289443 0.432094 0.2029049 0.42791 0.201037 0.419924 0.289443 0.432094 0.274843 0.44339 0.279872 0.440902 0.284745 0.437107 0.207411 0.434488 0.284745 0.437107 0.279872 0.440902 0.207411 0.434488 0.2029049 0.42791 0.284745 0.437107 0.103572 0.427369 0.279872 0.440902 0.274843 0.44339 0.103572 0.427369 0.207411 0.434488 0.279872 0.440902 0.09509795 0.432124 0.274843 0.44339 0.269679 0.444504 0.09509795 0.432124 0.103572 0.427369 0.274843 0.44339 0.08516895 0.432272 0.269679 0.444504 0.264424 0.444149 0.08516895 0.432272 0.09509795 0.432124 0.269679 0.444504 0.276936 0.432239 0.259093 0.442263 0.264424 0.444149 0.08516895 0.432272 0.264424 0.444149 0.259093 0.442263 0.266913 0.433587 0.25375 0.438768 0.259093 0.442263 0.07402199 0.427364 0.259093 0.442263 0.25375 0.438768 0.276936 0.432239 0.266913 0.433587 0.259093 0.442263 0.07402199 0.427364 0.08516895 0.432272 0.259093 0.442263 0.256604 0.428902 0.248408 0.433595 0.25375 0.438768 0.07402199 0.427364 0.25375 0.438768 0.248408 0.433595 0.266913 0.433587 0.256604 0.428902 0.25375 0.438768 0.246341 0.417634 0.243149 0.426708 0.248408 0.433595 0.06220096 0.41699 0.248408 0.433595 0.243149 0.426708 0.256604 0.428902 0.246341 0.417634 0.248408 0.433595 0.06220096 0.41699 0.07402199 0.427364 0.248408 0.433595 0.246341 0.417634 0.2379879 0.418034 0.243149 0.426708 0.06220096 0.41699 0.243149 0.426708 0.2379879 0.418034 0.236533 0.39945 0.233022 0.407613 0.2379879 0.418034 0.05046695 0.400912 0.2379879 0.418034 0.233022 0.407613 0.246341 0.417634 0.236533 0.39945 0.2379879 0.418034 0.05046695 0.400912 0.06220096 0.41699 0.2379879 0.418034 0.236533 0.39945 0.2282699 0.395376 0.233022 0.407613 0.05046695 0.400912 0.233022 0.407613 0.2282699 0.395376 0.227659 0.374435 0.2238399 0.381508 0.2282699 0.395376 0.03965193 0.379144 0.2282699 0.395376 0.2238399 0.381508 0.236533 0.39945 0.227659 0.374435 0.2282699 0.395376 0.03965193 0.379144 0.05046695 0.400912 0.2282699 0.395376 0.227659 0.374435 0.219759 0.365979 0.2238399 0.381508 0.03965193 0.379144 0.2238399 0.381508 0.219759 0.365979 0.220194 0.343164 0.216085 0.348883 0.219759 0.365979 0.03041189 0.352033 0.219759 0.365979 0.216085 0.348883 0.227659 0.374435 0.220194 0.343164 0.219759 0.365979 0.03041189 0.352033 0.03965193 0.379144 0.219759 0.365979 0.220194 0.343164 0.212841 0.3302 0.216085 0.348883 0.03041189 0.352033 0.216085 0.348883 0.212841 0.3302 0.2144629 0.3062 0.210112 0.31027 0.212841 0.3302 0.02293497 0.320245 0.212841 0.3302 0.210112 0.31027 0.220194 0.343164 0.2144629 0.3062 0.212841 0.3302 0.02293497 0.320245 0.03041189 0.352033 0.212841 0.3302 0.2144629 0.3062 0.207937 0.289185 0.210112 0.31027 0.01718389 0.284609 0.210112 0.31027 0.207937 0.289185 0.01718389 0.284609 0.02293497 0.320245 0.210112 0.31027 0.21087 0.265158 0.206355 0.267299 0.207937 0.289185 0.01718389 0.284609 0.207937 0.289185 0.206355 0.267299 0.2144629 0.3062 0.21087 0.265158 0.207937 0.289185 0.21087 0.265158 0.2054 0.244892 0.206355 0.267299 0.01371991 0.246266 0.206355 0.267299 0.2054 0.244892 0.01371991 0.246266 0.01718389 0.284609 0.206355 0.267299 0.209648 0.222023 0.2050729 0.222023 0.2054 0.244892 0.01312589 0.226617 0.2054 0.244892 0.2050729 0.222023 0.21087 0.265158 0.209648 0.222023 0.2054 0.244892 0.01312589 0.226617 0.01371991 0.246266 0.2054 0.244892 0.210884 0.178638 0.205114 0.213873 0.2050729 0.222023 0.01312589 0.226617 0.2050729 0.222023 0.205114 0.213873 0.210884 0.178638 0.2050729 0.222023 0.209648 0.222023 0.210884 0.178638 0.205238 0.2057369 0.205114 0.213873 0.01312589 0.226617 0.205114 0.213873 0.205238 0.2057369 0.210884 0.178638 0.207245 0.163331 0.205238 0.2057369 0.01329195 0.206915 0.205238 0.2057369 0.207245 0.163331 0.01329195 0.206915 0.01312589 0.226617 0.205238 0.2057369 0.2145079 0.1374689 0.211414 0.123624 0.207245 0.163331 0.01619696 0.167423 0.207245 0.163331 0.211414 0.123624 0.210884 0.178638 0.2145079 0.1374689 0.207245 0.163331 0.01441293 0.186955 0.01329195 0.206915 0.207245 0.163331 0.01619696 0.167423 0.01441293 0.186955 0.207245 0.163331 0.2202669 0.100508 0.2175 0.08816295 0.211414 0.123624 0.021649 0.130453 0.211414 0.123624 0.2175 0.08816295 0.2145079 0.1374689 0.2202669 0.100508 0.211414 0.123624 0.01862895 0.1485339 0.01619696 0.167423 0.211414 0.123624 0.021649 0.130453 0.01862895 0.1485339 0.211414 0.123624 0.22774 0.06933397 0.225167 0.05810195 0.2175 0.08816295 0.02899998 0.09718799 0.2175 0.08816295 0.225167 0.05810195 0.2202669 0.100508 0.22774 0.06933397 0.2175 0.08816295 0.02511799 0.113284 0.021649 0.130453 0.2175 0.08816295 0.02899998 0.09718799 0.02511799 0.113284 0.2175 0.08816295 0.236591 0.04446291 0.234032 0.034132 0.225167 0.05810195 0.038185 0.06864798 0.225167 0.05810195 0.234032 0.034132 0.22774 0.06933397 0.236591 0.04446291 0.225167 0.05810195 0.03337496 0.08227598 0.02899998 0.09718799 0.225167 0.05810195 0.038185 0.06864798 0.03337496 0.08227598 0.225167 0.05810195 0.246347 0.02640098 0.243697 0.016532 0.234032 0.034132 0.04907596 0.04560589 0.234032 0.034132 0.243697 0.016532 0.236591 0.04446291 0.246347 0.02640098 0.234032 0.034132 0.04341989 0.05640697 0.038185 0.06864798 0.234032 0.034132 0.04907596 0.04560589 0.04341989 0.05640697 0.234032 0.034132 0.25655 0.01518392 0.253783 0.00525099 0.243697 0.016532 0.06100291 0.02847898 0.243697 0.016532 0.253783 0.00525099 0.246347 0.02640098 0.25655 0.01518392 0.243697 0.016532 0.05497992 0.03628993 0.04907596 0.04560589 0.243697 0.016532 0.06100291 0.02847898 0.05497992 0.03628993 0.243697 0.016532 0.276816 0.011756 0.263948 0 0.253783 0.00525099 0.07302999 0.01733297 0.253783 0.00525099 0.263948 0 0.266813 0.0104739 0.276816 0.011756 0.253783 0.00525099 0.25655 0.01518392 0.266813 0.0104739 0.253783 0.00525099 0.06707096 0.02216392 0.06100291 0.02847898 0.253783 0.00525099 0.07302999 0.01733297 0.06707096 0.02216392 0.253783 0.00525099 0.08442395 0.01192688 0.263948 0 0.273902 3.42e-4 0.276816 0.011756 0.286306 0.01843392 0.263948 0 0.08442395 0.01192688 0.07302999 0.01733297 0.263948 0 0.09471297 0.01186388 0.08442395 0.01192688 0.273902 3.42e-4 0.06281995 0.222023 0.209648 0.222023 0.21087 0.265158 0.06441098 0.181628 0.210884 0.178638 0.209648 0.222023 0.06441098 0.181628 0.209648 0.222023 0.06281995 0.222023 0.06442999 0.262652 0.21087 0.265158 0.2144629 0.3062 0.06442999 0.262652 0.06281995 0.222023 0.21087 0.265158 0.06915998 0.30132 0.2144629 0.3062 0.220194 0.343164 0.06915998 0.30132 0.06442999 0.262652 0.2144629 0.3062 0.07669895 0.336237 0.220194 0.343164 0.227659 0.374435 0.07669895 0.336237 0.06915998 0.30132 0.220194 0.343164 0.08652597 0.365936 0.227659 0.374435 0.236533 0.39945 0.08652597 0.365936 0.07669895 0.336237 0.227659 0.374435 0.09822797 0.389906 0.236533 0.39945 0.246341 0.417634 0.09822797 0.389906 0.08652597 0.365936 0.236533 0.39945 0.111204 0.407595 0.246341 0.417634 0.256604 0.428902 0.111204 0.407595 0.09822797 0.389906 0.246341 0.417634 0.138685 0.423991 0.256604 0.428902 0.266913 0.433587 0.12486 0.418879 0.111204 0.407595 0.256604 0.428902 0.138685 0.423991 0.12486 0.418879 0.256604 0.428902 0.152242 0.42335 0.266913 0.433587 0.276936 0.432239 0.152242 0.42335 0.138685 0.423991 0.266913 0.433587 0.165178 0.417468 0.276936 0.432239 0.286418 0.4255 0.165178 0.417468 0.152242 0.42335 0.276936 0.432239 0.177215 0.406904 0.286418 0.4255 0.295172 0.414028 0.177215 0.406904 0.165178 0.417468 0.286418 0.4255 0.188142 0.39223 0.295172 0.414028 0.303065 0.398465 0.188142 0.39223 0.177215 0.406904 0.295172 0.414028 0.188142 0.39223 0.303065 0.398465 0.310008 0.379411 0.1978 0.374019 0.310008 0.379411 0.31594 0.357435 0.1978 0.374019 0.188142 0.39223 0.310008 0.379411 0.20607 0.352856 0.31594 0.357435 0.320813 0.333143 0.20607 0.352856 0.1978 0.374019 0.31594 0.357435 0.212862 0.329381 0.320813 0.333143 0.324598 0.307123 0.212862 0.329381 0.20607 0.352856 0.320813 0.333143 0.218131 0.304213 0.324598 0.307123 0.327332 0.279546 0.218131 0.304213 0.212862 0.329381 0.324598 0.307123 0.221928 0.277544 0.327332 0.279546 0.328976 0.251012 0.221928 0.277544 0.218131 0.304213 0.327332 0.279546 0.224207 0.249981 0.328976 0.251012 0.329525 0.222023 0.224207 0.249981 0.221928 0.277544 0.328976 0.251012 0.224965 0.222023 0.329525 0.222023 0.328983 0.193203 0.224965 0.222023 0.224207 0.249981 0.329525 0.222023 0.224198 0.193901 0.328983 0.193203 0.327353 0.1647689 0.224198 0.193901 0.224965 0.222023 0.328983 0.193203 0.221898 0.16624 0.327353 0.1647689 0.324634 0.137216 0.221898 0.16624 0.224198 0.193901 0.327353 0.1647689 0.2180809 0.139549 0.324634 0.137216 0.320856 0.111151 0.2180809 0.139549 0.221898 0.16624 0.324634 0.137216 0.212803 0.114426 0.320856 0.111151 0.315974 0.08675396 0.212803 0.114426 0.2180809 0.139549 0.320856 0.111151 0.206024 0.091053 0.315974 0.08675396 0.310013 0.06464898 0.206024 0.091053 0.212803 0.114426 0.315974 0.08675396 0.197794 0.07001298 0.310013 0.06464898 0.303027 0.04549199 0.197794 0.07001298 0.206024 0.091053 0.310013 0.06464898 0.177328 0.03726589 0.303027 0.04549199 0.29509 0.02988499 0.188195 0.0518999 0.197794 0.07001298 0.303027 0.04549199 0.177328 0.03726589 0.188195 0.0518999 0.303027 0.04549199 0.165331 0.02667999 0.29509 0.02988499 0.286306 0.01843392 0.165331 0.02667999 0.177328 0.03726589 0.29509 0.02988499 0.152405 0.020738 0.286306 0.01843392 0.276816 0.011756 0.152405 0.020738 0.165331 0.02667999 0.286306 0.01843392 0.13882 0.02003395 0.276816 0.011756 0.266813 0.0104739 0.13882 0.02003395 0.152405 0.020738 0.276816 0.011756 0.124932 0.02512598 0.266813 0.0104739 0.25655 0.01518392 0.124932 0.02512598 0.13882 0.02003395 0.266813 0.0104739 0.124932 0.02512598 0.25655 0.01518392 0.246347 0.02640098 0.111195 0.03646188 0.246347 0.02640098 0.236591 0.04446291 0.111195 0.03646188 0.124932 0.02512598 0.246347 0.02640098 0.09815096 0.05426889 0.236591 0.04446291 0.22774 0.06933397 0.09815096 0.05426889 0.111195 0.03646188 0.236591 0.04446291 0.08641898 0.07837396 0.22774 0.06933397 0.2202669 0.100508 0.08641898 0.07837396 0.09815096 0.05426889 0.22774 0.06933397 0.07660299 0.108164 0.2202669 0.100508 0.2145079 0.1374689 0.07660299 0.108164 0.08641898 0.07837396 0.2202669 0.100508 0.06909996 0.1430799 0.2145079 0.1374689 0.210884 0.178638 0.06909996 0.1430799 0.07660299 0.108164 0.2145079 0.1374689 0.06441098 0.181628 0.06909996 0.1430799 0.210884 0.178638 0.288588 0.230619 0.300559 0.227309 0.3 0.23195 0.286663 0.239062 0.3 0.23195 0.2999 0.232567 0.286663 0.239062 0.288588 0.230619 0.3 0.23195 0.286663 0.239062 0.2999 0.232567 0.297692 0.2416689 0.221898 0.16624 0.221928 0.277544 0.224198 0.193901 0.283562 0.247188 0.286663 0.239062 0.297692 0.2416689 0.283562 0.247188 0.297692 0.2416689 0.293953 0.250962 0.28144 0.251348 0.293953 0.250962 0.292882 0.253064 0.28144 0.251348 0.283562 0.247188 0.293953 0.250962 0.28144 0.251348 0.292882 0.253064 0.291417 0.255692 0.28144 0.251348 0.291417 0.255692 0.283381 0.269035 0.270178 0.271482 0.283381 0.269035 0.275616 0.281633 0.270178 0.271482 0.28144 0.251348 0.283381 0.269035 0.270178 0.271482 0.275616 0.281633 0.268146 0.29346 0.258564 0.291199 0.268146 0.29346 0.261011 0.304437 0.258564 0.291199 0.270178 0.271482 0.268146 0.29346 0.246834 0.310419 0.261011 0.304437 0.254195 0.314784 0.246834 0.310419 0.258564 0.291199 0.261011 0.304437 0.246834 0.310419 0.254195 0.314784 0.247663 0.32469 0.235265 0.32905 0.247663 0.32469 0.241447 0.334073 0.235265 0.32905 0.246834 0.310419 0.247663 0.32469 0.235265 0.32905 0.241447 0.334073 0.235572 0.343052 0.224201 0.346964 0.235572 0.343052 0.22486 0.35992 0.224201 0.346964 0.235265 0.32905 0.235572 0.343052 0.214047 0.364001 0.22486 0.35992 0.216 0.374962 0.214047 0.364001 0.224201 0.346964 0.22486 0.35992 0.205269 0.37995 0.216 0.374962 0.2091259 0.388325 0.205269 0.37995 0.214047 0.364001 0.216 0.374962 0.198356 0.394553 0.2091259 0.388325 0.204291 0.400194 0.198356 0.394553 0.205269 0.37995 0.2091259 0.388325 0.193742 0.407543 0.204291 0.400194 0.20156 0.410679 0.193742 0.407543 0.198356 0.394553 0.204291 0.400194 0.191705 0.418687 0.20156 0.410679 0.201037 0.419924 0.191705 0.418687 0.193742 0.407543 0.20156 0.410679 0.192358 0.427814 0.201037 0.419924 0.2029049 0.42791 0.191705 0.418687 0.201037 0.419924 0.192358 0.427814 0.206154 0.433996 0.2029049 0.42791 0.207411 0.434488 0.2180809 0.139549 0.218131 0.304213 0.221898 0.16624 0.206154 0.433996 0.204338 0.433297 0.2029049 0.42791 0.204155 0.433224 0.2029049 0.42791 0.204338 0.433297 0.203212 0.432838 0.2029049 0.42791 0.204155 0.433224 0.201961 0.432312 0.2029049 0.42791 0.203212 0.432838 0.200432 0.431659 0.2029049 0.42791 0.201961 0.432312 0.198703 0.430894 0.2029049 0.42791 0.200432 0.431659 0.196727 0.429984 0.2029049 0.42791 0.198703 0.430894 0.195488 0.429392 0.2029049 0.42791 0.196727 0.429984 0.19442 0.428867 0.2029049 0.42791 0.195488 0.429392 0.193005 0.428151 0.2029049 0.42791 0.19442 0.428867 0.192358 0.427814 0.2029049 0.42791 0.193005 0.428151 0.10449 0.426483 0.207411 0.434488 0.103572 0.427369 0.205032 0.433806 0.207411 0.434488 0.10449 0.426483 0.212803 0.114426 0.212862 0.329381 0.2180809 0.139549 0.205373 0.433779 0.207411 0.434488 0.205032 0.433806 0.205853 0.433893 0.207411 0.434488 0.205373 0.433779 0.206154 0.433996 0.207411 0.434488 0.205853 0.433893 0.09889596 0.42661 0.103572 0.427369 0.09509795 0.432124 0.10449 0.426483 0.103572 0.427369 0.09889596 0.42661 0.08077096 0.431224 0.09509795 0.432124 0.08516895 0.432272 0.09054195 0.431158 0.09509795 0.432124 0.08077096 0.431224 0.09889596 0.42661 0.09509795 0.432124 0.09054195 0.431158 0.06994098 0.426483 0.08516895 0.432272 0.07402199 0.427364 0.08077096 0.431224 0.08516895 0.432272 0.06994098 0.426483 0.05857288 0.416697 0.07402199 0.427364 0.06220096 0.41699 0.06994098 0.426483 0.07402199 0.427364 0.05857288 0.416697 0.04732197 0.401737 0.06220096 0.41699 0.05046695 0.400912 0.05857288 0.416697 0.06220096 0.41699 0.04732197 0.401737 0.03690797 0.381681 0.05046695 0.400912 0.03965193 0.379144 0.04732197 0.401737 0.05046695 0.400912 0.03690797 0.381681 0.027951 0.356862 0.03965193 0.379144 0.03041189 0.352033 0.03690797 0.381681 0.03965193 0.379144 0.027951 0.356862 0.02059292 0.327634 0.03041189 0.352033 0.02293497 0.320245 0.027951 0.356862 0.03041189 0.352033 0.02059292 0.327634 0.01471793 0.294602 0.02293497 0.320245 0.01718389 0.284609 0.02059292 0.327634 0.02293497 0.320245 0.01471793 0.294602 0.01076591 0.258943 0.01718389 0.284609 0.01371991 0.246266 0.01471793 0.294602 0.01718389 0.284609 0.01076591 0.258943 0.01076591 0.258943 0.01371991 0.246266 0.01312589 0.226617 0.009323954 0.222046 0.01312589 0.226617 0.01329195 0.206915 0.01076591 0.258943 0.01312589 0.226617 0.009323954 0.222046 0.009323954 0.222046 0.01329195 0.206915 0.01441293 0.186955 0.01071697 0.185176 0.01441293 0.186955 0.01619696 0.167423 0.009323954 0.222046 0.01441293 0.186955 0.01071697 0.185176 0.01469093 0.149532 0.01619696 0.167423 0.01862895 0.1485339 0.01071697 0.185176 0.01619696 0.167423 0.01469093 0.149532 0.01469093 0.149532 0.01862895 0.1485339 0.021649 0.130453 0.020563 0.116497 0.021649 0.130453 0.02511799 0.113284 0.01469093 0.149532 0.021649 0.130453 0.020563 0.116497 0.020563 0.116497 0.02511799 0.113284 0.02899998 0.09718799 0.02794295 0.08725696 0.02899998 0.09718799 0.03337496 0.08227598 0.020563 0.116497 0.02899998 0.09718799 0.02794295 0.08725696 0.02794295 0.08725696 0.03337496 0.08227598 0.038185 0.06864798 0.03690499 0.06243598 0.038185 0.06864798 0.04341989 0.05640697 0.02794295 0.08725696 0.038185 0.06864798 0.03690499 0.06243598 0.03690499 0.06243598 0.04341989 0.05640697 0.04907596 0.04560589 0.04735893 0.04236495 0.04907596 0.04560589 0.05497992 0.03628993 0.03690499 0.06243598 0.04907596 0.04560589 0.04735893 0.04236495 0.04735893 0.04236495 0.05497992 0.03628993 0.06100291 0.02847898 0.05859988 0.0273739 0.06100291 0.02847898 0.06707096 0.02216392 0.04735893 0.04236495 0.06100291 0.02847898 0.05859988 0.0273739 0.05859988 0.0273739 0.06707096 0.02216392 0.07302999 0.01733297 0.06989198 0.01757198 0.07302999 0.01733297 0.08442395 0.01192688 0.05859988 0.0273739 0.07302999 0.01733297 0.06989198 0.01757198 0.08063697 0.01283293 0.08442395 0.01192688 0.09471297 0.01186388 0.06989198 0.01757198 0.08442395 0.01192688 0.08063697 0.01283293 0.09041899 0.0128979 0.09471297 0.01186388 0.103559 0.01667797 0.08063697 0.01283293 0.09471297 0.01186388 0.09041899 0.0128979 0.100785 0.0191999 0.103559 0.01667797 0.104487 0.01756298 0.09888899 0.01744395 0.103559 0.01667797 0.100785 0.0191999 0.09041899 0.0128979 0.103559 0.01667797 0.09888899 0.01744395 0.276925 0.236818 0.278506 0.229477 0.288588 0.230619 0.279062 0.222023 0.288588 0.230619 0.278506 0.229477 0.286663 0.239062 0.276925 0.236818 0.288588 0.230619 0.279062 0.222023 0.289273 0.222023 0.288588 0.230619 0.268912 0.2350389 0.270214 0.228574 0.278506 0.229477 0.279062 0.222023 0.278506 0.229477 0.270214 0.228574 0.276925 0.236818 0.268912 0.2350389 0.278506 0.229477 0.26295 0.233797 0.264057 0.227949 0.270214 0.228574 0.27065 0.222023 0.270214 0.228574 0.264057 0.227949 0.268912 0.2350389 0.26295 0.233797 0.270214 0.228574 0.27065 0.222023 0.279062 0.222023 0.270214 0.228574 0.259243 0.23313 0.26025 0.22762 0.264057 0.227949 0.264414 0.222023 0.264057 0.227949 0.26025 0.22762 0.26295 0.233797 0.259243 0.23313 0.264057 0.227949 0.264414 0.222023 0.27065 0.222023 0.264057 0.227949 0.258504 0.230222 0.258906 0.2275699 0.26025 0.22762 0.260579 0.222023 0.26025 0.22762 0.258906 0.2275699 0.257904 0.233026 0.258504 0.230222 0.26025 0.22762 0.259243 0.23313 0.257904 0.233026 0.26025 0.22762 0.260579 0.222023 0.264414 0.222023 0.26025 0.22762 0.258482 0.2263399 0.258906 0.2275699 0.258504 0.230222 0.259242 0.222023 0.260579 0.222023 0.258906 0.2275699 0.258482 0.2263399 0.259242 0.222023 0.258906 0.2275699 0.257839 0.230602 0.258504 0.230222 0.257904 0.233026 0.257839 0.230602 0.258482 0.2263399 0.258504 0.230222 0.25627 0.238276 0.257904 0.233026 0.259243 0.23313 0.257286 0.232965 0.257904 0.233026 0.25627 0.238276 0.257582 0.2317799 0.257839 0.230602 0.257904 0.233026 0.257286 0.232965 0.257582 0.2317799 0.257904 0.233026 0.261117 0.239467 0.259243 0.23313 0.26295 0.233797 0.257587 0.23845 0.25627 0.238276 0.259243 0.23313 0.261117 0.239467 0.257587 0.23845 0.259243 0.23313 0.266771 0.24131 0.26295 0.233797 0.268912 0.2350389 0.266771 0.24131 0.261117 0.239467 0.26295 0.233797 0.266771 0.24131 0.268912 0.2350389 0.276925 0.236818 0.27436 0.24392 0.276925 0.236818 0.286663 0.239062 0.27436 0.24392 0.266771 0.24131 0.276925 0.236818 0.283562 0.247188 0.27436 0.24392 0.286663 0.239062 0.255784 0.23946 0.25627 0.238276 0.257587 0.23845 0.256014 0.23791 0.25627 0.238276 0.255717 0.23768 0.255587 0.2380239 0.255717 0.23768 0.25627 0.238276 0.256164 0.23652 0.25627 0.238276 0.256014 0.23791 0.25695 0.234158 0.257286 0.232965 0.25627 0.238276 0.256574 0.235347 0.25695 0.234158 0.25627 0.238276 0.256164 0.23652 0.256574 0.235347 0.25627 0.238276 0.255587 0.2380239 0.25627 0.238276 0.255784 0.23946 0.256474 0.241186 0.257587 0.23845 0.261117 0.239467 0.255784 0.23946 0.257587 0.23845 0.255133 0.240914 0.256474 0.241186 0.255133 0.240914 0.257587 0.23845 0.259891 0.242404 0.261117 0.239467 0.266771 0.24131 0.259891 0.242404 0.256474 0.241186 0.261117 0.239467 0.265325 0.244556 0.266771 0.24131 0.27436 0.24392 0.259891 0.242404 0.266771 0.24131 0.265325 0.244556 0.272602 0.2475759 0.27436 0.24392 0.283562 0.247188 0.265325 0.244556 0.27436 0.24392 0.272602 0.2475759 0.272602 0.2475759 0.283562 0.247188 0.28144 0.251348 0.288591 0.21345 0.289273 0.222023 0.279062 0.222023 0.278509 0.21459 0.279062 0.222023 0.27065 0.222023 0.288591 0.21345 0.279062 0.222023 0.278509 0.21459 0.264059 0.216114 0.27065 0.222023 0.264414 0.222023 0.270216 0.21549 0.27065 0.222023 0.264059 0.216114 0.278509 0.21459 0.27065 0.222023 0.270216 0.21549 0.260252 0.216441 0.264414 0.222023 0.260579 0.222023 0.264059 0.216114 0.264414 0.222023 0.260252 0.216441 0.260252 0.216441 0.260579 0.222023 0.259242 0.222023 0.260252 0.216441 0.259242 0.222023 0.258889 0.216339 0.258481 0.217702 0.258889 0.216339 0.259242 0.222023 0.258697 0.22202 0.258481 0.217702 0.259242 0.222023 0.258482 0.2263399 0.258697 0.22202 0.259242 0.222023 0.286677 0.205031 0.27436 0.200125 0.283562 0.196858 0.268922 0.209042 0.266771 0.202735 0.27436 0.200125 0.276937 0.2072679 0.268922 0.209042 0.27436 0.200125 0.286677 0.205031 0.276937 0.2072679 0.27436 0.200125 0.262959 0.210281 0.261117 0.204578 0.266771 0.202735 0.268922 0.209042 0.262959 0.210281 0.266771 0.202735 0.259251 0.210945 0.257587 0.205596 0.261117 0.204578 0.262959 0.210281 0.259251 0.210945 0.261117 0.204578 0.257878 0.210911 0.256262 0.205772 0.257587 0.205596 0.259251 0.210945 0.257878 0.210911 0.257587 0.205596 0.256164 0.207526 0.256262 0.205772 0.257878 0.210911 0.255275 0.205283 0.255724 0.204443 0.256262 0.205772 0.256014 0.206136 0.255726 0.206362 0.256262 0.205772 0.255613 0.206085 0.256262 0.205772 0.255726 0.206362 0.256164 0.207526 0.256014 0.206136 0.256262 0.205772 0.255499 0.205811 0.255275 0.205283 0.256262 0.205772 0.255613 0.206085 0.255499 0.205811 0.256262 0.205772 0.258384 0.2131879 0.257878 0.210911 0.259251 0.210945 0.257582 0.212265 0.257878 0.210911 0.258384 0.2131879 0.256575 0.2087 0.256164 0.207526 0.257878 0.210911 0.25695 0.209888 0.256575 0.2087 0.257878 0.210911 0.257286 0.21108 0.25695 0.209888 0.257878 0.210911 0.257582 0.212265 0.257286 0.21108 0.257878 0.210911 0.260252 0.216441 0.259251 0.210945 0.262959 0.210281 0.258889 0.216339 0.258384 0.2131879 0.259251 0.210945 0.260252 0.216441 0.258889 0.216339 0.259251 0.210945 0.264059 0.216114 0.262959 0.210281 0.268922 0.209042 0.264059 0.216114 0.260252 0.216441 0.262959 0.210281 0.270216 0.21549 0.268922 0.209042 0.276937 0.2072679 0.270216 0.21549 0.264059 0.216114 0.268922 0.209042 0.278509 0.21459 0.276937 0.2072679 0.286677 0.205031 0.278509 0.21459 0.270216 0.21549 0.276937 0.2072679 0.288591 0.21345 0.278509 0.21459 0.286677 0.205031 0.257839 0.2134439 0.258384 0.2131879 0.258889 0.216339 0.257839 0.2134439 0.257582 0.212265 0.258384 0.2131879 0.258481 0.217702 0.257839 0.2134439 0.258889 0.216339 0.2180809 0.139549 0.212862 0.329381 0.218131 0.304213 0.254802 0.204223 0.254669 0.203925 0.255724 0.204443 0.212803 0.114426 0.20607 0.352856 0.212862 0.329381 0.255044 0.204756 0.254802 0.204223 0.255724 0.204443 0.255275 0.205283 0.255044 0.204756 0.255724 0.204443 0.256164 0.207526 0.255726 0.206362 0.256014 0.206136 0.255792 0.206525 0.255613 0.206085 0.255726 0.206362 0.255839 0.206646 0.255726 0.206362 0.256164 0.207526 0.255792 0.206525 0.255726 0.206362 0.255839 0.206646 0.253969 0.202552 0.254626 0.2038249 0.254669 0.203925 0.254281 0.203195 0.254626 0.2038249 0.253969 0.202552 0.25197 0.1985239 0.254626 0.2038249 0.254281 0.203195 0.252599 0.199742 0.254626 0.2038249 0.25197 0.1985239 0.206024 0.091053 0.20607 0.352856 0.212803 0.114426 0.253969 0.202552 0.254669 0.203925 0.254183 0.2029899 0.254395 0.203427 0.254669 0.203925 0.254802 0.204223 0.254183 0.2029899 0.254669 0.203925 0.254395 0.203427 0.188195 0.0518999 0.1978 0.374019 0.197794 0.07001298 0.254395 0.203427 0.254802 0.204223 0.254599 0.203849 0.254788 0.204243 0.254802 0.204223 0.255044 0.204756 0.254788 0.204243 0.254599 0.203849 0.254802 0.204223 0.255225 0.205184 0.255044 0.204756 0.255275 0.205283 0.254788 0.204243 0.255044 0.204756 0.254793 0.204252 0.25501 0.204712 0.254793 0.204252 0.255044 0.204756 0.255225 0.205184 0.25501 0.204712 0.255044 0.204756 0.255428 0.205647 0.255275 0.205283 0.255499 0.205811 0.255428 0.205647 0.255225 0.205184 0.255275 0.205283 0.255792 0.206525 0.255499 0.205811 0.255613 0.206085 0.255617 0.2060959 0.255428 0.205647 0.255499 0.205811 0.255792 0.206525 0.255617 0.2060959 0.255499 0.205811 0.256164 0.23652 0.256014 0.23791 0.255717 0.23768 0.256343 0.236052 0.256164 0.23652 0.255717 0.23768 0.255839 0.237399 0.255717 0.23768 0.255587 0.2380239 0.256343 0.236052 0.255717 0.23768 0.255839 0.237399 0.256714 0.209093 0.256164 0.207526 0.256575 0.2087 0.255951 0.20693 0.255839 0.206646 0.256164 0.207526 0.256347 0.2080039 0.255951 0.20693 0.256164 0.207526 0.256714 0.209093 0.256347 0.2080039 0.256164 0.207526 0.257053 0.210198 0.256575 0.2087 0.25695 0.209888 0.257053 0.210198 0.256714 0.209093 0.256575 0.2087 0.257358 0.21131 0.25695 0.209888 0.257286 0.21108 0.257358 0.21131 0.257053 0.210198 0.25695 0.209888 0.257629 0.212417 0.257286 0.21108 0.257582 0.212265 0.257629 0.212417 0.257358 0.21131 0.257286 0.21108 0.257629 0.212417 0.257582 0.212265 0.257839 0.2134439 0.257857 0.213481 0.257839 0.2134439 0.258481 0.217702 0.257629 0.212417 0.257839 0.2134439 0.257857 0.213481 0.257866 0.21352 0.258481 0.217702 0.258697 0.22202 0.257866 0.21352 0.257857 0.213481 0.258481 0.217702 0.258708 0.222023 0.258697 0.22202 0.258482 0.2263399 0.258708 0.222023 0.257866 0.21352 0.258697 0.22202 0.258708 0.222023 0.258482 0.2263399 0.257839 0.230602 0.257857 0.230565 0.257839 0.230602 0.257582 0.2317799 0.258708 0.222023 0.257839 0.230602 0.257857 0.230565 0.257626 0.231642 0.257582 0.2317799 0.257286 0.232965 0.257866 0.230526 0.257857 0.230565 0.257582 0.2317799 0.257626 0.231642 0.257866 0.230526 0.257582 0.2317799 0.257353 0.232755 0.257286 0.232965 0.25695 0.234158 0.257353 0.232755 0.257626 0.231642 0.257286 0.232965 0.257047 0.233868 0.25695 0.234158 0.256574 0.235347 0.257047 0.233868 0.257353 0.232755 0.25695 0.234158 0.256709 0.23497 0.256574 0.235347 0.256164 0.23652 0.256709 0.23497 0.257047 0.233868 0.256574 0.235347 0.256343 0.236052 0.256709 0.23497 0.256164 0.23652 0.254709 0.240029 0.255133 0.240914 0.254626 0.24022 0.248691 0.254847 0.254626 0.24022 0.255133 0.240914 0.254167 0.241088 0.254709 0.240029 0.254626 0.24022 0.248691 0.254847 0.252813 0.243872 0.254626 0.24022 0.254281 0.24085 0.254626 0.24022 0.252813 0.243872 0.254167 0.241088 0.254626 0.24022 0.254281 0.24085 0.255151 0.239046 0.255784 0.23946 0.255133 0.240914 0.254805 0.239818 0.255151 0.239046 0.255133 0.240914 0.197794 0.07001298 0.1978 0.374019 0.206024 0.091053 0.254709 0.240029 0.254805 0.239818 0.255133 0.240914 0.177328 0.03726589 0.188142 0.39223 0.188195 0.0518999 0.245798 0.264049 0.248691 0.254847 0.255133 0.240914 0.256474 0.241186 0.245798 0.264049 0.255133 0.240914 0.255445 0.2383649 0.255587 0.2380239 0.255784 0.23946 0.255151 0.239046 0.255445 0.2383649 0.255784 0.23946 0.255606 0.237976 0.255587 0.2380239 0.255445 0.2383649 0.255951 0.237115 0.255839 0.237399 0.255587 0.2380239 0.255785 0.237536 0.255951 0.237115 0.255587 0.2380239 0.255606 0.237976 0.255785 0.237536 0.255587 0.2380239 0.255606 0.237976 0.255445 0.2383649 0.255151 0.239046 0.255212 0.238892 0.255151 0.239046 0.254805 0.239818 0.255212 0.238892 0.255606 0.237976 0.255151 0.239046 0.206024 0.091053 0.1978 0.374019 0.20607 0.352856 0.255212 0.238892 0.254805 0.239818 0.25479 0.239799 0.254375 0.240661 0.254805 0.239818 0.254709 0.240029 0.254586 0.240225 0.254805 0.239818 0.254375 0.240661 0.254793 0.239794 0.254805 0.239818 0.254586 0.240225 0.25479 0.239799 0.254805 0.239818 0.254793 0.239794 0.188195 0.0518999 0.188142 0.39223 0.1978 0.374019 0.254375 0.240661 0.254709 0.240029 0.254167 0.241088 0.248691 0.254847 0.250844 0.247824 0.252813 0.243872 0.25148 0.246499 0.252813 0.243872 0.250844 0.247824 0.254281 0.24085 0.252813 0.243872 0.25148 0.246499 0.248691 0.254847 0.248692 0.252068 0.250844 0.247824 0.25148 0.246499 0.250844 0.247824 0.248692 0.252068 0.248691 0.254847 0.246397 0.256516 0.248692 0.252068 0.248434 0.252488 0.248692 0.252068 0.246397 0.256516 0.25148 0.246499 0.248692 0.252068 0.248434 0.252488 0.242118 0.268382 0.243955 0.261168 0.246397 0.256516 0.245287 0.258525 0.246397 0.256516 0.243955 0.261168 0.248691 0.254847 0.242118 0.268382 0.246397 0.256516 0.248434 0.252488 0.246397 0.256516 0.245287 0.258525 0.242118 0.268382 0.241358 0.266027 0.243955 0.261168 0.2420679 0.264553 0.243955 0.261168 0.241358 0.266027 0.245287 0.258525 0.243955 0.261168 0.2420679 0.264553 0.242118 0.268382 0.238589 0.271112 0.241358 0.266027 0.238785 0.270554 0.241358 0.266027 0.238589 0.271112 0.2420679 0.264553 0.241358 0.266027 0.238785 0.270554 0.235453 0.281572 0.2356359 0.276427 0.238589 0.271112 0.238785 0.270554 0.238589 0.271112 0.2356359 0.276427 0.242118 0.268382 0.235453 0.281572 0.238589 0.271112 0.235453 0.281572 0.2324579 0.28203 0.2356359 0.276427 0.235444 0.276518 0.2356359 0.276427 0.2324579 0.28203 0.238785 0.270554 0.2356359 0.276427 0.235444 0.276518 0.228731 0.29444 0.229048 0.287912 0.2324579 0.28203 0.232047 0.282442 0.2324579 0.28203 0.229048 0.287912 0.235453 0.281572 0.228731 0.29444 0.2324579 0.28203 0.235444 0.276518 0.2324579 0.28203 0.232047 0.282442 0.228731 0.29444 0.2266539 0.291966 0.229048 0.287912 0.228595 0.288325 0.229048 0.287912 0.2266539 0.291966 0.232047 0.282442 0.229048 0.287912 0.228595 0.288325 0.221704 0.307515 0.224159 0.296125 0.2266539 0.291966 0.225087 0.294163 0.2266539 0.291966 0.224159 0.296125 0.228731 0.29444 0.221704 0.307515 0.2266539 0.291966 0.228595 0.288325 0.2266539 0.291966 0.225087 0.294163 0.221704 0.307515 0.221556 0.300396 0.224159 0.296125 0.225087 0.294163 0.224159 0.296125 0.221556 0.300396 0.221704 0.307515 0.218845 0.304771 0.221556 0.300396 0.221526 0.299956 0.221556 0.300396 0.218845 0.304771 0.225087 0.294163 0.221556 0.300396 0.221526 0.299956 0.2048619 0.335077 0.216014 0.309265 0.218845 0.304771 0.217912 0.305703 0.218845 0.304771 0.216014 0.309265 0.221704 0.307515 0.2048619 0.335077 0.218845 0.304771 0.221526 0.299956 0.218845 0.304771 0.217912 0.305703 0.2048619 0.335077 0.213043 0.313899 0.216014 0.309265 0.214246 0.311401 0.216014 0.309265 0.213043 0.313899 0.217912 0.305703 0.216014 0.309265 0.214246 0.311401 0.2048619 0.335077 0.2099339 0.318661 0.213043 0.313899 0.210527 0.317051 0.213043 0.313899 0.2099339 0.318661 0.214246 0.311401 0.213043 0.313899 0.210527 0.317051 0.2048619 0.335077 0.206688 0.323541 0.2099339 0.318661 0.210527 0.317051 0.2099339 0.318661 0.206688 0.323541 0.2048619 0.335077 0.203305 0.328532 0.206688 0.323541 0.206758 0.32265 0.206688 0.323541 0.203305 0.328532 0.210527 0.317051 0.206688 0.323541 0.206758 0.32265 0.2048619 0.335077 0.1997759 0.333635 0.203305 0.328532 0.202938 0.328199 0.203305 0.328532 0.1997759 0.333635 0.206758 0.32265 0.203305 0.328532 0.202938 0.328199 0.186627 0.361725 0.196096 0.338851 0.1997759 0.333635 0.1990669 0.333695 0.1997759 0.333635 0.196096 0.338851 0.2048619 0.335077 0.186627 0.361725 0.1997759 0.333635 0.202938 0.328199 0.1997759 0.333635 0.1990669 0.333695 0.186627 0.361725 0.192263 0.344173 0.196096 0.338851 0.195147 0.339138 0.196096 0.338851 0.192263 0.344173 0.1990669 0.333695 0.196096 0.338851 0.195147 0.339138 0.186627 0.361725 0.18928 0.348236 0.192263 0.344173 0.191178 0.344528 0.192263 0.344173 0.18928 0.348236 0.195147 0.339138 0.192263 0.344173 0.191178 0.344528 0.186627 0.361725 0.186204 0.35236 0.18928 0.348236 0.18716 0.349864 0.18928 0.348236 0.186204 0.35236 0.191178 0.344528 0.18928 0.348236 0.18716 0.349864 0.186627 0.361725 0.183032 0.356542 0.186204 0.35236 0.18716 0.349864 0.186204 0.35236 0.183032 0.356542 0.167174 0.387185 0.179761 0.36078 0.183032 0.356542 0.183094 0.355144 0.183032 0.356542 0.179761 0.36078 0.186627 0.361725 0.167174 0.387185 0.183032 0.356542 0.18716 0.349864 0.183032 0.356542 0.183094 0.355144 0.167174 0.387185 0.1763859 0.365078 0.179761 0.36078 0.178981 0.360369 0.179761 0.36078 0.1763859 0.365078 0.183094 0.355144 0.179761 0.36078 0.178981 0.360369 0.167174 0.387185 0.172906 0.369431 0.1763859 0.365078 0.17482 0.365537 0.1763859 0.365078 0.172906 0.369431 0.178981 0.360369 0.1763859 0.365078 0.17482 0.365537 0.167174 0.387185 0.169319 0.373836 0.172906 0.369431 0.170612 0.370648 0.172906 0.369431 0.169319 0.373836 0.17482 0.365537 0.172906 0.369431 0.170612 0.370648 0.167174 0.387185 0.165625 0.378289 0.169319 0.373836 0.170612 0.370648 0.169319 0.373836 0.165625 0.378289 0.1696979 0.401764 0.165625 0.378289 0.167174 0.387185 0.170612 0.370648 0.165625 0.378289 0.166356 0.375704 0.163525 0.378177 0.166356 0.375704 0.165625 0.378289 0.162731 0.380872 0.163525 0.378177 0.165625 0.378289 0.166499 0.404899 0.162731 0.380872 0.165625 0.378289 0.1696979 0.401764 0.166499 0.404899 0.165625 0.378289 0.179336 0.38344 0.167174 0.387185 0.186627 0.361725 0.16752 0.389098 0.167174 0.387185 0.179336 0.38344 0.1696979 0.401764 0.167174 0.387185 0.16752 0.389098 0.179336 0.38344 0.169868 0.401536 0.16752 0.389098 0.190311 0.363594 0.186627 0.361725 0.2048619 0.335077 0.190311 0.363594 0.179336 0.38344 0.186627 0.361725 0.2153609 0.319066 0.2048619 0.335077 0.221704 0.307515 0.196245 0.353069 0.190311 0.363594 0.2048619 0.335077 0.202428 0.342135 0.196245 0.353069 0.2048619 0.335077 0.20881 0.330809 0.202428 0.342135 0.2048619 0.335077 0.2153609 0.319066 0.20881 0.330809 0.2048619 0.335077 0.222921 0.308472 0.221704 0.307515 0.228731 0.29444 0.222921 0.308472 0.2153609 0.319066 0.221704 0.307515 0.234544 0.286502 0.228731 0.29444 0.235453 0.281572 0.234544 0.286502 0.222921 0.308472 0.228731 0.29444 0.234544 0.286502 0.235453 0.281572 0.242118 0.268382 0.245798 0.264049 0.242118 0.268382 0.248691 0.254847 0.245798 0.264049 0.234544 0.286502 0.242118 0.268382 0.1696979 0.401764 0.16752 0.389098 0.169868 0.401536 0.178688 0.389065 0.169868 0.401536 0.179336 0.38344 0.169798 0.402753 0.1696979 0.401764 0.169868 0.401536 0.178688 0.389065 0.169798 0.402753 0.169868 0.401536 0.188655 0.370361 0.179336 0.38344 0.190311 0.363594 0.188655 0.370361 0.178688 0.389065 0.179336 0.38344 0.199632 0.35055 0.190311 0.363594 0.196245 0.353069 0.199632 0.35055 0.188655 0.370361 0.190311 0.363594 0.199632 0.35055 0.196245 0.353069 0.202428 0.342135 0.211179 0.329864 0.202428 0.342135 0.20881 0.330809 0.211179 0.329864 0.199632 0.35055 0.202428 0.342135 0.211179 0.329864 0.20881 0.330809 0.2153609 0.319066 0.222921 0.308472 0.211179 0.329864 0.2153609 0.319066 0.170612 0.370648 0.166356 0.375704 0.169251 0.373064 0.163525 0.378177 0.169251 0.373064 0.166356 0.375704 0.17251 0.369127 0.170612 0.370648 0.169251 0.373064 0.180633 0.365213 0.17251 0.369127 0.169251 0.373064 0.167275 0.374968 0.169251 0.373064 0.163525 0.378177 0.183776 0.363589 0.169251 0.373064 0.167275 0.374968 0.180633 0.365213 0.169251 0.373064 0.183776 0.363589 0.175664 0.365252 0.17482 0.365537 0.170612 0.370648 0.17251 0.369127 0.175664 0.365252 0.170612 0.370648 0.178713 0.361442 0.178981 0.360369 0.17482 0.365537 0.175664 0.365252 0.178713 0.361442 0.17482 0.365537 0.181659 0.3577 0.183094 0.355144 0.178981 0.360369 0.178713 0.361442 0.181659 0.3577 0.178981 0.360369 0.185427 0.352823 0.18716 0.349864 0.183094 0.355144 0.181659 0.3577 0.185427 0.352823 0.183094 0.355144 0.189024 0.34807 0.191178 0.344528 0.18716 0.349864 0.185427 0.352823 0.189024 0.34807 0.18716 0.349864 0.195729 0.338947 0.195147 0.339138 0.191178 0.344528 0.1929579 0.34276 0.195729 0.338947 0.191178 0.344528 0.192457 0.343443 0.1929579 0.34276 0.191178 0.344528 0.189024 0.34807 0.192457 0.343443 0.191178 0.344528 0.198859 0.334567 0.1990669 0.333695 0.195147 0.339138 0.195729 0.338947 0.198859 0.334567 0.195147 0.339138 0.201847 0.33031 0.202938 0.328199 0.1990669 0.333695 0.198859 0.334567 0.201847 0.33031 0.1990669 0.333695 0.20744 0.322135 0.206758 0.32265 0.202938 0.328199 0.204703 0.32617 0.20744 0.322135 0.202938 0.328199 0.201847 0.33031 0.204703 0.32617 0.202938 0.328199 0.210057 0.318216 0.210527 0.317051 0.206758 0.32265 0.20744 0.322135 0.210057 0.318216 0.206758 0.32265 0.213784 0.312527 0.214246 0.311401 0.210527 0.317051 0.210057 0.318216 0.213784 0.312527 0.210527 0.317051 0.21728 0.307069 0.217912 0.305703 0.214246 0.311401 0.215221 0.310297 0.21728 0.307069 0.214246 0.311401 0.213784 0.312527 0.215221 0.310297 0.214246 0.311401 0.220575 0.301816 0.221526 0.299956 0.217912 0.305703 0.21728 0.307069 0.220575 0.301816 0.217912 0.305703 0.223679 0.296765 0.225087 0.294163 0.221526 0.299956 0.220575 0.301816 0.223679 0.296765 0.221526 0.299956 0.226618 0.291891 0.228595 0.288325 0.225087 0.294163 0.223679 0.296765 0.226618 0.291891 0.225087 0.294163 0.232056 0.282619 0.232047 0.282442 0.228595 0.288325 0.229405 0.28718 0.232056 0.282619 0.228595 0.288325 0.226618 0.291891 0.229405 0.28718 0.228595 0.288325 0.234594 0.278177 0.235444 0.276518 0.232047 0.282442 0.232056 0.282619 0.234594 0.278177 0.232047 0.282442 0.237027 0.273846 0.238785 0.270554 0.235444 0.276518 0.235872 0.275911 0.237027 0.273846 0.235444 0.276518 0.234594 0.278177 0.235872 0.275911 0.235444 0.276518 0.241604 0.265499 0.2420679 0.264553 0.238785 0.270554 0.2393659 0.269615 0.241604 0.265499 0.238785 0.270554 0.237027 0.273846 0.2393659 0.269615 0.238785 0.270554 0.243725 0.261539 0.245287 0.258525 0.2420679 0.264553 0.241604 0.265499 0.243725 0.261539 0.2420679 0.264553 0.247718 0.253914 0.248434 0.252488 0.245287 0.258525 0.245754 0.257693 0.247718 0.253914 0.245287 0.258525 0.243725 0.261539 0.245754 0.257693 0.245287 0.258525 0.251219 0.247036 0.25148 0.246499 0.248434 0.252488 0.249544 0.250351 0.251219 0.247036 0.248434 0.252488 0.247718 0.253914 0.249544 0.250351 0.248434 0.252488 0.253969 0.2414939 0.254281 0.24085 0.25148 0.246499 0.251219 0.247036 0.253969 0.2414939 0.25148 0.246499 0.254167 0.241088 0.254281 0.24085 0.253969 0.2414939 0.2395409 0.273517 0.253969 0.2414939 0.251219 0.247036 0.254167 0.241088 0.253969 0.2414939 0.2395409 0.273517 0.2395409 0.273517 0.251219 0.247036 0.249544 0.250351 0.235872 0.275911 0.249544 0.250351 0.247718 0.253914 0.2395409 0.273517 0.249544 0.250351 0.235872 0.275911 0.2393659 0.269615 0.247718 0.253914 0.245754 0.257693 0.237027 0.273846 0.247718 0.253914 0.2393659 0.269615 0.235872 0.275911 0.247718 0.253914 0.237027 0.273846 0.241604 0.265499 0.245754 0.257693 0.243725 0.261539 0.2393659 0.269615 0.245754 0.257693 0.241604 0.265499 0.232056 0.282619 0.235872 0.275911 0.234594 0.278177 0.229405 0.28718 0.235872 0.275911 0.232056 0.282619 0.226618 0.291891 0.235872 0.275911 0.229405 0.28718 0.223679 0.296765 0.235872 0.275911 0.226618 0.291891 0.220575 0.301816 0.235872 0.275911 0.223679 0.296765 0.21728 0.307069 0.235872 0.275911 0.220575 0.301816 0.215221 0.310297 0.235872 0.275911 0.21728 0.307069 0.2395409 0.273517 0.235872 0.275911 0.215221 0.310297 0.210057 0.318216 0.215221 0.310297 0.213784 0.312527 0.20744 0.322135 0.215221 0.310297 0.210057 0.318216 0.204703 0.32617 0.215221 0.310297 0.20744 0.322135 0.201847 0.33031 0.215221 0.310297 0.204703 0.32617 0.222189 0.306503 0.215221 0.310297 0.201847 0.33031 0.2395409 0.273517 0.215221 0.310297 0.222189 0.306503 0.222189 0.306503 0.201847 0.33031 0.198859 0.334567 0.222189 0.306503 0.198859 0.334567 0.195729 0.338947 0.222189 0.306503 0.195729 0.338947 0.1929579 0.34276 0.180633 0.365213 0.1929579 0.34276 0.192457 0.343443 0.203694 0.33752 0.1929579 0.34276 0.180633 0.365213 0.222189 0.306503 0.1929579 0.34276 0.203694 0.33752 0.180633 0.365213 0.192457 0.343443 0.189024 0.34807 0.180633 0.365213 0.189024 0.34807 0.185427 0.352823 0.180633 0.365213 0.185427 0.352823 0.181659 0.3577 0.180633 0.365213 0.181659 0.3577 0.178713 0.361442 0.180633 0.365213 0.178713 0.361442 0.175664 0.365252 0.180633 0.365213 0.175664 0.365252 0.17251 0.369127 0.1622959 0.377225 0.156316 0.380298 0.159538 0.377472 0.158903 0.376439 0.159538 0.377472 0.156316 0.380298 0.171033 0.36983 0.1622959 0.377225 0.159538 0.377472 0.158903 0.376439 0.171033 0.36983 0.159538 0.377472 0.163195 0.377008 0.160086 0.37975 0.156316 0.380298 0.155346 0.383214 0.156316 0.380298 0.160086 0.37975 0.1622959 0.377225 0.163195 0.377008 0.156316 0.380298 0.134935 0.398149 0.156316 0.380298 0.155346 0.383214 0.134935 0.398149 0.158903 0.376439 0.156316 0.380298 0.16492 0.376379 0.163525 0.378177 0.160086 0.37975 0.15921 0.382558 0.160086 0.37975 0.163525 0.378177 0.163195 0.377008 0.16492 0.376379 0.160086 0.37975 0.15921 0.382558 0.155346 0.383214 0.160086 0.37975 0.166528 0.375496 0.167275 0.374968 0.163525 0.378177 0.16492 0.376379 0.166528 0.375496 0.163525 0.378177 0.162731 0.380872 0.15921 0.382558 0.163525 0.378177 0.181469 0.365086 0.167275 0.374968 0.166528 0.375496 0.183776 0.363589 0.167275 0.374968 0.181469 0.365086 0.181469 0.365086 0.166528 0.375496 0.16492 0.376379 0.178865 0.365999 0.16492 0.376379 0.163195 0.377008 0.181469 0.365086 0.16492 0.376379 0.178865 0.365999 0.178865 0.365999 0.163195 0.377008 0.1622959 0.377225 0.178865 0.365999 0.1622959 0.377225 0.171033 0.36983 0.156268 0.394814 0.155346 0.383214 0.15921 0.382558 0.156268 0.394814 0.134935 0.398149 0.155346 0.383214 0.166499 0.404899 0.15921 0.382558 0.162731 0.380872 0.156268 0.394814 0.15921 0.382558 0.157471 0.407983 0.162227 0.40712 0.157471 0.407983 0.15921 0.382558 0.177328 0.03726589 0.177215 0.406904 0.188142 0.39223 0.166499 0.404899 0.162227 0.40712 0.15921 0.382558 0.165331 0.02667999 0.165178 0.417468 0.177215 0.406904 0.219852 0.331934 0.218323 0.331196 0.22336 0.325861 0.224606 0.321878 0.22336 0.325861 0.218323 0.331196 0.226041 0.325438 0.219852 0.331934 0.22336 0.325861 0.225125 0.324403 0.226041 0.325438 0.22336 0.325861 0.224606 0.321878 0.225125 0.324403 0.22336 0.325861 0.219852 0.331934 0.212597 0.336825 0.218323 0.331196 0.211212 0.332217 0.218323 0.331196 0.212597 0.336825 0.211212 0.332217 0.224606 0.321878 0.218323 0.331196 0.2124339 0.339131 0.206113 0.342761 0.212597 0.336825 0.211212 0.332217 0.212597 0.336825 0.206113 0.342761 0.219852 0.331934 0.2124339 0.339131 0.212597 0.336825 0.2034 0.347116 0.198796 0.34902 0.206113 0.342761 0.196161 0.344374 0.206113 0.342761 0.198796 0.34902 0.2124339 0.339131 0.2034 0.347116 0.206113 0.342761 0.196161 0.344374 0.211212 0.332217 0.206113 0.342761 0.1923699 0.356022 0.190567 0.355612 0.198796 0.34902 0.196161 0.344374 0.198796 0.34902 0.190567 0.355612 0.2034 0.347116 0.1923699 0.356022 0.198796 0.34902 0.1923699 0.356022 0.181344 0.362545 0.190567 0.355612 0.178961 0.35887 0.190567 0.355612 0.181344 0.362545 0.178961 0.35887 0.196161 0.344374 0.190567 0.355612 0.178865 0.365999 0.171033 0.36983 0.181344 0.362545 0.178961 0.35887 0.181344 0.362545 0.171033 0.36983 0.1923699 0.356022 0.178865 0.365999 0.181344 0.362545 0.158903 0.376439 0.178961 0.35887 0.171033 0.36983 0.181469 0.365086 0.178865 0.365999 0.1923699 0.356022 0.1949509 0.355048 0.1923699 0.356022 0.2034 0.347116 0.1949509 0.355048 0.181469 0.365086 0.1923699 0.356022 0.205952 0.346087 0.2034 0.347116 0.2124339 0.339131 0.205952 0.346087 0.1949509 0.355048 0.2034 0.347116 0.214954 0.338051 0.2124339 0.339131 0.219852 0.331934 0.214954 0.338051 0.205952 0.346087 0.2124339 0.339131 0.2223359 0.330809 0.219852 0.331934 0.226041 0.325438 0.2223359 0.330809 0.214954 0.338051 0.219852 0.331934 0.2223359 0.330809 0.226041 0.325438 0.228488 0.324271 0.228476 0.323401 0.228488 0.324271 0.226041 0.325438 0.228476 0.323401 0.226041 0.325438 0.225125 0.324403 0.2244 0.329037 0.2223359 0.330809 0.228488 0.324271 0.2244 0.329037 0.228488 0.324271 0.2304829 0.322447 0.230708 0.322435 0.2304829 0.322447 0.228488 0.324271 0.230708 0.322435 0.228488 0.324271 0.228476 0.323401 0.183776 0.363589 0.181469 0.365086 0.1949509 0.355048 0.197203 0.353472 0.1949509 0.355048 0.205952 0.346087 0.197203 0.353472 0.183776 0.363589 0.1949509 0.355048 0.208145 0.344439 0.205952 0.346087 0.214954 0.338051 0.208145 0.344439 0.197203 0.353472 0.205952 0.346087 0.217083 0.336338 0.214954 0.338051 0.2223359 0.330809 0.217083 0.336338 0.208145 0.344439 0.214954 0.338051 0.2244 0.329037 0.217083 0.336338 0.2223359 0.330809 0.226998 0.325557 0.2244 0.329037 0.2304829 0.322447 0.231486 0.320561 0.2304829 0.322447 0.231867 0.320125 0.232589 0.320895 0.231867 0.320125 0.2304829 0.322447 0.231486 0.320561 0.226998 0.325557 0.2304829 0.322447 0.232589 0.320895 0.2304829 0.322447 0.230708 0.322435 0.190843 0.357735 0.183776 0.363589 0.197203 0.353472 0.190843 0.357735 0.180633 0.365213 0.183776 0.363589 0.199955 0.35062 0.197203 0.353472 0.208145 0.344439 0.199955 0.35062 0.190843 0.357735 0.197203 0.353472 0.215184 0.337445 0.208145 0.344439 0.217083 0.336338 0.208039 0.343864 0.199955 0.35062 0.208145 0.344439 0.215184 0.337445 0.208039 0.343864 0.208145 0.344439 0.221478 0.331341 0.217083 0.336338 0.2244 0.329037 0.221478 0.331341 0.215184 0.337445 0.217083 0.336338 0.226998 0.325557 0.221478 0.331341 0.2244 0.329037 0.235621 0.308344 0.231486 0.320561 0.231867 0.320125 0.233174 0.319302 0.231867 0.320125 0.232589 0.320895 0.237793 0.308753 0.231867 0.320125 0.233174 0.319302 0.235621 0.308344 0.231867 0.320125 0.237793 0.308753 0.203694 0.33752 0.180633 0.365213 0.190843 0.357735 0.203694 0.33752 0.190843 0.357735 0.199955 0.35062 0.212607 0.332758 0.199955 0.35062 0.208039 0.343864 0.203694 0.33752 0.199955 0.35062 0.212607 0.332758 0.220017 0.328373 0.208039 0.343864 0.215184 0.337445 0.212607 0.332758 0.208039 0.343864 0.220017 0.328373 0.220017 0.328373 0.215184 0.337445 0.221478 0.331341 0.226215 0.324308 0.221478 0.331341 0.226998 0.325557 0.220017 0.328373 0.221478 0.331341 0.226215 0.324308 0.226215 0.324308 0.226998 0.325557 0.231486 0.320561 0.239935 0.294503 0.231486 0.320561 0.235621 0.308344 0.226215 0.324308 0.231486 0.320561 0.239935 0.294503 0.257059 0.314532 0.256092 0.314553 0.265274 0.313032 0.253855 0.314258 0.265274 0.313032 0.256092 0.314553 0.266074 0.313027 0.257059 0.314532 0.265274 0.313032 0.274319 0.31179 0.266074 0.313027 0.265274 0.313032 0.274319 0.31179 0.265274 0.313032 0.269028 0.312482 0.281002 0.310339 0.269028 0.312482 0.265274 0.313032 0.253855 0.314258 0.281002 0.310339 0.265274 0.313032 0.249329 0.316133 0.247568 0.316309 0.256092 0.314553 0.249117 0.314954 0.256092 0.314553 0.247568 0.316309 0.257059 0.314532 0.249329 0.316133 0.256092 0.314553 0.249117 0.314954 0.253855 0.314258 0.256092 0.314553 0.2426339 0.31782 0.239764 0.318304 0.247568 0.316309 0.240607 0.316346 0.247568 0.316309 0.239764 0.318304 0.249329 0.316133 0.2426339 0.31782 0.247568 0.316309 0.244715 0.31565 0.249117 0.314954 0.247568 0.316309 0.240607 0.316346 0.244715 0.31565 0.247568 0.316309 0.236897 0.319592 0.236185 0.319393 0.239764 0.318304 0.231367 0.318456 0.239764 0.318304 0.236185 0.319393 0.2426339 0.31782 0.236897 0.319592 0.239764 0.318304 0.2369419 0.317044 0.240607 0.316346 0.239764 0.318304 0.233912 0.317737 0.2369419 0.317044 0.239764 0.318304 0.231367 0.318456 0.233912 0.317737 0.239764 0.318304 0.236897 0.319592 0.232894 0.320538 0.236185 0.319393 0.227461 0.320072 0.236185 0.319393 0.232894 0.320538 0.2292439 0.319239 0.231367 0.318456 0.236185 0.319393 0.227461 0.320072 0.2292439 0.319239 0.236185 0.319393 0.232145 0.321452 0.229893 0.321746 0.232894 0.320538 0.225901 0.32095 0.232894 0.320538 0.229893 0.321746 0.236897 0.319592 0.232145 0.321452 0.232894 0.320538 0.225901 0.32095 0.227461 0.320072 0.232894 0.320538 0.228476 0.323401 0.227301 0.323033 0.229893 0.321746 0.224606 0.321878 0.229893 0.321746 0.227301 0.323033 0.232145 0.321452 0.228476 0.323401 0.229893 0.321746 0.224606 0.321878 0.225901 0.32095 0.229893 0.321746 0.228476 0.323401 0.225125 0.324403 0.227301 0.323033 0.224606 0.321878 0.227301 0.323033 0.225125 0.324403 0.230708 0.322435 0.228476 0.323401 0.232145 0.321452 0.23415 0.320667 0.232145 0.321452 0.236897 0.319592 0.23415 0.320667 0.230708 0.322435 0.232145 0.321452 0.238669 0.318971 0.236897 0.319592 0.2426339 0.31782 0.238669 0.318971 0.23415 0.320667 0.236897 0.319592 0.244168 0.317344 0.2426339 0.31782 0.249329 0.316133 0.244168 0.317344 0.238669 0.318971 0.2426339 0.31782 0.250622 0.315785 0.249329 0.316133 0.257059 0.314532 0.250622 0.315785 0.244168 0.317344 0.249329 0.316133 0.258105 0.314295 0.257059 0.314532 0.266074 0.313027 0.258105 0.314295 0.250622 0.315785 0.257059 0.314532 0.258105 0.314295 0.266074 0.313027 0.26686 0.312884 0.274319 0.31179 0.26686 0.312884 0.266074 0.313027 0.259099 0.313864 0.258105 0.314295 0.26686 0.312884 0.259099 0.313864 0.26686 0.312884 0.267619 0.312604 0.274319 0.31179 0.267619 0.312604 0.26686 0.312884 0.232589 0.320895 0.230708 0.322435 0.23415 0.320667 0.235891 0.319393 0.23415 0.320667 0.238669 0.318971 0.235891 0.319393 0.232589 0.320895 0.23415 0.320667 0.240249 0.317941 0.238669 0.318971 0.244168 0.317344 0.240249 0.317941 0.235891 0.319393 0.238669 0.318971 0.24557 0.316537 0.244168 0.317344 0.250622 0.315785 0.24557 0.316537 0.240249 0.317941 0.244168 0.317344 0.251829 0.315178 0.250622 0.315785 0.258105 0.314295 0.251829 0.315178 0.24557 0.316537 0.250622 0.315785 0.259099 0.313864 0.251829 0.315178 0.258105 0.314295 0.260136 0.313226 0.259099 0.313864 0.267619 0.312604 0.260136 0.313226 0.267619 0.312604 0.268337 0.312192 0.272067 0.311656 0.268337 0.312192 0.267619 0.312604 0.275771 0.311124 0.272067 0.311656 0.267619 0.312604 0.274319 0.31179 0.275771 0.311124 0.267619 0.312604 0.234953 0.31851 0.232589 0.320895 0.235891 0.319393 0.234953 0.31851 0.233174 0.319302 0.232589 0.320895 0.239742 0.317017 0.235891 0.319393 0.240249 0.317941 0.234986 0.318497 0.234953 0.31851 0.235891 0.319393 0.237203 0.317732 0.234986 0.318497 0.235891 0.319393 0.239742 0.317017 0.237203 0.317732 0.235891 0.319393 0.242586 0.316317 0.240249 0.317941 0.24557 0.316537 0.240198 0.316899 0.239742 0.317017 0.240249 0.317941 0.242586 0.316317 0.240198 0.316899 0.240249 0.317941 0.247573 0.315289 0.24557 0.316537 0.251829 0.315178 0.2456949 0.315656 0.242586 0.316317 0.24557 0.316537 0.247573 0.315289 0.2456949 0.315656 0.24557 0.316537 0.256995 0.313699 0.251829 0.315178 0.259099 0.313864 0.252563 0.314392 0.247573 0.315289 0.251829 0.315178 0.256995 0.313699 0.252563 0.314392 0.251829 0.315178 0.260136 0.313226 0.256995 0.313699 0.259099 0.313864 0.267841 0.309791 0.260136 0.313226 0.268337 0.312192 0.275771 0.311124 0.268337 0.312192 0.272067 0.311656 0.267841 0.309791 0.268337 0.312192 0.275771 0.311124 0.237793 0.308753 0.233174 0.319302 0.234953 0.31851 0.242646 0.307325 0.234953 0.31851 0.234986 0.318497 0.237793 0.308753 0.234953 0.31851 0.242646 0.307325 0.242646 0.307325 0.234986 0.318497 0.237203 0.317732 0.242646 0.307325 0.237203 0.317732 0.239742 0.317017 0.242646 0.307325 0.239742 0.317017 0.240198 0.316899 0.248913 0.307968 0.240198 0.316899 0.242586 0.316317 0.242646 0.307325 0.240198 0.316899 0.248913 0.307968 0.248913 0.307968 0.242586 0.316317 0.2456949 0.315656 0.248913 0.307968 0.2456949 0.315656 0.247573 0.315289 0.257303 0.308111 0.247573 0.315289 0.252563 0.314392 0.248913 0.307968 0.247573 0.315289 0.257303 0.308111 0.257303 0.308111 0.252563 0.314392 0.256995 0.313699 0.267841 0.309791 0.256995 0.313699 0.260136 0.313226 0.267638 0.306984 0.256995 0.313699 0.267841 0.309791 0.267725 0.303748 0.256995 0.313699 0.267638 0.306984 0.257303 0.308111 0.256995 0.313699 0.267725 0.303748 0.274319 0.31179 0.269028 0.312482 0.27276 0.311936 0.281002 0.310339 0.27276 0.311936 0.269028 0.312482 0.278973 0.311061 0.274319 0.31179 0.27276 0.311936 0.281002 0.310339 0.278973 0.311061 0.27276 0.311936 0.283379 0.310542 0.275771 0.311124 0.274319 0.31179 0.287725 0.309563 0.275771 0.311124 0.283379 0.310542 0.296732 0.306403 0.275771 0.311124 0.287725 0.309563 0.278192 0.308804 0.275771 0.311124 0.296732 0.306403 0.267841 0.309791 0.275771 0.311124 0.278192 0.308804 0.283379 0.310542 0.274319 0.31179 0.278973 0.311061 0.302479 0.308332 0.298196 0.308747 0.311605 0.307425 0.294213 0.308454 0.311605 0.307425 0.298196 0.308747 0.312631 0.307347 0.302479 0.308332 0.311605 0.307425 0.337187 0.305093 0.312631 0.307347 0.311605 0.307425 0.337187 0.305093 0.311605 0.307425 0.323941 0.306301 0.307215 0.306614 0.323941 0.306301 0.311605 0.307425 0.294213 0.308454 0.307215 0.306614 0.311605 0.307425 0.292753 0.309393 0.28528 0.31024 0.298196 0.308747 0.294213 0.308454 0.298196 0.308747 0.28528 0.31024 0.302479 0.308332 0.292753 0.309393 0.298196 0.308747 0.283379 0.310542 0.278973 0.311061 0.28528 0.31024 0.281002 0.310339 0.28528 0.31024 0.278973 0.311061 0.292753 0.309393 0.283379 0.310542 0.28528 0.31024 0.281002 0.310339 0.294213 0.308454 0.28528 0.31024 0.287725 0.309563 0.283379 0.310542 0.292753 0.309393 0.293943 0.308831 0.292753 0.309393 0.302479 0.308332 0.293943 0.308831 0.287725 0.309563 0.292753 0.309393 0.300286 0.308134 0.302479 0.308332 0.312631 0.307347 0.300286 0.308134 0.293943 0.308831 0.302479 0.308332 0.300286 0.308134 0.312631 0.307347 0.313591 0.306811 0.325874 0.305674 0.313591 0.306811 0.312631 0.307347 0.338188 0.304519 0.325874 0.305674 0.312631 0.307347 0.337187 0.305093 0.338188 0.304519 0.312631 0.307347 0.300286 0.308134 0.313591 0.306811 0.293943 0.308831 0.316415 0.304629 0.293943 0.308831 0.313591 0.306811 0.338188 0.304519 0.313591 0.306811 0.325874 0.305674 0.316415 0.304629 0.313591 0.306811 0.338188 0.304519 0.296732 0.306403 0.287725 0.309563 0.293943 0.308831 0.316415 0.304629 0.296732 0.306403 0.293943 0.308831 0.337187 0.305093 0.323941 0.306301 0.336114 0.305185 0.332488 0.303083 0.336114 0.305185 0.323941 0.306301 0.340934 0.30477 0.337187 0.305093 0.336114 0.305185 0.332488 0.303083 0.340934 0.30477 0.336114 0.305185 0.307215 0.306614 0.332488 0.303083 0.323941 0.306301 0.343492 0.304607 0.338188 0.304519 0.337187 0.305093 0.34285 0.304306 0.338188 0.304519 0.343492 0.304607 0.341618 0.303328 0.338188 0.304519 0.34285 0.304306 0.338728 0.301844 0.338188 0.304519 0.341618 0.303328 0.335085 0.303091 0.338188 0.304519 0.338728 0.301844 0.316415 0.304629 0.338188 0.304519 0.335085 0.303091 0.340934 0.30477 0.343492 0.304607 0.337187 0.305093 0.365668 0.303376 0.364729 0.303404 0.372362 0.303052 0.365133 0.303352 0.372362 0.303052 0.364729 0.303404 0.36895 0.303271 0.365668 0.303376 0.372362 0.303052 0.332488 0.303083 0.372362 0.303052 0.365133 0.303352 0.430379 0.303143 0.36895 0.303271 0.372362 0.303052 0.431301 0.302447 0.430379 0.303143 0.372362 0.303052 0.336903 0.302169 0.431301 0.302447 0.372362 0.303052 0.332488 0.303083 0.336903 0.302169 0.372362 0.303052 0.359368 0.303659 0.357308 0.303775 0.364729 0.303404 0.358374 0.303673 0.364729 0.303404 0.357308 0.303775 0.365668 0.303376 0.359368 0.303659 0.364729 0.303404 0.358374 0.303673 0.365133 0.303352 0.364729 0.303404 0.35341 0.303913 0.350201 0.304173 0.357308 0.303775 0.352071 0.304016 0.357308 0.303775 0.350201 0.304173 0.355389 0.30383 0.35341 0.303913 0.357308 0.303775 0.359368 0.303659 0.355389 0.30383 0.357308 0.303775 0.352071 0.304016 0.358374 0.303673 0.357308 0.303775 0.34556 0.304209 0.343492 0.304607 0.350201 0.304173 0.346249 0.304381 0.350201 0.304173 0.343492 0.304607 0.347884 0.304128 0.34556 0.304209 0.350201 0.304173 0.35341 0.303913 0.347884 0.304128 0.350201 0.304173 0.346249 0.304381 0.352071 0.304016 0.350201 0.304173 0.34556 0.304209 0.34285 0.304306 0.343492 0.304607 0.340934 0.30477 0.346249 0.304381 0.343492 0.304607 0.341618 0.303328 0.34285 0.304306 0.34556 0.304209 0.34613 0.302869 0.34556 0.304209 0.347884 0.304128 0.341618 0.303328 0.34556 0.304209 0.34613 0.302869 0.350315 0.303598 0.347884 0.304128 0.35341 0.303913 0.34613 0.302869 0.347884 0.304128 0.350315 0.303598 0.350315 0.303598 0.35341 0.303913 0.355389 0.30383 0.360021 0.303548 0.355389 0.30383 0.359368 0.303659 0.355164 0.303386 0.350315 0.303598 0.355389 0.30383 0.360021 0.303548 0.355164 0.303386 0.355389 0.30383 0.365755 0.303429 0.359368 0.303659 0.365668 0.303376 0.365755 0.303429 0.360021 0.303548 0.359368 0.303659 0.36895 0.303271 0.365755 0.303429 0.365668 0.303376 0.332488 0.303083 0.365133 0.303352 0.358374 0.303673 0.332488 0.303083 0.358374 0.303673 0.352071 0.304016 0.332488 0.303083 0.352071 0.304016 0.346249 0.304381 0.332488 0.303083 0.346249 0.304381 0.340934 0.30477 0.351159 0.302884 0.34613 0.302869 0.350315 0.303598 0.355164 0.303386 0.351159 0.302884 0.350315 0.303598 0.348046 0.301937 0.343119 0.301548 0.34613 0.302869 0.341618 0.303328 0.34613 0.302869 0.343119 0.301548 0.351159 0.302884 0.348046 0.301937 0.34613 0.302869 0.346105 0.300471 0.341401 0.299603 0.343119 0.301548 0.338728 0.301844 0.343119 0.301548 0.341401 0.299603 0.348046 0.301937 0.346105 0.300471 0.343119 0.301548 0.338728 0.301844 0.341618 0.303328 0.343119 0.301548 0.345395 0.298407 0.340894 0.297071 0.341401 0.299603 0.336978 0.299755 0.341401 0.299603 0.340894 0.297071 0.346105 0.300471 0.345395 0.298407 0.341401 0.299603 0.336978 0.299755 0.338728 0.301844 0.341401 0.299603 0.34583 0.295793 0.341395 0.294023 0.340894 0.297071 0.336282 0.297106 0.340894 0.297071 0.341395 0.294023 0.345395 0.298407 0.34583 0.295793 0.340894 0.297071 0.336282 0.297106 0.336978 0.299755 0.340894 0.297071 0.34731 0.292577 0.342687 0.290524 0.341395 0.294023 0.336465 0.29396 0.341395 0.294023 0.342687 0.290524 0.34645 0.294271 0.34731 0.292577 0.341395 0.294023 0.34583 0.295793 0.34645 0.294271 0.341395 0.294023 0.336465 0.29396 0.336282 0.297106 0.341395 0.294023 0.349793 0.288609 0.344588 0.286629 0.342687 0.290524 0.337349 0.290376 0.342687 0.290524 0.344588 0.286629 0.348424 0.290705 0.349793 0.288609 0.342687 0.290524 0.34731 0.292577 0.348424 0.290705 0.342687 0.290524 0.337349 0.290376 0.336465 0.29396 0.342687 0.290524 0.35015 0.282916 0.346962 0.282381 0.344588 0.286629 0.338782 0.286402 0.344588 0.286629 0.346962 0.282381 0.353322 0.283701 0.35015 0.282916 0.344588 0.286629 0.351423 0.286277 0.353322 0.283701 0.344588 0.286629 0.349793 0.288609 0.351423 0.286277 0.344588 0.286629 0.338782 0.286402 0.337349 0.290376 0.344588 0.286629 0.353618 0.276597 0.346962 0.282381 0.35015 0.282916 0.343785 0.2821 0.338782 0.286402 0.346962 0.282381 0.349413 0.275747 0.343785 0.2821 0.346962 0.282381 0.349413 0.275747 0.346962 0.282381 0.353618 0.276597 0.353618 0.276597 0.35015 0.282916 0.353322 0.283701 0.422131 0.276751 0.353322 0.283701 0.351423 0.286277 0.422131 0.276751 0.357815 0.277849 0.353322 0.283701 0.353618 0.276597 0.353322 0.283701 0.357815 0.277849 0.423519 0.286663 0.351423 0.286277 0.349793 0.288609 0.423519 0.286663 0.422131 0.276751 0.351423 0.286277 0.423519 0.286663 0.349793 0.288609 0.348424 0.290705 0.423519 0.286663 0.348424 0.290705 0.34731 0.292577 0.423519 0.286663 0.34731 0.292577 0.34645 0.294271 0.425096 0.294387 0.34645 0.294271 0.34583 0.295793 0.425096 0.294387 0.423519 0.286663 0.34645 0.294271 0.425096 0.294387 0.34583 0.295793 0.345395 0.298407 0.426803 0.299748 0.345395 0.298407 0.346105 0.300471 0.426803 0.299748 0.425096 0.294387 0.345395 0.298407 0.426803 0.299748 0.346105 0.300471 0.348046 0.301937 0.426803 0.299748 0.348046 0.301937 0.351159 0.302884 0.428583 0.302665 0.351159 0.302884 0.355164 0.303386 0.428583 0.302665 0.426803 0.299748 0.351159 0.302884 0.428583 0.302665 0.355164 0.303386 0.360021 0.303548 0.430379 0.303143 0.360021 0.303548 0.365755 0.303429 0.428583 0.302665 0.360021 0.303548 0.430379 0.303143 0.430379 0.303143 0.365755 0.303429 0.36895 0.303271 0.335085 0.303091 0.338728 0.301844 0.336978 0.299755 0.332862 0.300849 0.336978 0.299755 0.336282 0.297106 0.332862 0.300849 0.335085 0.303091 0.336978 0.299755 0.331714 0.29793 0.336282 0.297106 0.336465 0.29396 0.331714 0.29793 0.332862 0.300849 0.336282 0.297106 0.331609 0.294273 0.336465 0.29396 0.337349 0.290376 0.331554 0.296207 0.331714 0.29793 0.336465 0.29396 0.331609 0.294273 0.331554 0.296207 0.336465 0.29396 0.332516 0.289478 0.337349 0.290376 0.338782 0.286402 0.331903 0.292093 0.331609 0.294273 0.337349 0.290376 0.332516 0.289478 0.331903 0.292093 0.337349 0.290376 0.343785 0.2821 0.34065 0.282079 0.338782 0.286402 0.333434 0.28639 0.338782 0.286402 0.34065 0.282079 0.333434 0.28639 0.332516 0.289478 0.338782 0.286402 0.345257 0.275325 0.34065 0.282079 0.343785 0.2821 0.33759 0.282316 0.333434 0.28639 0.34065 0.282079 0.341214 0.27534 0.33759 0.282316 0.34065 0.282079 0.341214 0.27534 0.34065 0.282079 0.345257 0.275325 0.345257 0.275325 0.343785 0.2821 0.349413 0.275747 0.319128 0.302308 0.335085 0.303091 0.332862 0.300849 0.316415 0.304629 0.335085 0.303091 0.319128 0.302308 0.321727 0.299857 0.332862 0.300849 0.331714 0.29793 0.319128 0.302308 0.332862 0.300849 0.321727 0.299857 0.324217 0.29728 0.331714 0.29793 0.331554 0.296207 0.321727 0.299857 0.331714 0.29793 0.324217 0.29728 0.326588 0.294585 0.331554 0.296207 0.331609 0.294273 0.324217 0.29728 0.331554 0.296207 0.326588 0.294585 0.326588 0.294585 0.331609 0.294273 0.331903 0.292093 0.328818 0.291783 0.331903 0.292093 0.332516 0.289478 0.326588 0.294585 0.331903 0.292093 0.328818 0.291783 0.330899 0.288882 0.332516 0.289478 0.333434 0.28639 0.328818 0.291783 0.332516 0.289478 0.330899 0.288882 0.33759 0.282316 0.334629 0.282811 0.333434 0.28639 0.332836 0.285888 0.333434 0.28639 0.334629 0.282811 0.330899 0.288882 0.333434 0.28639 0.332836 0.285888 0.335927 0.279297 0.334629 0.282811 0.33759 0.282316 0.318789 0.281193 0.316139 0.2849 0.334629 0.282811 0.332836 0.285888 0.334629 0.282811 0.316139 0.2849 0.335927 0.279297 0.318789 0.281193 0.334629 0.282811 0.335927 0.279297 0.33759 0.282316 0.337355 0.275781 0.341214 0.27534 0.337355 0.275781 0.33759 0.282316 0.432198 0.301148 0.430379 0.303143 0.431301 0.302447 0.428583 0.302665 0.430379 0.303143 0.432198 0.301148 0.336903 0.302169 0.432198 0.301148 0.431301 0.302447 0.341044 0.300792 0.433073 0.299248 0.432198 0.301148 0.428583 0.302665 0.432198 0.301148 0.433073 0.299248 0.336903 0.302169 0.341044 0.300792 0.432198 0.301148 0.348488 0.29673 0.433918 0.296785 0.433073 0.299248 0.428583 0.302665 0.433073 0.299248 0.433918 0.296785 0.341044 0.300792 0.348488 0.29673 0.433073 0.299248 0.348488 0.29673 0.434726 0.293782 0.433918 0.296785 0.43068 0.29824 0.433918 0.296785 0.434726 0.293782 0.43068 0.29824 0.428583 0.302665 0.433918 0.296785 0.354806 0.291061 0.435494 0.290277 0.434726 0.293782 0.43392 0.291867 0.434726 0.293782 0.435494 0.290277 0.348488 0.29673 0.354806 0.291061 0.434726 0.293782 0.432346 0.296115 0.43068 0.29824 0.434726 0.293782 0.43392 0.291867 0.432346 0.296115 0.434726 0.293782 0.360035 0.283965 0.436215 0.286297 0.435494 0.290277 0.43392 0.291867 0.435494 0.290277 0.436215 0.286297 0.354806 0.291061 0.360035 0.283965 0.435494 0.290277 0.360035 0.283965 0.436887 0.281883 0.436215 0.286297 0.435363 0.285685 0.436215 0.286297 0.436887 0.281883 0.435363 0.285685 0.43392 0.291867 0.436215 0.286297 0.364239 0.275635 0.437505 0.277066 0.436887 0.281883 0.43664 0.277788 0.436887 0.281883 0.437505 0.277066 0.360035 0.283965 0.364239 0.275635 0.436887 0.281883 0.43664 0.277788 0.435363 0.285685 0.436887 0.281883 0.364239 0.275635 0.438067 0.271887 0.437505 0.277066 0.43664 0.277788 0.437505 0.277066 0.438067 0.271887 0.36751 0.266266 0.438569 0.26638 0.438067 0.271887 0.437722 0.268451 0.438067 0.271887 0.438569 0.26638 0.364239 0.275635 0.36751 0.266266 0.438067 0.271887 0.437722 0.268451 0.43664 0.277788 0.438067 0.271887 0.36751 0.266266 0.43901 0.260589 0.438569 0.26638 0.437722 0.268451 0.438569 0.26638 0.43901 0.260589 0.369944 0.256054 0.439386 0.254547 0.43901 0.260589 0.438583 0.257972 0.43901 0.260589 0.439386 0.254547 0.36751 0.266266 0.369944 0.256054 0.43901 0.260589 0.438583 0.257972 0.437722 0.268451 0.43901 0.260589 0.371624 0.245178 0.439696 0.248298 0.439386 0.254547 0.438583 0.257972 0.439386 0.254547 0.439696 0.248298 0.369944 0.256054 0.371624 0.245178 0.439386 0.254547 0.371624 0.245178 0.439939 0.2418799 0.439696 0.248298 0.439216 0.2465119 0.439696 0.248298 0.439939 0.2418799 0.439216 0.2465119 0.438583 0.257972 0.439696 0.248298 0.372616 0.233779 0.440114 0.235335 0.439939 0.2418799 0.439216 0.2465119 0.439939 0.2418799 0.440114 0.235335 0.371624 0.245178 0.372616 0.233779 0.439939 0.2418799 0.372616 0.233779 0.440218 0.2287279 0.440114 0.235335 0.439601 0.23442 0.440114 0.235335 0.440218 0.2287279 0.439601 0.23442 0.439216 0.2465119 0.440114 0.235335 0.372947 0.222023 0.440254 0.222023 0.440218 0.2287279 0.439601 0.23442 0.440218 0.2287279 0.440254 0.222023 0.372616 0.233779 0.372947 0.222023 0.440218 0.2287279 0.372617 0.2102749 0.440124 0.209184 0.440254 0.222023 0.43973 0.222023 0.440254 0.222023 0.440124 0.209184 0.372947 0.222023 0.372617 0.2102749 0.440254 0.222023 0.439601 0.23442 0.440254 0.222023 0.43973 0.222023 0.371626 0.198885 0.439735 0.196658 0.440124 0.209184 0.439221 0.197649 0.440124 0.209184 0.439735 0.196658 0.372617 0.2102749 0.371626 0.198885 0.440124 0.209184 0.439602 0.209694 0.43973 0.222023 0.440124 0.209184 0.439221 0.197649 0.439602 0.209694 0.440124 0.209184 0.369948 0.188017 0.439096 0.184735 0.439735 0.196658 0.438592 0.1862069 0.439735 0.196658 0.439096 0.184735 0.371626 0.198885 0.369948 0.188017 0.439735 0.196658 0.438592 0.1862069 0.439221 0.197649 0.439735 0.196658 0.367519 0.177809 0.438217 0.173703 0.439096 0.184735 0.437733 0.175714 0.439096 0.184735 0.438217 0.173703 0.369948 0.188017 0.367519 0.177809 0.439096 0.184735 0.437733 0.175714 0.438592 0.1862069 0.439096 0.184735 0.364253 0.168443 0.437114 0.1638399 0.438217 0.173703 0.436651 0.166337 0.438217 0.173703 0.437114 0.1638399 0.367519 0.177809 0.364253 0.168443 0.438217 0.173703 0.436651 0.166337 0.437733 0.175714 0.438217 0.173703 0.360053 0.160111 0.435809 0.155419 0.437114 0.1638399 0.435369 0.158392 0.437114 0.1638399 0.435809 0.155419 0.364253 0.168443 0.360053 0.160111 0.437114 0.1638399 0.435369 0.158392 0.436651 0.166337 0.437114 0.1638399 0.354827 0.153008 0.434327 0.148696 0.435809 0.155419 0.433919 0.152175 0.435809 0.155419 0.434327 0.148696 0.360053 0.160111 0.354827 0.153008 0.435809 0.155419 0.433919 0.152175 0.435369 0.158392 0.435809 0.155419 0.348508 0.14733 0.432701 0.143911 0.434327 0.148696 0.43067 0.1457999 0.434327 0.148696 0.432701 0.143911 0.354827 0.153008 0.348508 0.14733 0.434327 0.148696 0.432339 0.147917 0.433919 0.152175 0.434327 0.148696 0.43067 0.1457999 0.432339 0.147917 0.434327 0.148696 0.372362 0.140994 0.43097 0.141273 0.432701 0.143911 0.429115 0.140987 0.432701 0.143911 0.43097 0.141273 0.332488 0.140962 0.372362 0.140994 0.432701 0.143911 0.336911 0.141878 0.332488 0.140962 0.432701 0.143911 0.341057 0.143259 0.336911 0.141878 0.432701 0.143911 0.348508 0.14733 0.341057 0.143259 0.432701 0.143911 0.429115 0.140987 0.42726 0.143306 0.432701 0.143911 0.43067 0.1457999 0.432701 0.143911 0.42726 0.143306 0.36605 0.1406289 0.43097 0.141273 0.372362 0.140994 0.355875 0.140614 0.429115 0.140987 0.43097 0.141273 0.360567 0.140497 0.355875 0.140614 0.43097 0.141273 0.36605 0.1406289 0.360567 0.140497 0.43097 0.141273 0.36895 0.140855 0.372362 0.140994 0.332488 0.140962 0.368953 0.140825 0.36605 0.1406289 0.372362 0.140994 0.368559 0.140826 0.368953 0.140825 0.372362 0.140994 0.368559 0.140826 0.372362 0.140994 0.36895 0.140855 0.330746 0.141438 0.332488 0.140962 0.336911 0.141878 0.353444 0.14011 0.332488 0.140962 0.349774 0.139894 0.307214 0.137432 0.349774 0.139894 0.332488 0.140962 0.35675 0.140289 0.332488 0.140962 0.353444 0.14011 0.359728 0.14044 0.332488 0.140962 0.35675 0.140289 0.362407 0.140568 0.332488 0.140962 0.359728 0.14044 0.364816 0.140677 0.332488 0.140962 0.362407 0.140568 0.36895 0.140855 0.332488 0.140962 0.364816 0.140677 0.330746 0.141438 0.307214 0.137432 0.332488 0.140962 0.339049 0.1437 0.336911 0.141878 0.341057 0.143259 0.339049 0.1437 0.330746 0.141438 0.336911 0.141878 0.346514 0.147725 0.341057 0.143259 0.348508 0.14733 0.339049 0.1437 0.341057 0.143259 0.346514 0.147725 0.353003 0.1535 0.348508 0.14733 0.354827 0.153008 0.346514 0.147725 0.348508 0.14733 0.353003 0.1535 0.353003 0.1535 0.354827 0.153008 0.360053 0.160111 0.358451 0.160922 0.360053 0.160111 0.364253 0.168443 0.353003 0.1535 0.360053 0.160111 0.358451 0.160922 0.362835 0.169849 0.364253 0.168443 0.367519 0.177809 0.358451 0.160922 0.364253 0.168443 0.362835 0.169849 0.366203 0.180059 0.367519 0.177809 0.369948 0.188017 0.362835 0.169849 0.367519 0.177809 0.366203 0.180059 0.36863 0.191296 0.369948 0.188017 0.371626 0.198885 0.366203 0.180059 0.369948 0.188017 0.36863 0.191296 0.370193 0.203283 0.371626 0.198885 0.372617 0.2102749 0.36863 0.191296 0.371626 0.198885 0.370193 0.203283 0.370958 0.215725 0.372617 0.2102749 0.372947 0.222023 0.370193 0.203283 0.372617 0.2102749 0.370958 0.215725 0.370958 0.22832 0.372947 0.222023 0.372616 0.233779 0.370958 0.215725 0.372947 0.222023 0.370958 0.22832 0.370193 0.2407619 0.372616 0.233779 0.371624 0.245178 0.370958 0.22832 0.372616 0.233779 0.370193 0.2407619 0.36863 0.252749 0.371624 0.245178 0.369944 0.256054 0.370193 0.2407619 0.371624 0.245178 0.36863 0.252749 0.366203 0.263986 0.369944 0.256054 0.36751 0.266266 0.36863 0.252749 0.369944 0.256054 0.366203 0.263986 0.362836 0.274196 0.36751 0.266266 0.364239 0.275635 0.366203 0.263986 0.36751 0.266266 0.362836 0.274196 0.358451 0.283123 0.364239 0.275635 0.360035 0.283965 0.362836 0.274196 0.364239 0.275635 0.358451 0.283123 0.358451 0.283123 0.360035 0.283965 0.354806 0.291061 0.353003 0.290545 0.354806 0.291061 0.348488 0.29673 0.358451 0.283123 0.354806 0.291061 0.353003 0.290545 0.346514 0.296321 0.348488 0.29673 0.341044 0.300792 0.353003 0.290545 0.348488 0.29673 0.346514 0.296321 0.33905 0.300346 0.341044 0.300792 0.336903 0.302169 0.346514 0.296321 0.341044 0.300792 0.33905 0.300346 0.33905 0.300346 0.336903 0.302169 0.332488 0.303083 0.305789 0.306278 0.332488 0.303083 0.307215 0.306614 0.330746 0.302607 0.332488 0.303083 0.305789 0.306278 0.33905 0.300346 0.332488 0.303083 0.330746 0.302607 0.422131 0.276751 0.358095 0.277491 0.357815 0.277849 0.359847 0.27062 0.357815 0.277849 0.358095 0.277491 0.353618 0.276597 0.357815 0.277849 0.359847 0.27062 0.422131 0.276751 0.362664 0.271675 0.358095 0.277491 0.359847 0.27062 0.358095 0.277491 0.362664 0.271675 0.420985 0.264923 0.368865 0.263799 0.362664 0.271675 0.364722 0.262125 0.362664 0.271675 0.368865 0.263799 0.422131 0.276751 0.420985 0.264923 0.362664 0.271675 0.359847 0.27062 0.362664 0.271675 0.364722 0.262125 0.420129 0.251546 0.369529 0.262944 0.368865 0.263799 0.370912 0.253366 0.368865 0.263799 0.369529 0.262944 0.420985 0.264923 0.420129 0.251546 0.368865 0.263799 0.364722 0.262125 0.368865 0.263799 0.370912 0.253366 0.420129 0.251546 0.375402 0.255361 0.369529 0.262944 0.370912 0.253366 0.369529 0.262944 0.375402 0.255361 0.420129 0.251546 0.376086 0.254465 0.375402 0.255361 0.376398 0.243654 0.375402 0.255361 0.376086 0.254465 0.370912 0.253366 0.375402 0.255361 0.376398 0.243654 0.420129 0.251546 0.382163 0.246408 0.376086 0.254465 0.376398 0.243654 0.376086 0.254465 0.382163 0.246408 0.419599 0.237073 0.3831 0.245101 0.382163 0.246408 0.378011 0.2412379 0.382163 0.246408 0.3831 0.245101 0.420129 0.251546 0.419599 0.237073 0.382163 0.246408 0.376398 0.243654 0.382163 0.246408 0.378011 0.2412379 0.419599 0.237073 0.38399 0.2437649 0.3831 0.245101 0.378011 0.2412379 0.3831 0.245101 0.38399 0.2437649 0.419599 0.237073 0.387442 0.237053 0.38399 0.2437649 0.382089 0.23555 0.38399 0.2437649 0.387442 0.237053 0.382089 0.23555 0.378011 0.2412379 0.38399 0.2437649 0.419419 0.222023 0.387534 0.236823 0.387442 0.237053 0.384004 0.228925 0.387442 0.237053 0.387534 0.236823 0.419599 0.237073 0.419419 0.222023 0.387442 0.237053 0.382089 0.23555 0.387442 0.237053 0.384004 0.228925 0.419419 0.222023 0.389594 0.2297019 0.387534 0.236823 0.384004 0.228925 0.387534 0.236823 0.389594 0.2297019 0.419419 0.222023 0.389641 0.22946 0.389594 0.2297019 0.383527 0.222023 0.389594 0.2297019 0.389641 0.22946 0.384004 0.228925 0.389594 0.2297019 0.383527 0.222023 0.419419 0.222023 0.390326 0.222023 0.389641 0.22946 0.383527 0.222023 0.389641 0.22946 0.390326 0.222023 0.419612 0.206421 0.390326 0.222023 0.419419 0.222023 0.389904 0.2162179 0.390326 0.222023 0.419612 0.206421 0.384287 0.216834 0.390326 0.222023 0.389904 0.2162179 0.383527 0.222023 0.390326 0.222023 0.384287 0.216834 0.420136 0.222023 0.419419 0.222023 0.419599 0.237073 0.42031 0.207628 0.419612 0.206421 0.419419 0.222023 0.420136 0.222023 0.42031 0.207628 0.419419 0.222023 0.42082 0.250131 0.419599 0.237073 0.420129 0.251546 0.420309 0.236339 0.420136 0.222023 0.419599 0.237073 0.42082 0.250131 0.420309 0.236339 0.419599 0.237073 0.421647 0.262862 0.420129 0.251546 0.420985 0.264923 0.421647 0.262862 0.42082 0.250131 0.420129 0.251546 0.422746 0.274032 0.420985 0.264923 0.422131 0.276751 0.422746 0.274032 0.421647 0.262862 0.420985 0.264923 0.424087 0.283401 0.422131 0.276751 0.423519 0.286663 0.424087 0.283401 0.422746 0.274032 0.422131 0.276751 0.425612 0.290649 0.423519 0.286663 0.425096 0.294387 0.425612 0.290649 0.424087 0.283401 0.423519 0.286663 0.427259 0.295569 0.425096 0.294387 0.426803 0.299748 0.427259 0.295569 0.425612 0.290649 0.425096 0.294387 0.43068 0.29824 0.426803 0.299748 0.428583 0.302665 0.428967 0.29809 0.427259 0.295569 0.426803 0.299748 0.43068 0.29824 0.428967 0.29809 0.426803 0.299748 0.420827 0.193785 0.420182 0.191462 0.419612 0.206421 0.386701 0.205245 0.419612 0.206421 0.420182 0.191462 0.42031 0.207628 0.420827 0.193785 0.419612 0.206421 0.389566 0.214195 0.389904 0.2162179 0.419612 0.206421 0.388687 0.210593 0.389566 0.214195 0.419612 0.206421 0.387395 0.206872 0.388687 0.210593 0.419612 0.206421 0.386701 0.205245 0.387395 0.206872 0.419612 0.206421 0.421659 0.181039 0.421099 0.177721 0.420182 0.191462 0.372071 0.184367 0.420182 0.191462 0.421099 0.177721 0.420827 0.193785 0.421659 0.181039 0.420182 0.191462 0.38399 0.200281 0.386701 0.205245 0.420182 0.191462 0.3831 0.198944 0.38399 0.200281 0.420182 0.191462 0.382163 0.197637 0.3831 0.198944 0.420182 0.191462 0.372071 0.184367 0.382163 0.197637 0.420182 0.191462 0.422761 0.1698909 0.422323 0.165695 0.421099 0.177721 0.362665 0.172372 0.421099 0.177721 0.422323 0.165695 0.421659 0.181039 0.422761 0.1698909 0.421099 0.177721 0.362665 0.172372 0.372071 0.184367 0.421099 0.177721 0.4241 0.160569 0.423799 0.155779 0.422323 0.165695 0.353322 0.160345 0.422323 0.165695 0.423799 0.155779 0.422761 0.1698909 0.4241 0.160569 0.422323 0.165695 0.358066 0.166517 0.362665 0.172372 0.422323 0.165695 0.357815 0.166197 0.358066 0.166517 0.422323 0.165695 0.353322 0.160345 0.357815 0.166197 0.422323 0.165695 0.425619 0.15337 0.425466 0.148259 0.423799 0.155779 0.349551 0.1550779 0.423799 0.155779 0.425466 0.148259 0.4241 0.160569 0.425619 0.15337 0.423799 0.155779 0.351277 0.1575649 0.353322 0.160345 0.423799 0.155779 0.349551 0.1550779 0.351277 0.1575649 0.423799 0.155779 0.42896 0.145961 0.42726 0.143306 0.425466 0.148259 0.345648 0.147647 0.425466 0.148259 0.42726 0.143306 0.427257 0.148479 0.42896 0.145961 0.425466 0.148259 0.425619 0.15337 0.427257 0.148479 0.425466 0.148259 0.348134 0.152873 0.349551 0.1550779 0.425466 0.148259 0.347018 0.150933 0.348134 0.152873 0.425466 0.148259 0.346195 0.149197 0.347018 0.150933 0.425466 0.148259 0.345648 0.147647 0.346195 0.149197 0.425466 0.148259 0.348706 0.141831 0.42726 0.143306 0.429115 0.140987 0.42896 0.145961 0.43067 0.1457999 0.42726 0.143306 0.345394 0.146278 0.345648 0.147647 0.42726 0.143306 0.345456 0.145071 0.345394 0.146278 0.42726 0.143306 0.346487 0.1431429 0.345456 0.145071 0.42726 0.143306 0.348706 0.141831 0.346487 0.1431429 0.42726 0.143306 0.351917 0.141025 0.348706 0.141831 0.429115 0.140987 0.355875 0.140614 0.351917 0.141025 0.429115 0.140987 0.392787 0.222023 0.43973 0.222023 0.439602 0.209694 0.392611 0.234269 0.439601 0.23442 0.43973 0.222023 0.392611 0.234269 0.43973 0.222023 0.392787 0.222023 0.392609 0.209709 0.439602 0.209694 0.439221 0.197649 0.392609 0.209709 0.392787 0.222023 0.439602 0.209694 0.392076 0.197699 0.439221 0.197649 0.438592 0.1862069 0.392076 0.197699 0.392609 0.209709 0.439221 0.197649 0.391201 0.18632 0.438592 0.1862069 0.437733 0.175714 0.391201 0.18632 0.392076 0.197699 0.438592 0.1862069 0.390011 0.175916 0.437733 0.175714 0.436651 0.166337 0.390011 0.175916 0.391201 0.18632 0.437733 0.175714 0.388517 0.1666499 0.436651 0.166337 0.435369 0.158392 0.388517 0.1666499 0.390011 0.175916 0.436651 0.166337 0.386752 0.158818 0.435369 0.158392 0.433919 0.152175 0.386752 0.158818 0.388517 0.1666499 0.435369 0.158392 0.382587 0.148488 0.433919 0.152175 0.432339 0.147917 0.38476 0.152691 0.386752 0.158818 0.433919 0.152175 0.382587 0.148488 0.38476 0.152691 0.433919 0.152175 0.380288 0.146394 0.432339 0.147917 0.43067 0.1457999 0.380288 0.146394 0.382587 0.148488 0.432339 0.147917 0.377925 0.146558 0.43067 0.1457999 0.42896 0.145961 0.377925 0.146558 0.380288 0.146394 0.43067 0.1457999 0.37557 0.149075 0.42896 0.145961 0.427257 0.148479 0.37557 0.149075 0.377925 0.146558 0.42896 0.145961 0.37557 0.149075 0.427257 0.148479 0.425619 0.15337 0.3733 0.153969 0.425619 0.15337 0.4241 0.160569 0.3733 0.153969 0.37557 0.149075 0.425619 0.15337 0.371199 0.161169 0.4241 0.160569 0.422761 0.1698909 0.371199 0.161169 0.3733 0.153969 0.4241 0.160569 0.369353 0.170467 0.422761 0.1698909 0.421659 0.181039 0.369353 0.170467 0.371199 0.161169 0.422761 0.1698909 0.367839 0.181545 0.421659 0.181039 0.420827 0.193785 0.367839 0.181545 0.369353 0.170467 0.421659 0.181039 0.366701 0.194167 0.420827 0.193785 0.42031 0.207628 0.366701 0.194167 0.367839 0.181545 0.420827 0.193785 0.365997 0.207836 0.42031 0.207628 0.420136 0.222023 0.365997 0.207836 0.366701 0.194167 0.42031 0.207628 0.36576 0.222023 0.420136 0.222023 0.420309 0.236339 0.36576 0.222023 0.365997 0.207836 0.420136 0.222023 0.366 0.236288 0.420309 0.236339 0.42082 0.250131 0.366 0.236288 0.36576 0.222023 0.420309 0.236339 0.36671 0.250008 0.42082 0.250131 0.421647 0.262862 0.36671 0.250008 0.366 0.236288 0.42082 0.250131 0.367856 0.262644 0.421647 0.262862 0.422746 0.274032 0.367856 0.262644 0.36671 0.250008 0.421647 0.262862 0.369373 0.273702 0.422746 0.274032 0.424087 0.283401 0.369373 0.273702 0.367856 0.262644 0.422746 0.274032 0.371217 0.282953 0.424087 0.283401 0.425612 0.290649 0.371217 0.282953 0.369373 0.273702 0.424087 0.283401 0.373309 0.290103 0.425612 0.290649 0.427259 0.295569 0.373309 0.290103 0.371217 0.282953 0.425612 0.290649 0.377915 0.297482 0.427259 0.295569 0.428967 0.29809 0.375568 0.294968 0.373309 0.290103 0.427259 0.295569 0.377915 0.297482 0.375568 0.294968 0.427259 0.295569 0.380275 0.297657 0.428967 0.29809 0.43068 0.29824 0.380275 0.297657 0.377915 0.297482 0.428967 0.29809 0.382577 0.295572 0.43068 0.29824 0.432346 0.296115 0.382577 0.295572 0.380275 0.297657 0.43068 0.29824 0.384758 0.291358 0.432346 0.296115 0.43392 0.291867 0.384758 0.291358 0.382577 0.295572 0.432346 0.296115 0.384758 0.291358 0.43392 0.291867 0.435363 0.285685 0.386761 0.285197 0.435363 0.285685 0.43664 0.277788 0.386761 0.285197 0.384758 0.291358 0.435363 0.285685 0.388532 0.277317 0.43664 0.277788 0.437722 0.268451 0.388532 0.277317 0.386761 0.285197 0.43664 0.277788 0.390027 0.268011 0.437722 0.268451 0.438583 0.257972 0.390027 0.268011 0.388532 0.277317 0.437722 0.268451 0.391213 0.257594 0.438583 0.257972 0.439216 0.2465119 0.391213 0.257594 0.390027 0.268011 0.438583 0.257972 0.392083 0.246232 0.439216 0.2465119 0.439601 0.23442 0.392083 0.246232 0.391213 0.257594 0.439216 0.2465119 0.392611 0.234269 0.392083 0.246232 0.439601 0.23442 0.383203 0.211762 0.389904 0.2162179 0.389566 0.214195 0.384287 0.216834 0.389904 0.2162179 0.383203 0.211762 0.383203 0.211762 0.389566 0.214195 0.388687 0.210593 0.381428 0.206928 0.388687 0.210593 0.387395 0.206872 0.383203 0.211762 0.388687 0.210593 0.381428 0.206928 0.381428 0.206928 0.387395 0.206872 0.386701 0.205245 0.378011 0.202808 0.386701 0.205245 0.38399 0.200281 0.381428 0.206928 0.386701 0.205245 0.378011 0.202808 0.376398 0.200392 0.38399 0.200281 0.3831 0.198944 0.376398 0.200392 0.378011 0.202808 0.38399 0.200281 0.376398 0.200392 0.3831 0.198944 0.382163 0.197637 0.367789 0.186245 0.382163 0.197637 0.372071 0.184367 0.376398 0.200392 0.382163 0.197637 0.367789 0.186245 0.359847 0.173426 0.372071 0.184367 0.362665 0.172372 0.367789 0.186245 0.372071 0.184367 0.359847 0.173426 0.353618 0.16745 0.362665 0.172372 0.358066 0.166517 0.359847 0.173426 0.362665 0.172372 0.353618 0.16745 0.353618 0.16745 0.358066 0.166517 0.357815 0.166197 0.35015 0.1611289 0.357815 0.166197 0.353322 0.160345 0.353618 0.16745 0.357815 0.166197 0.35015 0.1611289 0.35015 0.1611289 0.353322 0.160345 0.351277 0.1575649 0.344588 0.1574169 0.351277 0.1575649 0.349551 0.1550779 0.346963 0.161665 0.351277 0.1575649 0.344588 0.1574169 0.35015 0.1611289 0.351277 0.1575649 0.346963 0.161665 0.342688 0.153522 0.349551 0.1550779 0.348134 0.152873 0.344588 0.1574169 0.349551 0.1550779 0.342688 0.153522 0.342688 0.153522 0.348134 0.152873 0.347018 0.150933 0.341393 0.15002 0.347018 0.150933 0.346195 0.149197 0.342688 0.153522 0.347018 0.150933 0.341393 0.15002 0.341393 0.15002 0.346195 0.149197 0.345648 0.147647 0.340895 0.146972 0.345648 0.147647 0.345394 0.146278 0.341393 0.15002 0.345648 0.147647 0.340895 0.146972 0.340895 0.146972 0.345394 0.146278 0.345456 0.145071 0.341402 0.1444399 0.345456 0.145071 0.346487 0.1431429 0.340895 0.146972 0.345456 0.145071 0.341402 0.1444399 0.343122 0.142496 0.346487 0.1431429 0.348706 0.141831 0.341402 0.1444399 0.346487 0.1431429 0.343122 0.142496 0.346136 0.141176 0.348706 0.141831 0.351917 0.141025 0.343122 0.142496 0.348706 0.141831 0.346136 0.141176 0.35032 0.140447 0.351917 0.141025 0.355875 0.140614 0.346136 0.141176 0.351917 0.141025 0.35032 0.140447 0.355389 0.1402159 0.355875 0.140614 0.360567 0.140497 0.35032 0.140447 0.355875 0.140614 0.355389 0.1402159 0.359321 0.140385 0.360567 0.140497 0.36605 0.1406289 0.359321 0.140385 0.355389 0.1402159 0.360567 0.140497 0.362431 0.140523 0.359321 0.140385 0.36605 0.1406289 0.365642 0.140669 0.362431 0.140523 0.36605 0.1406289 0.368953 0.140825 0.365642 0.140669 0.36605 0.1406289 0.361429 0.211134 0.36081 0.207728 0.355961 0.208287 0.355462 0.207275 0.355961 0.208287 0.36081 0.207728 0.357268 0.21143 0.361429 0.211134 0.355961 0.208287 0.34285 0.2123219 0.357268 0.21143 0.355961 0.208287 0.34285 0.2123219 0.355961 0.208287 0.348244 0.208151 0.355462 0.207275 0.348244 0.208151 0.355961 0.208287 0.366034 0.210512 0.366225 0.206598 0.36081 0.207728 0.359746 0.2057729 0.36081 0.207728 0.366225 0.206598 0.361429 0.211134 0.366034 0.210512 0.36081 0.207728 0.355462 0.207275 0.36081 0.207728 0.355014 0.2064 0.359746 0.2057729 0.355014 0.2064 0.36081 0.207728 0.370978 0.209588 0.372024 0.2049379 0.366225 0.206598 0.365005 0.204531 0.366225 0.206598 0.372024 0.2049379 0.366034 0.210512 0.370978 0.209588 0.366225 0.206598 0.359746 0.2057729 0.366225 0.206598 0.365005 0.204531 0.376149 0.208383 0.378011 0.202808 0.372024 0.2049379 0.376398 0.200392 0.372024 0.2049379 0.378011 0.202808 0.370978 0.209588 0.376149 0.208383 0.372024 0.2049379 0.370617 0.2027159 0.372024 0.2049379 0.376398 0.200392 0.365005 0.204531 0.372024 0.2049379 0.370617 0.2027159 0.376149 0.208383 0.381428 0.206928 0.378011 0.202808 0.383203 0.211762 0.381428 0.206928 0.376149 0.208383 0.377712 0.212763 0.376149 0.208383 0.370978 0.209588 0.377712 0.212763 0.383203 0.211762 0.376149 0.208383 0.372345 0.213587 0.370978 0.209588 0.366034 0.210512 0.372345 0.213587 0.377712 0.212763 0.370978 0.209588 0.367228 0.214214 0.366034 0.210512 0.361429 0.211134 0.367228 0.214214 0.372345 0.213587 0.366034 0.210512 0.362479 0.2146289 0.361429 0.211134 0.357268 0.21143 0.362479 0.2146289 0.367228 0.214214 0.361429 0.211134 0.362479 0.2146289 0.357268 0.21143 0.357612 0.2124879 0.34285 0.2123219 0.357612 0.2124879 0.357268 0.21143 0.358214 0.214814 0.362479 0.2146289 0.357612 0.2124879 0.34285 0.2123219 0.358214 0.214814 0.357612 0.2124879 0.384287 0.216834 0.383203 0.211762 0.377712 0.212763 0.378663 0.217344 0.377712 0.212763 0.372345 0.213587 0.378663 0.217344 0.384287 0.216834 0.377712 0.212763 0.373174 0.2177619 0.372345 0.213587 0.367228 0.214214 0.373174 0.2177619 0.378663 0.217344 0.372345 0.213587 0.367948 0.218079 0.367228 0.214214 0.362479 0.2146289 0.367948 0.218079 0.373174 0.2177619 0.367228 0.214214 0.363111 0.218286 0.362479 0.2146289 0.358214 0.214814 0.363111 0.218286 0.367948 0.218079 0.362479 0.2146289 0.363111 0.218286 0.358214 0.214814 0.358626 0.217118 0.344381 0.21703 0.358626 0.217118 0.358214 0.214814 0.34285 0.2123219 0.344381 0.21703 0.358214 0.214814 0.358782 0.218369 0.363111 0.218286 0.358626 0.217118 0.344381 0.21703 0.358782 0.218369 0.358626 0.217118 0.383527 0.222023 0.384287 0.216834 0.378663 0.217344 0.376754 0.222023 0.378663 0.217344 0.373174 0.2177619 0.376754 0.222023 0.383527 0.222023 0.378663 0.217344 0.370248 0.222023 0.373174 0.2177619 0.367948 0.218079 0.370248 0.222023 0.376754 0.222023 0.373174 0.2177619 0.364247 0.222023 0.367948 0.218079 0.363111 0.218286 0.364247 0.222023 0.370248 0.222023 0.367948 0.218079 0.364247 0.222023 0.363111 0.218286 0.358782 0.218369 0.364247 0.222023 0.358782 0.218369 0.35897 0.222023 0.344905 0.221984 0.35897 0.222023 0.358782 0.218369 0.344381 0.21703 0.344905 0.221984 0.358782 0.218369 0.362947 0.226994 0.364247 0.222023 0.35897 0.222023 0.344396 0.226947 0.358634 0.22687 0.35897 0.222023 0.362947 0.226994 0.35897 0.222023 0.358634 0.22687 0.344905 0.221984 0.344396 0.226947 0.35897 0.222023 0.378415 0.228248 0.383527 0.222023 0.376754 0.222023 0.378415 0.228248 0.384004 0.228925 0.383527 0.222023 0.372958 0.227692 0.376754 0.222023 0.370248 0.222023 0.372958 0.227692 0.378415 0.228248 0.376754 0.222023 0.367761 0.22727 0.370248 0.222023 0.364247 0.222023 0.367761 0.22727 0.372958 0.227692 0.370248 0.222023 0.362947 0.226994 0.367761 0.22727 0.364247 0.222023 0.34285 0.2123219 0.348244 0.208151 0.340359 0.208005 0.355462 0.207275 0.340359 0.208005 0.348244 0.208151 0.334048 0.213281 0.34285 0.2123219 0.340359 0.208005 0.340239 0.207849 0.340359 0.208005 0.355462 0.207275 0.340129 0.207693 0.340359 0.208005 0.340239 0.207849 0.336047 0.207723 0.340359 0.208005 0.340129 0.207693 0.336248 0.208065 0.334048 0.213281 0.340359 0.208005 0.336248 0.208065 0.340359 0.208005 0.336047 0.207723 0.342868 0.231682 0.357625 0.231512 0.358634 0.22687 0.361822 0.231777 0.358634 0.22687 0.357625 0.231512 0.344396 0.226947 0.342868 0.231682 0.358634 0.22687 0.361822 0.231777 0.362947 0.226994 0.358634 0.22687 0.348244 0.235895 0.355961 0.235758 0.357625 0.231512 0.36081 0.236318 0.357625 0.231512 0.355961 0.235758 0.340359 0.236041 0.348244 0.235895 0.357625 0.231512 0.342868 0.231682 0.340359 0.236041 0.357625 0.231512 0.361822 0.231777 0.357625 0.231512 0.36081 0.236318 0.340239 0.2361969 0.355961 0.235758 0.348244 0.235895 0.340129 0.236353 0.355961 0.235758 0.340239 0.2361969 0.339868 0.236832 0.355961 0.235758 0.340129 0.236353 0.339868 0.236832 0.355522 0.236652 0.355961 0.235758 0.359746 0.238272 0.355961 0.235758 0.355522 0.236652 0.359746 0.238272 0.36081 0.236318 0.355961 0.235758 0.340239 0.2361969 0.348244 0.235895 0.340359 0.236041 0.336248 0.235981 0.340359 0.236041 0.342868 0.231682 0.336047 0.2363229 0.340359 0.236041 0.336248 0.235981 0.340129 0.236353 0.340239 0.2361969 0.340359 0.236041 0.336047 0.2363229 0.340129 0.236353 0.340359 0.236041 0.334049 0.230758 0.342868 0.231682 0.344396 0.226947 0.332162 0.235967 0.342868 0.231682 0.334049 0.230758 0.336248 0.235981 0.342868 0.231682 0.332162 0.235967 0.334995 0.2249619 0.344396 0.226947 0.344905 0.221984 0.334049 0.230758 0.344396 0.226947 0.334995 0.2249619 0.334991 0.2190459 0.344905 0.221984 0.344381 0.21703 0.334995 0.2249619 0.344905 0.221984 0.334991 0.2190459 0.334048 0.213281 0.344381 0.21703 0.34285 0.2123219 0.334991 0.2190459 0.344381 0.21703 0.334048 0.213281 0.340551 0.206232 0.348012 0.20627 0.340871 0.206133 0.349877 0.195522 0.340871 0.206133 0.348012 0.20627 0.330272 0.203451 0.340551 0.206232 0.340871 0.206133 0.349877 0.195522 0.34194 0.2035199 0.340871 0.206133 0.335527 0.204542 0.340871 0.206133 0.34194 0.2035199 0.330272 0.203451 0.340871 0.206133 0.335527 0.204542 0.340551 0.206232 0.355014 0.2064 0.348012 0.20627 0.349877 0.195522 0.348012 0.20627 0.355014 0.2064 0.339738 0.206742 0.355462 0.207275 0.355014 0.2064 0.339787 0.206614 0.339738 0.206742 0.355014 0.2064 0.339892 0.206522 0.339787 0.206614 0.355014 0.2064 0.339991 0.2064599 0.339892 0.206522 0.355014 0.2064 0.340126 0.206392 0.339991 0.2064599 0.355014 0.2064 0.340319 0.206313 0.340126 0.206392 0.355014 0.2064 0.340551 0.206232 0.340319 0.206313 0.355014 0.2064 0.359746 0.2057729 0.349877 0.195522 0.355014 0.2064 0.340129 0.207693 0.340239 0.207849 0.355462 0.207275 0.339875 0.2072319 0.340129 0.207693 0.355462 0.207275 0.339738 0.206742 0.339875 0.2072319 0.355462 0.207275 0.336047 0.207723 0.340129 0.207693 0.339875 0.2072319 0.331727 0.207085 0.339875 0.2072319 0.339738 0.206742 0.331979 0.207714 0.339875 0.2072319 0.331727 0.207085 0.336047 0.207723 0.339875 0.2072319 0.331979 0.207714 0.335613 0.206634 0.339738 0.206742 0.339787 0.206614 0.331727 0.207085 0.339738 0.206742 0.335613 0.206634 0.330822 0.2052569 0.339787 0.206614 0.339892 0.206522 0.331521 0.206466 0.335613 0.206634 0.339787 0.206614 0.331134 0.205865 0.331521 0.206466 0.339787 0.206614 0.330822 0.2052569 0.331134 0.205865 0.339787 0.206614 0.330822 0.2052569 0.339892 0.206522 0.339991 0.2064599 0.330576 0.204648 0.339991 0.2064599 0.340126 0.206392 0.330576 0.204648 0.330822 0.2052569 0.339991 0.2064599 0.330392 0.204044 0.340126 0.206392 0.340319 0.206313 0.330392 0.204044 0.330576 0.204648 0.340126 0.206392 0.330272 0.203451 0.340319 0.206313 0.340551 0.206232 0.330272 0.203451 0.330392 0.204044 0.340319 0.206313 0.349877 0.195522 0.342727 0.200394 0.34194 0.2035199 0.335871 0.200833 0.34194 0.2035199 0.342727 0.200394 0.335527 0.204542 0.34194 0.2035199 0.335871 0.200833 0.349877 0.195522 0.343225 0.196671 0.342727 0.200394 0.335364 0.196795 0.342727 0.200394 0.343225 0.196671 0.335871 0.200833 0.342727 0.200394 0.335364 0.196795 0.349877 0.195522 0.343406 0.192715 0.343225 0.196671 0.334289 0.1926389 0.343225 0.196671 0.343406 0.192715 0.335364 0.196795 0.343225 0.196671 0.334289 0.1926389 0.347414 0.190295 0.343255 0.188977 0.343406 0.192715 0.332821 0.188458 0.343406 0.192715 0.343255 0.188977 0.349877 0.195522 0.347414 0.190295 0.343406 0.192715 0.334289 0.1926389 0.343406 0.192715 0.332821 0.188458 0.345065 0.185276 0.342769 0.185021 0.343255 0.188977 0.332821 0.188458 0.343255 0.188977 0.342769 0.185021 0.347414 0.190295 0.345065 0.185276 0.343255 0.188977 0.345065 0.185276 0.342245 0.182085 0.342769 0.185021 0.331079 0.184307 0.342769 0.185021 0.342245 0.182085 0.332821 0.188458 0.342769 0.185021 0.331079 0.184307 0.345065 0.185276 0.341554 0.178986 0.342245 0.182085 0.32914 0.180218 0.342245 0.182085 0.341554 0.178986 0.331079 0.184307 0.342245 0.182085 0.32914 0.180218 0.345065 0.185276 0.340688 0.175741 0.341554 0.178986 0.327047 0.176208 0.341554 0.178986 0.340688 0.175741 0.32914 0.180218 0.341554 0.178986 0.327047 0.176208 0.351114 0.1902599 0.340688 0.175741 0.345065 0.185276 0.327047 0.176208 0.340688 0.175741 0.324829 0.17229 0.339198 0.172493 0.324829 0.17229 0.340688 0.175741 0.343219 0.17598 0.339198 0.172493 0.340688 0.175741 0.351114 0.1902599 0.343219 0.17598 0.340688 0.175741 0.351114 0.1902599 0.345065 0.185276 0.347414 0.190295 0.359746 0.2057729 0.347414 0.190295 0.349877 0.195522 0.359746 0.2057729 0.351114 0.1902599 0.347414 0.190295 0.27819 0.135239 0.299214 0.139927 0.296597 0.137521 0.319125 0.141734 0.296597 0.137521 0.299214 0.139927 0.319125 0.141734 0.316413 0.139415 0.296597 0.137521 0.280601 0.13763 0.301863 0.1425 0.299214 0.139927 0.321723 0.144185 0.299214 0.139927 0.301863 0.1425 0.27819 0.135239 0.280601 0.13763 0.299214 0.139927 0.321723 0.144185 0.319125 0.141734 0.299214 0.139927 0.283018 0.140076 0.304528 0.145238 0.301863 0.1425 0.324212 0.14676 0.301863 0.1425 0.304528 0.145238 0.280601 0.13763 0.283018 0.140076 0.301863 0.1425 0.324212 0.14676 0.321723 0.144185 0.301863 0.1425 0.285437 0.142558 0.307194 0.148133 0.304528 0.145238 0.326584 0.149455 0.304528 0.145238 0.307194 0.148133 0.283018 0.140076 0.285437 0.142558 0.304528 0.145238 0.326584 0.149455 0.324212 0.14676 0.304528 0.145238 0.290135 0.147539 0.309847 0.151181 0.307194 0.148133 0.328815 0.152258 0.307194 0.148133 0.309847 0.151181 0.287807 0.145053 0.290135 0.147539 0.307194 0.148133 0.285437 0.142558 0.287807 0.145053 0.307194 0.148133 0.328815 0.152258 0.326584 0.149455 0.307194 0.148133 0.292426 0.150037 0.312475 0.154374 0.309847 0.151181 0.330897 0.15516 0.309847 0.151181 0.312475 0.154374 0.290135 0.147539 0.292426 0.150037 0.309847 0.151181 0.330897 0.15516 0.328815 0.152258 0.309847 0.151181 0.296907 0.155045 0.315066 0.157707 0.312475 0.154374 0.332835 0.158155 0.312475 0.154374 0.315066 0.157707 0.29469 0.152546 0.296907 0.155045 0.312475 0.154374 0.292426 0.150037 0.29469 0.152546 0.312475 0.154374 0.332835 0.158155 0.330897 0.15516 0.312475 0.154374 0.299069 0.157524 0.317609 0.161172 0.315066 0.157707 0.33463 0.161242 0.315066 0.157707 0.317609 0.161172 0.296907 0.155045 0.299069 0.157524 0.315066 0.157707 0.33463 0.161242 0.332835 0.158155 0.315066 0.157707 0.303192 0.16236 0.320092 0.164763 0.317609 0.161172 0.335445 0.163494 0.317609 0.161172 0.320092 0.164763 0.301172 0.15997 0.303192 0.16236 0.317609 0.161172 0.299069 0.157524 0.301172 0.15997 0.317609 0.161172 0.335445 0.163494 0.33463 0.161242 0.317609 0.161172 0.305137 0.164689 0.322505 0.168471 0.320092 0.164763 0.336438 0.16604 0.320092 0.164763 0.322505 0.168471 0.303192 0.16236 0.305137 0.164689 0.320092 0.164763 0.336438 0.16604 0.335445 0.163494 0.320092 0.164763 0.308803 0.169176 0.324829 0.17229 0.322505 0.168471 0.339198 0.172493 0.322505 0.168471 0.324829 0.17229 0.307007 0.1669639 0.308803 0.169176 0.322505 0.168471 0.305137 0.164689 0.307007 0.1669639 0.322505 0.168471 0.337352 0.168258 0.336438 0.16604 0.322505 0.168471 0.337512 0.168636 0.337352 0.168258 0.322505 0.168471 0.339198 0.172493 0.337512 0.168636 0.322505 0.168471 0.310527 0.171333 0.327047 0.176208 0.324829 0.17229 0.308803 0.169176 0.310527 0.171333 0.324829 0.17229 0.313765 0.1754699 0.32914 0.180218 0.327047 0.176208 0.310527 0.171333 0.313765 0.1754699 0.327047 0.176208 0.316874 0.179567 0.331079 0.184307 0.32914 0.180218 0.313765 0.1754699 0.316874 0.179567 0.32914 0.180218 0.322347 0.187194 0.332821 0.188458 0.331079 0.184307 0.319762 0.183511 0.322347 0.187194 0.331079 0.184307 0.316874 0.179567 0.319762 0.183511 0.331079 0.184307 0.324731 0.190794 0.334289 0.1926389 0.332821 0.188458 0.322347 0.187194 0.324731 0.190794 0.332821 0.188458 0.3269 0.194376 0.335364 0.196795 0.334289 0.1926389 0.324731 0.190794 0.3269 0.194376 0.334289 0.1926389 0.328653 0.1977249 0.335871 0.200833 0.335364 0.196795 0.3269 0.194376 0.328653 0.1977249 0.335364 0.196795 0.330215 0.202867 0.335527 0.204542 0.335871 0.200833 0.329774 0.200572 0.330215 0.202867 0.335871 0.200833 0.328653 0.1977249 0.329774 0.200572 0.335871 0.200833 0.330272 0.203451 0.335527 0.204542 0.330215 0.202867 0.286184 0.2066929 0.330215 0.202867 0.329774 0.200572 0.286184 0.2066929 0.330272 0.203451 0.330215 0.202867 0.286184 0.2066929 0.329774 0.200572 0.328653 0.1977249 0.286184 0.2066929 0.328653 0.1977249 0.3269 0.194376 0.281166 0.1908479 0.3269 0.194376 0.324731 0.190794 0.281166 0.1908479 0.286184 0.2066929 0.3269 0.194376 0.281166 0.1908479 0.324731 0.190794 0.322347 0.187194 0.281166 0.1908479 0.322347 0.187194 0.319762 0.183511 0.281166 0.1908479 0.319762 0.183511 0.316874 0.179567 0.276528 0.176354 0.316874 0.179567 0.313765 0.1754699 0.276528 0.176354 0.281166 0.1908479 0.316874 0.179567 0.276528 0.176354 0.313765 0.1754699 0.310527 0.171333 0.276528 0.176354 0.310527 0.171333 0.308803 0.169176 0.276528 0.176354 0.308803 0.169176 0.307007 0.1669639 0.276528 0.176354 0.307007 0.1669639 0.305137 0.164689 0.272612 0.163482 0.305137 0.164689 0.303192 0.16236 0.272612 0.163482 0.276528 0.176354 0.305137 0.164689 0.272612 0.163482 0.303192 0.16236 0.301172 0.15997 0.272612 0.163482 0.301172 0.15997 0.299069 0.157524 0.272612 0.163482 0.299069 0.157524 0.296907 0.155045 0.269741 0.1526679 0.296907 0.155045 0.29469 0.152546 0.269741 0.1526679 0.272612 0.163482 0.296907 0.155045 0.269741 0.1526679 0.29469 0.152546 0.292426 0.150037 0.269741 0.1526679 0.292426 0.150037 0.290135 0.147539 0.268093 0.143941 0.290135 0.147539 0.287807 0.145053 0.268093 0.143941 0.269741 0.1526679 0.290135 0.147539 0.268093 0.143941 0.287807 0.145053 0.285437 0.142558 0.267723 0.140268 0.285437 0.142558 0.283018 0.140076 0.267723 0.140268 0.268093 0.143941 0.285437 0.142558 0.267639 0.1370429 0.283018 0.140076 0.280601 0.13763 0.267639 0.1370429 0.267723 0.140268 0.283018 0.140076 0.267639 0.1370429 0.280601 0.13763 0.27819 0.135239 0.267842 0.134246 0.267639 0.1370429 0.27819 0.135239 0.336292 0.140258 0.316413 0.139415 0.319125 0.141734 0.333368 0.142488 0.319125 0.141734 0.321723 0.144185 0.334695 0.141238 0.336292 0.140258 0.319125 0.141734 0.333368 0.142488 0.334695 0.141238 0.319125 0.141734 0.331767 0.1459079 0.321723 0.144185 0.324212 0.14676 0.332374 0.144035 0.333368 0.142488 0.321723 0.144185 0.331767 0.1459079 0.332374 0.144035 0.321723 0.144185 0.331549 0.148147 0.324212 0.14676 0.326584 0.149455 0.331549 0.148147 0.331767 0.1459079 0.324212 0.14676 0.331744 0.15081 0.326584 0.149455 0.328815 0.152258 0.331744 0.15081 0.331549 0.148147 0.326584 0.149455 0.33233 0.153883 0.328815 0.152258 0.330897 0.15516 0.33233 0.153883 0.331744 0.15081 0.328815 0.152258 0.333295 0.157342 0.330897 0.15516 0.332835 0.158155 0.333295 0.157342 0.33233 0.153883 0.330897 0.15516 0.333295 0.157342 0.332835 0.158155 0.33463 0.161242 0.341215 0.1687059 0.33463 0.161242 0.335445 0.163494 0.338783 0.157644 0.333295 0.157342 0.33463 0.161242 0.337591 0.161729 0.338783 0.157644 0.33463 0.161242 0.341215 0.1687059 0.337591 0.161729 0.33463 0.161242 0.341215 0.1687059 0.335445 0.163494 0.336438 0.16604 0.341215 0.1687059 0.336438 0.16604 0.337352 0.168258 0.343219 0.17598 0.337352 0.168258 0.337512 0.168636 0.343219 0.17598 0.341215 0.1687059 0.337352 0.168258 0.343219 0.17598 0.337512 0.168636 0.339198 0.172493 0.338727 0.142203 0.336292 0.140258 0.334695 0.141238 0.338727 0.142203 0.341617 0.140718 0.336292 0.140258 0.338727 0.142203 0.334695 0.141238 0.333368 0.142488 0.336979 0.144291 0.333368 0.142488 0.332374 0.144035 0.336979 0.144291 0.338727 0.142203 0.333368 0.142488 0.336282 0.1469399 0.332374 0.144035 0.331767 0.1459079 0.336282 0.1469399 0.336979 0.144291 0.332374 0.144035 0.336282 0.1469399 0.331767 0.1459079 0.331549 0.148147 0.336464 0.1500869 0.331549 0.148147 0.331744 0.15081 0.336464 0.1500869 0.336282 0.1469399 0.331549 0.148147 0.337351 0.153672 0.331744 0.15081 0.33233 0.153883 0.337351 0.153672 0.336464 0.1500869 0.331744 0.15081 0.338783 0.157644 0.33233 0.153883 0.333295 0.157342 0.338783 0.157644 0.337351 0.153672 0.33233 0.153883 0.341617 0.140718 0.342821 0.13974 0.340463 0.139644 0.340058 0.139149 0.340463 0.139644 0.342821 0.13974 0.341617 0.140718 0.345555 0.139837 0.342821 0.13974 0.343314 0.139402 0.342821 0.13974 0.345555 0.139837 0.340058 0.139149 0.342821 0.13974 0.343314 0.139402 0.346136 0.141176 0.345555 0.139837 0.341617 0.140718 0.35032 0.140447 0.347833 0.139916 0.345555 0.139837 0.346666 0.13964 0.345555 0.139837 0.347833 0.139916 0.346136 0.141176 0.35032 0.140447 0.345555 0.139837 0.343314 0.139402 0.345555 0.139837 0.346666 0.13964 0.343122 0.142496 0.341617 0.140718 0.338727 0.142203 0.343122 0.142496 0.346136 0.141176 0.341617 0.140718 0.341402 0.1444399 0.338727 0.142203 0.336979 0.144291 0.341402 0.1444399 0.343122 0.142496 0.338727 0.142203 0.340895 0.146972 0.336979 0.144291 0.336282 0.1469399 0.340895 0.146972 0.341402 0.1444399 0.336979 0.144291 0.341393 0.15002 0.336282 0.1469399 0.336464 0.1500869 0.341393 0.15002 0.340895 0.146972 0.336282 0.1469399 0.342688 0.153522 0.336464 0.1500869 0.337351 0.153672 0.342688 0.153522 0.341393 0.15002 0.336464 0.1500869 0.344588 0.1574169 0.337351 0.153672 0.338783 0.157644 0.344588 0.1574169 0.342688 0.153522 0.337351 0.153672 0.337591 0.161729 0.340651 0.161967 0.338783 0.157644 0.344588 0.1574169 0.338783 0.157644 0.340651 0.161967 0.341215 0.1687059 0.340651 0.161967 0.337591 0.161729 0.343786 0.161945 0.344588 0.1574169 0.340651 0.161967 0.345257 0.168721 0.343786 0.161945 0.340651 0.161967 0.341215 0.1687059 0.345257 0.168721 0.340651 0.161967 0.35032 0.140447 0.350525 0.140017 0.347833 0.139916 0.346666 0.13964 0.347833 0.139916 0.350525 0.140017 0.35032 0.140447 0.353354 0.1401309 0.350525 0.140017 0.350113 0.139863 0.350525 0.140017 0.353354 0.1401309 0.346666 0.13964 0.350525 0.140017 0.350113 0.139863 0.35032 0.140447 0.355389 0.1402159 0.353354 0.1401309 0.353652 0.140074 0.353354 0.1401309 0.355389 0.1402159 0.350113 0.139863 0.353354 0.1401309 0.353652 0.140074 0.357278 0.140275 0.355389 0.1402159 0.359321 0.140385 0.353652 0.140074 0.355389 0.1402159 0.357278 0.140275 0.343786 0.161945 0.346963 0.161665 0.344588 0.1574169 0.349413 0.1683 0.346963 0.161665 0.343786 0.161945 0.353618 0.16745 0.35015 0.1611289 0.346963 0.161665 0.349413 0.1683 0.353618 0.16745 0.346963 0.161665 0.345257 0.168721 0.349413 0.1683 0.343786 0.161945 0.36098 0.140466 0.359321 0.140385 0.362431 0.140523 0.357278 0.140275 0.359321 0.140385 0.36098 0.140466 0.364745 0.140649 0.362431 0.140523 0.365642 0.140669 0.36098 0.140466 0.362431 0.140523 0.364745 0.140649 0.368559 0.140826 0.365642 0.140669 0.368953 0.140825 0.364745 0.140649 0.365642 0.140669 0.368559 0.140826 0.343314 0.139402 0.342712 0.139411 0.339521 0.139158 0.307214 0.137432 0.339521 0.139158 0.342712 0.139411 0.340058 0.139149 0.343314 0.139402 0.339521 0.139158 0.343314 0.139402 0.345691 0.139627 0.342712 0.139411 0.307214 0.137432 0.342712 0.139411 0.345691 0.139627 0.346666 0.13964 0.349774 0.139894 0.345691 0.139627 0.307214 0.137432 0.345691 0.139627 0.349774 0.139894 0.343314 0.139402 0.346666 0.13964 0.345691 0.139627 0.353652 0.140074 0.353444 0.14011 0.349774 0.139894 0.350113 0.139863 0.353652 0.140074 0.349774 0.139894 0.346666 0.13964 0.350113 0.139863 0.349774 0.139894 0.357278 0.140275 0.35675 0.140289 0.353444 0.14011 0.353652 0.140074 0.357278 0.140275 0.353444 0.14011 0.357278 0.140275 0.359728 0.14044 0.35675 0.140289 0.36098 0.140466 0.362407 0.140568 0.359728 0.14044 0.357278 0.140275 0.36098 0.140466 0.359728 0.14044 0.364745 0.140649 0.364816 0.140677 0.362407 0.140568 0.36098 0.140466 0.364745 0.140649 0.362407 0.140568 0.368559 0.140826 0.36895 0.140855 0.364816 0.140677 0.364745 0.140649 0.368559 0.140826 0.364816 0.140677 0.27955 0.134054 0.253855 0.129788 0.281001 0.133707 0.25202 0.130309 0.249041 0.1290799 0.253855 0.129788 0.25202 0.130309 0.253855 0.129788 0.27955 0.134054 0.305789 0.137768 0.281001 0.133707 0.294212 0.135592 0.305789 0.137768 0.27955 0.134054 0.281001 0.133707 0.305789 0.137768 0.294212 0.135592 0.307214 0.137432 0.305789 0.137768 0.307214 0.137432 0.330746 0.141438 0.100785 0.0191999 0.104487 0.01756298 0.105418 0.01844096 0.100785 0.0191999 0.105418 0.01844096 0.134935 0.04589688 0.1360819 0.0512579 0.134935 0.04589688 0.158903 0.06760597 0.100785 0.0191999 0.134935 0.04589688 0.1360819 0.0512579 0.163763 0.07559198 0.158903 0.06760597 0.178961 0.08517599 0.1360819 0.0512579 0.158903 0.06760597 0.163763 0.07559198 0.186374 0.09465497 0.178961 0.08517599 0.196161 0.09967195 0.163763 0.07559198 0.178961 0.08517599 0.186374 0.09465497 0.205442 0.109975 0.196161 0.09967195 0.211212 0.111828 0.186374 0.09465497 0.196161 0.09967195 0.205442 0.109975 0.205442 0.109975 0.211212 0.111828 0.224607 0.122168 0.221948 0.122553 0.224607 0.122168 0.225874 0.123079 0.205442 0.109975 0.224607 0.122168 0.221948 0.122553 0.224278 0.124054 0.225874 0.123079 0.227407 0.123946 0.224278 0.124054 0.221948 0.122553 0.225874 0.123079 0.224278 0.124054 0.227407 0.123946 0.22916 0.124772 0.227313 0.1254619 0.22916 0.124772 0.231253 0.125553 0.224278 0.124054 0.22916 0.124772 0.227313 0.1254619 0.231423 0.126732 0.231253 0.125553 0.233767 0.126272 0.227313 0.1254619 0.231253 0.125553 0.231423 0.126732 0.231423 0.126732 0.233767 0.126272 0.236779 0.126968 0.237037 0.127928 0.236779 0.126968 0.240449 0.127671 0.231423 0.126732 0.236779 0.126968 0.237037 0.127928 0.237037 0.127928 0.240449 0.127671 0.244586 0.1283749 0.244129 0.129126 0.244586 0.1283749 0.249041 0.1290799 0.237037 0.127928 0.244586 0.1283749 0.244129 0.129126 0.244129 0.129126 0.249041 0.1290799 0.25202 0.130309 0.248925 0.1333079 0.27519 0.139311 0.247927 0.135523 0.281667 0.140202 0.247927 0.135523 0.27519 0.139311 0.240878 0.132133 0.248925 0.1333079 0.247927 0.135523 0.278785 0.1508769 0.247927 0.135523 0.281667 0.140202 0.239805 0.134356 0.247927 0.135523 0.23949 0.1343089 0.233759 0.15535 0.23949 0.1343089 0.247927 0.135523 0.240878 0.132133 0.247927 0.135523 0.239805 0.134356 0.278459 0.151001 0.247927 0.135523 0.278785 0.1508769 0.268166 0.157464 0.242559 0.15628 0.247927 0.135523 0.233759 0.15535 0.247927 0.135523 0.242559 0.15628 0.273205 0.153654 0.268166 0.157464 0.247927 0.135523 0.278459 0.151001 0.273205 0.153654 0.247927 0.135523 0.248925 0.1333079 0.275932 0.137546 0.27519 0.139311 0.281667 0.140202 0.27519 0.139311 0.275932 0.137546 0.248925 0.1333079 0.276945 0.136027 0.275932 0.137546 0.302243 0.141184 0.275932 0.137546 0.276945 0.136027 0.30152 0.142912 0.275932 0.137546 0.302243 0.141184 0.288459 0.141133 0.275932 0.137546 0.30152 0.142912 0.281667 0.140202 0.275932 0.137546 0.288459 0.141133 0.250327 0.131515 0.278172 0.134842 0.276945 0.136027 0.303233 0.139697 0.276945 0.136027 0.278172 0.134842 0.248925 0.1333079 0.250327 0.131515 0.276945 0.136027 0.302243 0.141184 0.276945 0.136027 0.303233 0.139697 0.25202 0.130309 0.27955 0.134054 0.278172 0.134842 0.304436 0.138537 0.278172 0.134842 0.27955 0.134054 0.250327 0.131515 0.25202 0.130309 0.278172 0.134842 0.303233 0.139697 0.278172 0.134842 0.304436 0.138537 0.304436 0.138537 0.27955 0.134054 0.305789 0.137768 0.244129 0.129126 0.25202 0.130309 0.250327 0.131515 0.2423509 0.1303319 0.250327 0.131515 0.248925 0.1333079 0.244129 0.129126 0.250327 0.131515 0.2423509 0.1303319 0.2423509 0.1303319 0.248925 0.1333079 0.240878 0.132133 0.302243 0.141184 0.32783 0.144248 0.32691 0.146327 0.33603 0.14638 0.32691 0.146327 0.32783 0.144248 0.314194 0.1446239 0.302243 0.141184 0.32691 0.146327 0.331593 0.147248 0.314194 0.1446239 0.32691 0.146327 0.33603 0.14638 0.331593 0.147248 0.32691 0.146327 0.303233 0.139697 0.329146 0.142565 0.32783 0.144248 0.337422 0.144803 0.32783 0.144248 0.329146 0.142565 0.302243 0.141184 0.303233 0.139697 0.32783 0.144248 0.337422 0.144803 0.33603 0.14638 0.32783 0.144248 0.304436 0.138537 0.330746 0.141438 0.329146 0.142565 0.339049 0.1437 0.329146 0.142565 0.330746 0.141438 0.303233 0.139697 0.304436 0.138537 0.329146 0.142565 0.339049 0.1437 0.337422 0.144803 0.329146 0.142565 0.304436 0.138537 0.305789 0.137768 0.330746 0.141438 0.314194 0.1446239 0.30152 0.142912 0.302243 0.141184 0.288715 0.149456 0.30152 0.142912 0.314194 0.1446239 0.288715 0.149456 0.288459 0.141133 0.30152 0.142912 0.335931 0.148658 0.314194 0.1446239 0.331593 0.147248 0.339943 0.150564 0.314194 0.1446239 0.335931 0.148658 0.343628 0.152938 0.314194 0.1446239 0.339943 0.150564 0.344162 0.153339 0.314194 0.1446239 0.343628 0.152938 0.312242 0.151823 0.314194 0.1446239 0.344162 0.153339 0.306665 0.151265 0.314194 0.1446239 0.312242 0.151823 0.306665 0.151265 0.288715 0.149456 0.314194 0.1446239 0.288715 0.149456 0.281667 0.140202 0.288459 0.141133 0.28372 0.14959 0.278785 0.1508769 0.281667 0.140202 0.288715 0.149456 0.28372 0.14959 0.281667 0.140202 0.21748 0.125496 0.218507 0.129257 0.216064 0.127788 0.2116529 0.138921 0.216064 0.127788 0.218507 0.129257 0.216033 0.127771 0.21748 0.125496 0.216064 0.127788 0.2116529 0.138921 0.216033 0.127771 0.216064 0.127788 0.219909 0.1269879 0.218628 0.129319 0.218507 0.129257 0.2116529 0.138921 0.218507 0.129257 0.218628 0.129319 0.21748 0.125496 0.219909 0.1269879 0.218507 0.129257 0.22311 0.128407 0.221759 0.130661 0.218628 0.129319 0.210686 0.151289 0.218628 0.129319 0.221759 0.130661 0.219909 0.1269879 0.22311 0.128407 0.218628 0.129319 0.210686 0.151289 0.2116529 0.138921 0.218628 0.129319 0.22311 0.128407 0.22193 0.130721 0.221759 0.130661 0.210686 0.151289 0.221759 0.130661 0.22193 0.130721 0.227523 0.129708 0.226256 0.131954 0.22193 0.130721 0.214357 0.1524209 0.22193 0.130721 0.226256 0.131954 0.22311 0.128407 0.227523 0.129708 0.22193 0.130721 0.210686 0.151289 0.22193 0.130721 0.214357 0.1524209 0.227523 0.129708 0.232055 0.133116 0.226256 0.131954 0.219263 0.153441 0.226256 0.131954 0.232055 0.133116 0.214357 0.1524209 0.226256 0.131954 0.219263 0.153441 0.23949 0.1343089 0.232055 0.133116 0.232313 0.133162 0.233514 0.13093 0.232313 0.133162 0.232055 0.133116 0.225764 0.154398 0.232055 0.133116 0.23949 0.1343089 0.227523 0.129708 0.233514 0.13093 0.232055 0.133116 0.219263 0.153441 0.232055 0.133116 0.225764 0.154398 0.233514 0.13093 0.23949 0.1343089 0.232313 0.133162 0.240878 0.132133 0.239805 0.134356 0.23949 0.1343089 0.233514 0.13093 0.240878 0.132133 0.23949 0.1343089 0.225764 0.154398 0.23949 0.1343089 0.233759 0.15535 0.235109 0.129126 0.240878 0.132133 0.233514 0.13093 0.235109 0.129126 0.2423509 0.1303319 0.240878 0.132133 0.229287 0.127909 0.233514 0.13093 0.227523 0.129708 0.229287 0.127909 0.235109 0.129126 0.233514 0.13093 0.22501 0.126615 0.227523 0.129708 0.22311 0.128407 0.22501 0.126615 0.229287 0.127909 0.227523 0.129708 0.2218829 0.125194 0.22311 0.128407 0.219909 0.1269879 0.2218829 0.125194 0.22501 0.126615 0.22311 0.128407 0.219499 0.123692 0.219909 0.1269879 0.21748 0.125496 0.2218829 0.125194 0.219909 0.1269879 0.219499 0.123692 0.200554 0.113164 0.219499 0.123692 0.21748 0.125496 0.20197 0.117821 0.21748 0.125496 0.216033 0.127771 0.20197 0.117821 0.200554 0.113164 0.21748 0.125496 0.221948 0.122553 0.2218829 0.125194 0.219499 0.123692 0.202768 0.111211 0.221948 0.122553 0.219499 0.123692 0.202768 0.111211 0.219499 0.123692 0.200554 0.113164 0.237037 0.127928 0.2423509 0.1303319 0.235109 0.129126 0.237037 0.127928 0.244129 0.129126 0.2423509 0.1303319 0.231423 0.126732 0.235109 0.129126 0.229287 0.127909 0.231423 0.126732 0.237037 0.127928 0.235109 0.129126 0.227313 0.1254619 0.229287 0.127909 0.22501 0.126615 0.227313 0.1254619 0.231423 0.126732 0.229287 0.127909 0.224278 0.124054 0.22501 0.126615 0.2218829 0.125194 0.224278 0.124054 0.227313 0.1254619 0.22501 0.126615 0.224278 0.124054 0.2218829 0.125194 0.221948 0.122553 0.205442 0.109975 0.221948 0.122553 0.202768 0.111211 0.20197 0.117821 0.216033 0.127771 0.198982 0.115652 0.2116529 0.138921 0.198982 0.115652 0.216033 0.127771 0.186137 0.106128 0.180972 0.098149 0.200554 0.113164 0.202768 0.111211 0.200554 0.113164 0.180972 0.098149 0.198982 0.115652 0.186137 0.106128 0.200554 0.113164 0.20197 0.117821 0.198982 0.115652 0.200554 0.113164 0.1680099 0.09219497 0.157725 0.07946997 0.180972 0.098149 0.1834239 0.09601098 0.180972 0.098149 0.157725 0.07946997 0.1791869 0.100849 0.1680099 0.09219497 0.180972 0.098149 0.186137 0.106128 0.1791869 0.100849 0.180972 0.098149 0.1834239 0.09601098 0.202768 0.111211 0.180972 0.098149 0.146833 0.07531797 0.129233 0.055637 0.157725 0.07946997 0.160472 0.07710099 0.157725 0.07946997 0.129233 0.055637 0.155676 0.08243399 0.146833 0.07531797 0.157725 0.07946997 0.1680099 0.09219497 0.155676 0.08243399 0.157725 0.07946997 0.160472 0.07710099 0.1834239 0.09601098 0.157725 0.07946997 0.09022498 0.02814197 0.09287297 0.02425789 0.129233 0.055637 0.132356 0.05296891 0.129233 0.055637 0.09287297 0.02425789 0.121483 0.05447489 0.09022498 0.02814197 0.129233 0.055637 0.126841 0.05892795 0.121483 0.05447489 0.129233 0.055637 0.146833 0.07531797 0.126841 0.05892795 0.129233 0.055637 0.132356 0.05296891 0.160472 0.07710099 0.129233 0.055637 0.09091097 0.02253198 0.09287297 0.02425789 0.09022498 0.02814197 0.09648895 0.02119195 0.132356 0.05296891 0.09287297 0.02425789 0.09091097 0.02253198 0.09648895 0.02119195 0.09287297 0.02425789 0.126841 0.05892795 0.09022498 0.02814197 0.121483 0.05447489 0.085581 0.03793191 0.09022498 0.02814197 0.126841 0.05892795 0.08922696 0.02729195 0.09022498 0.02814197 0.085581 0.03793191 0.09091097 0.02253198 0.09022498 0.02814197 0.08922696 0.02729195 0.155676 0.08243399 0.126841 0.05892795 0.146833 0.07531797 0.115217 0.08621895 0.126841 0.05892795 0.155676 0.08243399 0.114956 0.08188599 0.126841 0.05892795 0.115217 0.08621895 0.1123329 0.07528597 0.085581 0.03793191 0.126841 0.05892795 0.113995 0.07779699 0.1123329 0.07528597 0.126841 0.05892795 0.114956 0.08188599 0.113995 0.07779699 0.126841 0.05892795 0.1791869 0.100849 0.155676 0.08243399 0.1680099 0.09219497 0.171461 0.119771 0.155676 0.08243399 0.1791869 0.100849 0.115217 0.08621895 0.155676 0.08243399 0.143691 0.112066 0.171461 0.119771 0.143691 0.112066 0.155676 0.08243399 0.198982 0.115652 0.1791869 0.100849 0.186137 0.106128 0.171461 0.119771 0.1791869 0.100849 0.198982 0.115652 0.189772 0.139926 0.171461 0.119771 0.198982 0.115652 0.189772 0.139926 0.198982 0.115652 0.2116529 0.138921 0.205442 0.109975 0.202768 0.111211 0.1834239 0.09601098 0.186374 0.09465497 0.1834239 0.09601098 0.160472 0.07710099 0.186374 0.09465497 0.205442 0.109975 0.1834239 0.09601098 0.163763 0.07559198 0.160472 0.07710099 0.132356 0.05296891 0.163763 0.07559198 0.186374 0.09465497 0.160472 0.07710099 0.1360819 0.0512579 0.132356 0.05296891 0.09648895 0.02119195 0.1360819 0.0512579 0.163763 0.07559198 0.132356 0.05296891 0.100785 0.0191999 0.1360819 0.0512579 0.09648895 0.02119195 0.09455597 0.01944392 0.100785 0.0191999 0.09648895 0.02119195 0.09091097 0.02253198 0.09455597 0.01944392 0.09648895 0.02119195 0.09455597 0.01944392 0.09888899 0.01744395 0.100785 0.0191999 0.128587 0.269892 0.1094869 0.275187 0.111806 0.242473 0.148485 0.242624 0.111806 0.242473 0.1094869 0.275187 0.125551 0.238029 0.128587 0.269892 0.111806 0.242473 0.112381 0.23609 0.125551 0.238029 0.111806 0.242473 0.149217 0.234827 0.112381 0.23609 0.111806 0.242473 0.149217 0.234827 0.111806 0.242473 0.148485 0.242624 0.134644 0.301308 0.110109 0.308641 0.1094869 0.275187 0.148485 0.242624 0.1094869 0.275187 0.110109 0.308641 0.128587 0.269892 0.134644 0.301308 0.1094869 0.275187 0.134644 0.301308 0.113794 0.34244 0.110109 0.308641 0.148485 0.242624 0.110109 0.308641 0.113794 0.34244 0.14369 0.331978 0.114808 0.350214 0.113794 0.34244 0.136026 0.342987 0.113794 0.34244 0.114808 0.350214 0.134644 0.301308 0.14369 0.331978 0.113794 0.34244 0.136026 0.342987 0.148485 0.242624 0.113794 0.34244 0.155676 0.361612 0.1152099 0.356755 0.114808 0.350214 0.134587 0.352251 0.114808 0.350214 0.1152099 0.356755 0.14369 0.331978 0.155676 0.361612 0.114808 0.350214 0.134587 0.352251 0.136026 0.342987 0.114808 0.350214 0.155676 0.361612 0.115217 0.357827 0.1152099 0.356755 0.134587 0.352251 0.1152099 0.356755 0.115217 0.357827 0.146834 0.368728 0.126843 0.385116 0.115217 0.357827 0.114955 0.362165 0.115217 0.357827 0.126843 0.385116 0.155676 0.361612 0.146834 0.368728 0.115217 0.357827 0.13279 0.359973 0.115217 0.357827 0.114955 0.362165 0.13279 0.359973 0.134587 0.352251 0.115217 0.357827 0.1292099 0.388429 0.126843 0.385116 0.146834 0.368728 0.113994 0.366251 0.114955 0.362165 0.126843 0.385116 0.1123329 0.36876 0.113994 0.366251 0.126843 0.385116 0.09761798 0.381632 0.1123329 0.36876 0.126843 0.385116 0.08118599 0.396202 0.09761798 0.381632 0.126843 0.385116 0.08557999 0.406112 0.08118599 0.396202 0.126843 0.385116 0.09022498 0.415903 0.08557999 0.406112 0.126843 0.385116 0.09287697 0.419786 0.09022498 0.415903 0.126843 0.385116 0.1292099 0.388429 0.09287697 0.419786 0.126843 0.385116 0.1292099 0.388429 0.146834 0.368728 0.155676 0.361612 0.179188 0.343197 0.155676 0.361612 0.14369 0.331978 0.157709 0.364589 0.155676 0.361612 0.179188 0.343197 0.157709 0.364589 0.1292099 0.388429 0.155676 0.361612 0.1650789 0.304856 0.14369 0.331978 0.134644 0.301308 0.171461 0.324274 0.179188 0.343197 0.14369 0.331978 0.1650789 0.304856 0.171461 0.324274 0.14369 0.331978 0.1489779 0.286467 0.134644 0.301308 0.128587 0.269892 0.160301 0.285223 0.1650789 0.304856 0.134644 0.301308 0.151162 0.28698 0.160301 0.285223 0.134644 0.301308 0.150102 0.286945 0.151162 0.28698 0.134644 0.301308 0.1489779 0.286467 0.150102 0.286945 0.134644 0.301308 0.139273 0.267608 0.128587 0.269892 0.125551 0.238029 0.146547 0.284157 0.1489779 0.286467 0.128587 0.269892 0.144014 0.280131 0.146547 0.284157 0.128587 0.269892 0.141519 0.274508 0.144014 0.280131 0.128587 0.269892 0.139273 0.267608 0.141519 0.274508 0.128587 0.269892 0.11238 0.2079499 0.125551 0.206015 0.125551 0.238029 0.133935 0.222016 0.125551 0.238029 0.125551 0.206015 0.112716 0.214861 0.11238 0.2079499 0.125551 0.238029 0.112825 0.222015 0.112716 0.214861 0.125551 0.238029 0.112716 0.229175 0.112825 0.222015 0.125551 0.238029 0.112381 0.23609 0.112716 0.229175 0.125551 0.238029 0.137383 0.259436 0.139273 0.267608 0.125551 0.238029 0.134809 0.241041 0.137383 0.259436 0.125551 0.238029 0.133935 0.222016 0.134809 0.241041 0.125551 0.238029 0.111806 0.201573 0.128587 0.174152 0.125551 0.206015 0.134807 0.203021 0.125551 0.206015 0.128587 0.174152 0.11238 0.2079499 0.111806 0.201573 0.125551 0.206015 0.134807 0.203021 0.133935 0.222016 0.125551 0.206015 0.110109 0.135405 0.134645 0.142737 0.128587 0.174152 0.141531 0.169506 0.128587 0.174152 0.134645 0.142737 0.1094869 0.168859 0.110109 0.135405 0.128587 0.174152 0.111806 0.201573 0.1094869 0.168859 0.128587 0.174152 0.137383 0.18461 0.134807 0.203021 0.128587 0.174152 0.139275 0.176431 0.137383 0.18461 0.128587 0.174152 0.141531 0.169506 0.139275 0.176431 0.128587 0.174152 0.113794 0.101606 0.143691 0.112066 0.134645 0.142737 0.1650789 0.139189 0.134645 0.142737 0.143691 0.112066 0.110109 0.135405 0.113794 0.101606 0.134645 0.142737 0.144039 0.163869 0.141531 0.169506 0.134645 0.142737 0.146577 0.159852 0.144039 0.163869 0.134645 0.142737 0.148998 0.157567 0.146577 0.159852 0.134645 0.142737 0.1501139 0.157096 0.148998 0.157567 0.134645 0.142737 0.151162 0.157066 0.1501139 0.157096 0.134645 0.142737 0.160301 0.158822 0.151162 0.157066 0.134645 0.142737 0.1650789 0.139189 0.160301 0.158822 0.134645 0.142737 0.1152099 0.08729797 0.115217 0.08621895 0.143691 0.112066 0.114807 0.09383797 0.1152099 0.08729797 0.143691 0.112066 0.113794 0.101606 0.114807 0.09383797 0.143691 0.112066 0.171461 0.119771 0.1650789 0.139189 0.143691 0.112066 0.13279 0.08407199 0.115217 0.08621895 0.1152099 0.08729797 0.13279 0.08407199 0.114956 0.08188599 0.115217 0.08621895 0.134587 0.09179395 0.1152099 0.08729797 0.114807 0.09383797 0.134587 0.09179395 0.13279 0.08407199 0.1152099 0.08729797 0.134587 0.09179395 0.114807 0.09383797 0.113794 0.101606 0.136026 0.101058 0.113794 0.101606 0.110109 0.135405 0.134587 0.09179395 0.113794 0.101606 0.136026 0.101058 0.136026 0.101058 0.110109 0.135405 0.1094869 0.168859 0.136026 0.101058 0.1094869 0.168859 0.111806 0.201573 0.148485 0.201422 0.111806 0.201573 0.11238 0.2079499 0.136026 0.101058 0.111806 0.201573 0.148485 0.201422 0.149217 0.209218 0.11238 0.2079499 0.112716 0.214861 0.149217 0.209218 0.148485 0.201422 0.11238 0.2079499 0.149591 0.21768 0.112716 0.214861 0.112825 0.222015 0.149591 0.21768 0.149217 0.209218 0.112716 0.214861 0.149591 0.226365 0.112825 0.222015 0.112716 0.229175 0.149591 0.226365 0.149591 0.21768 0.112825 0.222015 0.149217 0.234827 0.112716 0.229175 0.112381 0.23609 0.149217 0.234827 0.149591 0.226365 0.112716 0.229175 0.130711 0.365752 0.114955 0.362165 0.113994 0.366251 0.130711 0.365752 0.13279 0.359973 0.114955 0.362165 0.130711 0.365752 0.113994 0.366251 0.1123329 0.36876 0.128442 0.369252 0.1123329 0.36876 0.09761798 0.381632 0.130711 0.365752 0.1123329 0.36876 0.128442 0.369252 0.128442 0.369252 0.09761798 0.381632 0.08118599 0.396202 0.08029198 0.396954 0.08118599 0.396202 0.08557999 0.406112 0.08029198 0.396954 0.09982496 0.396975 0.08118599 0.396202 0.128442 0.369252 0.08118599 0.396202 0.09982496 0.396975 0.083682 0.407678 0.08557999 0.406112 0.09022498 0.415903 0.08029198 0.396954 0.08557999 0.406112 0.07938295 0.397628 0.083682 0.407678 0.07938295 0.397628 0.08557999 0.406112 0.08922499 0.416758 0.083682 0.407678 0.09022498 0.415903 0.09287697 0.419786 0.08922499 0.416758 0.09022498 0.415903 0.186137 0.337918 0.179188 0.343197 0.171461 0.324274 0.180965 0.345903 0.179188 0.343197 0.186137 0.337918 0.180965 0.345903 0.157709 0.364589 0.179188 0.343197 0.189772 0.304118 0.171461 0.324274 0.1650789 0.304856 0.198982 0.328394 0.186137 0.337918 0.171461 0.324274 0.189772 0.304118 0.198982 0.328394 0.171461 0.324274 0.173123 0.282237 0.1650789 0.304856 0.160301 0.285223 0.173123 0.282237 0.189772 0.304118 0.1650789 0.304856 0.162071 0.283495 0.160301 0.285223 0.151162 0.28698 0.172246 0.281266 0.173123 0.282237 0.160301 0.285223 0.162071 0.283495 0.172246 0.281266 0.160301 0.285223 0.151011 0.285501 0.151162 0.28698 0.150102 0.286945 0.162071 0.283495 0.151162 0.28698 0.151011 0.285501 0.148974 0.285 0.150102 0.286945 0.1489779 0.286467 0.148974 0.285 0.151011 0.285501 0.150102 0.286945 0.146685 0.282783 0.1489779 0.286467 0.146547 0.284157 0.146685 0.282783 0.148974 0.285 0.1489779 0.286467 0.144279 0.278859 0.146547 0.284157 0.144014 0.280131 0.144279 0.278859 0.146685 0.282783 0.146547 0.284157 0.141915 0.273378 0.144014 0.280131 0.141519 0.274508 0.141915 0.273378 0.144279 0.278859 0.144014 0.280131 0.139778 0.266611 0.141519 0.274508 0.139273 0.267608 0.139778 0.266611 0.141915 0.273378 0.141519 0.274508 0.138014 0.258775 0.139273 0.267608 0.137383 0.259436 0.138014 0.258775 0.139778 0.266611 0.139273 0.267608 0.138014 0.258775 0.137383 0.259436 0.134809 0.241041 0.1354539 0.240661 0.134809 0.241041 0.133935 0.222016 0.1354539 0.240661 0.138014 0.258775 0.134809 0.241041 0.135453 0.2034 0.133935 0.222016 0.134807 0.203021 0.134596 0.222034 0.1354539 0.240661 0.133935 0.222016 0.135453 0.2034 0.134596 0.222034 0.133935 0.222016 0.135453 0.2034 0.134807 0.203021 0.137383 0.18461 0.138014 0.185271 0.137383 0.18461 0.139275 0.176431 0.138014 0.185271 0.135453 0.2034 0.137383 0.18461 0.139777 0.177438 0.139275 0.176431 0.141531 0.169506 0.139777 0.177438 0.138014 0.185271 0.139275 0.176431 0.141914 0.1706719 0.141531 0.169506 0.144039 0.163869 0.141914 0.1706719 0.139777 0.177438 0.141531 0.169506 0.144277 0.16519 0.144039 0.163869 0.146577 0.159852 0.144277 0.16519 0.141914 0.1706719 0.144039 0.163869 0.146684 0.161265 0.146577 0.159852 0.148998 0.157567 0.146684 0.161265 0.144277 0.16519 0.146577 0.159852 0.148972 0.159047 0.148998 0.157567 0.1501139 0.157096 0.148972 0.159047 0.146684 0.161265 0.148998 0.157567 0.148972 0.159047 0.1501139 0.157096 0.151162 0.157066 0.151011 0.158544 0.151162 0.157066 0.160301 0.158822 0.151011 0.158544 0.148972 0.159047 0.151162 0.157066 0.173123 0.161809 0.160301 0.158822 0.1650789 0.139189 0.162071 0.1605499 0.160301 0.158822 0.173123 0.161809 0.162071 0.1605499 0.151011 0.158544 0.160301 0.158822 0.189772 0.139926 0.1650789 0.139189 0.171461 0.119771 0.1832219 0.164766 0.1650789 0.139189 0.189772 0.139926 0.173123 0.161809 0.1650789 0.139189 0.1832219 0.164766 0.180965 0.345903 0.186137 0.337918 0.198982 0.328394 0.216033 0.316274 0.198982 0.328394 0.189772 0.304118 0.200549 0.330885 0.198982 0.328394 0.216033 0.316274 0.200549 0.330885 0.180965 0.345903 0.198982 0.328394 0.173123 0.282237 0.1832219 0.27928 0.189772 0.304118 0.207732 0.293547 0.189772 0.304118 0.1832219 0.27928 0.216064 0.316258 0.216033 0.316274 0.189772 0.304118 0.21161 0.305008 0.216064 0.316258 0.189772 0.304118 0.207732 0.293547 0.21161 0.305008 0.189772 0.304118 0.181622 0.278741 0.1832219 0.27928 0.173123 0.282237 0.190393 0.276717 0.207732 0.293547 0.1832219 0.27928 0.1902649 0.275836 0.190393 0.276717 0.1832219 0.27928 0.181622 0.278741 0.1902649 0.275836 0.1832219 0.27928 0.172246 0.281266 0.181622 0.278741 0.173123 0.282237 0.217481 0.31855 0.216033 0.316274 0.216064 0.316258 0.200549 0.330885 0.216033 0.316274 0.217481 0.31855 0.2184669 0.314809 0.216064 0.316258 0.21161 0.305008 0.217481 0.31855 0.216064 0.316258 0.2184669 0.314809 0.210686 0.292757 0.21161 0.305008 0.207732 0.293547 0.218626 0.314727 0.21161 0.305008 0.210686 0.292757 0.2184669 0.314809 0.21161 0.305008 0.218626 0.314727 0.192595 0.272974 0.201734 0.27011 0.207732 0.293547 0.204849 0.269773 0.207732 0.293547 0.201734 0.27011 0.1917 0.275447 0.192595 0.272974 0.207732 0.293547 0.1911 0.276232 0.1917 0.275447 0.207732 0.293547 0.190393 0.276717 0.1911 0.276232 0.207732 0.293547 0.210686 0.292757 0.207732 0.293547 0.204849 0.269773 0.1931329 0.252923 0.198118 0.246186 0.201734 0.27011 0.201286 0.246078 0.201734 0.27011 0.198118 0.246186 0.193354 0.25928 0.1931329 0.252923 0.201734 0.27011 0.1933709 0.264744 0.193354 0.25928 0.201734 0.27011 0.1931329 0.269352 0.1933709 0.264744 0.201734 0.27011 0.192595 0.272974 0.1931329 0.269352 0.201734 0.27011 0.204849 0.269773 0.201734 0.27011 0.201286 0.246078 0.192332 0.222017 0.19691 0.222018 0.198118 0.246186 0.200083 0.222023 0.198118 0.246186 0.19691 0.222018 0.1924369 0.232707 0.192332 0.222017 0.198118 0.246186 0.192727 0.243172 0.1924369 0.232707 0.198118 0.246186 0.1931329 0.252923 0.192727 0.243172 0.198118 0.246186 0.201286 0.246078 0.198118 0.246186 0.200083 0.222023 0.1924369 0.211313 0.19691 0.221523 0.19691 0.222018 0.200083 0.222023 0.19691 0.222018 0.19691 0.221523 0.192332 0.222017 0.1924369 0.211313 0.19691 0.222018 0.1924369 0.211313 0.196912 0.221029 0.19691 0.221523 0.200083 0.222023 0.19691 0.221523 0.196912 0.221029 0.192727 0.2008669 0.198194 0.197114 0.196912 0.221029 0.201286 0.197968 0.196912 0.221029 0.198194 0.197114 0.1924369 0.211313 0.192727 0.2008669 0.196912 0.221029 0.200083 0.222023 0.196912 0.221029 0.201286 0.197968 0.193139 0.174745 0.201834 0.1734459 0.198194 0.197114 0.204849 0.174273 0.198194 0.197114 0.201834 0.1734459 0.193372 0.179381 0.193139 0.174745 0.198194 0.197114 0.1933529 0.184853 0.193372 0.179381 0.198194 0.197114 0.1931329 0.191123 0.1933529 0.184853 0.198194 0.197114 0.192727 0.2008669 0.1931329 0.191123 0.198194 0.197114 0.201286 0.197968 0.198194 0.197114 0.204849 0.174273 0.190393 0.167329 0.207806 0.15026 0.201834 0.1734459 0.210686 0.151289 0.201834 0.1734459 0.207806 0.15026 0.1910949 0.1677989 0.190393 0.167329 0.201834 0.1734459 0.191694 0.168581 0.1910949 0.1677989 0.201834 0.1734459 0.192193 0.169679 0.191694 0.168581 0.201834 0.1734459 0.192597 0.1710889 0.192193 0.169679 0.201834 0.1734459 0.193139 0.174745 0.192597 0.1710889 0.201834 0.1734459 0.204849 0.174273 0.201834 0.1734459 0.210686 0.151289 0.189772 0.139926 0.2116529 0.138921 0.207806 0.15026 0.210686 0.151289 0.207806 0.15026 0.2116529 0.138921 0.1832219 0.164766 0.189772 0.139926 0.207806 0.15026 0.190393 0.167329 0.1832219 0.164766 0.207806 0.15026 0.181622 0.165302 0.1832219 0.164766 0.190393 0.167329 0.181622 0.165302 0.173123 0.161809 0.1832219 0.164766 0.1902649 0.168208 0.190393 0.167329 0.1910949 0.1677989 0.1902649 0.168208 0.181622 0.165302 0.190393 0.167329 0.191488 0.169333 0.1910949 0.1677989 0.191694 0.168581 0.191488 0.169333 0.1902649 0.168208 0.1910949 0.1677989 0.191488 0.169333 0.191694 0.168581 0.192193 0.169679 0.192381 0.171692 0.192193 0.169679 0.192597 0.1710889 0.192381 0.171692 0.191488 0.169333 0.192193 0.169679 0.192939 0.17524 0.192597 0.1710889 0.193139 0.174745 0.192939 0.17524 0.192381 0.171692 0.192597 0.1710889 0.193192 0.179843 0.193139 0.174745 0.193372 0.179381 0.193192 0.179843 0.192939 0.17524 0.193139 0.174745 0.19319 0.1853049 0.193372 0.179381 0.1933529 0.184853 0.19319 0.1853049 0.193192 0.179843 0.193372 0.179381 0.192984 0.1914809 0.1933529 0.184853 0.1931329 0.191123 0.192984 0.1914809 0.19319 0.1853049 0.1933529 0.184853 0.192984 0.1914809 0.1931329 0.191123 0.192727 0.2008669 0.192522 0.203381 0.192727 0.2008669 0.1924369 0.211313 0.192522 0.203381 0.192984 0.1914809 0.192727 0.2008669 0.1922529 0.215773 0.1924369 0.211313 0.192332 0.222017 0.1922529 0.215773 0.192522 0.203381 0.1924369 0.211313 0.1922529 0.228244 0.192332 0.222017 0.1924369 0.232707 0.1922529 0.228244 0.1922529 0.215773 0.192332 0.222017 0.192522 0.2406589 0.1924369 0.232707 0.192727 0.243172 0.192522 0.2406589 0.1922529 0.228244 0.1924369 0.232707 0.192522 0.2406589 0.192727 0.243172 0.1931329 0.252923 0.192984 0.252564 0.1931329 0.252923 0.193354 0.25928 0.192984 0.252564 0.192522 0.2406589 0.1931329 0.252923 0.19319 0.25874 0.193354 0.25928 0.1933709 0.264744 0.19319 0.25874 0.192984 0.252564 0.193354 0.25928 0.193192 0.264201 0.1933709 0.264744 0.1931329 0.269352 0.193192 0.264201 0.19319 0.25874 0.1933709 0.264744 0.192938 0.268805 0.1931329 0.269352 0.192595 0.272974 0.192938 0.268805 0.193192 0.264201 0.1931329 0.269352 0.192381 0.272352 0.192595 0.272974 0.1917 0.275447 0.192381 0.272352 0.192938 0.268805 0.192595 0.272974 0.191487 0.274711 0.1917 0.275447 0.1911 0.276232 0.191487 0.274711 0.192381 0.272352 0.1917 0.275447 0.191487 0.274711 0.1911 0.276232 0.190393 0.276717 0.1902649 0.275836 0.191487 0.274711 0.190393 0.276717 0.172246 0.162779 0.162071 0.1605499 0.173123 0.161809 0.181622 0.165302 0.172246 0.162779 0.173123 0.161809 0.1123329 0.07528597 0.08118599 0.04784291 0.085581 0.03793191 0.08029597 0.0470969 0.085581 0.03793191 0.08118599 0.04784291 0.07937699 0.046422 0.085581 0.03793191 0.08029597 0.0470969 0.08368098 0.03637492 0.085581 0.03793191 0.07937699 0.046422 0.08823496 0.02644091 0.085581 0.03793191 0.08368098 0.03637492 0.08922696 0.02729195 0.085581 0.03793191 0.08823496 0.02644091 0.1123329 0.07528597 0.09761697 0.06241291 0.08118599 0.04784291 0.09982496 0.04707098 0.08118599 0.04784291 0.09761697 0.06241291 0.09877097 0.04611599 0.08118599 0.04784291 0.09982496 0.04707098 0.08029597 0.0470969 0.08118599 0.04784291 0.09877097 0.04611599 0.09982496 0.04707098 0.09761697 0.06241291 0.1123329 0.07528597 0.128442 0.07479399 0.1123329 0.07528597 0.113995 0.07779699 0.09982496 0.04707098 0.1123329 0.07528597 0.128442 0.07479399 0.130711 0.07829397 0.113995 0.07779699 0.114956 0.08188599 0.130711 0.07829397 0.128442 0.07479399 0.113995 0.07779699 0.13279 0.08407199 0.130711 0.07829397 0.114956 0.08188599 0.148485 0.201422 0.148485 0.242624 0.136026 0.342987 0.149217 0.209218 0.148485 0.242624 0.148485 0.201422 0.149217 0.234827 0.148485 0.242624 0.149217 0.209218 0.136026 0.101058 0.148485 0.201422 0.136026 0.342987 0.134587 0.352251 0.136026 0.101058 0.136026 0.342987 0.149217 0.234827 0.149217 0.209218 0.149591 0.21768 0.149217 0.234827 0.149591 0.21768 0.149591 0.226365 0.134587 0.352251 0.134587 0.09179395 0.136026 0.101058 0.128442 0.369252 0.128442 0.07479399 0.130711 0.07829397 0.09982496 0.396975 0.09982496 0.04707098 0.128442 0.07479399 0.128442 0.369252 0.09982496 0.396975 0.128442 0.07479399 0.130711 0.365752 0.130711 0.07829397 0.13279 0.08407199 0.130711 0.365752 0.128442 0.369252 0.130711 0.07829397 0.13279 0.359973 0.13279 0.08407199 0.134587 0.09179395 0.130711 0.365752 0.13279 0.08407199 0.13279 0.359973 0.13279 0.359973 0.134587 0.09179395 0.134587 0.352251 0.09877097 0.397929 0.09982496 0.04707098 0.09982496 0.396975 0.09877097 0.04611599 0.09982496 0.04707098 0.09877097 0.397929 0.08029198 0.396954 0.09877097 0.397929 0.09982496 0.396975 0.09877097 0.04611599 0.09877097 0.397929 0.09770798 0.398773 0.07886099 0.397977 0.09770798 0.398773 0.09877097 0.397929 0.07912296 0.397805 0.07886099 0.397977 0.09877097 0.397929 0.07938295 0.397628 0.07912296 0.397805 0.09877097 0.397929 0.08029198 0.396954 0.07938295 0.397628 0.09877097 0.397929 0.09770798 0.04527288 0.09770798 0.398773 0.09406197 0.400773 0.07060796 0.400526 0.09406197 0.400773 0.09770798 0.398773 0.09877097 0.04611599 0.09770798 0.398773 0.09770798 0.04527288 0.07886099 0.397977 0.07060796 0.400526 0.09770798 0.398773 0.090406 0.04260092 0.09406197 0.400773 0.09036397 0.401445 0.07060796 0.400526 0.09036397 0.401445 0.09406197 0.400773 0.09408497 0.04327899 0.09406197 0.400773 0.090406 0.04260092 0.09770798 0.04527288 0.09406197 0.400773 0.09408497 0.04327899 0.08665698 0.04330599 0.09036397 0.401445 0.08659797 0.400717 0.06584495 0.400052 0.08659797 0.400717 0.09036397 0.401445 0.090406 0.04260092 0.09036397 0.401445 0.08665698 0.04330599 0.07060796 0.400526 0.06584495 0.400052 0.09036397 0.401445 0.08286798 0.045448 0.08659797 0.400717 0.08279597 0.398542 0.06069391 0.398303 0.08279597 0.398542 0.08659797 0.400717 0.08665698 0.04330599 0.08659797 0.400717 0.08286798 0.045448 0.06584495 0.400052 0.06069391 0.398303 0.08659797 0.400717 0.07909995 0.0490809 0.08279597 0.398542 0.07902097 0.394871 0.05529391 0.39522 0.07902097 0.394871 0.08279597 0.398542 0.08286798 0.045448 0.08279597 0.398542 0.07909995 0.0490809 0.06069391 0.398303 0.05529391 0.39522 0.08279597 0.398542 0.07536399 0.0542519 0.07902097 0.394871 0.07528096 0.389661 0.049649 0.390746 0.07528096 0.389661 0.07902097 0.394871 0.07909995 0.0490809 0.07902097 0.394871 0.07536399 0.0542519 0.05529391 0.39522 0.049649 0.390746 0.07902097 0.394871 0.07173401 0.0609219 0.07528096 0.389661 0.07165497 0.38296 0.04396498 0.384903 0.07165497 0.38296 0.07528096 0.389661 0.07536399 0.0542519 0.07528096 0.389661 0.07173401 0.0609219 0.049649 0.390746 0.04396498 0.384903 0.07528096 0.389661 0.068219 0.06915599 0.07165497 0.38296 0.06814897 0.374704 0.03828191 0.377728 0.06814897 0.374704 0.07165497 0.38296 0.07173401 0.0609219 0.07165497 0.38296 0.068219 0.06915599 0.04396498 0.384903 0.03828191 0.377728 0.07165497 0.38296 0.06486296 0.07895195 0.06814897 0.374704 0.06480497 0.364908 0.03270792 0.369144 0.06480497 0.364908 0.06814897 0.374704 0.068219 0.06915599 0.06814897 0.374704 0.06486296 0.07895195 0.03828191 0.377728 0.03270792 0.369144 0.06814897 0.374704 0.06167888 0.09035998 0.06480497 0.364908 0.06163793 0.353525 0.02729696 0.359065 0.06163793 0.353525 0.06480497 0.364908 0.06486296 0.07895195 0.06480497 0.364908 0.06167888 0.09035998 0.03270792 0.369144 0.02729696 0.359065 0.06480497 0.364908 0.05875897 0.10317 0.06163793 0.353525 0.0587359 0.340762 0.02219092 0.347582 0.0587359 0.340762 0.06163793 0.353525 0.06167888 0.09035998 0.06163793 0.353525 0.05875897 0.10317 0.02729696 0.359065 0.02219092 0.347582 0.06163793 0.353525 0.05612289 0.1174049 0.0587359 0.340762 0.05611598 0.326601 0.01761299 0.334823 0.05611598 0.326601 0.0587359 0.340762 0.05875897 0.10317 0.0587359 0.340762 0.05612289 0.1174049 0.02219092 0.347582 0.01761299 0.334823 0.0587359 0.340762 0.05612289 0.1174049 0.05611598 0.326601 0.05383199 0.311279 0.01352393 0.320865 0.05383199 0.311279 0.05611598 0.326601 0.01761299 0.334823 0.01352393 0.320865 0.05611598 0.326601 0.05382692 0.132811 0.05383199 0.311279 0.051907 0.294825 0.009817957 0.305878 0.051907 0.294825 0.05383199 0.311279 0.05612289 0.1174049 0.05383199 0.311279 0.05382692 0.132811 0.01352393 0.320865 0.009817957 0.305878 0.05383199 0.311279 0.05189293 0.149357 0.051907 0.294825 0.05037695 0.277523 0.006551921 0.290005 0.05037695 0.277523 0.051907 0.294825 0.05382692 0.132811 0.051907 0.294825 0.05189293 0.149357 0.009817957 0.305878 0.006551921 0.290005 0.051907 0.294825 0.05035996 0.16674 0.05037695 0.277523 0.049263 0.259472 0.003858983 0.273371 0.049263 0.259472 0.05037695 0.277523 0.05189293 0.149357 0.05037695 0.277523 0.05035996 0.16674 0.006551921 0.290005 0.003858983 0.273371 0.05037695 0.277523 0.04924899 0.184855 0.049263 0.259472 0.04858398 0.240968 0.001726925 0.256107 0.04858398 0.240968 0.049263 0.259472 0.05035996 0.16674 0.049263 0.259472 0.04924899 0.184855 0.003858983 0.273371 0.001726925 0.256107 0.049263 0.259472 0.04857695 0.203401 0.04858398 0.240968 0.04835593 0.222191 4.11e-4 0.238641 0.04835593 0.222191 0.04858398 0.240968 0.04924899 0.184855 0.04858398 0.240968 0.04857695 0.203401 0.001726925 0.256107 4.11e-4 0.238641 0.04858398 0.240968 4.35e-4 0.204153 0.04857695 0.203401 0.04835593 0.222191 0 0.221364 4.35e-4 0.204153 0.04835593 0.222191 4.11e-4 0.238641 0 0.221364 0.04835593 0.222191 0.0017879 0.186892 0.04924899 0.184855 0.04857695 0.203401 4.35e-4 0.204153 0.0017879 0.186892 0.04857695 0.203401 0.003942966 0.169941 0.05035996 0.16674 0.04924899 0.184855 0.0017879 0.186892 0.003942966 0.169941 0.04924899 0.184855 0.006614983 0.153665 0.05189293 0.149357 0.05035996 0.16674 0.003942966 0.169941 0.006614983 0.153665 0.05035996 0.16674 0.009814977 0.1381829 0.05382692 0.132811 0.05189293 0.149357 0.006614983 0.153665 0.009814977 0.1381829 0.05189293 0.149357 0.01342797 0.123552 0.05612289 0.1174049 0.05382692 0.132811 0.009814977 0.1381829 0.01342797 0.123552 0.05382692 0.132811 0.01739192 0.109911 0.05875897 0.10317 0.05612289 0.1174049 0.01342797 0.123552 0.01739192 0.109911 0.05612289 0.1174049 0.02184891 0.09736096 0.06167888 0.09035998 0.05875897 0.10317 0.01739192 0.109911 0.02184891 0.09736096 0.05875897 0.10317 0.026847 0.08598196 0.06486296 0.07895195 0.06167888 0.09035998 0.02184891 0.09736096 0.026847 0.08598196 0.06167888 0.09035998 0.03217893 0.07589197 0.068219 0.06915599 0.06486296 0.07895195 0.026847 0.08598196 0.03217893 0.07589197 0.06486296 0.07895195 0.03772497 0.06718599 0.07173401 0.0609219 0.068219 0.06915599 0.03217893 0.07589197 0.03772497 0.06718599 0.068219 0.06915599 0.04341799 0.05983191 0.07536399 0.0542519 0.07173401 0.0609219 0.03772497 0.06718599 0.04341799 0.05983191 0.07173401 0.0609219 0.0491259 0.05378997 0.07909995 0.0490809 0.07536399 0.0542519 0.04341799 0.05983191 0.0491259 0.05378997 0.07536399 0.0542519 0.05481588 0.0491259 0.08286798 0.045448 0.07909995 0.0490809 0.0491259 0.05378997 0.05481588 0.0491259 0.07909995 0.0490809 0.0602889 0.04589295 0.08665698 0.04330599 0.08286798 0.045448 0.05481588 0.0491259 0.0602889 0.04589295 0.08286798 0.045448 0.065539 0.04404091 0.090406 0.04260092 0.08665698 0.04330599 0.0602889 0.04589295 0.065539 0.04404091 0.08665698 0.04330599 0.07040399 0.04352295 0.09408497 0.04327899 0.090406 0.04260092 0.065539 0.04404091 0.07040399 0.04352295 0.090406 0.04260092 0.07884496 0.04606992 0.09770798 0.04527288 0.09408497 0.04327899 0.07483297 0.04423499 0.07884496 0.04606992 0.09408497 0.04327899 0.07040399 0.04352295 0.07483297 0.04423499 0.09408497 0.04327899 0.07937699 0.046422 0.09877097 0.04611599 0.09770798 0.04527288 0.07911396 0.0462439 0.07937699 0.046422 0.09770798 0.04527288 0.07884496 0.04606992 0.07911396 0.0462439 0.09770798 0.04527288 0.07937699 0.046422 0.08029597 0.0470969 0.09877097 0.04611599 0.08368098 0.03637492 0.07937699 0.046422 0.07911396 0.0462439 0.08823496 0.02644091 0.07911396 0.0462439 0.07884496 0.04606992 0.08823496 0.02644091 0.08368098 0.03637492 0.07911396 0.0462439 0.08823496 0.02644091 0.07884496 0.04606992 0.07483297 0.04423499 0.080343 0.02239799 0.07483297 0.04423499 0.07040399 0.04352295 0.080343 0.02239799 0.08823496 0.02644091 0.07483297 0.04423499 0.080343 0.02239799 0.07040399 0.04352295 0.065539 0.04404091 0.07076096 0.02267789 0.065539 0.04404091 0.0602889 0.04589295 0.07076096 0.02267789 0.080343 0.02239799 0.065539 0.04404091 0.06415599 0.02532196 0.0602889 0.04589295 0.05481588 0.0491259 0.07034999 0.022789 0.07076096 0.02267789 0.0602889 0.04589295 0.06992596 0.02291095 0.07034999 0.022789 0.0602889 0.04589295 0.06415599 0.02532196 0.06992596 0.02291095 0.0602889 0.04589295 0.05815088 0.02924299 0.05481588 0.0491259 0.0491259 0.05378997 0.05815088 0.02924299 0.06415599 0.02532196 0.05481588 0.0491259 0.05199992 0.03471297 0.0491259 0.05378997 0.04341799 0.05983191 0.0580089 0.02935296 0.05815088 0.02924299 0.0491259 0.05378997 0.05786591 0.029464 0.0580089 0.02935296 0.0491259 0.05378997 0.05199992 0.03471297 0.05786591 0.029464 0.0491259 0.05378997 0.04612499 0.04139596 0.04341799 0.05983191 0.03772497 0.06718599 0.04612499 0.04139596 0.05199992 0.03471297 0.04341799 0.05983191 0.043401 0.04500198 0.03772497 0.06718599 0.03217893 0.07589197 0.044761 0.04315888 0.04612499 0.04139596 0.03772497 0.06718599 0.043401 0.04500198 0.044761 0.04315888 0.03772497 0.06718599 0.03330993 0.06173795 0.03217893 0.07589197 0.026847 0.08598196 0.03330993 0.06173795 0.043401 0.04500198 0.03217893 0.07589197 0.03330993 0.06173795 0.026847 0.08598196 0.02184891 0.09736096 0.02429795 0.082969 0.02184891 0.09736096 0.01739192 0.109911 0.02429795 0.082969 0.03330993 0.06173795 0.02184891 0.09736096 0.01670897 0.108589 0.01739192 0.109911 0.01342797 0.123552 0.01670897 0.108589 0.02429795 0.082969 0.01739192 0.109911 0.01670897 0.108589 0.01342797 0.123552 0.009814977 0.1381829 0.01106894 0.134775 0.009814977 0.1381829 0.006614983 0.153665 0.01106894 0.134775 0.01670897 0.108589 0.009814977 0.1381829 0.01106894 0.134775 0.006614983 0.153665 0.003942966 0.169941 0.006688952 0.162952 0.003942966 0.169941 0.0017879 0.186892 0.006688952 0.162952 0.01106894 0.134775 0.003942966 0.169941 0.003850996 0.192369 0.0017879 0.186892 4.35e-4 0.204153 0.003850996 0.192369 0.006688952 0.162952 0.0017879 0.186892 0.003850996 0.192369 4.35e-4 0.204153 0 0.221364 0.002899885 0.222095 0 0.221364 4.11e-4 0.238641 0.002899885 0.222095 0.003850996 0.192369 0 0.221364 0.003890991 0.251672 4.11e-4 0.238641 0.001726925 0.256107 0.003890991 0.251672 0.002899885 0.222095 4.11e-4 0.238641 0.006687939 0.280876 0.001726925 0.256107 0.003858983 0.273371 0.006687939 0.280876 0.003890991 0.251672 0.001726925 0.256107 0.006687939 0.280876 0.003858983 0.273371 0.006551921 0.290005 0.01100796 0.308865 0.006551921 0.290005 0.009817957 0.305878 0.01100796 0.308865 0.006687939 0.280876 0.006551921 0.290005 0.01657193 0.334906 0.009817957 0.305878 0.01352393 0.320865 0.01657193 0.334906 0.01100796 0.308865 0.009817957 0.305878 0.01676696 0.335691 0.01352393 0.320865 0.01761299 0.334823 0.01676696 0.335691 0.01657193 0.334906 0.01352393 0.320865 0.02555888 0.364591 0.01761299 0.334823 0.02219092 0.347582 0.016963 0.336474 0.01676696 0.335691 0.01761299 0.334823 0.021025 0.351164 0.016963 0.336474 0.01761299 0.334823 0.02555888 0.364591 0.021025 0.351164 0.01761299 0.334823 0.03055089 0.376663 0.02219092 0.347582 0.02729696 0.359065 0.03055089 0.376663 0.02555888 0.364591 0.02219092 0.347582 0.03592795 0.387335 0.02729696 0.359065 0.03270792 0.369144 0.03592795 0.387335 0.03055089 0.376663 0.02729696 0.359065 0.04159688 0.39657 0.03270792 0.369144 0.03828191 0.377728 0.04159688 0.39657 0.03592795 0.387335 0.03270792 0.369144 0.04744988 0.404356 0.03828191 0.377728 0.04396498 0.384903 0.04744988 0.404356 0.04159688 0.39657 0.03828191 0.377728 0.05338388 0.410712 0.04396498 0.384903 0.049649 0.390746 0.05338388 0.410712 0.04744988 0.404356 0.04396498 0.384903 0.059264 0.415622 0.049649 0.390746 0.05529391 0.39522 0.059264 0.415622 0.05338388 0.410712 0.049649 0.390746 0.06498396 0.419121 0.05529391 0.39522 0.06069391 0.398303 0.06498396 0.419121 0.059264 0.415622 0.05529391 0.39522 0.07043695 0.421262 0.06069391 0.398303 0.06584495 0.400052 0.07043695 0.421262 0.06498396 0.419121 0.06069391 0.398303 0.07553899 0.422108 0.06584495 0.400052 0.07060796 0.400526 0.07553899 0.422108 0.07043695 0.421262 0.06584495 0.400052 0.08023697 0.421721 0.07060796 0.400526 0.07886099 0.397977 0.08023697 0.421721 0.07553899 0.422108 0.07060796 0.400526 0.08023697 0.421721 0.07886099 0.397977 0.07912296 0.397805 0.08023697 0.421721 0.07912296 0.397805 0.07938295 0.397628 0.08023697 0.421721 0.07938295 0.397628 0.083682 0.407678 0.08922499 0.416758 0.08823597 0.417615 0.083682 0.407678 0.08023697 0.421721 0.083682 0.407678 0.08823597 0.417615 0.09287697 0.419786 0.08823597 0.417615 0.08922499 0.416758 0.08287698 0.425733 0.08023697 0.421721 0.08823597 0.417615 0.09090995 0.421525 0.08287698 0.425733 0.08823597 0.417615 0.09287697 0.419786 0.09090995 0.421525 0.08823597 0.417615 0.09091097 0.02253198 0.08823496 0.02644091 0.080343 0.02239799 0.09091097 0.02253198 0.08922696 0.02729195 0.08823496 0.02644091 0.08275896 0.018332 0.080343 0.02239799 0.07076096 0.02267789 0.08275896 0.018332 0.09091097 0.02253198 0.080343 0.02239799 0.07329499 0.01847696 0.07076096 0.02267789 0.07034999 0.022789 0.07329499 0.01847696 0.08275896 0.018332 0.07076096 0.02267789 0.07329499 0.01847696 0.07034999 0.022789 0.06992596 0.02291095 0.07329499 0.01847696 0.06992596 0.02291095 0.06415599 0.02532196 0.06289899 0.02320796 0.06415599 0.02532196 0.05815088 0.02924299 0.06289899 0.02320796 0.07329499 0.01847696 0.06415599 0.02532196 0.06289899 0.02320796 0.05815088 0.02924299 0.0580089 0.02935296 0.06289899 0.02320796 0.0580089 0.02935296 0.05786591 0.029464 0.06289899 0.02320796 0.05786591 0.029464 0.05199992 0.03471297 0.05196493 0.03276991 0.05199992 0.03471297 0.04612499 0.04139596 0.05196493 0.03276991 0.06289899 0.02320796 0.05199992 0.03471297 0.05196493 0.03276991 0.04612499 0.04139596 0.044761 0.04315888 0.05196493 0.03276991 0.044761 0.04315888 0.043401 0.04500198 0.04104799 0.04733192 0.043401 0.04500198 0.03330993 0.06173795 0.04104799 0.04733192 0.05196493 0.03276991 0.043401 0.04500198 0.03086799 0.06685298 0.03330993 0.06173795 0.02429795 0.082969 0.03086799 0.06685298 0.04104799 0.04733192 0.03330993 0.06173795 0.022143 0.09101498 0.02429795 0.082969 0.01670897 0.108589 0.022143 0.09101498 0.03086799 0.06685298 0.02429795 0.082969 0.01499599 0.11935 0.01670897 0.108589 0.01106894 0.134775 0.01499599 0.11935 0.022143 0.09101498 0.01670897 0.108589 0.009329974 0.151295 0.01106894 0.134775 0.006688952 0.162952 0.009329974 0.151295 0.01499599 0.11935 0.01106894 0.134775 0.005477905 0.185976 0.006688952 0.162952 0.003850996 0.192369 0.005477905 0.185976 0.009329974 0.151295 0.006688952 0.162952 0.004121959 0.222055 0.003850996 0.192369 0.002899885 0.222095 0.004121959 0.222055 0.005477905 0.185976 0.003850996 0.192369 0.004121959 0.222055 0.002899885 0.222095 0.003890991 0.251672 0.005523979 0.258143 0.003890991 0.251672 0.006687939 0.280876 0.005523979 0.258143 0.004121959 0.222055 0.003890991 0.251672 0.009352982 0.292821 0.006687939 0.280876 0.01100796 0.308865 0.009352982 0.292821 0.005523979 0.258143 0.006687939 0.280876 0.01502794 0.324784 0.01100796 0.308865 0.01657193 0.334906 0.01502794 0.324784 0.009352982 0.292821 0.01100796 0.308865 0.01502794 0.324784 0.01657193 0.334906 0.01676696 0.335691 0.01502794 0.324784 0.01676696 0.335691 0.016963 0.336474 0.02214795 0.353096 0.016963 0.336474 0.021025 0.351164 0.02214795 0.353096 0.01502794 0.324784 0.016963 0.336474 0.02214795 0.353096 0.021025 0.351164 0.02555888 0.364591 0.03086698 0.377253 0.02555888 0.364591 0.03055089 0.376663 0.03086698 0.377253 0.02214795 0.353096 0.02555888 0.364591 0.03086698 0.377253 0.03055089 0.376663 0.03592795 0.387335 0.04100793 0.396764 0.03592795 0.387335 0.04159688 0.39657 0.04100793 0.396764 0.03086698 0.377253 0.03592795 0.387335 0.04100793 0.396764 0.04159688 0.39657 0.04744988 0.404356 0.05194389 0.411307 0.04744988 0.404356 0.05338388 0.410712 0.05194389 0.411307 0.04100793 0.396764 0.04744988 0.404356 0.05194389 0.411307 0.05338388 0.410712 0.059264 0.415622 0.06296098 0.420855 0.059264 0.415622 0.06498396 0.419121 0.06296098 0.420855 0.05194389 0.411307 0.059264 0.415622 0.06296098 0.420855 0.06498396 0.419121 0.07043695 0.421262 0.073435 0.425585 0.07043695 0.421262 0.07553899 0.422108 0.073435 0.425585 0.06296098 0.420855 0.07043695 0.421262 0.073435 0.425585 0.07553899 0.422108 0.08023697 0.421721 0.08287698 0.425733 0.073435 0.425585 0.08023697 0.421721 0.08622097 0.01507896 0.09888899 0.01744395 0.09455597 0.01944392 0.09041899 0.0128979 0.09888899 0.01744395 0.08622097 0.01507896 0.08275896 0.018332 0.09455597 0.01944392 0.09091097 0.02253198 0.08622097 0.01507896 0.09455597 0.01944392 0.08275896 0.018332 0.08622097 0.01507896 0.08275896 0.018332 0.07329499 0.01847696 0.076568 0.01512789 0.07329499 0.01847696 0.06289899 0.02320796 0.076568 0.01512789 0.08622097 0.01507896 0.07329499 0.01847696 0.06597 0.01988291 0.06289899 0.02320796 0.05196493 0.03276991 0.06597 0.01988291 0.076568 0.01512789 0.06289899 0.02320796 0.05483597 0.02959597 0.05196493 0.03276991 0.04104799 0.04733192 0.05483597 0.02959597 0.06597 0.01988291 0.05196493 0.03276991 0.04373997 0.04441791 0.04104799 0.04733192 0.03086799 0.06685298 0.04373997 0.04441791 0.05483597 0.02959597 0.04104799 0.04733192 0.03341192 0.06427299 0.03086799 0.06685298 0.022143 0.09101498 0.03341192 0.06427299 0.04373997 0.04441791 0.03086799 0.06685298 0.0245639 0.08883297 0.022143 0.09101498 0.01499599 0.11935 0.0245639 0.08883297 0.03341192 0.06427299 0.022143 0.09101498 0.01730698 0.117693 0.01499599 0.11935 0.009329974 0.151295 0.01730698 0.117693 0.0245639 0.08883297 0.01499599 0.11935 0.011554 0.150258 0.009329974 0.151295 0.005477905 0.185976 0.011554 0.150258 0.01730698 0.117693 0.009329974 0.151295 0.007659912 0.185499 0.005477905 0.185976 0.004121959 0.222055 0.007659912 0.185499 0.011554 0.150258 0.005477905 0.185976 0.006293952 0.222051 0.004121959 0.222055 0.005523979 0.258143 0.006293952 0.222051 0.007659912 0.185499 0.004121959 0.222055 0.00770694 0.25862 0.005523979 0.258143 0.009352982 0.292821 0.00770694 0.25862 0.006293952 0.222051 0.005523979 0.258143 0.01157891 0.293867 0.009352982 0.292821 0.01502794 0.324784 0.01157891 0.293867 0.00770694 0.25862 0.009352982 0.292821 0.01733595 0.32644 0.01502794 0.324784 0.02214795 0.353096 0.01733595 0.32644 0.01157891 0.293867 0.01502794 0.324784 0.02456992 0.355282 0.02214795 0.353096 0.03086698 0.377253 0.02456992 0.355282 0.01733595 0.32644 0.02214795 0.353096 0.03341299 0.379839 0.03086698 0.377253 0.04100793 0.396764 0.03341299 0.379839 0.02456992 0.355282 0.03086698 0.377253 0.04370188 0.399681 0.04100793 0.396764 0.05194389 0.411307 0.04370188 0.399681 0.03341299 0.379839 0.04100793 0.396764 0.05481195 0.414478 0.05194389 0.411307 0.06296098 0.420855 0.05481195 0.414478 0.04370188 0.399681 0.05194389 0.411307 0.06602698 0.424176 0.06296098 0.420855 0.073435 0.425585 0.06602698 0.424176 0.05481195 0.414478 0.06296098 0.420855 0.07670599 0.428931 0.073435 0.425585 0.08287698 0.425733 0.07670599 0.428931 0.06602698 0.424176 0.073435 0.425585 0.08634197 0.428981 0.08287698 0.425733 0.09090995 0.421525 0.08634197 0.428981 0.07670599 0.428931 0.08287698 0.425733 0.09456098 0.424609 0.08634197 0.428981 0.09090995 0.421525 0.09648996 0.422854 0.09456098 0.424609 0.09090995 0.421525 0.09287697 0.419786 0.09648996 0.422854 0.09090995 0.421525 0.09041899 0.0128979 0.08622097 0.01507896 0.076568 0.01512789 0.08063697 0.01283293 0.076568 0.01512789 0.06597 0.01988291 0.08063697 0.01283293 0.09041899 0.0128979 0.076568 0.01512789 0.06989198 0.01757198 0.06597 0.01988291 0.05483597 0.02959597 0.06989198 0.01757198 0.08063697 0.01283293 0.06597 0.01988291 0.05859988 0.0273739 0.05483597 0.02959597 0.04373997 0.04441791 0.05859988 0.0273739 0.06989198 0.01757198 0.05483597 0.02959597 0.04735893 0.04236495 0.04373997 0.04441791 0.03341192 0.06427299 0.04735893 0.04236495 0.05859988 0.0273739 0.04373997 0.04441791 0.03690499 0.06243598 0.03341192 0.06427299 0.0245639 0.08883297 0.03690499 0.06243598 0.04735893 0.04236495 0.03341192 0.06427299 0.02794295 0.08725696 0.0245639 0.08883297 0.01730698 0.117693 0.02794295 0.08725696 0.03690499 0.06243598 0.0245639 0.08883297 0.020563 0.116497 0.01730698 0.117693 0.011554 0.150258 0.020563 0.116497 0.02794295 0.08725696 0.01730698 0.117693 0.01469093 0.149532 0.011554 0.150258 0.007659912 0.185499 0.01469093 0.149532 0.020563 0.116497 0.011554 0.150258 0.01071697 0.185176 0.007659912 0.185499 0.006293952 0.222051 0.01071697 0.185176 0.01469093 0.149532 0.007659912 0.185499 0.009323954 0.222046 0.006293952 0.222051 0.00770694 0.25862 0.009323954 0.222046 0.01071697 0.185176 0.006293952 0.222051 0.01076591 0.258943 0.00770694 0.25862 0.01157891 0.293867 0.01076591 0.258943 0.009323954 0.222046 0.00770694 0.25862 0.01471793 0.294602 0.01157891 0.293867 0.01733595 0.32644 0.01471793 0.294602 0.01076591 0.258943 0.01157891 0.293867 0.02059292 0.327634 0.01733595 0.32644 0.02456992 0.355282 0.02059292 0.327634 0.01471793 0.294602 0.01733595 0.32644 0.027951 0.356862 0.02456992 0.355282 0.03341299 0.379839 0.027951 0.356862 0.02059292 0.327634 0.02456992 0.355282 0.03690797 0.381681 0.03341299 0.379839 0.04370188 0.399681 0.03690797 0.381681 0.027951 0.356862 0.03341299 0.379839 0.04732197 0.401737 0.04370188 0.399681 0.05481195 0.414478 0.04732197 0.401737 0.03690797 0.381681 0.04370188 0.399681 0.05857288 0.416697 0.05481195 0.414478 0.06602698 0.424176 0.05857288 0.416697 0.04732197 0.401737 0.05481195 0.414478 0.06994098 0.426483 0.06602698 0.424176 0.07670599 0.428931 0.06994098 0.426483 0.05857288 0.416697 0.06602698 0.424176 0.08077096 0.431224 0.07670599 0.428931 0.08634197 0.428981 0.08077096 0.431224 0.06994098 0.426483 0.07670599 0.428931 0.09054195 0.431158 0.08634197 0.428981 0.09456098 0.424609 0.09054195 0.431158 0.08077096 0.431224 0.08634197 0.428981 0.09889596 0.42661 0.09054195 0.431158 0.09456098 0.424609 0.100786 0.424842 0.09889596 0.42661 0.09456098 0.424609 0.09648996 0.422854 0.100786 0.424842 0.09456098 0.424609 0.105418 0.425604 0.10449 0.426483 0.09889596 0.42661 0.100786 0.424842 0.105418 0.425604 0.09889596 0.42661 0.202718 0.433126 0.10449 0.426483 0.105418 0.425604 0.202718 0.433126 0.205032 0.433806 0.10449 0.426483 0.136059 0.392808 0.105418 0.425604 0.100786 0.424842 0.166342 0.41854 0.105418 0.425604 0.134935 0.398149 0.136059 0.392808 0.134935 0.398149 0.105418 0.425604 0.200467 0.43245 0.202718 0.433126 0.105418 0.425604 0.198281 0.431776 0.200467 0.43245 0.105418 0.425604 0.196157 0.431104 0.198281 0.431776 0.105418 0.425604 0.194095 0.430436 0.196157 0.431104 0.105418 0.425604 0.192095 0.429771 0.194095 0.430436 0.105418 0.425604 0.190156 0.429109 0.192095 0.429771 0.105418 0.425604 0.188278 0.42845 0.190156 0.429109 0.105418 0.425604 0.186459 0.427794 0.188278 0.42845 0.105418 0.425604 0.1847 0.427141 0.186459 0.427794 0.105418 0.425604 0.182829 0.426426 0.1847 0.427141 0.105418 0.425604 0.181024 0.425712 0.182829 0.426426 0.105418 0.425604 0.179285 0.425 0.181024 0.425712 0.105418 0.425604 0.177615 0.424293 0.179285 0.425 0.105418 0.425604 0.176014 0.42359 0.177615 0.424293 0.105418 0.425604 0.174484 0.422892 0.176014 0.42359 0.105418 0.425604 0.173027 0.422201 0.174484 0.422892 0.105418 0.425604 0.171642 0.421516 0.173027 0.422201 0.105418 0.425604 0.170332 0.42084 0.171642 0.421516 0.105418 0.425604 0.169097 0.420172 0.170332 0.42084 0.105418 0.425604 0.167662 0.41935 0.169097 0.420172 0.105418 0.425604 0.166342 0.41854 0.167662 0.41935 0.105418 0.425604 0.132332 0.391098 0.100786 0.424842 0.09648996 0.422854 0.136059 0.392808 0.100786 0.424842 0.132332 0.391098 0.1292099 0.388429 0.09648996 0.422854 0.09287697 0.419786 0.132332 0.391098 0.09648996 0.422854 0.1292099 0.388429 0.279553 0.309991 0.307215 0.306614 0.294213 0.308454 0.279553 0.309991 0.305789 0.306278 0.307215 0.306614 0.279553 0.309991 0.294213 0.308454 0.281002 0.310339 0.25202 0.313737 0.281002 0.310339 0.253855 0.314258 0.279553 0.309991 0.281002 0.310339 0.25202 0.313737 0.25202 0.313737 0.253855 0.314258 0.249117 0.314954 0.244105 0.314924 0.249117 0.314954 0.244715 0.31565 0.244105 0.314924 0.25202 0.313737 0.249117 0.314954 0.244105 0.314924 0.244715 0.31565 0.240607 0.316346 0.23702 0.316121 0.240607 0.316346 0.2369419 0.317044 0.23702 0.316121 0.244105 0.314924 0.240607 0.316346 0.23702 0.316121 0.2369419 0.317044 0.233912 0.317737 0.231409 0.317317 0.233912 0.317737 0.231367 0.318456 0.231409 0.317317 0.23702 0.316121 0.233912 0.317737 0.227309 0.318586 0.231367 0.318456 0.2292439 0.319239 0.227309 0.318586 0.231409 0.317317 0.231367 0.318456 0.227309 0.318586 0.2292439 0.319239 0.227461 0.320072 0.224276 0.319993 0.227461 0.320072 0.225901 0.32095 0.224276 0.319993 0.227309 0.318586 0.227461 0.320072 0.224276 0.319993 0.225901 0.32095 0.224606 0.321878 0.221948 0.321493 0.224606 0.321878 0.211212 0.332217 0.221948 0.321493 0.224276 0.319993 0.224606 0.321878 0.205438 0.334074 0.211212 0.332217 0.196161 0.344374 0.205438 0.334074 0.221948 0.321493 0.211212 0.332217 0.186367 0.349397 0.196161 0.344374 0.178961 0.35887 0.205438 0.334074 0.196161 0.344374 0.186367 0.349397 0.163748 0.368467 0.178961 0.35887 0.158903 0.376439 0.186367 0.349397 0.178961 0.35887 0.163748 0.368467 0.136059 0.392808 0.158903 0.376439 0.134935 0.398149 0.163748 0.368467 0.158903 0.376439 0.136059 0.392808 0.1651329 0.417741 0.166342 0.41854 0.134935 0.398149 0.164027 0.416951 0.1651329 0.417741 0.134935 0.398149 0.163018 0.41617 0.164027 0.416951 0.134935 0.398149 0.1621 0.415396 0.163018 0.41617 0.134935 0.398149 0.161267 0.414628 0.1621 0.415396 0.134935 0.398149 0.1605139 0.413865 0.161267 0.414628 0.134935 0.398149 0.159841 0.413107 0.1605139 0.413865 0.134935 0.398149 0.159254 0.412356 0.159841 0.413107 0.134935 0.398149 0.158751 0.411611 0.159254 0.412356 0.134935 0.398149 0.158331 0.410873 0.158751 0.411611 0.134935 0.398149 0.157995 0.410141 0.158331 0.410873 0.134935 0.398149 0.1577399 0.409416 0.157995 0.410141 0.134935 0.398149 0.1575649 0.408696 0.1577399 0.409416 0.134935 0.398149 0.157471 0.407983 0.1575649 0.408696 0.134935 0.398149 0.156268 0.394814 0.157471 0.407983 0.134935 0.398149 0.203145 0.433119 0.205032 0.433806 0.202718 0.433126 0.221898 0.16624 0.218131 0.304213 0.221928 0.277544 0.201061 0.432429 0.202718 0.433126 0.200467 0.43245 0.201061 0.432429 0.203145 0.433119 0.202718 0.433126 0.199009 0.431733 0.200467 0.43245 0.198281 0.431776 0.199009 0.431733 0.201061 0.432429 0.200467 0.43245 0.196994 0.431033 0.198281 0.431776 0.196157 0.431104 0.196994 0.431033 0.199009 0.431733 0.198281 0.431776 0.195022 0.430331 0.196157 0.431104 0.194095 0.430436 0.195022 0.430331 0.196994 0.431033 0.196157 0.431104 0.193093 0.429625 0.194095 0.430436 0.192095 0.429771 0.193093 0.429625 0.195022 0.430331 0.194095 0.430436 0.191207 0.428915 0.192095 0.429771 0.190156 0.429109 0.191207 0.428915 0.193093 0.429625 0.192095 0.429771 0.191207 0.428915 0.190156 0.429109 0.188278 0.42845 0.189366 0.428202 0.188278 0.42845 0.186459 0.427794 0.189366 0.428202 0.191207 0.428915 0.188278 0.42845 0.18757 0.427485 0.186459 0.427794 0.1847 0.427141 0.18757 0.427485 0.189366 0.428202 0.186459 0.427794 0.18582 0.426763 0.1847 0.427141 0.182829 0.426426 0.18582 0.426763 0.18757 0.427485 0.1847 0.427141 0.184119 0.426037 0.182829 0.426426 0.181024 0.425712 0.184119 0.426037 0.18582 0.426763 0.182829 0.426426 0.1824679 0.425306 0.181024 0.425712 0.179285 0.425 0.1824679 0.425306 0.184119 0.426037 0.181024 0.425712 0.180867 0.424571 0.179285 0.425 0.177615 0.424293 0.180867 0.424571 0.1824679 0.425306 0.179285 0.425 0.179319 0.42383 0.177615 0.424293 0.176014 0.42359 0.179319 0.42383 0.180867 0.424571 0.177615 0.424293 0.177825 0.423084 0.176014 0.42359 0.174484 0.422892 0.177825 0.423084 0.179319 0.42383 0.176014 0.42359 0.1763859 0.422333 0.174484 0.422892 0.173027 0.422201 0.1763859 0.422333 0.177825 0.423084 0.174484 0.422892 0.175004 0.421577 0.173027 0.422201 0.171642 0.421516 0.175004 0.421577 0.1763859 0.422333 0.173027 0.422201 0.173681 0.420815 0.171642 0.421516 0.170332 0.42084 0.173681 0.420815 0.175004 0.421577 0.171642 0.421516 0.17242 0.420047 0.170332 0.42084 0.169097 0.420172 0.17242 0.420047 0.173681 0.420815 0.170332 0.42084 0.171221 0.419275 0.169097 0.420172 0.167662 0.41935 0.171221 0.419275 0.17242 0.420047 0.169097 0.420172 0.1700879 0.418497 0.167662 0.41935 0.166342 0.41854 0.1700879 0.418497 0.171221 0.419275 0.167662 0.41935 0.169021 0.417714 0.166342 0.41854 0.1651329 0.417741 0.169021 0.417714 0.1700879 0.418497 0.166342 0.41854 0.168023 0.416926 0.1651329 0.417741 0.164027 0.416951 0.168023 0.416926 0.169021 0.417714 0.1651329 0.417741 0.167096 0.416134 0.164027 0.416951 0.163018 0.41617 0.167096 0.416134 0.168023 0.416926 0.164027 0.416951 0.166242 0.415336 0.163018 0.41617 0.1621 0.415396 0.166242 0.415336 0.167096 0.416134 0.163018 0.41617 0.165462 0.414534 0.1621 0.415396 0.161267 0.414628 0.165462 0.414534 0.166242 0.415336 0.1621 0.415396 0.164759 0.413727 0.161267 0.414628 0.1605139 0.413865 0.164759 0.413727 0.165462 0.414534 0.161267 0.414628 0.164135 0.412917 0.1605139 0.413865 0.159841 0.413107 0.164135 0.412917 0.164759 0.413727 0.1605139 0.413865 0.163592 0.412102 0.159841 0.413107 0.159254 0.412356 0.163592 0.412102 0.164135 0.412917 0.159841 0.413107 0.1631309 0.411284 0.159254 0.412356 0.158751 0.411611 0.1631309 0.411284 0.163592 0.412102 0.159254 0.412356 0.162755 0.410463 0.158751 0.411611 0.158331 0.410873 0.162755 0.410463 0.1631309 0.411284 0.158751 0.411611 0.162465 0.409638 0.158331 0.410873 0.157995 0.410141 0.162465 0.409638 0.162755 0.410463 0.158331 0.410873 0.162263 0.408812 0.157995 0.410141 0.1577399 0.409416 0.162263 0.408812 0.162465 0.409638 0.157995 0.410141 0.16215 0.407983 0.1577399 0.409416 0.1575649 0.408696 0.16215 0.407983 0.162263 0.408812 0.1577399 0.409416 0.16215 0.407983 0.1575649 0.408696 0.157471 0.407983 0.162227 0.40712 0.16215 0.407983 0.157471 0.407983 0.32783 0.299798 0.314194 0.299421 0.32691 0.297718 0.312242 0.292223 0.32691 0.297718 0.314194 0.299421 0.331592 0.296798 0.32783 0.299798 0.32691 0.297718 0.312242 0.292223 0.331592 0.296798 0.32691 0.297718 0.32783 0.299798 0.301521 0.301133 0.314194 0.299421 0.283756 0.294461 0.314194 0.299421 0.301521 0.301133 0.283756 0.294461 0.288715 0.294589 0.314194 0.299421 0.306665 0.292781 0.314194 0.299421 0.288715 0.294589 0.306665 0.292781 0.312242 0.292223 0.314194 0.299421 0.32783 0.299798 0.302243 0.302861 0.301521 0.301133 0.288459 0.302912 0.301521 0.301133 0.302243 0.302861 0.278787 0.293169 0.301521 0.301133 0.288459 0.302912 0.278787 0.293169 0.283756 0.294461 0.301521 0.301133 0.32783 0.299798 0.303233 0.304349 0.302243 0.302861 0.275935 0.306499 0.302243 0.302861 0.303233 0.304349 0.275191 0.304734 0.302243 0.302861 0.275935 0.306499 0.281667 0.303843 0.302243 0.302861 0.275191 0.304734 0.288459 0.302912 0.302243 0.302861 0.281667 0.303843 0.329146 0.301481 0.304436 0.305509 0.303233 0.304349 0.276948 0.308018 0.303233 0.304349 0.304436 0.305509 0.32783 0.299798 0.329146 0.301481 0.303233 0.304349 0.275935 0.306499 0.303233 0.304349 0.276948 0.308018 0.330746 0.302607 0.305789 0.306278 0.304436 0.305509 0.278175 0.309204 0.304436 0.305509 0.305789 0.306278 0.329146 0.301481 0.330746 0.302607 0.304436 0.305509 0.276948 0.308018 0.304436 0.305509 0.278175 0.309204 0.278175 0.309204 0.305789 0.306278 0.279553 0.309991 0.337422 0.299242 0.330746 0.302607 0.329146 0.301481 0.33905 0.300346 0.330746 0.302607 0.337422 0.299242 0.33603 0.297666 0.329146 0.301481 0.32783 0.299798 0.337422 0.299242 0.329146 0.301481 0.33603 0.297666 0.33603 0.297666 0.32783 0.299798 0.331592 0.296798 0.275935 0.306499 0.248925 0.310737 0.247927 0.308523 0.240854 0.311916 0.247927 0.308523 0.248925 0.310737 0.275191 0.304734 0.275935 0.306499 0.247927 0.308523 0.242559 0.287766 0.275191 0.304734 0.247927 0.308523 0.2337599 0.288697 0.242559 0.287766 0.247927 0.308523 0.243758 0.309113 0.2337599 0.288697 0.247927 0.308523 0.240854 0.311916 0.243758 0.309113 0.247927 0.308523 0.276948 0.308018 0.250327 0.312531 0.248925 0.310737 0.242327 0.313718 0.248925 0.310737 0.250327 0.312531 0.275935 0.306499 0.276948 0.308018 0.248925 0.310737 0.240854 0.311916 0.248925 0.310737 0.242327 0.313718 0.278175 0.309204 0.25202 0.313737 0.250327 0.312531 0.244105 0.314924 0.250327 0.312531 0.25202 0.313737 0.276948 0.308018 0.278175 0.309204 0.250327 0.312531 0.242327 0.313718 0.250327 0.312531 0.244105 0.314924 0.278175 0.309204 0.279553 0.309991 0.25202 0.313737 0.242559 0.287766 0.281667 0.303843 0.275191 0.304734 0.278787 0.293169 0.288459 0.302912 0.281667 0.303843 0.242559 0.287766 0.278787 0.293169 0.281667 0.303843 0.33603 0.14638 0.335931 0.148658 0.331593 0.147248 0.343392 0.150224 0.339943 0.150564 0.335931 0.148658 0.33603 0.14638 0.343392 0.150224 0.335931 0.148658 0.343392 0.150224 0.343628 0.152938 0.339943 0.150564 0.349783 0.155768 0.344162 0.153339 0.343628 0.152938 0.343392 0.150224 0.349783 0.155768 0.343628 0.152938 0.350003 0.158959 0.344162 0.153339 0.346973 0.155736 0.349783 0.155768 0.346973 0.155736 0.344162 0.153339 0.342256 0.161375 0.344162 0.153339 0.350003 0.158959 0.338665 0.158423 0.344162 0.153339 0.342256 0.161375 0.324199 0.153012 0.312242 0.151823 0.344162 0.153339 0.331765 0.1547549 0.324199 0.153012 0.344162 0.153339 0.338665 0.158423 0.331765 0.1547549 0.344162 0.153339 0.349783 0.155768 0.350003 0.158959 0.346973 0.155736 0.355137 0.162917 0.35273 0.162577 0.350003 0.158959 0.342256 0.161375 0.350003 0.158959 0.35273 0.162577 0.349783 0.155768 0.355137 0.162917 0.350003 0.158959 0.355137 0.162917 0.355174 0.166592 0.35273 0.162577 0.344767 0.163985 0.35273 0.162577 0.355174 0.166592 0.344767 0.163985 0.342256 0.161375 0.35273 0.162577 0.359436 0.171532 0.357334 0.1709589 0.355174 0.166592 0.344767 0.163985 0.355174 0.166592 0.357334 0.1709589 0.355137 0.162917 0.359436 0.171532 0.355174 0.166592 0.359436 0.171532 0.359233 0.175686 0.357334 0.1709589 0.34979 0.171048 0.357334 0.1709589 0.359233 0.175686 0.34979 0.171048 0.344767 0.163985 0.357334 0.1709589 0.36273 0.1814 0.36087 0.1807129 0.359233 0.175686 0.353868 0.179536 0.359233 0.175686 0.36087 0.1807129 0.359436 0.171532 0.36273 0.1814 0.359233 0.175686 0.353868 0.179536 0.34979 0.171048 0.359233 0.175686 0.36273 0.1814 0.362267 0.186051 0.36087 0.1807129 0.353868 0.179536 0.36087 0.1807129 0.362267 0.186051 0.365097 0.1922709 0.363425 0.1916249 0.362267 0.186051 0.356975 0.189115 0.362267 0.186051 0.363425 0.1916249 0.36273 0.1814 0.365097 0.1922709 0.362267 0.186051 0.356975 0.189115 0.353868 0.179536 0.362267 0.186051 0.365097 0.1922709 0.36436 0.1974419 0.363425 0.1916249 0.356975 0.189115 0.363425 0.1916249 0.36436 0.1974419 0.36662 0.203874 0.365077 0.203419 0.36436 0.1974419 0.359189 0.199717 0.36436 0.1974419 0.365077 0.203419 0.365097 0.1922709 0.36662 0.203874 0.36436 0.1974419 0.359189 0.199717 0.356975 0.189115 0.36436 0.1974419 0.36662 0.203874 0.365583 0.209549 0.365077 0.203419 0.359189 0.199717 0.365077 0.203419 0.365583 0.209549 0.367363 0.215924 0.365886 0.215759 0.365583 0.209549 0.360481 0.210782 0.365583 0.209549 0.365886 0.215759 0.36662 0.203874 0.367363 0.215924 0.365583 0.209549 0.360481 0.210782 0.359189 0.199717 0.365583 0.209549 0.367363 0.215924 0.365985 0.22202 0.365886 0.215759 0.360481 0.210782 0.365886 0.215759 0.365985 0.22202 0.367363 0.228121 0.365886 0.228282 0.365985 0.22202 0.360903 0.222023 0.365985 0.22202 0.365886 0.228282 0.367363 0.215924 0.367363 0.228121 0.365985 0.22202 0.360903 0.222023 0.360481 0.210782 0.365985 0.22202 0.36662 0.240171 0.365584 0.234492 0.365886 0.228282 0.360495 0.233071 0.365886 0.228282 0.365584 0.234492 0.367363 0.228121 0.36662 0.240171 0.365886 0.228282 0.360495 0.233071 0.360903 0.222023 0.365886 0.228282 0.36662 0.240171 0.365078 0.240622 0.365584 0.234492 0.360495 0.233071 0.365584 0.234492 0.365078 0.240622 0.365097 0.251774 0.364361 0.246599 0.365078 0.240622 0.359239 0.244018 0.365078 0.240622 0.364361 0.246599 0.36662 0.240171 0.365097 0.251774 0.365078 0.240622 0.359239 0.244018 0.360495 0.233071 0.365078 0.240622 0.365097 0.251774 0.363426 0.252416 0.364361 0.246599 0.359239 0.244018 0.364361 0.246599 0.363426 0.252416 0.36273 0.262645 0.362268 0.25799 0.363426 0.252416 0.357065 0.254585 0.363426 0.252416 0.362268 0.25799 0.365097 0.251774 0.36273 0.262645 0.363426 0.252416 0.357065 0.254585 0.359239 0.244018 0.363426 0.252416 0.36273 0.262645 0.360872 0.263328 0.362268 0.25799 0.357065 0.254585 0.362268 0.25799 0.360872 0.263328 0.359436 0.272513 0.359235 0.268355 0.360872 0.263328 0.353997 0.264182 0.360872 0.263328 0.359235 0.268355 0.36273 0.262645 0.359436 0.272513 0.360872 0.263328 0.353997 0.264182 0.357065 0.254585 0.360872 0.263328 0.359436 0.272513 0.357336 0.273083 0.359235 0.268355 0.349943 0.272734 0.359235 0.268355 0.357336 0.273083 0.349943 0.272734 0.353997 0.264182 0.359235 0.268355 0.355137 0.281129 0.355175 0.277451 0.357336 0.273083 0.349943 0.272734 0.357336 0.273083 0.355175 0.277451 0.359436 0.272513 0.355137 0.281129 0.357336 0.273083 0.355137 0.281129 0.352731 0.281467 0.355175 0.277451 0.344921 0.279883 0.355175 0.277451 0.352731 0.281467 0.344921 0.279883 0.349943 0.272734 0.355175 0.277451 0.349783 0.288277 0.350004 0.285085 0.352731 0.281467 0.342259 0.282668 0.352731 0.281467 0.350004 0.285085 0.355137 0.281129 0.349783 0.288277 0.352731 0.281467 0.344921 0.279883 0.352731 0.281467 0.342259 0.282668 0.349783 0.288277 0.346975 0.288309 0.350004 0.285085 0.342259 0.282668 0.350004 0.285085 0.346975 0.288309 0.343393 0.293822 0.344162 0.290706 0.346975 0.288309 0.342259 0.282668 0.346975 0.288309 0.344162 0.290706 0.349783 0.288277 0.343393 0.293822 0.346975 0.288309 0.343393 0.293822 0.343628 0.291107 0.344162 0.290706 0.312242 0.292223 0.344162 0.290706 0.343628 0.291107 0.324199 0.291034 0.344162 0.290706 0.312242 0.292223 0.338798 0.285528 0.342259 0.282668 0.344162 0.290706 0.331843 0.289261 0.338798 0.285528 0.344162 0.290706 0.324199 0.291034 0.331843 0.289261 0.344162 0.290706 0.343393 0.293822 0.339942 0.293482 0.343628 0.291107 0.312242 0.292223 0.343628 0.291107 0.339942 0.293482 0.33603 0.297666 0.335929 0.295388 0.339942 0.293482 0.312242 0.292223 0.339942 0.293482 0.335929 0.295388 0.343393 0.293822 0.33603 0.297666 0.339942 0.293482 0.33603 0.297666 0.331592 0.296798 0.335929 0.295388 0.312242 0.292223 0.335929 0.295388 0.331592 0.296798 0.337422 0.299242 0.33603 0.297666 0.343393 0.293822 0.344853 0.295272 0.343393 0.293822 0.349783 0.288277 0.344853 0.295272 0.337422 0.299242 0.343393 0.293822 0.351305 0.289582 0.349783 0.288277 0.355137 0.281129 0.351305 0.289582 0.344853 0.295272 0.349783 0.288277 0.356713 0.282271 0.355137 0.281129 0.359436 0.272513 0.356713 0.282271 0.351305 0.289582 0.355137 0.281129 0.361059 0.273475 0.359436 0.272513 0.36273 0.262645 0.361059 0.273475 0.356713 0.282271 0.359436 0.272513 0.364393 0.263412 0.36273 0.262645 0.365097 0.251774 0.364393 0.263412 0.361059 0.273475 0.36273 0.262645 0.366791 0.252333 0.365097 0.251774 0.36662 0.240171 0.366791 0.252333 0.364393 0.263412 0.365097 0.251774 0.368334 0.24051 0.36662 0.240171 0.367363 0.228121 0.368334 0.24051 0.366791 0.252333 0.36662 0.240171 0.369088 0.228235 0.367363 0.228121 0.367363 0.215924 0.369088 0.228235 0.368334 0.24051 0.367363 0.228121 0.369088 0.21581 0.367363 0.215924 0.36662 0.203874 0.369088 0.21581 0.369088 0.228235 0.367363 0.215924 0.368334 0.203535 0.36662 0.203874 0.365097 0.1922709 0.368334 0.203535 0.369088 0.21581 0.36662 0.203874 0.366791 0.191713 0.365097 0.1922709 0.36273 0.1814 0.366791 0.191713 0.368334 0.203535 0.365097 0.1922709 0.364392 0.180633 0.36273 0.1814 0.359436 0.171532 0.364392 0.180633 0.366791 0.191713 0.36273 0.1814 0.361059 0.17057 0.359436 0.171532 0.355137 0.162917 0.361059 0.17057 0.364392 0.180633 0.359436 0.171532 0.356713 0.1617749 0.355137 0.162917 0.349783 0.155768 0.356713 0.1617749 0.361059 0.17057 0.355137 0.162917 0.351304 0.154464 0.349783 0.155768 0.343392 0.150224 0.351304 0.154464 0.356713 0.1617749 0.349783 0.155768 0.344853 0.148773 0.343392 0.150224 0.33603 0.14638 0.344853 0.148773 0.351304 0.154464 0.343392 0.150224 0.337422 0.144803 0.344853 0.148773 0.33603 0.14638 0.33905 0.300346 0.337422 0.299242 0.344853 0.295272 0.346514 0.296321 0.344853 0.295272 0.351305 0.289582 0.346514 0.296321 0.33905 0.300346 0.344853 0.295272 0.353003 0.290545 0.351305 0.289582 0.356713 0.282271 0.353003 0.290545 0.346514 0.296321 0.351305 0.289582 0.358451 0.283123 0.356713 0.282271 0.361059 0.273475 0.358451 0.283123 0.353003 0.290545 0.356713 0.282271 0.362836 0.274196 0.361059 0.273475 0.364393 0.263412 0.362836 0.274196 0.358451 0.283123 0.361059 0.273475 0.366203 0.263986 0.364393 0.263412 0.366791 0.252333 0.366203 0.263986 0.362836 0.274196 0.364393 0.263412 0.36863 0.252749 0.366791 0.252333 0.368334 0.24051 0.36863 0.252749 0.366203 0.263986 0.366791 0.252333 0.370193 0.2407619 0.368334 0.24051 0.369088 0.228235 0.370193 0.2407619 0.36863 0.252749 0.368334 0.24051 0.370958 0.22832 0.369088 0.228235 0.369088 0.21581 0.370958 0.22832 0.370193 0.2407619 0.369088 0.228235 0.370958 0.215725 0.369088 0.21581 0.368334 0.203535 0.370958 0.215725 0.370958 0.22832 0.369088 0.21581 0.370193 0.203283 0.368334 0.203535 0.366791 0.191713 0.370193 0.203283 0.370958 0.215725 0.368334 0.203535 0.36863 0.191296 0.366791 0.191713 0.364392 0.180633 0.36863 0.191296 0.370193 0.203283 0.366791 0.191713 0.366203 0.180059 0.364392 0.180633 0.361059 0.17057 0.366203 0.180059 0.36863 0.191296 0.364392 0.180633 0.362835 0.169849 0.361059 0.17057 0.356713 0.1617749 0.362835 0.169849 0.366203 0.180059 0.361059 0.17057 0.358451 0.160922 0.356713 0.1617749 0.351304 0.154464 0.358451 0.160922 0.362835 0.169849 0.356713 0.1617749 0.353003 0.1535 0.351304 0.154464 0.344853 0.148773 0.353003 0.1535 0.358451 0.160922 0.351304 0.154464 0.346514 0.147725 0.344853 0.148773 0.337422 0.144803 0.346514 0.147725 0.353003 0.1535 0.344853 0.148773 0.339049 0.1437 0.346514 0.147725 0.337422 0.144803 0.293788 0.294954 0.288715 0.294589 0.283756 0.294461 0.329613 0.291378 0.306665 0.292781 0.288715 0.294589 0.329613 0.291378 0.288715 0.294589 0.293788 0.294954 0.28876 0.294814 0.283756 0.294461 0.278787 0.293169 0.28876 0.294814 0.293788 0.294954 0.283756 0.294461 0.242559 0.287766 0.278514 0.293066 0.278787 0.293169 0.28876 0.294814 0.278787 0.293169 0.278514 0.293066 0.329613 0.291378 0.312242 0.292223 0.306665 0.292781 0.329613 0.291378 0.324199 0.291034 0.312242 0.292223 0.242559 0.287766 0.273256 0.290424 0.278514 0.293066 0.283841 0.293411 0.278514 0.293066 0.273256 0.290424 0.283841 0.293411 0.28876 0.294814 0.278514 0.293066 0.242559 0.287766 0.268198 0.286611 0.273256 0.290424 0.279172 0.290771 0.273256 0.290424 0.268198 0.286611 0.279172 0.290771 0.283841 0.293411 0.273256 0.290424 0.242559 0.287766 0.265768 0.284253 0.268198 0.286611 0.274911 0.286967 0.268198 0.286611 0.265768 0.284253 0.274911 0.286967 0.279172 0.290771 0.268198 0.286611 0.23869 0.266606 0.263435 0.281604 0.265768 0.284253 0.274911 0.286967 0.265768 0.284253 0.263435 0.281604 0.242559 0.287766 0.23869 0.266606 0.265768 0.284253 0.23869 0.266606 0.249537 0.263738 0.263435 0.281604 0.271193 0.282085 0.263435 0.281604 0.249537 0.263738 0.271193 0.282085 0.274911 0.286967 0.263435 0.281604 0.23869 0.266606 0.236325 0.245176 0.249537 0.263738 0.271193 0.282085 0.249537 0.263738 0.236325 0.245176 0.2295809 0.266908 0.236325 0.245176 0.23869 0.266606 0.234624 0.242649 0.271193 0.282085 0.236325 0.245176 0.227041 0.244597 0.234624 0.242649 0.236325 0.245176 0.2295809 0.266908 0.227041 0.244597 0.236325 0.245176 0.2295809 0.266908 0.23869 0.266606 0.242559 0.287766 0.2337599 0.288697 0.2295809 0.266908 0.242559 0.287766 0.345203 0.285768 0.342259 0.282668 0.338798 0.285528 0.352185 0.280215 0.344921 0.279883 0.342259 0.282668 0.345203 0.285768 0.352185 0.280215 0.342259 0.282668 0.337615 0.289542 0.338798 0.285528 0.331843 0.289261 0.337615 0.289542 0.345203 0.285768 0.338798 0.285528 0.337615 0.289542 0.331843 0.289261 0.324199 0.291034 0.337615 0.289542 0.324199 0.291034 0.329613 0.291378 0.345202 0.158277 0.342256 0.161375 0.344767 0.163985 0.345202 0.158277 0.338665 0.158423 0.342256 0.161375 0.352184 0.16383 0.344767 0.163985 0.34979 0.171048 0.352184 0.16383 0.345202 0.158277 0.344767 0.163985 0.358386 0.170966 0.34979 0.171048 0.353868 0.179536 0.358386 0.170966 0.352184 0.16383 0.34979 0.171048 0.363662 0.1794649 0.353868 0.179536 0.356975 0.189115 0.363662 0.1794649 0.358386 0.170966 0.353868 0.179536 0.367894 0.1890839 0.356975 0.189115 0.359189 0.199717 0.367894 0.1890839 0.363662 0.1794649 0.356975 0.189115 0.370988 0.1995649 0.359189 0.199717 0.360481 0.210782 0.370988 0.1995649 0.367894 0.1890839 0.359189 0.199717 0.372874 0.210635 0.360481 0.210782 0.360903 0.222023 0.372874 0.210635 0.370988 0.1995649 0.360481 0.210782 0.37351 0.222023 0.360903 0.222023 0.360495 0.233071 0.37351 0.222023 0.372874 0.210635 0.360903 0.222023 0.372874 0.233411 0.360495 0.233071 0.359239 0.244018 0.372874 0.233411 0.37351 0.222023 0.360495 0.233071 0.370988 0.24448 0.359239 0.244018 0.357065 0.254585 0.370988 0.24448 0.372874 0.233411 0.359239 0.244018 0.367894 0.254961 0.357065 0.254585 0.353997 0.264182 0.367894 0.254961 0.370988 0.24448 0.357065 0.254585 0.363663 0.26458 0.353997 0.264182 0.349943 0.272734 0.363663 0.26458 0.367894 0.254961 0.353997 0.264182 0.352185 0.280215 0.349943 0.272734 0.344921 0.279883 0.358387 0.273079 0.363663 0.26458 0.349943 0.272734 0.352185 0.280215 0.358387 0.273079 0.349943 0.272734 0.293788 0.149092 0.312242 0.151823 0.324199 0.153012 0.293788 0.149092 0.306665 0.151265 0.312242 0.151823 0.329613 0.1526679 0.324199 0.153012 0.331765 0.1547549 0.293788 0.149092 0.324199 0.153012 0.329613 0.1526679 0.337614 0.154504 0.331765 0.1547549 0.338665 0.158423 0.337614 0.154504 0.329613 0.1526679 0.331765 0.1547549 0.345202 0.158277 0.337614 0.154504 0.338665 0.158423 0.28876 0.149231 0.278785 0.1508769 0.28372 0.14959 0.283841 0.150635 0.278459 0.151001 0.278785 0.1508769 0.28876 0.149231 0.283841 0.150635 0.278785 0.1508769 0.28876 0.149231 0.28372 0.14959 0.288715 0.149456 0.293788 0.149092 0.288715 0.149456 0.306665 0.151265 0.28876 0.149231 0.288715 0.149456 0.293788 0.149092 0.263434 0.162442 0.23869 0.177439 0.242559 0.15628 0.233759 0.15535 0.242559 0.15628 0.23869 0.177439 0.265751 0.159811 0.263434 0.162442 0.242559 0.15628 0.268166 0.157464 0.265751 0.159811 0.242559 0.15628 0.249537 0.1803089 0.236325 0.19887 0.23869 0.177439 0.2295809 0.177139 0.23869 0.177439 0.236325 0.19887 0.263434 0.162442 0.249537 0.1803089 0.23869 0.177439 0.2295809 0.177139 0.233759 0.15535 0.23869 0.177439 0.244881 0.203657 0.236325 0.19887 0.249537 0.1803089 0.234624 0.201397 0.236325 0.19887 0.244881 0.203657 0.227041 0.19945 0.236325 0.19887 0.234624 0.201397 0.227041 0.19945 0.2295809 0.177139 0.236325 0.19887 0.244881 0.203657 0.249537 0.1803089 0.263434 0.162442 0.271193 0.161961 0.263434 0.162442 0.265751 0.159811 0.244881 0.203657 0.263434 0.162442 0.271193 0.161961 0.274911 0.157079 0.265751 0.159811 0.268166 0.157464 0.274911 0.157079 0.271193 0.161961 0.265751 0.159811 0.279172 0.153275 0.268166 0.157464 0.273205 0.153654 0.279172 0.153275 0.274911 0.157079 0.268166 0.157464 0.283841 0.150635 0.273205 0.153654 0.278459 0.151001 0.283841 0.150635 0.279172 0.153275 0.273205 0.153654 0.293788 0.149092 0.293788 0.294954 0.28876 0.294814 0.329613 0.1526679 0.329613 0.291378 0.293788 0.294954 0.293788 0.149092 0.329613 0.1526679 0.293788 0.294954 0.28876 0.149231 0.28876 0.294814 0.283841 0.293411 0.28876 0.149231 0.293788 0.149092 0.28876 0.294814 0.283841 0.150635 0.283841 0.293411 0.279172 0.290771 0.28876 0.149231 0.283841 0.293411 0.283841 0.150635 0.279172 0.153275 0.279172 0.290771 0.274911 0.286967 0.283841 0.150635 0.279172 0.290771 0.279172 0.153275 0.274911 0.157079 0.274911 0.286967 0.271193 0.282085 0.279172 0.153275 0.274911 0.286967 0.274911 0.157079 0.274911 0.157079 0.271193 0.282085 0.271193 0.161961 0.244881 0.240389 0.271193 0.161961 0.271193 0.282085 0.232969 0.24015 0.271193 0.282085 0.234624 0.242649 0.244881 0.240389 0.271193 0.282085 0.232969 0.24015 0.337614 0.154504 0.329613 0.291378 0.329613 0.1526679 0.337615 0.289542 0.329613 0.291378 0.337614 0.154504 0.337615 0.289542 0.337614 0.154504 0.345202 0.158277 0.345203 0.285768 0.345202 0.158277 0.352184 0.16383 0.337615 0.289542 0.345202 0.158277 0.345203 0.285768 0.352185 0.280215 0.352184 0.16383 0.358386 0.170966 0.345203 0.285768 0.352184 0.16383 0.352185 0.280215 0.358387 0.273079 0.358386 0.170966 0.363662 0.1794649 0.352185 0.280215 0.358386 0.170966 0.358387 0.273079 0.363663 0.26458 0.363662 0.1794649 0.367894 0.1890839 0.358387 0.273079 0.363662 0.1794649 0.363663 0.26458 0.367894 0.254961 0.367894 0.1890839 0.370988 0.1995649 0.363663 0.26458 0.367894 0.1890839 0.367894 0.254961 0.370988 0.24448 0.370988 0.1995649 0.372874 0.210635 0.367894 0.254961 0.370988 0.1995649 0.370988 0.24448 0.372874 0.233411 0.372874 0.210635 0.37351 0.222023 0.370988 0.24448 0.372874 0.210635 0.372874 0.233411 0.244881 0.240389 0.244881 0.203657 0.271193 0.161961 0.234624 0.201397 0.244881 0.203657 0.2329699 0.203896 0.242174 0.209159 0.2329699 0.203896 0.244881 0.203657 0.227041 0.19945 0.234624 0.201397 0.2329699 0.203896 0.227041 0.19945 0.2329699 0.203896 0.23018 0.209341 0.242174 0.209159 0.23018 0.209341 0.2329699 0.203896 0.242174 0.234887 0.244881 0.203657 0.244881 0.240389 0.242174 0.234887 0.242174 0.209159 0.244881 0.203657 0.227041 0.244597 0.232969 0.24015 0.234624 0.242649 0.227041 0.244597 0.23018 0.234705 0.232969 0.24015 0.244881 0.240389 0.232969 0.24015 0.23018 0.234705 0.226184 0.222023 0.228442 0.228547 0.23018 0.234705 0.240481 0.228645 0.23018 0.234705 0.228442 0.228547 0.227041 0.244597 0.226184 0.222023 0.23018 0.234705 0.242174 0.234887 0.244881 0.240389 0.23018 0.234705 0.242174 0.234887 0.23018 0.234705 0.240481 0.228645 0.226184 0.222023 0.227851 0.222023 0.228442 0.228547 0.240481 0.228645 0.228442 0.228547 0.227851 0.222023 0.227041 0.19945 0.228442 0.215499 0.227851 0.222023 0.2399049 0.222023 0.227851 0.222023 0.228442 0.215499 0.226184 0.222023 0.227041 0.19945 0.227851 0.222023 0.240481 0.228645 0.227851 0.222023 0.2399049 0.222023 0.227041 0.19945 0.23018 0.209341 0.228442 0.215499 0.240481 0.2154 0.228442 0.215499 0.23018 0.209341 0.2399049 0.222023 0.228442 0.215499 0.240481 0.2154 0.240481 0.2154 0.23018 0.209341 0.242174 0.209159 0.22117 0.176476 0.233759 0.15535 0.2295809 0.177139 0.22117 0.176476 0.225764 0.154398 0.233759 0.15535 0.218376 0.199109 0.2295809 0.177139 0.227041 0.19945 0.218376 0.199109 0.22117 0.176476 0.2295809 0.177139 0.218376 0.199109 0.227041 0.19945 0.226184 0.222023 0.217434 0.222023 0.226184 0.222023 0.227041 0.244597 0.217434 0.222023 0.218376 0.199109 0.226184 0.222023 0.218376 0.244937 0.227041 0.244597 0.2295809 0.266908 0.218376 0.244937 0.217434 0.222023 0.227041 0.244597 0.22117 0.267571 0.2295809 0.266908 0.2337599 0.288697 0.22117 0.267571 0.218376 0.244937 0.2295809 0.266908 0.239675 0.309709 0.239487 0.309737 0.2337599 0.288697 0.225764 0.289649 0.2337599 0.288697 0.239487 0.309737 0.243758 0.309113 0.239675 0.309709 0.2337599 0.288697 0.225764 0.289649 0.22117 0.267571 0.2337599 0.288697 0.233496 0.313119 0.239487 0.309737 0.239675 0.309709 0.232145 0.310913 0.225764 0.289649 0.239487 0.309737 0.233496 0.313119 0.232145 0.310913 0.239487 0.309737 0.240854 0.311916 0.239675 0.309709 0.243758 0.309113 0.233496 0.313119 0.239675 0.309709 0.240854 0.311916 0.214144 0.175795 0.225764 0.154398 0.22117 0.176476 0.214144 0.175795 0.219263 0.153441 0.225764 0.154398 0.211026 0.198756 0.22117 0.176476 0.218376 0.199109 0.211026 0.198756 0.214144 0.175795 0.22117 0.176476 0.209974 0.222023 0.218376 0.199109 0.217434 0.222023 0.209974 0.222023 0.211026 0.198756 0.218376 0.199109 0.209974 0.222023 0.217434 0.222023 0.218376 0.244937 0.211026 0.24529 0.218376 0.244937 0.22117 0.267571 0.211026 0.24529 0.209974 0.222023 0.218376 0.244937 0.214144 0.26825 0.22117 0.267571 0.225764 0.289649 0.214144 0.26825 0.211026 0.24529 0.22117 0.267571 0.232145 0.310913 0.232051 0.31093 0.225764 0.289649 0.219263 0.290605 0.225764 0.289649 0.232051 0.31093 0.219263 0.290605 0.214144 0.26825 0.225764 0.289649 0.227509 0.314341 0.232051 0.31093 0.232145 0.310913 0.2262589 0.312091 0.219263 0.290605 0.232051 0.31093 0.227509 0.314341 0.2262589 0.312091 0.232051 0.31093 0.227509 0.314341 0.232145 0.310913 0.233496 0.313119 0.208799 0.175067 0.219263 0.153441 0.214144 0.175795 0.208799 0.175067 0.214357 0.1524209 0.219263 0.153441 0.20541 0.198377 0.214144 0.175795 0.211026 0.198756 0.20541 0.198377 0.208799 0.175067 0.214144 0.175795 0.20541 0.198377 0.211026 0.198756 0.209974 0.222023 0.2042649 0.222023 0.209974 0.222023 0.211026 0.24529 0.2042649 0.222023 0.20541 0.198377 0.209974 0.222023 0.20541 0.245669 0.211026 0.24529 0.214144 0.26825 0.20541 0.245669 0.2042649 0.222023 0.211026 0.24529 0.208799 0.268978 0.214144 0.26825 0.219263 0.290605 0.208799 0.268978 0.20541 0.245669 0.214144 0.26825 0.214357 0.291625 0.219263 0.290605 0.2262589 0.312091 0.214357 0.291625 0.208799 0.268978 0.219263 0.290605 0.226097 0.312129 0.214357 0.291625 0.2262589 0.312091 0.223105 0.315641 0.226097 0.312129 0.2262589 0.312091 0.223105 0.315641 0.2262589 0.312091 0.227509 0.314341 0.204849 0.174273 0.214357 0.1524209 0.208799 0.175067 0.204849 0.174273 0.210686 0.151289 0.214357 0.1524209 0.201286 0.197968 0.208799 0.175067 0.20541 0.198377 0.201286 0.197968 0.204849 0.174273 0.208799 0.175067 0.201286 0.197968 0.20541 0.198377 0.2042649 0.222023 0.200083 0.222023 0.2042649 0.222023 0.20541 0.245669 0.200083 0.222023 0.201286 0.197968 0.2042649 0.222023 0.201286 0.246078 0.20541 0.245669 0.208799 0.268978 0.201286 0.246078 0.200083 0.222023 0.20541 0.245669 0.204849 0.269773 0.208799 0.268978 0.214357 0.291625 0.204849 0.269773 0.201286 0.246078 0.208799 0.268978 0.226097 0.312129 0.221927 0.313326 0.214357 0.291625 0.210686 0.292757 0.214357 0.291625 0.221927 0.313326 0.210686 0.292757 0.204849 0.269773 0.214357 0.291625 0.223105 0.315641 0.221927 0.313326 0.226097 0.312129 0.221671 0.313416 0.210686 0.292757 0.221927 0.313326 0.223105 0.315641 0.221671 0.313416 0.221927 0.313326 0.221671 0.313416 0.218626 0.314727 0.210686 0.292757 0.2199079 0.317059 0.218626 0.314727 0.221671 0.313416 0.2199079 0.317059 0.2184669 0.314809 0.218626 0.314727 0.2199079 0.317059 0.221671 0.313416 0.223105 0.315641 0.217481 0.31855 0.2184669 0.314809 0.2199079 0.317059 0.240481 0.228645 0.240481 0.2154 0.242174 0.209159 0.242174 0.234887 0.240481 0.228645 0.242174 0.209159 0.240481 0.228645 0.2399049 0.222023 0.240481 0.2154 0.242327 0.313718 0.244105 0.314924 0.23702 0.316121 0.235092 0.314923 0.23702 0.316121 0.231409 0.317317 0.235092 0.314923 0.242327 0.313718 0.23702 0.316121 0.229273 0.31614 0.231409 0.317317 0.227309 0.318586 0.229273 0.31614 0.235092 0.314923 0.231409 0.317317 0.225005 0.317433 0.227309 0.318586 0.224276 0.319993 0.225005 0.317433 0.229273 0.31614 0.227309 0.318586 0.221882 0.318853 0.224276 0.319993 0.221948 0.321493 0.221882 0.318853 0.225005 0.317433 0.224276 0.319993 0.219499 0.320354 0.221882 0.318853 0.221948 0.321493 0.205438 0.334074 0.219499 0.320354 0.221948 0.321493 0.240854 0.311916 0.242327 0.313718 0.235092 0.314923 0.233496 0.313119 0.235092 0.314923 0.229273 0.31614 0.233496 0.313119 0.240854 0.311916 0.235092 0.314923 0.227509 0.314341 0.229273 0.31614 0.225005 0.317433 0.227509 0.314341 0.233496 0.313119 0.229273 0.31614 0.223105 0.315641 0.225005 0.317433 0.221882 0.318853 0.223105 0.315641 0.227509 0.314341 0.225005 0.317433 0.2199079 0.317059 0.221882 0.318853 0.219499 0.320354 0.2199079 0.317059 0.223105 0.315641 0.221882 0.318853 0.217481 0.31855 0.2199079 0.317059 0.219499 0.320354 0.202764 0.332838 0.217481 0.31855 0.219499 0.320354 0.205438 0.334074 0.202764 0.332838 0.219499 0.320354 0.202764 0.332838 0.200549 0.330885 0.217481 0.31855 0.132332 0.391098 0.1292099 0.388429 0.157709 0.364589 0.160456 0.366959 0.157709 0.364589 0.180965 0.345903 0.160456 0.366959 0.132332 0.391098 0.157709 0.364589 0.183417 0.348041 0.180965 0.345903 0.200549 0.330885 0.183417 0.348041 0.160456 0.366959 0.180965 0.345903 0.202764 0.332838 0.183417 0.348041 0.200549 0.330885 0.136059 0.392808 0.132332 0.391098 0.160456 0.366959 0.163748 0.368467 0.160456 0.366959 0.183417 0.348041 0.163748 0.368467 0.136059 0.392808 0.160456 0.366959 0.186367 0.349397 0.183417 0.348041 0.202764 0.332838 0.186367 0.349397 0.163748 0.368467 0.183417 0.348041 0.205438 0.334074 0.186367 0.349397 0.202764 0.332838 0.205373 0.433779 0.205032 0.433806 0.203145 0.433119 0.203388 0.433068 0.203145 0.433119 0.201061 0.432429 0.203388 0.433068 0.205373 0.433779 0.203145 0.433119 0.201427 0.432348 0.201061 0.432429 0.199009 0.431733 0.201427 0.432348 0.203388 0.433068 0.201061 0.432429 0.1995 0.43162 0.199009 0.431733 0.196994 0.431033 0.1995 0.43162 0.201427 0.432348 0.199009 0.431733 0.197611 0.430884 0.196994 0.431033 0.195022 0.430331 0.197611 0.430884 0.1995 0.43162 0.196994 0.431033 0.195766 0.430144 0.195022 0.430331 0.193093 0.429625 0.195766 0.430144 0.197611 0.430884 0.195022 0.430331 0.193964 0.429397 0.193093 0.429625 0.191207 0.428915 0.193964 0.429397 0.195766 0.430144 0.193093 0.429625 0.192206 0.428645 0.191207 0.428915 0.189366 0.428202 0.192206 0.428645 0.193964 0.429397 0.191207 0.428915 0.190493 0.427886 0.189366 0.428202 0.18757 0.427485 0.190493 0.427886 0.192206 0.428645 0.189366 0.428202 0.188826 0.427121 0.18757 0.427485 0.18582 0.426763 0.188826 0.427121 0.190493 0.427886 0.18757 0.427485 0.187206 0.426349 0.18582 0.426763 0.184119 0.426037 0.187206 0.426349 0.188826 0.427121 0.18582 0.426763 0.185635 0.42557 0.184119 0.426037 0.1824679 0.425306 0.185635 0.42557 0.187206 0.426349 0.184119 0.426037 0.184113 0.424785 0.1824679 0.425306 0.180867 0.424571 0.184113 0.424785 0.185635 0.42557 0.1824679 0.425306 0.1826429 0.423993 0.180867 0.424571 0.179319 0.42383 0.1826429 0.423993 0.184113 0.424785 0.180867 0.424571 0.181225 0.423194 0.179319 0.42383 0.177825 0.423084 0.181225 0.423194 0.1826429 0.423993 0.179319 0.42383 0.1798599 0.422388 0.177825 0.423084 0.1763859 0.422333 0.1798599 0.422388 0.181225 0.423194 0.177825 0.423084 0.17855 0.421575 0.1763859 0.422333 0.175004 0.421577 0.17855 0.421575 0.1798599 0.422388 0.1763859 0.422333 0.177296 0.420755 0.175004 0.421577 0.173681 0.420815 0.177296 0.420755 0.17855 0.421575 0.175004 0.421577 0.176101 0.419928 0.173681 0.420815 0.17242 0.420047 0.176101 0.419928 0.177296 0.420755 0.173681 0.420815 0.174966 0.419095 0.17242 0.420047 0.171221 0.419275 0.174966 0.419095 0.176101 0.419928 0.17242 0.420047 0.173892 0.418255 0.171221 0.419275 0.1700879 0.418497 0.173892 0.418255 0.174966 0.419095 0.171221 0.419275 0.172882 0.417408 0.1700879 0.418497 0.169021 0.417714 0.172882 0.417408 0.173892 0.418255 0.1700879 0.418497 0.171937 0.416555 0.169021 0.417714 0.168023 0.416926 0.171937 0.416555 0.172882 0.417408 0.169021 0.417714 0.1710579 0.415696 0.168023 0.416926 0.167096 0.416134 0.1710579 0.415696 0.171937 0.416555 0.168023 0.416926 0.170248 0.414831 0.167096 0.416134 0.166242 0.415336 0.170248 0.414831 0.1710579 0.415696 0.167096 0.416134 0.169508 0.413961 0.166242 0.415336 0.165462 0.414534 0.169508 0.413961 0.170248 0.414831 0.166242 0.415336 0.168839 0.413085 0.165462 0.414534 0.164759 0.413727 0.168839 0.413085 0.169508 0.413961 0.165462 0.414534 0.168245 0.412204 0.164759 0.413727 0.164135 0.412917 0.168245 0.412204 0.168839 0.413085 0.164759 0.413727 0.167726 0.411319 0.164135 0.412917 0.163592 0.412102 0.167726 0.411319 0.168245 0.412204 0.164135 0.412917 0.1672829 0.410429 0.163592 0.412102 0.1631309 0.411284 0.1672829 0.410429 0.167726 0.411319 0.163592 0.412102 0.16692 0.409534 0.1631309 0.411284 0.162755 0.410463 0.16692 0.409534 0.1672829 0.410429 0.1631309 0.411284 0.166636 0.408636 0.162755 0.410463 0.162465 0.409638 0.166636 0.408636 0.16692 0.409534 0.162755 0.410463 0.166435 0.407735 0.162465 0.409638 0.162263 0.408812 0.166435 0.407735 0.166636 0.408636 0.162465 0.409638 0.166317 0.406831 0.162263 0.408812 0.16215 0.407983 0.166317 0.406831 0.166435 0.407735 0.162263 0.408812 0.166283 0.405924 0.16215 0.407983 0.162227 0.40712 0.166283 0.405924 0.166317 0.406831 0.16215 0.407983 0.165331 0.02667999 0.177215 0.406904 0.177328 0.03726589 0.166499 0.404899 0.166283 0.405924 0.162227 0.40712 0.204338 0.433297 0.205373 0.433779 0.203388 0.433068 0.204338 0.433297 0.205853 0.433893 0.205373 0.433779 0.202285 0.432462 0.203388 0.433068 0.201427 0.432348 0.224198 0.193901 0.221928 0.277544 0.224207 0.249981 0.204155 0.433224 0.204338 0.433297 0.203388 0.433068 0.202285 0.432462 0.204155 0.433224 0.203388 0.433068 0.200432 0.431659 0.201427 0.432348 0.1995 0.43162 0.200432 0.431659 0.202285 0.432462 0.201427 0.432348 0.198703 0.430894 0.1995 0.43162 0.197611 0.430884 0.198703 0.430894 0.200432 0.431659 0.1995 0.43162 0.196921 0.43011 0.197611 0.430884 0.195766 0.430144 0.196921 0.43011 0.198703 0.430894 0.197611 0.430884 0.195219 0.429304 0.195766 0.430144 0.193964 0.429397 0.195219 0.429304 0.196921 0.43011 0.195766 0.430144 0.193562 0.428488 0.193964 0.429397 0.192206 0.428645 0.193562 0.428488 0.195219 0.429304 0.193964 0.429397 0.19195 0.42766 0.192206 0.428645 0.190493 0.427886 0.19195 0.42766 0.193562 0.428488 0.192206 0.428645 0.190383 0.426822 0.190493 0.427886 0.188826 0.427121 0.190383 0.426822 0.19195 0.42766 0.190493 0.427886 0.188929 0.425927 0.188826 0.427121 0.187206 0.426349 0.188929 0.425927 0.190383 0.426822 0.188826 0.427121 0.187393 0.425112 0.187206 0.426349 0.185635 0.42557 0.187393 0.425112 0.188929 0.425927 0.187206 0.426349 0.18597 0.42424 0.185635 0.42557 0.184113 0.424785 0.18597 0.42424 0.187393 0.425112 0.185635 0.42557 0.184598 0.423359 0.184113 0.424785 0.1826429 0.423993 0.184598 0.423359 0.18597 0.42424 0.184113 0.424785 0.183396 0.422414 0.1826429 0.423993 0.181225 0.423194 0.183396 0.422414 0.184598 0.423359 0.1826429 0.423993 0.182008 0.421563 0.181225 0.423194 0.1798599 0.422388 0.182008 0.421563 0.183396 0.422414 0.181225 0.423194 0.180792 0.420649 0.1798599 0.422388 0.17855 0.421575 0.180792 0.420649 0.182008 0.421563 0.1798599 0.422388 0.1796309 0.419725 0.17855 0.421575 0.177296 0.420755 0.1796309 0.419725 0.180792 0.420649 0.17855 0.421575 0.178526 0.418791 0.177296 0.420755 0.176101 0.419928 0.178526 0.418791 0.1796309 0.419725 0.177296 0.420755 0.177478 0.417848 0.176101 0.419928 0.174966 0.419095 0.177478 0.417848 0.178526 0.418791 0.176101 0.419928 0.1764889 0.416895 0.174966 0.419095 0.173892 0.418255 0.1764889 0.416895 0.177478 0.417848 0.174966 0.419095 0.1755599 0.415934 0.173892 0.418255 0.172882 0.417408 0.1755599 0.415934 0.1764889 0.416895 0.173892 0.418255 0.174693 0.414963 0.172882 0.417408 0.171937 0.416555 0.174693 0.414963 0.1755599 0.415934 0.172882 0.417408 0.173888 0.413985 0.171937 0.416555 0.1710579 0.415696 0.173888 0.413985 0.174693 0.414963 0.171937 0.416555 0.173149 0.412999 0.1710579 0.415696 0.170248 0.414831 0.173149 0.412999 0.173888 0.413985 0.1710579 0.415696 0.172475 0.412005 0.170248 0.414831 0.169508 0.413961 0.172475 0.412005 0.173149 0.412999 0.170248 0.414831 0.171869 0.411005 0.169508 0.413961 0.168839 0.413085 0.171869 0.411005 0.172475 0.412005 0.169508 0.413961 0.171332 0.409998 0.168839 0.413085 0.168245 0.412204 0.171332 0.409998 0.171869 0.411005 0.168839 0.413085 0.1708649 0.408985 0.168245 0.412204 0.167726 0.411319 0.1708649 0.408985 0.171332 0.409998 0.168245 0.412204 0.170471 0.407966 0.167726 0.411319 0.1672829 0.410429 0.170471 0.407966 0.1708649 0.408985 0.167726 0.411319 0.17015 0.406942 0.1672829 0.410429 0.16692 0.409534 0.17015 0.406942 0.170471 0.407966 0.1672829 0.410429 0.1699039 0.405914 0.16692 0.409534 0.166636 0.408636 0.1699039 0.405914 0.17015 0.406942 0.16692 0.409534 0.169734 0.404881 0.166636 0.408636 0.166435 0.407735 0.169734 0.404881 0.1699039 0.405914 0.166636 0.408636 0.169642 0.403845 0.166435 0.407735 0.166317 0.406831 0.169642 0.403845 0.169734 0.404881 0.166435 0.407735 0.16963 0.402806 0.166317 0.406831 0.166283 0.405924 0.16963 0.402806 0.169642 0.403845 0.166317 0.406831 0.16963 0.402806 0.166283 0.405924 0.166499 0.404899 0.152405 0.020738 0.165178 0.417468 0.165331 0.02667999 0.1696979 0.401764 0.16963 0.402806 0.166499 0.404899 0.206154 0.433996 0.205853 0.433893 0.204338 0.433297 0.203212 0.432838 0.204155 0.433224 0.202285 0.432462 0.201961 0.432312 0.202285 0.432462 0.200432 0.431659 0.201961 0.432312 0.203212 0.432838 0.202285 0.432462 0.152405 0.020738 0.152242 0.42335 0.165178 0.417468 0.13882 0.02003395 0.152242 0.42335 0.152405 0.020738 0.124932 0.02512598 0.138685 0.423991 0.13882 0.02003395 0.13882 0.02003395 0.138685 0.423991 0.152242 0.42335 0.196727 0.429984 0.196921 0.43011 0.195219 0.429304 0.196727 0.429984 0.198703 0.430894 0.196921 0.43011 0.19442 0.428867 0.195219 0.429304 0.193562 0.428488 0.195488 0.429392 0.196727 0.429984 0.195219 0.429304 0.19442 0.428867 0.195488 0.429392 0.195219 0.429304 0.193005 0.428151 0.193562 0.428488 0.19195 0.42766 0.193005 0.428151 0.19442 0.428867 0.193562 0.428488 0.191465 0.42734 0.19195 0.42766 0.190383 0.426822 0.192358 0.427814 0.193005 0.428151 0.19195 0.42766 0.191465 0.42734 0.192358 0.427814 0.19195 0.42766 0.190107 0.426597 0.190383 0.426822 0.188929 0.425927 0.190107 0.426597 0.191465 0.42734 0.190383 0.426822 0.111195 0.03646188 0.12486 0.418879 0.124932 0.02512598 0.124932 0.02512598 0.12486 0.418879 0.138685 0.423991 0.186516 0.424477 0.187393 0.425112 0.18597 0.42424 0.187735 0.425224 0.188929 0.425927 0.187393 0.425112 0.186516 0.424477 0.187735 0.425224 0.187393 0.425112 0.185555 0.423867 0.18597 0.42424 0.184598 0.423359 0.185555 0.423867 0.186516 0.424477 0.18597 0.42424 0.184502 0.423173 0.184598 0.423359 0.183396 0.422414 0.184502 0.423173 0.185555 0.423867 0.184598 0.423359 0.182657 0.421888 0.183396 0.422414 0.182008 0.421563 0.09815096 0.05426889 0.09822797 0.389906 0.111195 0.03646188 0.111195 0.03646188 0.111204 0.407595 0.12486 0.418879 0.181199 0.420798 0.182008 0.421563 0.180792 0.420649 0.182217 0.421566 0.182657 0.421888 0.182008 0.421563 0.181199 0.420798 0.182217 0.421566 0.182008 0.421563 0.180052 0.419887 0.180792 0.420649 0.1796309 0.419725 0.180052 0.419887 0.181199 0.420798 0.180792 0.420649 0.1788769 0.418896 0.1796309 0.419725 0.178526 0.418791 0.1788769 0.418896 0.180052 0.419887 0.1796309 0.419725 0.177811 0.417935 0.178526 0.418791 0.177478 0.417848 0.177811 0.417935 0.1788769 0.418896 0.178526 0.418791 0.17696 0.41712 0.177478 0.417848 0.1764889 0.416895 0.17696 0.41712 0.177811 0.417935 0.177478 0.417848 0.176272 0.416423 0.1764889 0.416895 0.1755599 0.415934 0.176272 0.416423 0.17696 0.41712 0.1764889 0.416895 0.175485 0.415578 0.1755599 0.415934 0.174693 0.414963 0.176168 0.416315 0.176272 0.416423 0.1755599 0.415934 0.175485 0.415578 0.176168 0.416315 0.1755599 0.415934 0.174741 0.414722 0.174693 0.414963 0.173888 0.413985 0.174741 0.414722 0.175485 0.415578 0.174693 0.414963 0.173967 0.413757 0.173888 0.413985 0.173149 0.412999 0.173967 0.413757 0.174741 0.414722 0.173888 0.413985 0.1727409 0.412023 0.173149 0.412999 0.172475 0.412005 0.173352 0.412926 0.173967 0.413757 0.173149 0.412999 0.1727409 0.412023 0.173352 0.412926 0.173149 0.412999 0.172299 0.41131 0.172475 0.412005 0.171869 0.411005 0.172299 0.41131 0.1727409 0.412023 0.172475 0.412005 0.171581 0.410001 0.171869 0.411005 0.171332 0.409998 0.172142 0.411043 0.172299 0.41131 0.171869 0.411005 0.171581 0.410001 0.172142 0.411043 0.171869 0.411005 0.17106 0.408874 0.171332 0.409998 0.1708649 0.408985 0.17106 0.408874 0.171581 0.410001 0.171332 0.409998 0.170718 0.408002 0.1708649 0.408985 0.170471 0.407966 0.170718 0.408002 0.17106 0.408874 0.1708649 0.408985 0.170411 0.407066 0.170471 0.407966 0.17015 0.406942 0.170411 0.407066 0.170718 0.408002 0.170471 0.407966 0.17022 0.406363 0.17015 0.406942 0.1699039 0.405914 0.17022 0.406363 0.170411 0.407066 0.17015 0.406942 0.169955 0.405021 0.1699039 0.405914 0.169734 0.404881 0.170152 0.406072 0.17022 0.406363 0.1699039 0.405914 0.169955 0.405021 0.170152 0.406072 0.1699039 0.405914 0.169832 0.403915 0.169734 0.404881 0.169642 0.403845 0.169832 0.403915 0.169955 0.405021 0.169734 0.404881 0.169798 0.402753 0.169642 0.403845 0.16963 0.402806 0.169798 0.402753 0.169832 0.403915 0.169642 0.403845 0.169798 0.402753 0.16963 0.402806 0.1696979 0.401764 0.191705 0.418687 0.192358 0.427814 0.191465 0.42734 0.191705 0.418687 0.191465 0.42734 0.190107 0.426597 0.191705 0.418687 0.190107 0.426597 0.188929 0.425927 0.191705 0.418687 0.188929 0.425927 0.187735 0.425224 0.191705 0.418687 0.187735 0.425224 0.186516 0.424477 0.191705 0.418687 0.186516 0.424477 0.185555 0.423867 0.191705 0.418687 0.185555 0.423867 0.184502 0.423173 0.191705 0.418687 0.184502 0.423173 0.183396 0.422414 0.191705 0.418687 0.183396 0.422414 0.182657 0.421888 0.185142 0.410324 0.182657 0.421888 0.182217 0.421566 0.185142 0.410324 0.191705 0.418687 0.182657 0.421888 0.185142 0.410324 0.182217 0.421566 0.181199 0.420798 0.185142 0.410324 0.181199 0.420798 0.180052 0.419887 0.185142 0.410324 0.180052 0.419887 0.1788769 0.418896 0.185142 0.410324 0.1788769 0.418896 0.177811 0.417935 0.185142 0.410324 0.177811 0.417935 0.17696 0.41712 0.185142 0.410324 0.17696 0.41712 0.176272 0.416423 0.180783 0.403836 0.176272 0.416423 0.176168 0.416315 0.180783 0.403836 0.185142 0.410324 0.176272 0.416423 0.180783 0.403836 0.176168 0.416315 0.175485 0.415578 0.180783 0.403836 0.175485 0.415578 0.174741 0.414722 0.180783 0.403836 0.174741 0.414722 0.173967 0.413757 0.180783 0.403836 0.173967 0.413757 0.173352 0.412926 0.180783 0.403836 0.173352 0.412926 0.1727409 0.412023 0.180783 0.403836 0.1727409 0.412023 0.172299 0.41131 0.178822 0.396451 0.172299 0.41131 0.172142 0.411043 0.178822 0.396451 0.180783 0.403836 0.172299 0.41131 0.178822 0.396451 0.172142 0.411043 0.171581 0.410001 0.178822 0.396451 0.171581 0.410001 0.17106 0.408874 0.178822 0.396451 0.17106 0.408874 0.170718 0.408002 0.178822 0.396451 0.170718 0.408002 0.170411 0.407066 0.178822 0.396451 0.170411 0.407066 0.17022 0.406363 0.178688 0.389065 0.17022 0.406363 0.170152 0.406072 0.178822 0.396451 0.17022 0.406363 0.178688 0.389065 0.178688 0.389065 0.170152 0.406072 0.169955 0.405021 0.178688 0.389065 0.169955 0.405021 0.169832 0.403915 0.178688 0.389065 0.169832 0.403915 0.169798 0.402753 0.187018 0.380105 0.178688 0.389065 0.188655 0.370361 0.178822 0.396451 0.178688 0.389065 0.187018 0.380105 0.196482 0.362544 0.188655 0.370361 0.199632 0.35055 0.187018 0.380105 0.188655 0.370361 0.196482 0.362544 0.206799 0.344015 0.199632 0.35055 0.211179 0.329864 0.196482 0.362544 0.199632 0.35055 0.206799 0.344015 0.217592 0.324718 0.211179 0.329864 0.222921 0.308472 0.206799 0.344015 0.211179 0.329864 0.217592 0.324718 0.228542 0.304801 0.222921 0.308472 0.234544 0.286502 0.217592 0.324718 0.222921 0.308472 0.228542 0.304801 0.23938 0.284385 0.234544 0.286502 0.245798 0.264049 0.228542 0.304801 0.234544 0.286502 0.23938 0.284385 0.24989 0.26356 0.245798 0.264049 0.256474 0.241186 0.23938 0.284385 0.245798 0.264049 0.24989 0.26356 0.24989 0.26356 0.256474 0.241186 0.259891 0.242404 0.272602 0.2475759 0.28144 0.251348 0.270178 0.271482 0.261741 0.268413 0.270178 0.271482 0.258564 0.291199 0.261741 0.268413 0.272602 0.2475759 0.270178 0.271482 0.250446 0.288883 0.258564 0.291199 0.246834 0.310419 0.250446 0.288883 0.261741 0.268413 0.258564 0.291199 0.2389439 0.308891 0.246834 0.310419 0.235265 0.32905 0.2389439 0.308891 0.250446 0.288883 0.246834 0.310419 0.2275069 0.328327 0.235265 0.32905 0.224201 0.346964 0.2275069 0.328327 0.2389439 0.308891 0.235265 0.32905 0.216475 0.347045 0.224201 0.346964 0.214047 0.364001 0.216475 0.347045 0.2275069 0.328327 0.224201 0.346964 0.206251 0.364862 0.214047 0.364001 0.205269 0.37995 0.206251 0.364862 0.216475 0.347045 0.214047 0.364001 0.197302 0.381542 0.205269 0.37995 0.198356 0.394553 0.197302 0.381542 0.206251 0.364862 0.205269 0.37995 0.1901209 0.396795 0.198356 0.394553 0.193742 0.407543 0.1901209 0.396795 0.197302 0.381542 0.198356 0.394553 0.185142 0.410324 0.193742 0.407543 0.191705 0.418687 0.185142 0.410324 0.1901209 0.396795 0.193742 0.407543 0.265325 0.244556 0.272602 0.2475759 0.261741 0.268413 0.2454 0.283982 0.261741 0.268413 0.250446 0.288883 0.255583 0.264417 0.265325 0.244556 0.261741 0.268413 0.2454 0.283982 0.255583 0.264417 0.261741 0.268413 0.234943 0.303179 0.250446 0.288883 0.2389439 0.308891 0.234943 0.303179 0.2454 0.283982 0.250446 0.288883 0.224411 0.321921 0.2389439 0.308891 0.2275069 0.328327 0.224411 0.321921 0.234943 0.303179 0.2389439 0.308891 0.214051 0.340096 0.2275069 0.328327 0.216475 0.347045 0.214051 0.340096 0.224411 0.321921 0.2275069 0.328327 0.204152 0.35757 0.216475 0.347045 0.206251 0.364862 0.204152 0.35757 0.214051 0.340096 0.216475 0.347045 0.195056 0.374168 0.206251 0.364862 0.197302 0.381542 0.195056 0.374168 0.204152 0.35757 0.206251 0.364862 0.187142 0.389671 0.197302 0.381542 0.1901209 0.396795 0.187142 0.389671 0.195056 0.374168 0.197302 0.381542 0.180783 0.403836 0.1901209 0.396795 0.185142 0.410324 0.180783 0.403836 0.187142 0.389671 0.1901209 0.396795 0.259891 0.242404 0.265325 0.244556 0.255583 0.264417 0.24989 0.26356 0.255583 0.264417 0.2454 0.283982 0.24989 0.26356 0.259891 0.242404 0.255583 0.264417 0.23938 0.284385 0.2454 0.283982 0.234943 0.303179 0.23938 0.284385 0.24989 0.26356 0.2454 0.283982 0.228542 0.304801 0.234943 0.303179 0.224411 0.321921 0.228542 0.304801 0.23938 0.284385 0.234943 0.303179 0.217592 0.324718 0.224411 0.321921 0.214051 0.340096 0.217592 0.324718 0.228542 0.304801 0.224411 0.321921 0.206799 0.344015 0.214051 0.340096 0.204152 0.35757 0.206799 0.344015 0.217592 0.324718 0.214051 0.340096 0.196482 0.362544 0.204152 0.35757 0.195056 0.374168 0.196482 0.362544 0.206799 0.344015 0.204152 0.35757 0.187018 0.380105 0.195056 0.374168 0.187142 0.389671 0.187018 0.380105 0.196482 0.362544 0.195056 0.374168 0.178822 0.396451 0.187142 0.389671 0.180783 0.403836 0.178822 0.396451 0.187018 0.380105 0.187142 0.389671 0.151167 0.284033 0.151011 0.285501 0.148974 0.285 0.1627579 0.282077 0.151011 0.285501 0.151167 0.284033 0.1627579 0.282077 0.162071 0.283495 0.151011 0.285501 0.1492159 0.283502 0.148974 0.285 0.146685 0.282783 0.1492159 0.283502 0.151167 0.284033 0.148974 0.285 0.144881 0.277534 0.146685 0.282783 0.144279 0.278859 0.147088 0.281327 0.1492159 0.283502 0.146685 0.282783 0.144881 0.277534 0.147088 0.281327 0.146685 0.282783 0.142722 0.272258 0.144279 0.278859 0.141915 0.273378 0.142722 0.272258 0.144881 0.277534 0.144279 0.278859 0.140768 0.265763 0.141915 0.273378 0.139778 0.266611 0.140768 0.265763 0.142722 0.272258 0.141915 0.273378 0.1398929 0.262049 0.139778 0.266611 0.138014 0.258775 0.1398929 0.262049 0.140768 0.265763 0.139778 0.266611 0.1398929 0.262049 0.138014 0.258775 0.139111 0.258105 0.136527 0.24035 0.139111 0.258105 0.138014 0.258775 0.136527 0.24035 0.138014 0.258775 0.1354539 0.240661 0.148294 0.253512 0.1398929 0.262049 0.139111 0.258105 0.143453 0.25283 0.139111 0.258105 0.136527 0.24035 0.143453 0.25283 0.148294 0.253512 0.139111 0.258105 0.154223 0.269357 0.151167 0.284033 0.1492159 0.283502 0.164863 0.267029 0.1627579 0.282077 0.151167 0.284033 0.154223 0.269357 0.164863 0.267029 0.151167 0.284033 0.152846 0.268888 0.1492159 0.283502 0.147088 0.281327 0.153536 0.269313 0.154223 0.269357 0.1492159 0.283502 0.152846 0.268888 0.153536 0.269313 0.1492159 0.283502 0.151493 0.26691 0.147088 0.281327 0.144881 0.277534 0.152161 0.268082 0.152846 0.268888 0.147088 0.281327 0.151493 0.26691 0.152161 0.268082 0.147088 0.281327 0.150239 0.263546 0.144881 0.277534 0.142722 0.272258 0.150849 0.265393 0.151493 0.26691 0.144881 0.277534 0.150239 0.263546 0.150849 0.265393 0.144881 0.277534 0.149155 0.259021 0.142722 0.272258 0.140768 0.265763 0.149155 0.259021 0.150239 0.263546 0.142722 0.272258 0.148294 0.253512 0.140768 0.265763 0.1398929 0.262049 0.148294 0.253512 0.149155 0.259021 0.140768 0.265763 0.135667 0.222041 0.1354539 0.240661 0.134596 0.222034 0.135667 0.222041 0.136527 0.24035 0.1354539 0.240661 0.136524 0.2037259 0.134596 0.222034 0.135453 0.2034 0.136524 0.2037259 0.135667 0.222041 0.134596 0.222034 0.136524 0.2037259 0.135453 0.2034 0.138014 0.185271 0.136524 0.2037259 0.138014 0.185271 0.139111 0.18594 0.139777 0.177438 0.139111 0.18594 0.138014 0.185271 0.147864 0.209508 0.136524 0.2037259 0.139111 0.18594 0.139891 0.182005 0.139111 0.18594 0.139777 0.177438 0.143453 0.191215 0.139111 0.18594 0.139891 0.182005 0.143453 0.191215 0.147864 0.209508 0.139111 0.18594 0.147864 0.232931 0.136527 0.24035 0.135667 0.222041 0.143453 0.25283 0.136527 0.24035 0.147745 0.247598 0.147864 0.232931 0.147745 0.247598 0.136527 0.24035 0.147918 0.221107 0.135667 0.222041 0.136524 0.2037259 0.147864 0.232931 0.135667 0.222041 0.147918 0.221107 0.147918 0.221107 0.136524 0.2037259 0.147864 0.209508 0.140765 0.178293 0.139777 0.177438 0.141914 0.1706719 0.140765 0.178293 0.139891 0.182005 0.139777 0.177438 0.142719 0.171797 0.141914 0.1706719 0.144277 0.16519 0.1417109 0.174897 0.140765 0.178293 0.141914 0.1706719 0.142719 0.171797 0.1417109 0.174897 0.141914 0.1706719 0.144879 0.1665149 0.144277 0.16519 0.146684 0.161265 0.143783 0.168986 0.142719 0.171797 0.144277 0.16519 0.144879 0.1665149 0.143783 0.168986 0.144277 0.16519 0.147088 0.162719 0.146684 0.161265 0.148972 0.159047 0.145986 0.16442 0.144879 0.1665149 0.146684 0.161265 0.147088 0.162719 0.145986 0.16442 0.146684 0.161265 0.150219 0.160069 0.148972 0.159047 0.151011 0.158544 0.148169 0.161427 0.147088 0.162719 0.148972 0.159047 0.1492159 0.160544 0.148169 0.161427 0.148972 0.159047 0.150219 0.160069 0.1492159 0.160544 0.148972 0.159047 0.150219 0.160069 0.151011 0.158544 0.151167 0.160013 0.162071 0.1605499 0.151167 0.160013 0.151011 0.158544 0.153527 0.174736 0.150219 0.160069 0.151167 0.160013 0.1627579 0.161969 0.151167 0.160013 0.162071 0.1605499 0.154223 0.1746889 0.151167 0.160013 0.1627579 0.161969 0.154223 0.1746889 0.153527 0.174736 0.151167 0.160013 0.148292 0.19055 0.139891 0.182005 0.140765 0.178293 0.143453 0.191215 0.139891 0.182005 0.147745 0.196448 0.14798 0.193482 0.147745 0.196448 0.139891 0.182005 0.148292 0.19055 0.14798 0.193482 0.139891 0.182005 0.148683 0.187731 0.140765 0.178293 0.1417109 0.174897 0.148683 0.187731 0.148292 0.19055 0.140765 0.178293 0.149139 0.185108 0.1417109 0.174897 0.142719 0.171797 0.149139 0.185108 0.148683 0.187731 0.1417109 0.174897 0.149649 0.1827329 0.142719 0.171797 0.143783 0.168986 0.149649 0.1827329 0.149139 0.185108 0.142719 0.171797 0.150209 0.1806 0.143783 0.168986 0.144879 0.1665149 0.150209 0.1806 0.149649 0.1827329 0.143783 0.168986 0.1508229 0.178724 0.144879 0.1665149 0.145986 0.16442 0.1508229 0.178724 0.150209 0.1806 0.144879 0.1665149 0.151472 0.177179 0.145986 0.16442 0.147088 0.162719 0.151472 0.177179 0.1508229 0.178724 0.145986 0.16442 0.152142 0.175992 0.147088 0.162719 0.148169 0.161427 0.152142 0.175992 0.151472 0.177179 0.147088 0.162719 0.152829 0.175172 0.148169 0.161427 0.1492159 0.160544 0.152829 0.175172 0.152142 0.175992 0.148169 0.161427 0.153527 0.174736 0.1492159 0.160544 0.150219 0.160069 0.153527 0.174736 0.152829 0.175172 0.1492159 0.160544 0.1627579 0.161969 0.162071 0.1605499 0.172246 0.162779 0.173027 0.164113 0.172246 0.162779 0.181622 0.165302 0.173027 0.164113 0.1627579 0.161969 0.172246 0.162779 0.182151 0.166479 0.181622 0.165302 0.1902649 0.168208 0.182151 0.166479 0.173027 0.164113 0.181622 0.165302 0.182151 0.166479 0.1902649 0.168208 0.190271 0.169097 0.191488 0.169333 0.190271 0.169097 0.1902649 0.168208 0.183369 0.181087 0.182151 0.166479 0.190271 0.169097 0.190917 0.169488 0.190271 0.169097 0.191488 0.169333 0.191461 0.182874 0.190271 0.169097 0.190917 0.169488 0.183369 0.181087 0.190271 0.169097 0.191461 0.182874 0.174537 0.179141 0.1627579 0.161969 0.173027 0.164113 0.164863 0.177017 0.154223 0.1746889 0.1627579 0.161969 0.164863 0.177017 0.1627579 0.161969 0.174537 0.179141 0.183369 0.181087 0.173027 0.164113 0.182151 0.166479 0.174537 0.179141 0.173027 0.164113 0.183369 0.181087 0.191484 0.170209 0.191488 0.169333 0.192381 0.171692 0.191484 0.170209 0.190917 0.169488 0.191488 0.169333 0.19236 0.172541 0.192381 0.171692 0.192939 0.17524 0.191965 0.171237 0.191484 0.170209 0.192381 0.171692 0.19236 0.172541 0.191965 0.171237 0.192381 0.171692 0.193082 0.178112 0.192939 0.17524 0.193192 0.179843 0.1926749 0.174133 0.19236 0.172541 0.192939 0.17524 0.192914 0.175992 0.1926749 0.174133 0.192939 0.17524 0.193082 0.178112 0.192914 0.175992 0.192939 0.17524 0.193226 0.183001 0.193192 0.179843 0.19319 0.1853049 0.193185 0.180464 0.193082 0.178112 0.193192 0.179843 0.193226 0.183001 0.193185 0.180464 0.193192 0.179843 0.193146 0.188731 0.19319 0.1853049 0.192984 0.1914809 0.193212 0.1857579 0.193226 0.183001 0.19319 0.1853049 0.193146 0.188731 0.193212 0.1857579 0.19319 0.1853049 0.193146 0.188731 0.192984 0.1914809 0.1930299 0.191852 0.192582 0.203565 0.1930299 0.191852 0.192984 0.1914809 0.192582 0.203565 0.192984 0.1914809 0.192522 0.203381 0.19481 0.199635 0.193146 0.188731 0.1930299 0.191852 0.193909 0.196922 0.1930299 0.191852 0.192582 0.203565 0.193909 0.196922 0.19481 0.199635 0.1930299 0.191852 0.192364 0.1836889 0.190917 0.169488 0.191484 0.170209 0.191916 0.183131 0.191461 0.182874 0.190917 0.169488 0.191916 0.183131 0.190917 0.169488 0.192364 0.1836889 0.192797 0.184547 0.191484 0.170209 0.191965 0.171237 0.192364 0.1836889 0.191484 0.170209 0.192797 0.184547 0.192797 0.184547 0.191965 0.171237 0.19236 0.172541 0.1932049 0.185692 0.19236 0.172541 0.1926749 0.174133 0.192797 0.184547 0.19236 0.172541 0.1932049 0.185692 0.1935819 0.187108 0.1926749 0.174133 0.192914 0.175992 0.1932049 0.185692 0.1926749 0.174133 0.1935819 0.187108 0.193919 0.188773 0.192914 0.175992 0.193082 0.178112 0.1935819 0.187108 0.192914 0.175992 0.193919 0.188773 0.1942059 0.19064 0.193082 0.178112 0.193185 0.180464 0.193919 0.188773 0.193082 0.178112 0.1942059 0.19064 0.194442 0.192685 0.193185 0.180464 0.193226 0.183001 0.1942059 0.19064 0.193185 0.180464 0.194442 0.192685 0.194624 0.1948969 0.193226 0.183001 0.193212 0.1857579 0.194442 0.192685 0.193226 0.183001 0.194624 0.1948969 0.194748 0.197235 0.193212 0.1857579 0.193146 0.188731 0.194624 0.1948969 0.193212 0.1857579 0.194748 0.197235 0.194748 0.197235 0.193146 0.188731 0.19481 0.199635 0.192309 0.21583 0.192522 0.203381 0.1922529 0.215773 0.192309 0.21583 0.192582 0.203565 0.192522 0.203381 0.192309 0.228188 0.1922529 0.215773 0.1922529 0.228244 0.192309 0.228188 0.192309 0.21583 0.1922529 0.215773 0.192582 0.24047 0.1922529 0.228244 0.192522 0.2406589 0.192582 0.24047 0.192309 0.228188 0.1922529 0.228244 0.192582 0.24047 0.192522 0.2406589 0.192984 0.252564 0.192582 0.24047 0.192984 0.252564 0.1930299 0.252194 0.19319 0.25874 0.1930299 0.252194 0.192984 0.252564 0.19482 0.234089 0.192582 0.24047 0.1930299 0.252194 0.193211 0.258257 0.1930299 0.252194 0.19319 0.25874 0.193909 0.247123 0.1930299 0.252194 0.193211 0.258257 0.193909 0.247123 0.19482 0.234089 0.1930299 0.252194 0.194824 0.212444 0.192582 0.203565 0.192309 0.21583 0.194824 0.212444 0.1948119 0.20204 0.192582 0.203565 0.193909 0.196922 0.192582 0.203565 0.1948119 0.20204 0.194828 0.2214339 0.192309 0.21583 0.192309 0.228188 0.194824 0.212444 0.192309 0.21583 0.194828 0.2214339 0.194826 0.227398 0.192309 0.228188 0.192582 0.24047 0.194828 0.2214339 0.192309 0.228188 0.194826 0.227398 0.194826 0.227398 0.192582 0.24047 0.19482 0.234089 0.193211 0.258257 0.19319 0.25874 0.193192 0.264201 0.193186 0.263552 0.193192 0.264201 0.192938 0.268805 0.193186 0.263552 0.193211 0.258257 0.193192 0.264201 0.1923609 0.271501 0.192938 0.268805 0.192381 0.272352 0.192916 0.268037 0.193186 0.263552 0.192938 0.268805 0.1923609 0.271501 0.192916 0.268037 0.192938 0.268805 0.191483 0.273839 0.192381 0.272352 0.191487 0.274711 0.191483 0.273839 0.1923609 0.271501 0.192381 0.272352 0.190916 0.274559 0.191487 0.274711 0.1902649 0.275836 0.190916 0.274559 0.191483 0.273839 0.191487 0.274711 0.190916 0.274559 0.1902649 0.275836 0.190271 0.274951 0.181622 0.278741 0.190271 0.274951 0.1902649 0.275836 0.192356 0.260371 0.190916 0.274559 0.190271 0.274951 0.182151 0.277567 0.190271 0.274951 0.181622 0.278741 0.191461 0.261172 0.190271 0.274951 0.182151 0.277567 0.192356 0.260371 0.190271 0.274951 0.191461 0.261172 0.1944479 0.251306 0.193211 0.258257 0.193186 0.263552 0.194747 0.2468309 0.1948119 0.242005 0.193211 0.258257 0.193909 0.247123 0.193211 0.258257 0.1948119 0.242005 0.194747 0.2468309 0.193211 0.258257 0.1944479 0.251306 0.194207 0.253403 0.193186 0.263552 0.192916 0.268037 0.1944479 0.251306 0.193186 0.263552 0.194207 0.253403 0.19357 0.256989 0.192916 0.268037 0.1923609 0.271501 0.19391 0.25532 0.192916 0.268037 0.19357 0.256989 0.194207 0.253403 0.192916 0.268037 0.19391 0.25532 0.193192 0.258396 0.1923609 0.271501 0.191483 0.273839 0.19357 0.256989 0.1923609 0.271501 0.193192 0.258396 0.192356 0.260371 0.191483 0.273839 0.190916 0.274559 0.192785 0.259527 0.191483 0.273839 0.192356 0.260371 0.193192 0.258396 0.191483 0.273839 0.192785 0.259527 0.173026 0.279933 0.181622 0.278741 0.172246 0.281266 0.173026 0.279933 0.182151 0.277567 0.181622 0.278741 0.1627579 0.282077 0.172246 0.281266 0.162071 0.283495 0.1627579 0.282077 0.173026 0.279933 0.172246 0.281266 0.183369 0.262959 0.182151 0.277567 0.173026 0.279933 0.183369 0.262959 0.191461 0.261172 0.182151 0.277567 0.174537 0.264904 0.173026 0.279933 0.1627579 0.282077 0.174537 0.264904 0.183369 0.262959 0.173026 0.279933 0.164863 0.267029 0.174537 0.264904 0.1627579 0.282077 0.154336 0.268634 0.191461 0.261172 0.183369 0.262959 0.154375 0.267908 0.191461 0.261172 0.154336 0.268634 0.191478 0.260918 0.191461 0.261172 0.154375 0.267908 0.192348 0.259873 0.191461 0.261172 0.191478 0.260918 0.192356 0.260371 0.191461 0.261172 0.192348 0.259873 0.154336 0.268634 0.183369 0.262959 0.174537 0.264904 0.154336 0.268634 0.174537 0.264904 0.164863 0.267029 0.154336 0.268634 0.164863 0.267029 0.154223 0.269357 0.154336 0.268634 0.154223 0.269357 0.153536 0.269313 0.153234 0.268319 0.153536 0.269313 0.152846 0.268888 0.153234 0.268319 0.154336 0.268634 0.153536 0.269313 0.153234 0.268319 0.152846 0.268888 0.152161 0.268082 0.152181 0.266959 0.152161 0.268082 0.151493 0.26691 0.152181 0.266959 0.153234 0.268319 0.152161 0.268082 0.151217 0.26463 0.151493 0.26691 0.150849 0.265393 0.151217 0.26463 0.152181 0.266959 0.151493 0.26691 0.151217 0.26463 0.150849 0.265393 0.150239 0.263546 0.15037 0.261407 0.150239 0.263546 0.149155 0.259021 0.15037 0.261407 0.151217 0.26463 0.150239 0.263546 0.149678 0.257392 0.149155 0.259021 0.148294 0.253512 0.149678 0.257392 0.15037 0.261407 0.149155 0.259021 0.143453 0.25283 0.147745 0.247598 0.148294 0.253512 0.1491799 0.252723 0.148294 0.253512 0.147745 0.247598 0.1491799 0.252723 0.149678 0.257392 0.148294 0.253512 0.1489109 0.247526 0.1491799 0.252723 0.147745 0.247598 0.148909 0.196519 0.1489109 0.247526 0.147745 0.247598 0.147864 0.232931 0.148909 0.196519 0.147745 0.247598 0.154375 0.267908 0.154336 0.268634 0.153234 0.268319 0.153174 0.267435 0.153234 0.268319 0.152181 0.266959 0.153174 0.267435 0.154375 0.267908 0.153234 0.268319 0.152034 0.265546 0.152181 0.266959 0.151217 0.26463 0.152034 0.265546 0.153174 0.267435 0.152181 0.266959 0.151042 0.262342 0.151217 0.26463 0.15037 0.261407 0.151042 0.262342 0.152034 0.265546 0.151217 0.26463 0.150272 0.258038 0.15037 0.261407 0.149678 0.257392 0.150272 0.258038 0.151042 0.262342 0.15037 0.261407 0.149781 0.252946 0.149678 0.257392 0.1491799 0.252723 0.149781 0.252946 0.150272 0.258038 0.149678 0.257392 0.149781 0.252946 0.1491799 0.252723 0.1489109 0.247526 0.1496 0.247442 0.149781 0.252946 0.1489109 0.247526 0.149559 0.222298 0.1496 0.247442 0.1489109 0.247526 0.149559 0.222298 0.1489109 0.247526 0.1496 0.196603 0.148909 0.196519 0.1496 0.196603 0.1489109 0.247526 0.154375 0.176138 0.154375 0.267908 0.153174 0.267435 0.1914809 0.260664 0.191478 0.260918 0.154375 0.267908 0.185954 0.237509 0.1914809 0.260664 0.154375 0.267908 0.160588 0.2002519 0.154375 0.267908 0.154375 0.176138 0.167758 0.238556 0.168357 0.237299 0.154375 0.267908 0.170462 0.238758 0.154375 0.267908 0.168357 0.237299 0.167105 0.239028 0.167758 0.238556 0.154375 0.267908 0.160588 0.239553 0.167105 0.239028 0.154375 0.267908 0.160588 0.2002519 0.160588 0.239553 0.154375 0.267908 0.170462 0.238758 0.17214 0.238623 0.154375 0.267908 0.1734679 0.238516 0.154375 0.267908 0.17214 0.238623 0.1734679 0.238516 0.175015 0.238391 0.154375 0.267908 0.1789219 0.238076 0.154375 0.267908 0.175015 0.238391 0.1789219 0.238076 0.185954 0.237509 0.154375 0.267908 0.153169 0.176614 0.153174 0.267435 0.152034 0.265546 0.153169 0.176614 0.154375 0.176138 0.153174 0.267435 0.152028 0.178513 0.152034 0.265546 0.151042 0.262342 0.152028 0.178513 0.153169 0.176614 0.152034 0.265546 0.151037 0.181727 0.151042 0.262342 0.150272 0.258038 0.151037 0.181727 0.152028 0.178513 0.151042 0.262342 0.150268 0.186035 0.150272 0.258038 0.149781 0.252946 0.150268 0.186035 0.151037 0.181727 0.150272 0.258038 0.149779 0.191118 0.149781 0.252946 0.1496 0.247442 0.149779 0.191118 0.150268 0.186035 0.149781 0.252946 0.149559 0.222298 0.1496 0.196603 0.1496 0.247442 0.149779 0.191118 0.1496 0.247442 0.1496 0.196603 0.192348 0.259873 0.191478 0.260918 0.1914809 0.260664 0.191482 0.183382 0.192348 0.259873 0.1914809 0.260664 0.186177 0.209478 0.191482 0.183382 0.1914809 0.260664 0.185954 0.237509 0.186177 0.209478 0.1914809 0.260664 0.149179 0.191319 0.149779 0.191118 0.1496 0.196603 0.149179 0.191319 0.1496 0.196603 0.148909 0.196519 0.192348 0.184172 0.193147 0.257909 0.192348 0.259873 0.192356 0.260371 0.192348 0.259873 0.193147 0.257909 0.191482 0.183382 0.192348 0.184172 0.192348 0.259873 0.193147 0.186137 0.193828 0.254921 0.193147 0.257909 0.193192 0.258396 0.193147 0.257909 0.193828 0.254921 0.192348 0.184172 0.193147 0.186137 0.193147 0.257909 0.192785 0.259527 0.192356 0.260371 0.193147 0.257909 0.193192 0.258396 0.192785 0.259527 0.193147 0.257909 0.194348 0.192936 0.194348 0.25111 0.193828 0.254921 0.19391 0.25532 0.193828 0.254921 0.194348 0.25111 0.193828 0.189126 0.194348 0.192936 0.193828 0.254921 0.193147 0.186137 0.193828 0.189126 0.193828 0.254921 0.19357 0.256989 0.193192 0.258396 0.193828 0.254921 0.19391 0.25532 0.19357 0.256989 0.193828 0.254921 0.1946769 0.197324 0.1946769 0.2467229 0.194348 0.25111 0.1944479 0.251306 0.194348 0.25111 0.1946769 0.2467229 0.194348 0.192936 0.1946769 0.197324 0.194348 0.25111 0.194207 0.253403 0.19391 0.25532 0.194348 0.25111 0.1944479 0.251306 0.194207 0.253403 0.194348 0.25111 0.194793 0.202013 0.194793 0.242032 0.1946769 0.2467229 0.194747 0.2468309 0.1946769 0.2467229 0.194793 0.242032 0.1946769 0.197324 0.194793 0.202013 0.1946769 0.2467229 0.194747 0.2468309 0.1944479 0.251306 0.1946769 0.2467229 0.194793 0.202013 0.194799 0.222275 0.194793 0.242032 0.194886 0.202026 0.194793 0.242032 0.194799 0.222275 0.194885 0.24202 0.194793 0.242032 0.194886 0.202026 0.194747 0.2468309 0.194793 0.242032 0.194885 0.24202 0.194886 0.202026 0.194799 0.222275 0.194793 0.202013 0.194886 0.202026 0.194793 0.202013 0.1946769 0.197324 0.194624 0.1948969 0.1946769 0.197324 0.194348 0.192936 0.1948119 0.20204 0.194886 0.202026 0.1946769 0.197324 0.19481 0.199635 0.1948119 0.20204 0.1946769 0.197324 0.194748 0.197235 0.19481 0.199635 0.1946769 0.197324 0.194624 0.1948969 0.194748 0.197235 0.1946769 0.197324 0.1942059 0.19064 0.194348 0.192936 0.193828 0.189126 0.194442 0.192685 0.194624 0.1948969 0.194348 0.192936 0.1942059 0.19064 0.194442 0.192685 0.194348 0.192936 0.1935819 0.187108 0.193828 0.189126 0.193147 0.186137 0.193919 0.188773 0.1942059 0.19064 0.193828 0.189126 0.1935819 0.187108 0.193919 0.188773 0.193828 0.189126 0.192797 0.184547 0.193147 0.186137 0.192348 0.184172 0.1932049 0.185692 0.1935819 0.187108 0.193147 0.186137 0.192797 0.184547 0.1932049 0.185692 0.193147 0.186137 0.191916 0.183131 0.192348 0.184172 0.191482 0.183382 0.192364 0.1836889 0.192797 0.184547 0.192348 0.184172 0.191916 0.183131 0.192364 0.1836889 0.192348 0.184172 0.160588 0.2002519 0.154375 0.176138 0.191482 0.183382 0.154336 0.175411 0.191482 0.183382 0.154375 0.176138 0.160588 0.2002519 0.191482 0.183382 0.162319 0.200425 0.170462 0.201238 0.162319 0.200425 0.191482 0.183382 0.17214 0.201406 0.170462 0.201238 0.191482 0.183382 0.1734679 0.201539 0.17214 0.201406 0.191482 0.183382 0.178134 0.202006 0.1734679 0.201539 0.191482 0.183382 0.178842 0.202077 0.178134 0.202006 0.191482 0.183382 0.186177 0.202812 0.178842 0.202077 0.191482 0.183382 0.186177 0.209478 0.186177 0.202812 0.191482 0.183382 0.191478 0.183127 0.191482 0.183382 0.154336 0.175411 0.191916 0.183131 0.191482 0.183382 0.191478 0.183127 0.154336 0.175411 0.154375 0.176138 0.153169 0.176614 0.152181 0.1770859 0.153169 0.176614 0.152028 0.178513 0.153234 0.175725 0.154336 0.175411 0.153169 0.176614 0.152181 0.1770859 0.153234 0.175725 0.153169 0.176614 0.151216 0.179416 0.152028 0.178513 0.151037 0.181727 0.151216 0.179416 0.152181 0.1770859 0.152028 0.178513 0.15037 0.182639 0.151037 0.181727 0.150268 0.186035 0.15037 0.182639 0.151216 0.179416 0.151037 0.181727 0.149678 0.186651 0.150268 0.186035 0.149779 0.191118 0.149678 0.186651 0.15037 0.182639 0.150268 0.186035 0.149179 0.191319 0.149678 0.186651 0.149779 0.191118 0.170462 0.201238 0.162319 0.2145259 0.162319 0.200425 0.170462 0.201238 0.16926 0.220779 0.168869 0.21829 0.170462 0.238758 0.169506 0.229941 0.170462 0.201238 0.175015 0.238391 0.175015 0.208748 0.178134 0.208952 0.1734679 0.201539 0.17214 0.238623 0.17214 0.201406 0.170462 0.201238 0.169506 0.223672 0.16926 0.220779 0.178842 0.208998 0.1789219 0.231157 0.175015 0.238391 0.1789219 0.238076 0.175015 0.238391 0.1789219 0.231157 0.167105 0.222023 0.162319 0.231918 0.162319 0.222023 0.167105 0.222023 0.167105 0.231699 0.162319 0.231918 0.167306 0.222126 0.167306 0.231586 0.167105 0.231699 0.167105 0.222023 0.167306 0.222126 0.167105 0.231699 0.16749 0.222397 0.16749 0.231308 0.167306 0.231586 0.167306 0.222126 0.16749 0.222397 0.167306 0.231586 0.167661 0.222843 0.167661 0.230854 0.16749 0.231308 0.16749 0.222397 0.167661 0.222843 0.16749 0.231308 0.16781 0.223435 0.16781 0.230255 0.167661 0.230854 0.167661 0.222843 0.16781 0.223435 0.167661 0.230854 0.167932 0.224158 0.167932 0.229526 0.16781 0.230255 0.16781 0.223435 0.167932 0.224158 0.16781 0.230255 0.168024 0.224982 0.168024 0.228698 0.167932 0.229526 0.167932 0.224158 0.168024 0.224982 0.167932 0.229526 0.168079 0.225872 0.168079 0.227806 0.168024 0.228698 0.168024 0.224982 0.168079 0.225872 0.168024 0.228698 0.168079 0.225872 0.1680999 0.2268379 0.168079 0.227806 0.147864 0.209508 0.147745 0.196448 0.148909 0.196519 0.14798 0.193482 0.148909 0.196519 0.147745 0.196448 0.147918 0.221107 0.147864 0.209508 0.148909 0.196519 0.147864 0.232931 0.147918 0.221107 0.148909 0.196519 0.149179 0.191319 0.148909 0.196519 0.14798 0.193482 0.143453 0.191215 0.147745 0.196448 0.147864 0.209508 0.149179 0.191319 0.14798 0.193482 0.148292 0.19055 0.149179 0.191319 0.148292 0.19055 0.148683 0.187731 0.149678 0.186651 0.148683 0.187731 0.149139 0.185108 0.149179 0.191319 0.148683 0.187731 0.149678 0.186651 0.149678 0.186651 0.149139 0.185108 0.149649 0.1827329 0.15037 0.182639 0.149649 0.1827329 0.150209 0.1806 0.149678 0.186651 0.149649 0.1827329 0.15037 0.182639 0.15037 0.182639 0.150209 0.1806 0.1508229 0.178724 0.151216 0.179416 0.1508229 0.178724 0.151472 0.177179 0.15037 0.182639 0.1508229 0.178724 0.151216 0.179416 0.152181 0.1770859 0.151472 0.177179 0.152142 0.175992 0.151216 0.179416 0.151472 0.177179 0.152181 0.1770859 0.152181 0.1770859 0.152142 0.175992 0.152829 0.175172 0.153234 0.175725 0.152829 0.175172 0.153527 0.174736 0.152181 0.1770859 0.152829 0.175172 0.153234 0.175725 0.153234 0.175725 0.153527 0.174736 0.154223 0.1746889 0.153234 0.175725 0.154223 0.1746889 0.154336 0.175411 0.154336 0.175411 0.154223 0.1746889 0.164863 0.177017 0.174537 0.179141 0.183369 0.181087 0.154336 0.175411 0.164863 0.177017 0.174537 0.179141 0.154336 0.175411 0.183369 0.181087 0.191461 0.182874 0.154336 0.175411 0.191478 0.183127 0.154336 0.175411 0.191461 0.182874 0.191916 0.183131 0.191478 0.183127 0.191461 0.182874 0.194885 0.24202 0.194886 0.202026 0.1948119 0.20204 0.193909 0.196922 0.1948119 0.20204 0.19481 0.199635 0.194824 0.212444 0.194885 0.24202 0.1948119 0.20204 0.19482 0.234089 0.1948119 0.242005 0.194885 0.24202 0.194747 0.2468309 0.194885 0.24202 0.1948119 0.242005 0.194826 0.227398 0.19482 0.234089 0.194885 0.24202 0.194828 0.2214339 0.194826 0.227398 0.194885 0.24202 0.194824 0.212444 0.194828 0.2214339 0.194885 0.24202 0.193909 0.247123 0.1948119 0.242005 0.19482 0.234089 0.357008 0.17431 0.353618 0.16745 0.349413 0.1683 0.357008 0.17431 0.359847 0.173426 0.353618 0.16745 0.351347 0.175544 0.349413 0.1683 0.345257 0.168721 0.354168 0.175018 0.357008 0.17431 0.349413 0.1683 0.351347 0.175544 0.354168 0.175018 0.349413 0.1683 0.348568 0.17588 0.345257 0.168721 0.341215 0.1687059 0.348568 0.17588 0.351347 0.175544 0.345257 0.168721 0.345852 0.176026 0.348568 0.17588 0.341215 0.1687059 0.343219 0.17598 0.345852 0.176026 0.341215 0.1687059 0.367789 0.186245 0.359847 0.173426 0.357008 0.17431 0.36348 0.187799 0.357008 0.17431 0.354168 0.175018 0.36348 0.187799 0.367789 0.186245 0.357008 0.17431 0.36348 0.187799 0.354168 0.175018 0.351347 0.175544 0.359217 0.189001 0.351347 0.175544 0.348568 0.17588 0.359217 0.189001 0.36348 0.187799 0.351347 0.175544 0.355072 0.1898249 0.348568 0.17588 0.345852 0.176026 0.355072 0.1898249 0.359217 0.189001 0.348568 0.17588 0.351114 0.1902599 0.345852 0.176026 0.343219 0.17598 0.351114 0.1902599 0.355072 0.1898249 0.345852 0.176026 0.376398 0.200392 0.367789 0.186245 0.36348 0.187799 0.370617 0.2027159 0.36348 0.187799 0.359217 0.189001 0.370617 0.2027159 0.376398 0.200392 0.36348 0.187799 0.365005 0.204531 0.359217 0.189001 0.355072 0.1898249 0.365005 0.204531 0.370617 0.2027159 0.359217 0.189001 0.359746 0.2057729 0.355072 0.1898249 0.351114 0.1902599 0.359746 0.2057729 0.365005 0.204531 0.355072 0.1898249 0.331727 0.207085 0.335613 0.206634 0.331521 0.206466 0.286184 0.2066929 0.331521 0.206466 0.331134 0.205865 0.331727 0.207085 0.331521 0.206466 0.286184 0.2066929 0.286184 0.2066929 0.331134 0.205865 0.330822 0.2052569 0.286184 0.2066929 0.330822 0.2052569 0.330576 0.204648 0.286184 0.2066929 0.330576 0.204648 0.330392 0.204044 0.286184 0.2066929 0.330392 0.204044 0.330272 0.203451 0.275357 0.204348 0.286184 0.2066929 0.281166 0.1908479 0.331727 0.207085 0.286184 0.2066929 0.286345 0.207302 0.275357 0.204348 0.286345 0.207302 0.286184 0.2066929 0.267037 0.1750079 0.281166 0.1908479 0.276528 0.176354 0.271082 0.1889809 0.275357 0.204348 0.281166 0.1908479 0.271082 0.1889809 0.281166 0.1908479 0.267037 0.1750079 0.263465 0.162627 0.276528 0.176354 0.272612 0.163482 0.267037 0.1750079 0.276528 0.176354 0.263465 0.162627 0.260573 0.151974 0.272612 0.163482 0.269741 0.1526679 0.263465 0.162627 0.272612 0.163482 0.260573 0.151974 0.2585 0.143094 0.269741 0.1526679 0.268093 0.143941 0.260573 0.151974 0.269741 0.1526679 0.2585 0.143094 0.257303 0.135936 0.268093 0.143941 0.267723 0.140268 0.2585 0.143094 0.268093 0.143941 0.257303 0.135936 0.257303 0.135936 0.267723 0.140268 0.267639 0.1370429 0.331727 0.207085 0.286345 0.207302 0.286492 0.207915 0.275357 0.204348 0.286492 0.207915 0.286345 0.207302 0.331979 0.207714 0.331727 0.207085 0.286492 0.207915 0.286603 0.209957 0.331979 0.207714 0.286492 0.207915 0.275627 0.205724 0.286492 0.207915 0.275357 0.204348 0.286603 0.209957 0.286492 0.207915 0.275627 0.205724 0.332073 0.207892 0.331979 0.207714 0.286603 0.209957 0.336248 0.208065 0.331979 0.207714 0.332073 0.207892 0.336248 0.208065 0.336047 0.207723 0.331979 0.207714 0.253295 0.1922259 0.252859 0.190309 0.249559 0.183516 0.248866 0.174365 0.249559 0.183516 0.252859 0.190309 0.249832 0.184578 0.253295 0.1922259 0.249559 0.183516 0.246868 0.1770009 0.249832 0.184578 0.249559 0.183516 0.246868 0.1770009 0.249559 0.183516 0.248318 0.178793 0.248866 0.174365 0.248318 0.178793 0.249559 0.183516 0.258763 0.197826 0.258405 0.19611 0.252859 0.190309 0.254046 0.178382 0.252859 0.190309 0.258405 0.19611 0.253295 0.1922259 0.258763 0.197826 0.252859 0.190309 0.254046 0.178382 0.248866 0.174365 0.252859 0.190309 0.266292 0.202347 0.265987 0.200811 0.258405 0.19611 0.261818 0.18442 0.258405 0.19611 0.265987 0.200811 0.258763 0.197826 0.266292 0.202347 0.258405 0.19611 0.261818 0.18442 0.254046 0.178382 0.258405 0.19611 0.275627 0.205724 0.275357 0.204348 0.265987 0.200811 0.271082 0.1889809 0.265987 0.200811 0.275357 0.204348 0.266292 0.202347 0.275627 0.205724 0.265987 0.200811 0.271082 0.1889809 0.261818 0.18442 0.265987 0.200811 0.275928 0.208559 0.275627 0.205724 0.266292 0.202347 0.275928 0.208559 0.286603 0.209957 0.275627 0.205724 0.266867 0.206137 0.266292 0.202347 0.258763 0.197826 0.275928 0.208559 0.266292 0.202347 0.266867 0.206137 0.254641 0.198306 0.258763 0.197826 0.253295 0.1922259 0.259688 0.202706 0.258763 0.197826 0.254641 0.198306 0.266867 0.206137 0.258763 0.197826 0.259688 0.202706 0.249832 0.184578 0.250108 0.18565 0.253295 0.1922259 0.251927 0.192923 0.253295 0.1922259 0.250108 0.18565 0.254641 0.198306 0.253295 0.1922259 0.251927 0.192923 0.246868 0.1770009 0.250108 0.18565 0.249832 0.184578 0.251927 0.192923 0.250108 0.18565 0.246868 0.1770009 0.236835 0.147432 0.226303 0.119837 0.220103 0.115765 0.239975 0.1496739 0.235647 0.135783 0.226303 0.119837 0.240157 0.1502709 0.239975 0.1496739 0.226303 0.119837 0.236835 0.147432 0.240157 0.1502709 0.226303 0.119837 0.232841 0.144376 0.220103 0.115765 0.212686 0.111371 0.232841 0.144376 0.236835 0.147432 0.220103 0.115765 0.22803 0.141113 0.212686 0.111371 0.20376 0.106599 0.22803 0.141113 0.232841 0.144376 0.212686 0.111371 0.192339 0.100443 0.193028 0.101383 0.20376 0.106599 0.222226 0.137606 0.20376 0.106599 0.193028 0.101383 0.189788 0.09699898 0.192339 0.100443 0.20376 0.106599 0.187146 0.09348297 0.189788 0.09699898 0.20376 0.106599 0.184413 0.08990198 0.187146 0.09348297 0.20376 0.106599 0.181585 0.08625197 0.184413 0.08990198 0.20376 0.106599 0.178655 0.08252996 0.181585 0.08625197 0.20376 0.106599 0.1756229 0.07874298 0.178655 0.08252996 0.20376 0.106599 0.172489 0.07489299 0.1756229 0.07874298 0.20376 0.106599 0.222226 0.137606 0.22803 0.141113 0.20376 0.106599 0.193639 0.102845 0.193028 0.101383 0.192339 0.100443 0.196043 0.105535 0.222226 0.137606 0.193028 0.101383 0.193639 0.102845 0.196043 0.105535 0.193028 0.101383 0.190343 0.09839898 0.192339 0.100443 0.189788 0.09699898 0.193639 0.102845 0.192339 0.100443 0.190343 0.09839898 0.187014 0.09398996 0.189788 0.09699898 0.187146 0.09348297 0.190343 0.09839898 0.189788 0.09699898 0.187014 0.09398996 0.1836529 0.08961898 0.187146 0.09348297 0.184413 0.08990198 0.187014 0.09398996 0.187146 0.09348297 0.1836529 0.08961898 0.180258 0.08528697 0.184413 0.08990198 0.181585 0.08625197 0.1836529 0.08961898 0.184413 0.08990198 0.180258 0.08528697 0.180258 0.08528697 0.181585 0.08625197 0.178655 0.08252996 0.176831 0.08099299 0.178655 0.08252996 0.1756229 0.07874298 0.180258 0.08528697 0.178655 0.08252996 0.176831 0.08099299 0.173372 0.07673698 0.1756229 0.07874298 0.172489 0.07489299 0.176831 0.08099299 0.1756229 0.07874298 0.173372 0.07673698 0.173372 0.07673698 0.172489 0.07489299 0.169881 0.07252097 0.241155 0.146728 0.235647 0.135783 0.239975 0.1496739 0.241155 0.146728 0.2377949 0.135298 0.235647 0.135783 0.241155 0.146728 0.239975 0.1496739 0.240157 0.1502709 0.244679 0.165598 0.240157 0.1502709 0.236835 0.147432 0.244902 0.159786 0.240157 0.1502709 0.244679 0.165598 0.244902 0.159786 0.241155 0.146728 0.240157 0.1502709 0.246868 0.1770009 0.236835 0.147432 0.232841 0.144376 0.248318 0.178793 0.244679 0.165598 0.236835 0.147432 0.246868 0.1770009 0.248318 0.178793 0.236835 0.147432 0.244966 0.174973 0.232841 0.144376 0.22803 0.141113 0.244966 0.174973 0.246868 0.1770009 0.232841 0.144376 0.242566 0.172845 0.22803 0.141113 0.222226 0.137606 0.242566 0.172845 0.244966 0.174973 0.22803 0.141113 0.212678 0.129817 0.215313 0.1338919 0.222226 0.137606 0.239575 0.170597 0.222226 0.137606 0.215313 0.1338919 0.209919 0.12562 0.212678 0.129817 0.222226 0.137606 0.207301 0.121703 0.209919 0.12562 0.222226 0.137606 0.204564 0.117673 0.207301 0.121703 0.222226 0.137606 0.20171 0.11354 0.204564 0.117673 0.222226 0.137606 0.1989369 0.10959 0.20171 0.11354 0.222226 0.137606 0.196043 0.105535 0.1989369 0.10959 0.222226 0.137606 0.239575 0.170597 0.242566 0.172845 0.222226 0.137606 0.212698 0.130278 0.215313 0.1338919 0.212678 0.129817 0.217153 0.136776 0.239575 0.170597 0.215313 0.1338919 0.215753 0.134972 0.217153 0.136776 0.215313 0.1338919 0.215753 0.134972 0.215313 0.1338919 0.212698 0.130278 0.209608 0.125618 0.212678 0.129817 0.209919 0.12562 0.212698 0.130278 0.212678 0.129817 0.209608 0.125618 0.209608 0.125618 0.209919 0.12562 0.207301 0.121703 0.206483 0.120992 0.207301 0.121703 0.204564 0.117673 0.209608 0.125618 0.207301 0.121703 0.206483 0.120992 0.203323 0.116401 0.204564 0.117673 0.20171 0.11354 0.206483 0.120992 0.204564 0.117673 0.203323 0.116401 0.200129 0.111846 0.20171 0.11354 0.1989369 0.10959 0.203323 0.116401 0.20171 0.11354 0.200129 0.111846 0.196901 0.107327 0.1989369 0.10959 0.196043 0.105535 0.200129 0.111846 0.1989369 0.10959 0.196901 0.107327 0.196901 0.107327 0.196043 0.105535 0.193639 0.102845 0.248866 0.174365 0.244679 0.165598 0.248318 0.178793 0.248866 0.174365 0.244902 0.159786 0.244679 0.165598 0.255946 0.207845 0.246868 0.1770009 0.244966 0.174973 0.25277 0.196421 0.251927 0.192923 0.246868 0.1770009 0.253773 0.200716 0.25277 0.196421 0.246868 0.1770009 0.255611 0.209046 0.253773 0.200716 0.246868 0.1770009 0.255946 0.207845 0.255611 0.209046 0.246868 0.1770009 0.255971 0.206664 0.244966 0.174973 0.242566 0.172845 0.255971 0.206664 0.255946 0.207845 0.244966 0.174973 0.255614 0.2054809 0.242566 0.172845 0.239575 0.170597 0.255614 0.2054809 0.255971 0.206664 0.242566 0.172845 0.2345409 0.165774 0.235932 0.168242 0.239575 0.170597 0.254599 0.203849 0.239575 0.170597 0.235932 0.168242 0.231989 0.16131 0.2345409 0.165774 0.239575 0.170597 0.229324 0.156728 0.231989 0.16131 0.239575 0.170597 0.227472 0.153589 0.229324 0.156728 0.239575 0.170597 0.2255589 0.150387 0.227472 0.153589 0.239575 0.170597 0.223573 0.147105 0.2255589 0.150387 0.239575 0.170597 0.2215149 0.143748 0.223573 0.147105 0.239575 0.170597 0.2193779 0.140309 0.2215149 0.143748 0.239575 0.170597 0.217153 0.136776 0.2193779 0.140309 0.239575 0.170597 0.254599 0.203849 0.255614 0.2054809 0.239575 0.170597 0.236119 0.16872 0.235932 0.168242 0.2345409 0.165774 0.254395 0.203427 0.254599 0.203849 0.235932 0.168242 0.254183 0.2029899 0.254395 0.203427 0.235932 0.168242 0.253969 0.202552 0.254183 0.2029899 0.235932 0.168242 0.252683 0.199944 0.253969 0.202552 0.235932 0.168242 0.251209 0.196991 0.252683 0.199944 0.235932 0.168242 0.249539 0.193686 0.251209 0.196991 0.235932 0.168242 0.2477149 0.190126 0.249539 0.193686 0.235932 0.168242 0.237659 0.171335 0.2477149 0.190126 0.235932 0.168242 0.236119 0.16872 0.237659 0.171335 0.235932 0.168242 0.233322 0.163809 0.2345409 0.165774 0.231989 0.16131 0.236119 0.16872 0.2345409 0.165774 0.233322 0.163809 0.230486 0.158927 0.231989 0.16131 0.229324 0.156728 0.233322 0.163809 0.231989 0.16131 0.230486 0.158927 0.227613 0.154074 0.229324 0.156728 0.227472 0.153589 0.230486 0.158927 0.229324 0.156728 0.227613 0.154074 0.227613 0.154074 0.227472 0.153589 0.2255589 0.150387 0.224703 0.149251 0.2255589 0.150387 0.223573 0.147105 0.227613 0.154074 0.2255589 0.150387 0.224703 0.149251 0.221756 0.144459 0.223573 0.147105 0.2215149 0.143748 0.224703 0.149251 0.223573 0.147105 0.221756 0.144459 0.221756 0.144459 0.2215149 0.143748 0.2193779 0.140309 0.218773 0.139699 0.2193779 0.140309 0.217153 0.136776 0.221756 0.144459 0.2193779 0.140309 0.218773 0.139699 0.218773 0.139699 0.217153 0.136776 0.215753 0.134972 0.254641 0.198306 0.251927 0.192923 0.25277 0.196421 0.254641 0.198306 0.25277 0.196421 0.253773 0.200716 0.256006 0.204764 0.253773 0.200716 0.255611 0.209046 0.254641 0.198306 0.253773 0.200716 0.256006 0.204764 0.256318 0.212462 0.255611 0.209046 0.255946 0.207845 0.256006 0.204764 0.255611 0.209046 0.257351 0.211529 0.257876 0.214314 0.257351 0.211529 0.255611 0.209046 0.257876 0.214314 0.255611 0.209046 0.256318 0.212462 0.257733 0.215407 0.255946 0.207845 0.255971 0.206664 0.111195 0.03646188 0.09822797 0.389906 0.111204 0.407595 0.257008 0.2160159 0.256318 0.212462 0.255946 0.207845 0.257733 0.215407 0.257008 0.2160159 0.255946 0.207845 0.25816 0.214798 0.255971 0.206664 0.255614 0.2054809 0.25816 0.214798 0.257733 0.215407 0.255971 0.206664 0.254599 0.203849 0.254793 0.204252 0.255614 0.2054809 0.258226 0.214177 0.255614 0.2054809 0.254793 0.204252 0.258226 0.214177 0.25816 0.214798 0.255614 0.2054809 0.254788 0.204243 0.254793 0.204252 0.254599 0.203849 0.258226 0.214177 0.254793 0.204252 0.25501 0.204712 0.254281 0.203195 0.253969 0.202552 0.252683 0.199944 0.25197 0.1985239 0.252683 0.199944 0.251209 0.196991 0.25197 0.1985239 0.254281 0.203195 0.252683 0.199944 0.25197 0.1985239 0.251209 0.196991 0.249539 0.193686 0.249483 0.193604 0.249539 0.193686 0.2477149 0.190126 0.25197 0.1985239 0.249539 0.193686 0.249483 0.193604 0.239336 0.174377 0.2457489 0.186343 0.2477149 0.190126 0.2469069 0.188609 0.2477149 0.190126 0.2457489 0.186343 0.237659 0.171335 0.239336 0.174377 0.2477149 0.190126 0.249483 0.193604 0.2477149 0.190126 0.2469069 0.188609 0.241584 0.1785089 0.243713 0.182485 0.2457489 0.186343 0.244278 0.183615 0.2457489 0.186343 0.243713 0.182485 0.239336 0.174377 0.241584 0.1785089 0.2457489 0.186343 0.2469069 0.188609 0.2457489 0.186343 0.244278 0.183615 0.241598 0.178625 0.243713 0.182485 0.241584 0.1785089 0.244278 0.183615 0.243713 0.182485 0.241598 0.178625 0.241598 0.178625 0.241584 0.1785089 0.239336 0.174377 0.238878 0.173659 0.239336 0.174377 0.237659 0.171335 0.241598 0.178625 0.239336 0.174377 0.238878 0.173659 0.238878 0.173659 0.237659 0.171335 0.236119 0.16872 0.245899 0.148493 0.2377949 0.135298 0.241155 0.146728 0.245899 0.148493 0.242647 0.1367239 0.2377949 0.135298 0.2497799 0.162427 0.241155 0.146728 0.244902 0.159786 0.2497799 0.162427 0.245899 0.148493 0.241155 0.146728 0.254046 0.178382 0.244902 0.159786 0.248866 0.174365 0.254046 0.178382 0.2497799 0.162427 0.244902 0.159786 0.251148 0.145305 0.242647 0.1367239 0.245899 0.148493 0.251148 0.145305 0.248914 0.136081 0.242647 0.1367239 0.254158 0.156482 0.245899 0.148493 0.2497799 0.162427 0.254158 0.156482 0.251148 0.145305 0.245899 0.148493 0.257788 0.169569 0.2497799 0.162427 0.254046 0.178382 0.257788 0.169569 0.254158 0.156482 0.2497799 0.162427 0.261818 0.18442 0.257788 0.169569 0.254046 0.178382 0.2585 0.143094 0.248914 0.136081 0.251148 0.145305 0.2585 0.143094 0.257303 0.135936 0.248914 0.136081 0.260573 0.151974 0.251148 0.145305 0.254158 0.156482 0.260573 0.151974 0.2585 0.143094 0.251148 0.145305 0.263465 0.162627 0.254158 0.156482 0.257788 0.169569 0.263465 0.162627 0.260573 0.151974 0.254158 0.156482 0.267037 0.1750079 0.257788 0.169569 0.261818 0.18442 0.267037 0.1750079 0.263465 0.162627 0.257788 0.169569 0.271082 0.1889809 0.267037 0.1750079 0.261818 0.18442 0.276426 0.2115769 0.277088 0.214731 0.287644 0.214398 0.288022 0.215489 0.287644 0.214398 0.277088 0.214731 0.286996 0.212124 0.276426 0.2115769 0.287644 0.214398 0.334048 0.213281 0.286996 0.212124 0.287644 0.214398 0.288022 0.215489 0.334048 0.213281 0.287644 0.214398 0.276426 0.2115769 0.268335 0.214374 0.277088 0.214731 0.277405 0.216055 0.277088 0.214731 0.268335 0.214374 0.277405 0.216055 0.288022 0.215489 0.277088 0.214731 0.267558 0.210166 0.261668 0.213309 0.268335 0.214374 0.268672 0.216116 0.268335 0.214374 0.261668 0.213309 0.276426 0.2115769 0.267558 0.210166 0.268335 0.214374 0.277405 0.216055 0.268335 0.214374 0.268672 0.216116 0.260667 0.207889 0.257351 0.211529 0.261668 0.213309 0.262073 0.21554 0.261668 0.213309 0.257351 0.211529 0.267558 0.210166 0.260667 0.207889 0.261668 0.213309 0.268672 0.216116 0.261668 0.213309 0.262073 0.21554 0.260667 0.207889 0.256006 0.204764 0.257351 0.211529 0.262073 0.21554 0.257351 0.211529 0.257876 0.214314 0.259688 0.202706 0.256006 0.204764 0.260667 0.207889 0.259688 0.202706 0.254641 0.198306 0.256006 0.204764 0.266867 0.206137 0.260667 0.207889 0.267558 0.210166 0.266867 0.206137 0.259688 0.202706 0.260667 0.207889 0.275928 0.208559 0.267558 0.210166 0.276426 0.2115769 0.275928 0.208559 0.266867 0.206137 0.267558 0.210166 0.275928 0.208559 0.276426 0.2115769 0.286996 0.212124 0.275928 0.208559 0.286996 0.212124 0.286603 0.209957 0.332162 0.208079 0.286603 0.209957 0.286996 0.212124 0.334048 0.213281 0.332162 0.208079 0.286996 0.212124 0.332162 0.208079 0.332073 0.207892 0.286603 0.209957 0.336248 0.208065 0.332073 0.207892 0.332162 0.208079 0.336248 0.208065 0.332162 0.208079 0.334048 0.213281 0.288384 0.216458 0.334991 0.2190459 0.334048 0.213281 0.288022 0.215489 0.288384 0.216458 0.334048 0.213281 0.09815096 0.05426889 0.08652597 0.365936 0.09822797 0.389906 0.289253 0.224368 0.334995 0.2249619 0.334991 0.2190459 0.289314 0.223917 0.289253 0.224368 0.334991 0.2190459 0.289371 0.220603 0.289314 0.223917 0.334991 0.2190459 0.289316 0.220146 0.289371 0.220603 0.334991 0.2190459 0.288384 0.216458 0.289316 0.220146 0.334991 0.2190459 0.287644 0.2296479 0.334049 0.230758 0.334995 0.2249619 0.287983 0.228667 0.287644 0.2296479 0.334995 0.2249619 0.08641898 0.07837396 0.07669895 0.336237 0.08652597 0.365936 0.288384 0.2275879 0.287983 0.228667 0.334995 0.2249619 0.289253 0.224368 0.288384 0.2275879 0.334995 0.2249619 0.286604 0.2340829 0.332162 0.235967 0.334049 0.230758 0.286997 0.231919 0.286604 0.2340829 0.334049 0.230758 0.287644 0.2296479 0.286997 0.231919 0.334049 0.230758 0.286492 0.2361299 0.332073 0.236153 0.332162 0.235967 0.336047 0.2363229 0.332162 0.235967 0.332073 0.236153 0.286604 0.2340829 0.286492 0.2361299 0.332162 0.235967 0.336047 0.2363229 0.336248 0.235981 0.332162 0.235967 0.286492 0.2361299 0.331979 0.2363319 0.332073 0.236153 0.336047 0.2363229 0.332073 0.236153 0.331979 0.2363319 0.286345 0.236744 0.331979 0.2363319 0.286492 0.2361299 0.331728 0.236961 0.336047 0.2363229 0.331979 0.2363319 0.331728 0.236961 0.331979 0.2363319 0.286345 0.236744 0.275929 0.2354789 0.286492 0.2361299 0.286604 0.2340829 0.275929 0.2354789 0.275628 0.2383199 0.286492 0.2361299 0.286345 0.236744 0.286492 0.2361299 0.275628 0.2383199 0.276427 0.232465 0.286604 0.2340829 0.286997 0.231919 0.276427 0.232465 0.275929 0.2354789 0.286604 0.2340829 0.277088 0.2293159 0.286997 0.231919 0.287644 0.2296479 0.276427 0.232465 0.286997 0.231919 0.277088 0.2293159 0.277419 0.227939 0.287644 0.2296479 0.287983 0.228667 0.277419 0.227939 0.277088 0.2293159 0.287644 0.2296479 0.06909996 0.1430799 0.06915998 0.30132 0.07660299 0.108164 0.277794 0.226585 0.287983 0.228667 0.288384 0.2275879 0.277419 0.227939 0.287983 0.228667 0.277794 0.226585 0.278403 0.223542 0.288384 0.2275879 0.289253 0.224368 0.278403 0.223542 0.277794 0.226585 0.288384 0.2275879 0.278403 0.223542 0.289253 0.224368 0.289314 0.223917 0.2784 0.220473 0.289314 0.223917 0.289371 0.220603 0.2784 0.220473 0.278403 0.223542 0.289314 0.223917 0.2784 0.220473 0.289371 0.220603 0.289316 0.220146 0.277794 0.217461 0.289316 0.220146 0.288384 0.216458 0.2784 0.220473 0.289316 0.220146 0.277794 0.217461 0.277794 0.217461 0.288384 0.216458 0.288022 0.215489 0.07660299 0.108164 0.07669895 0.336237 0.08641898 0.07837396 0.277405 0.216055 0.277794 0.217461 0.288022 0.215489 0.331728 0.236961 0.340129 0.236353 0.336047 0.2363229 0.331728 0.236961 0.339868 0.236832 0.340129 0.236353 0.348012 0.237776 0.355014 0.237646 0.355522 0.236652 0.359746 0.238272 0.355522 0.236652 0.355014 0.237646 0.340871 0.2379119 0.348012 0.237776 0.355522 0.236652 0.340514 0.237801 0.340871 0.2379119 0.355522 0.236652 0.340249 0.237705 0.340514 0.237801 0.355522 0.236652 0.340062 0.237623 0.340249 0.237705 0.355522 0.236652 0.339938 0.237556 0.340062 0.237623 0.355522 0.236652 0.339806 0.237457 0.339938 0.237556 0.355522 0.236652 0.339738 0.237303 0.339806 0.237457 0.355522 0.236652 0.339868 0.236832 0.339738 0.237303 0.355522 0.236652 0.341868 0.240244 0.355014 0.237646 0.348012 0.237776 0.353639 0.248726 0.359746 0.238272 0.355014 0.237646 0.350405 0.247406 0.353639 0.248726 0.355014 0.237646 0.343167 0.246854 0.350405 0.247406 0.355014 0.237646 0.342632 0.243192 0.343167 0.246854 0.355014 0.237646 0.341868 0.240244 0.342632 0.243192 0.355014 0.237646 0.341868 0.240244 0.348012 0.237776 0.340871 0.2379119 0.335526 0.239504 0.340871 0.2379119 0.340514 0.237801 0.335862 0.243419 0.341868 0.240244 0.340871 0.2379119 0.335526 0.239504 0.335862 0.243419 0.340871 0.2379119 0.330282 0.240548 0.340514 0.237801 0.340249 0.237705 0.330214 0.241178 0.335526 0.239504 0.340514 0.237801 0.330282 0.240548 0.330214 0.241178 0.340514 0.237801 0.330411 0.239929 0.340249 0.237705 0.340062 0.237623 0.330282 0.240548 0.340249 0.237705 0.330411 0.239929 0.330603 0.23932 0.340062 0.237623 0.339938 0.237556 0.330411 0.239929 0.340062 0.237623 0.330603 0.23932 0.330853 0.238723 0.339938 0.237556 0.339806 0.237457 0.330603 0.23932 0.339938 0.237556 0.330853 0.238723 0.330853 0.238723 0.339806 0.237457 0.339738 0.237303 0.335613 0.237412 0.339738 0.237303 0.339868 0.236832 0.335613 0.237412 0.330853 0.238723 0.339738 0.237303 0.331728 0.236961 0.331521 0.23758 0.339868 0.236832 0.335613 0.237412 0.339868 0.236832 0.331521 0.23758 0.359746 0.238272 0.366225 0.237448 0.36081 0.236318 0.36648 0.23233 0.36081 0.236318 0.366225 0.237448 0.361822 0.231777 0.36081 0.236318 0.36648 0.23233 0.370617 0.24133 0.372024 0.239107 0.366225 0.237448 0.371489 0.233159 0.366225 0.237448 0.372024 0.239107 0.365005 0.239515 0.370617 0.24133 0.366225 0.237448 0.359746 0.238272 0.365005 0.239515 0.366225 0.237448 0.36648 0.23233 0.366225 0.237448 0.371489 0.233159 0.376398 0.243654 0.378011 0.2412379 0.372024 0.239107 0.376732 0.2342399 0.372024 0.239107 0.378011 0.2412379 0.370617 0.24133 0.376398 0.243654 0.372024 0.239107 0.371489 0.233159 0.372024 0.239107 0.376732 0.2342399 0.376732 0.2342399 0.378011 0.2412379 0.382089 0.23555 0.36643 0.25165 0.376398 0.243654 0.370617 0.24133 0.36643 0.25165 0.370912 0.253366 0.376398 0.243654 0.362003 0.250287 0.370617 0.24133 0.365005 0.239515 0.362003 0.250287 0.36643 0.25165 0.370617 0.24133 0.357713 0.249306 0.365005 0.239515 0.359746 0.238272 0.357713 0.249306 0.362003 0.250287 0.365005 0.239515 0.353639 0.248726 0.357713 0.249306 0.359746 0.238272 0.382089 0.23555 0.384004 0.228925 0.378415 0.228248 0.376732 0.2342399 0.378415 0.228248 0.372958 0.227692 0.376732 0.2342399 0.382089 0.23555 0.378415 0.228248 0.371489 0.233159 0.372958 0.227692 0.367761 0.22727 0.371489 0.233159 0.376732 0.2342399 0.372958 0.227692 0.36648 0.23233 0.367761 0.22727 0.362947 0.226994 0.36648 0.23233 0.371489 0.233159 0.367761 0.22727 0.361822 0.231777 0.36648 0.23233 0.362947 0.226994 0.364722 0.262125 0.370912 0.253366 0.36643 0.25165 0.360586 0.260737 0.36643 0.25165 0.362003 0.250287 0.360586 0.260737 0.364722 0.262125 0.36643 0.25165 0.356488 0.259695 0.362003 0.250287 0.357713 0.249306 0.356488 0.259695 0.360586 0.260737 0.362003 0.250287 0.352491 0.259018 0.357713 0.249306 0.353639 0.248726 0.352491 0.259018 0.356488 0.259695 0.357713 0.249306 0.350405 0.247406 0.349888 0.248507 0.353639 0.248726 0.348658 0.258718 0.353639 0.248726 0.349888 0.248507 0.348658 0.258718 0.352491 0.259018 0.353639 0.248726 0.343406 0.25081 0.349888 0.248507 0.350405 0.247406 0.348658 0.258718 0.349888 0.248507 0.345558 0.257713 0.3433 0.254531 0.345558 0.257713 0.349888 0.248507 0.343406 0.25081 0.3433 0.254531 0.349888 0.248507 0.343167 0.246854 0.343406 0.25081 0.350405 0.247406 0.345078 0.258753 0.348658 0.258718 0.345558 0.257713 0.34284 0.258543 0.345078 0.258753 0.345558 0.257713 0.3433 0.254531 0.34284 0.258543 0.345558 0.257713 0.357007 0.269736 0.364722 0.262125 0.360586 0.260737 0.357007 0.269736 0.359847 0.27062 0.364722 0.262125 0.354167 0.269028 0.360586 0.260737 0.356488 0.259695 0.354167 0.269028 0.357007 0.269736 0.360586 0.260737 0.351347 0.268502 0.356488 0.259695 0.352491 0.259018 0.351347 0.268502 0.354167 0.269028 0.356488 0.259695 0.345852 0.26802 0.352491 0.259018 0.348658 0.258718 0.348568 0.268166 0.351347 0.268502 0.352491 0.259018 0.345852 0.26802 0.348568 0.268166 0.352491 0.259018 0.343218 0.268066 0.348658 0.258718 0.345078 0.258753 0.343218 0.268066 0.345852 0.26802 0.348658 0.258718 0.343218 0.268066 0.345078 0.258753 0.340687 0.268305 0.341596 0.264856 0.340687 0.268305 0.345078 0.258753 0.34231 0.261596 0.341596 0.264856 0.345078 0.258753 0.34284 0.258543 0.34231 0.261596 0.345078 0.258753 0.341214 0.27534 0.343218 0.268066 0.340687 0.268305 0.326242 0.269299 0.340687 0.268305 0.341596 0.264856 0.3392 0.27155 0.340687 0.268305 0.326242 0.269299 0.341214 0.27534 0.340687 0.268305 0.3392 0.27155 0.353618 0.276597 0.359847 0.27062 0.357007 0.269736 0.353618 0.276597 0.357007 0.269736 0.354167 0.269028 0.349413 0.275747 0.354167 0.269028 0.351347 0.268502 0.349413 0.275747 0.353618 0.276597 0.354167 0.269028 0.345257 0.275325 0.351347 0.268502 0.348568 0.268166 0.345257 0.275325 0.349413 0.275747 0.351347 0.268502 0.345257 0.275325 0.348568 0.268166 0.345852 0.26802 0.341214 0.27534 0.345852 0.26802 0.343218 0.268066 0.341214 0.27534 0.345257 0.275325 0.345852 0.26802 0.328492 0.265112 0.341596 0.264856 0.34231 0.261596 0.328492 0.265112 0.326242 0.269299 0.341596 0.264856 0.330581 0.260832 0.34231 0.261596 0.34284 0.258543 0.330581 0.260832 0.328492 0.265112 0.34231 0.261596 0.332467 0.256477 0.34284 0.258543 0.3433 0.254531 0.332467 0.256477 0.330581 0.260832 0.34284 0.258543 0.334077 0.252076 0.3433 0.254531 0.343406 0.25081 0.334077 0.252076 0.332467 0.256477 0.3433 0.254531 0.334077 0.252076 0.343406 0.25081 0.343167 0.246854 0.335273 0.247689 0.343167 0.246854 0.342632 0.243192 0.335273 0.247689 0.334077 0.252076 0.343167 0.246854 0.335862 0.243419 0.342632 0.243192 0.341868 0.240244 0.335862 0.243419 0.335273 0.247689 0.342632 0.243192 0.319128 0.302308 0.299489 0.303857 0.296732 0.306403 0.278192 0.308804 0.296732 0.306403 0.299489 0.303857 0.316415 0.304629 0.319128 0.302308 0.296732 0.306403 0.321727 0.299857 0.302281 0.301125 0.299489 0.303857 0.280606 0.306411 0.299489 0.303857 0.302281 0.301125 0.319128 0.302308 0.321727 0.299857 0.299489 0.303857 0.280606 0.306411 0.278192 0.308804 0.299489 0.303857 0.324217 0.29728 0.305087 0.298213 0.302281 0.301125 0.283024 0.303963 0.302281 0.301125 0.305087 0.298213 0.321727 0.299857 0.324217 0.29728 0.302281 0.301125 0.283024 0.303963 0.280606 0.306411 0.302281 0.301125 0.326588 0.294585 0.307891 0.295128 0.305087 0.298213 0.287815 0.298984 0.305087 0.298213 0.307891 0.295128 0.324217 0.29728 0.326588 0.294585 0.305087 0.298213 0.285445 0.301479 0.283024 0.303963 0.305087 0.298213 0.287815 0.298984 0.285445 0.301479 0.305087 0.298213 0.328818 0.291783 0.310677 0.291875 0.307891 0.295128 0.290143 0.296496 0.307891 0.295128 0.310677 0.291875 0.326588 0.294585 0.328818 0.291783 0.307891 0.295128 0.290143 0.296496 0.287815 0.298984 0.307891 0.295128 0.330899 0.288882 0.313431 0.288464 0.310677 0.291875 0.292435 0.293998 0.310677 0.291875 0.313431 0.288464 0.328818 0.291783 0.330899 0.288882 0.310677 0.291875 0.292435 0.293998 0.290143 0.296496 0.310677 0.291875 0.332836 0.285888 0.316139 0.2849 0.313431 0.288464 0.296915 0.28899 0.313431 0.288464 0.316139 0.2849 0.330899 0.288882 0.332836 0.285888 0.313431 0.288464 0.294699 0.291489 0.292435 0.293998 0.313431 0.288464 0.296915 0.28899 0.294699 0.291489 0.313431 0.288464 0.299076 0.286513 0.316139 0.2849 0.318789 0.281193 0.299076 0.286513 0.296915 0.28899 0.316139 0.2849 0.335927 0.279297 0.321366 0.277351 0.318789 0.281193 0.303195 0.281681 0.318789 0.281193 0.321366 0.277351 0.301177 0.284069 0.299076 0.286513 0.318789 0.281193 0.303195 0.281681 0.301177 0.284069 0.318789 0.281193 0.337514 0.275406 0.323857 0.273383 0.321366 0.277351 0.307007 0.27708 0.321366 0.277351 0.323857 0.273383 0.337355 0.275781 0.337514 0.275406 0.321366 0.277351 0.335927 0.279297 0.337355 0.275781 0.321366 0.277351 0.305139 0.279354 0.303195 0.281681 0.321366 0.277351 0.307007 0.27708 0.305139 0.279354 0.321366 0.277351 0.3392 0.27155 0.326242 0.269299 0.323857 0.273383 0.308803 0.274869 0.323857 0.273383 0.326242 0.269299 0.337514 0.275406 0.3392 0.27155 0.323857 0.273383 0.308803 0.274869 0.307007 0.27708 0.323857 0.273383 0.313767 0.268577 0.326242 0.269299 0.328492 0.265112 0.310528 0.272713 0.308803 0.274869 0.326242 0.269299 0.313767 0.268577 0.310528 0.272713 0.326242 0.269299 0.316874 0.26448 0.328492 0.265112 0.330581 0.260832 0.316874 0.26448 0.313767 0.268577 0.328492 0.265112 0.319763 0.260533 0.330581 0.260832 0.332467 0.256477 0.319763 0.260533 0.316874 0.26448 0.330581 0.260832 0.322349 0.256847 0.332467 0.256477 0.334077 0.252076 0.322349 0.256847 0.319763 0.260533 0.332467 0.256477 0.326912 0.249653 0.334077 0.252076 0.335273 0.247689 0.324737 0.253242 0.322349 0.256847 0.334077 0.252076 0.326912 0.249653 0.324737 0.253242 0.334077 0.252076 0.328661 0.246302 0.335273 0.247689 0.335862 0.243419 0.328661 0.246302 0.326912 0.249653 0.335273 0.247689 0.329777 0.243463 0.335862 0.243419 0.335526 0.239504 0.329777 0.243463 0.328661 0.246302 0.335862 0.243419 0.330214 0.241178 0.329777 0.243463 0.335526 0.239504 0.341214 0.27534 0.3392 0.27155 0.337514 0.275406 0.341214 0.27534 0.337514 0.275406 0.337355 0.275781 0.267841 0.309791 0.278192 0.308804 0.280606 0.306411 0.267638 0.306984 0.280606 0.306411 0.283024 0.303963 0.267638 0.306984 0.267841 0.309791 0.280606 0.306411 0.267725 0.303748 0.283024 0.303963 0.285445 0.301479 0.267725 0.303748 0.267638 0.306984 0.283024 0.303963 0.267725 0.303748 0.285445 0.301479 0.287815 0.298984 0.268098 0.300064 0.287815 0.298984 0.290143 0.296496 0.268098 0.300064 0.267725 0.303748 0.287815 0.298984 0.268098 0.300064 0.290143 0.296496 0.292435 0.293998 0.268098 0.300064 0.292435 0.293998 0.294699 0.291489 0.269755 0.291316 0.294699 0.291489 0.296915 0.28899 0.269755 0.291316 0.268098 0.300064 0.294699 0.291489 0.269755 0.291316 0.296915 0.28899 0.299076 0.286513 0.269755 0.291316 0.299076 0.286513 0.301177 0.284069 0.269755 0.291316 0.301177 0.284069 0.303195 0.281681 0.272632 0.280493 0.303195 0.281681 0.305139 0.279354 0.272632 0.280493 0.269755 0.291316 0.303195 0.281681 0.272632 0.280493 0.305139 0.279354 0.307007 0.27708 0.272632 0.280493 0.307007 0.27708 0.308803 0.274869 0.272632 0.280493 0.308803 0.274869 0.310528 0.272713 0.272632 0.280493 0.310528 0.272713 0.313767 0.268577 0.276546 0.267631 0.313767 0.268577 0.316874 0.26448 0.276546 0.267631 0.272632 0.280493 0.313767 0.268577 0.276546 0.267631 0.316874 0.26448 0.319763 0.260533 0.276546 0.267631 0.319763 0.260533 0.322349 0.256847 0.276546 0.267631 0.322349 0.256847 0.324737 0.253242 0.281175 0.253168 0.324737 0.253242 0.326912 0.249653 0.281175 0.253168 0.276546 0.267631 0.324737 0.253242 0.281175 0.253168 0.326912 0.249653 0.328661 0.246302 0.281175 0.253168 0.328661 0.246302 0.329777 0.243463 0.281175 0.253168 0.329777 0.243463 0.330214 0.241178 0.330282 0.240548 0.281175 0.253168 0.330214 0.241178 0.257303 0.308111 0.267725 0.303748 0.268098 0.300064 0.258499 0.300955 0.268098 0.300064 0.269755 0.291316 0.258499 0.300955 0.257303 0.308111 0.268098 0.300064 0.260571 0.292079 0.269755 0.291316 0.272632 0.280493 0.260571 0.292079 0.258499 0.300955 0.269755 0.291316 0.263461 0.281431 0.272632 0.280493 0.276546 0.267631 0.263461 0.281431 0.260571 0.292079 0.272632 0.280493 0.267031 0.269055 0.276546 0.267631 0.281175 0.253168 0.267031 0.269055 0.263461 0.281431 0.276546 0.267631 0.331521 0.23758 0.286184 0.237353 0.281175 0.253168 0.271074 0.255091 0.281175 0.253168 0.286184 0.237353 0.330853 0.238723 0.331521 0.23758 0.281175 0.253168 0.330603 0.23932 0.330853 0.238723 0.281175 0.253168 0.330411 0.239929 0.330603 0.23932 0.281175 0.253168 0.330282 0.240548 0.330411 0.239929 0.281175 0.253168 0.271074 0.255091 0.267031 0.269055 0.281175 0.253168 0.331728 0.236961 0.286184 0.237353 0.331521 0.23758 0.275357 0.239697 0.271074 0.255091 0.286184 0.237353 0.275628 0.2383199 0.275357 0.239697 0.286184 0.237353 0.286345 0.236744 0.275628 0.2383199 0.286184 0.237353 0.331728 0.236961 0.286345 0.236744 0.286184 0.237353 0.335613 0.237412 0.331521 0.23758 0.330853 0.238723 0.248913 0.307968 0.257303 0.308111 0.258499 0.300955 0.251147 0.298747 0.258499 0.300955 0.260571 0.292079 0.251147 0.298747 0.248913 0.307968 0.258499 0.300955 0.254154 0.287576 0.260571 0.292079 0.263461 0.281431 0.254154 0.287576 0.251147 0.298747 0.260571 0.292079 0.257783 0.274494 0.263461 0.281431 0.267031 0.269055 0.257783 0.274494 0.254154 0.287576 0.263461 0.281431 0.261811 0.259654 0.267031 0.269055 0.271074 0.255091 0.261811 0.259654 0.257783 0.274494 0.267031 0.269055 0.261811 0.259654 0.271074 0.255091 0.275357 0.239697 0.265986 0.243235 0.261811 0.259654 0.275357 0.239697 0.275628 0.2383199 0.265986 0.243235 0.275357 0.239697 0.242646 0.307325 0.248913 0.307968 0.251147 0.298747 0.245895 0.295563 0.251147 0.298747 0.254154 0.287576 0.245895 0.295563 0.242646 0.307325 0.251147 0.298747 0.249776 0.281634 0.254154 0.287576 0.257783 0.274494 0.249776 0.281634 0.245895 0.295563 0.254154 0.287576 0.254039 0.265692 0.257783 0.274494 0.261811 0.259654 0.254039 0.265692 0.249776 0.281634 0.257783 0.274494 0.254039 0.265692 0.261811 0.259654 0.265986 0.243235 0.258405 0.2479349 0.254039 0.265692 0.265986 0.243235 0.266293 0.241697 0.258405 0.2479349 0.265986 0.243235 0.266293 0.241697 0.265986 0.243235 0.275628 0.2383199 0.237793 0.308753 0.242646 0.307325 0.245895 0.295563 0.241152 0.297328 0.245895 0.295563 0.249776 0.281634 0.241152 0.297328 0.237793 0.308753 0.245895 0.295563 0.244897 0.284277 0.249776 0.281634 0.254039 0.265692 0.244897 0.284277 0.241152 0.297328 0.249776 0.281634 0.248858 0.26971 0.254039 0.265692 0.258405 0.2479349 0.248858 0.26971 0.244897 0.284277 0.254039 0.265692 0.252858 0.253736 0.248858 0.26971 0.258405 0.2479349 0.258762 0.2462199 0.252858 0.253736 0.258405 0.2479349 0.258762 0.2462199 0.258405 0.2479349 0.266293 0.241697 0.235621 0.308344 0.237793 0.308753 0.241152 0.297328 0.239935 0.294503 0.241152 0.297328 0.244897 0.284277 0.239935 0.294503 0.235621 0.308344 0.241152 0.297328 0.2446449 0.278564 0.244897 0.284277 0.248858 0.26971 0.2401379 0.293835 0.239935 0.294503 0.244897 0.284277 0.2446449 0.278564 0.2401379 0.293835 0.244897 0.284277 0.2483 0.265321 0.248858 0.26971 0.252858 0.253736 0.2483 0.265321 0.2446449 0.278564 0.248858 0.26971 0.2495599 0.26053 0.2483 0.265321 0.252858 0.253736 0.249832 0.259468 0.2495599 0.26053 0.252858 0.253736 0.249832 0.259468 0.252858 0.253736 0.250107 0.258396 0.253293 0.25182 0.250107 0.258396 0.252858 0.253736 0.253293 0.25182 0.252858 0.253736 0.258762 0.2462199 0.226215 0.324308 0.239935 0.294503 0.2401379 0.293835 0.236814 0.296671 0.2401379 0.293835 0.2446449 0.278564 0.236814 0.296671 0.226215 0.324308 0.2401379 0.293835 0.236814 0.296671 0.2446449 0.278564 0.2483 0.265321 0.246849 0.267105 0.2483 0.265321 0.2495599 0.26053 0.246849 0.267105 0.236814 0.296671 0.2483 0.265321 0.249832 0.259468 0.246849 0.267105 0.2495599 0.26053 0.236814 0.296671 0.220017 0.328373 0.226215 0.324308 0.2328169 0.299729 0.212607 0.332758 0.220017 0.328373 0.236814 0.296671 0.2328169 0.299729 0.220017 0.328373 0.228 0.302994 0.203694 0.33752 0.212607 0.332758 0.2328169 0.299729 0.228 0.302994 0.212607 0.332758 0.228 0.302994 0.222189 0.306503 0.203694 0.33752 0.242538 0.271266 0.222189 0.306503 0.228 0.302994 0.242538 0.271266 0.2395409 0.273517 0.222189 0.306503 0.244943 0.269136 0.228 0.302994 0.2328169 0.299729 0.244943 0.269136 0.242538 0.271266 0.228 0.302994 0.246849 0.267105 0.2328169 0.299729 0.236814 0.296671 0.246849 0.267105 0.244943 0.269136 0.2328169 0.299729 0.255615 0.238557 0.2395409 0.273517 0.242538 0.271266 0.254375 0.240661 0.254167 0.241088 0.2395409 0.273517 0.254586 0.240225 0.254375 0.240661 0.2395409 0.273517 0.254793 0.239794 0.254586 0.240225 0.2395409 0.273517 0.255615 0.238557 0.254793 0.239794 0.2395409 0.273517 0.255973 0.23737 0.242538 0.271266 0.244943 0.269136 0.255973 0.23737 0.255615 0.238557 0.242538 0.271266 0.255947 0.236191 0.244943 0.269136 0.246849 0.267105 0.255947 0.236191 0.255973 0.23737 0.244943 0.269136 0.255611 0.235 0.255947 0.236191 0.246849 0.267105 0.253557 0.244268 0.255611 0.235 0.246849 0.267105 0.252554 0.248529 0.253557 0.244268 0.246849 0.267105 0.251949 0.251031 0.252554 0.248529 0.246849 0.267105 0.250107 0.258396 0.251949 0.251031 0.246849 0.267105 0.249832 0.259468 0.250107 0.258396 0.246849 0.267105 0.258226 0.229869 0.254793 0.239794 0.255615 0.238557 0.255212 0.238892 0.25479 0.239799 0.254793 0.239794 0.258226 0.229869 0.255212 0.238892 0.254793 0.239794 0.258161 0.229249 0.255615 0.238557 0.255973 0.23737 0.258161 0.229249 0.258226 0.229869 0.255615 0.238557 0.257734 0.22864 0.255973 0.23737 0.255947 0.236191 0.257734 0.22864 0.258161 0.229249 0.255973 0.23737 0.256267 0.231835 0.255947 0.236191 0.255611 0.235 0.256324 0.231552 0.257008 0.22803 0.255947 0.236191 0.257734 0.22864 0.255947 0.236191 0.257008 0.22803 0.256324 0.231552 0.255947 0.236191 0.256267 0.231835 0.256007 0.239273 0.255611 0.235 0.253557 0.244268 0.256267 0.231835 0.255611 0.235 0.257351 0.232517 0.256007 0.239273 0.257351 0.232517 0.255611 0.235 0.254644 0.245724 0.253557 0.244268 0.252554 0.248529 0.256007 0.239273 0.253557 0.244268 0.254644 0.245724 0.254644 0.245724 0.252554 0.248529 0.251949 0.251031 0.253293 0.25182 0.251949 0.251031 0.250107 0.258396 0.254644 0.245724 0.251949 0.251031 0.253293 0.25182 0.256343 0.236052 0.255839 0.237399 0.255951 0.237115 0.257866 0.230526 0.255951 0.237115 0.255785 0.237536 0.256343 0.236052 0.255951 0.237115 0.257866 0.230526 0.257866 0.230526 0.255785 0.237536 0.255606 0.237976 0.258226 0.229869 0.255606 0.237976 0.255212 0.238892 0.258226 0.229869 0.257866 0.230526 0.255606 0.237976 0.258708 0.222023 0.257857 0.230565 0.257866 0.230526 0.257353 0.232755 0.257866 0.230526 0.257626 0.231642 0.257047 0.233868 0.257866 0.230526 0.257353 0.232755 0.256709 0.23497 0.257866 0.230526 0.257047 0.233868 0.256343 0.236052 0.257866 0.230526 0.256709 0.23497 0.258226 0.229869 0.258708 0.222023 0.257866 0.230526 0.257629 0.212417 0.257857 0.213481 0.257866 0.21352 0.258991 0.222023 0.257866 0.21352 0.258708 0.222023 0.258226 0.214177 0.257629 0.212417 0.257866 0.21352 0.258991 0.222023 0.258226 0.214177 0.257866 0.21352 0.258991 0.222023 0.258708 0.222023 0.258226 0.229869 0.255792 0.206525 0.255839 0.206646 0.255951 0.20693 0.258226 0.214177 0.255951 0.20693 0.256347 0.2080039 0.258226 0.214177 0.255792 0.206525 0.255951 0.20693 0.258226 0.214177 0.256347 0.2080039 0.256714 0.209093 0.258226 0.214177 0.256714 0.209093 0.257053 0.210198 0.258226 0.214177 0.257053 0.210198 0.257358 0.21131 0.258226 0.214177 0.257358 0.21131 0.257629 0.212417 0.258226 0.214177 0.25501 0.204712 0.255225 0.205184 0.258226 0.214177 0.255225 0.205184 0.255428 0.205647 0.258226 0.214177 0.255428 0.205647 0.255617 0.2060959 0.258226 0.214177 0.255617 0.2060959 0.255792 0.206525 0.172043 0.073547 0.173372 0.07673698 0.169881 0.07252097 0.168875 0.06966996 0.172043 0.073547 0.169881 0.07252097 0.175128 0.07738399 0.176831 0.08099299 0.173372 0.07673698 0.172043 0.073547 0.175128 0.07738399 0.173372 0.07673698 0.1781319 0.08117997 0.180258 0.08528697 0.176831 0.08099299 0.175128 0.07738399 0.1781319 0.08117997 0.176831 0.08099299 0.181055 0.08493298 0.1836529 0.08961898 0.180258 0.08528697 0.1781319 0.08117997 0.181055 0.08493298 0.180258 0.08528697 0.184598 0.08955895 0.187014 0.09398996 0.1836529 0.08961898 0.181055 0.08493298 0.184598 0.08955895 0.1836529 0.08961898 0.188023 0.094114 0.190343 0.09839898 0.187014 0.09398996 0.184598 0.08955895 0.188023 0.094114 0.187014 0.09398996 0.191335 0.09860098 0.193639 0.102845 0.190343 0.09839898 0.188023 0.094114 0.191335 0.09860098 0.190343 0.09839898 0.194535 0.103014 0.196901 0.107327 0.193639 0.102845 0.191335 0.09860098 0.194535 0.103014 0.193639 0.102845 0.197627 0.107352 0.200129 0.111846 0.196901 0.107327 0.194535 0.103014 0.197627 0.107352 0.196901 0.107327 0.200617 0.111617 0.203323 0.116401 0.200129 0.111846 0.197627 0.107352 0.200617 0.111617 0.200129 0.111846 0.206297 0.119925 0.206483 0.120992 0.203323 0.116401 0.2035059 0.11581 0.206297 0.119925 0.203323 0.116401 0.200617 0.111617 0.2035059 0.11581 0.203323 0.116401 0.208992 0.12396 0.209608 0.125618 0.206483 0.120992 0.206297 0.119925 0.208992 0.12396 0.206483 0.120992 0.211591 0.1279129 0.212698 0.130278 0.209608 0.125618 0.208992 0.12396 0.211591 0.1279129 0.209608 0.125618 0.2140949 0.13178 0.215753 0.134972 0.212698 0.130278 0.211591 0.1279129 0.2140949 0.13178 0.212698 0.130278 0.216511 0.135565 0.218773 0.139699 0.215753 0.134972 0.2140949 0.13178 0.216511 0.135565 0.215753 0.134972 0.219601 0.140487 0.221756 0.144459 0.218773 0.139699 0.216511 0.135565 0.219601 0.140487 0.218773 0.139699 0.222541 0.145258 0.224703 0.149251 0.221756 0.144459 0.219601 0.140487 0.222541 0.145258 0.221756 0.144459 0.225349 0.149896 0.227613 0.154074 0.224703 0.149251 0.222541 0.145258 0.225349 0.149896 0.224703 0.149251 0.228034 0.154409 0.230486 0.158927 0.227613 0.154074 0.225349 0.149896 0.228034 0.154409 0.227613 0.154074 0.233036 0.163027 0.233322 0.163809 0.230486 0.158927 0.230596 0.158788 0.233036 0.163027 0.230486 0.158927 0.228034 0.154409 0.230596 0.158788 0.230486 0.158927 0.235357 0.167123 0.236119 0.16872 0.233322 0.163809 0.233036 0.163027 0.235357 0.167123 0.233322 0.163809 0.2375659 0.171081 0.238878 0.173659 0.236119 0.16872 0.235357 0.167123 0.2375659 0.171081 0.236119 0.16872 0.241654 0.178567 0.241598 0.178625 0.238878 0.173659 0.239661 0.174892 0.241654 0.178567 0.238878 0.173659 0.2375659 0.171081 0.239661 0.174892 0.238878 0.173659 0.243562 0.182137 0.244278 0.183615 0.241598 0.178625 0.241654 0.178567 0.243562 0.182137 0.241598 0.178625 0.245387 0.185593 0.2469069 0.188609 0.244278 0.183615 0.243562 0.182137 0.245387 0.185593 0.244278 0.183615 0.247974 0.190578 0.249483 0.193604 0.2469069 0.188609 0.245387 0.185593 0.247974 0.190578 0.2469069 0.188609 0.25039 0.195321 0.25197 0.1985239 0.249483 0.193604 0.247974 0.190578 0.25039 0.195321 0.249483 0.193604 0.25039 0.195321 0.252599 0.199742 0.25197 0.1985239 0.2044849 0.108388 0.2035059 0.11581 0.200617 0.111617 0.2044849 0.108388 0.200617 0.111617 0.197627 0.107352 0.2044849 0.108388 0.197627 0.107352 0.194535 0.103014 0.2044849 0.108388 0.194535 0.103014 0.191335 0.09860098 0.2044849 0.108388 0.191335 0.09860098 0.188023 0.094114 0.2044849 0.108388 0.188023 0.094114 0.184598 0.08955895 0.186426 0.08204197 0.184598 0.08955895 0.181055 0.08493298 0.186426 0.08204197 0.2044849 0.108388 0.184598 0.08955895 0.186426 0.08204197 0.181055 0.08493298 0.1781319 0.08117997 0.186426 0.08204197 0.1781319 0.08117997 0.175128 0.07738399 0.186426 0.08204197 0.175128 0.07738399 0.172043 0.073547 0.186426 0.08204197 0.172043 0.073547 0.168875 0.06966996 0.08641898 0.07837396 0.08652597 0.365936 0.09815096 0.05426889 0.258419 0.217242 0.256318 0.212462 0.257008 0.2160159 0.257876 0.214314 0.256318 0.212462 0.258419 0.217242 0.257514 0.220027 0.257008 0.2160159 0.257733 0.215407 0.257514 0.220027 0.258419 0.217242 0.257008 0.2160159 0.258569 0.222023 0.257733 0.215407 0.25816 0.214798 0.257514 0.220027 0.257733 0.215407 0.257576 0.222016 0.258569 0.222023 0.257576 0.222016 0.257733 0.215407 0.06441098 0.181628 0.06442999 0.262652 0.06909996 0.1430799 0.258991 0.222023 0.25816 0.214798 0.258226 0.214177 0.258991 0.222023 0.258569 0.222023 0.25816 0.214798 0.277405 0.216055 0.269066 0.217949 0.277794 0.217461 0.2784 0.220473 0.277794 0.217461 0.269066 0.217949 0.262073 0.21554 0.262514 0.217884 0.269066 0.217949 0.269466 0.220646 0.269066 0.217949 0.262514 0.217884 0.268672 0.216116 0.262073 0.21554 0.269066 0.217949 0.277405 0.216055 0.268672 0.216116 0.269066 0.217949 0.2784 0.220473 0.269066 0.217949 0.269466 0.220646 0.257876 0.214314 0.258419 0.217242 0.262514 0.217884 0.258756 0.220398 0.262514 0.217884 0.258419 0.217242 0.262073 0.21554 0.257876 0.214314 0.262514 0.217884 0.262823 0.220624 0.262514 0.217884 0.258756 0.220398 0.269466 0.220646 0.262514 0.217884 0.262823 0.220624 0.258756 0.220398 0.258419 0.217242 0.257514 0.220027 0.278403 0.223542 0.269066 0.226097 0.277794 0.226585 0.277419 0.227939 0.277794 0.226585 0.269066 0.226097 0.262824 0.223394 0.262514 0.226162 0.269066 0.226097 0.268685 0.227862 0.269066 0.226097 0.262514 0.226162 0.269468 0.223372 0.262824 0.223394 0.269066 0.226097 0.278403 0.223542 0.269468 0.223372 0.269066 0.226097 0.277419 0.227939 0.269066 0.226097 0.268685 0.227862 0.258757 0.223616 0.258418 0.226803 0.262514 0.226162 0.257896 0.229624 0.262514 0.226162 0.258418 0.226803 0.262824 0.223394 0.258757 0.223616 0.262514 0.226162 0.262089 0.228419 0.262514 0.226162 0.257896 0.229624 0.268685 0.227862 0.262514 0.226162 0.262089 0.228419 0.257512 0.224038 0.257008 0.22803 0.258418 0.226803 0.257896 0.229624 0.258418 0.226803 0.257008 0.22803 0.258757 0.223616 0.257512 0.224038 0.258418 0.226803 0.06441098 0.181628 0.06281995 0.222023 0.06442999 0.262652 0.257734 0.22864 0.257008 0.22803 0.257512 0.224038 0.257896 0.229624 0.257008 0.22803 0.256324 0.231552 0.06909996 0.1430799 0.06442999 0.262652 0.06915998 0.30132 0.258756 0.220398 0.258757 0.223616 0.262824 0.223394 0.257576 0.222016 0.257512 0.224038 0.258757 0.223616 0.257514 0.220027 0.257576 0.222016 0.258757 0.223616 0.07660299 0.108164 0.06915998 0.30132 0.07669895 0.336237 0.258756 0.220398 0.257514 0.220027 0.258757 0.223616 0.262823 0.220624 0.262824 0.223394 0.269468 0.223372 0.262823 0.220624 0.258756 0.220398 0.262824 0.223394 0.269466 0.220646 0.269468 0.223372 0.278403 0.223542 0.269466 0.220646 0.262823 0.220624 0.269468 0.223372 0.2784 0.220473 0.269466 0.220646 0.278403 0.223542 0.258569 0.222023 0.257512 0.224038 0.257576 0.222016 0.258569 0.222023 0.257734 0.22864 0.257512 0.224038 0.277419 0.227939 0.268335 0.229672 0.277088 0.2293159 0.276427 0.232465 0.277088 0.2293159 0.268335 0.229672 0.268685 0.227862 0.261668 0.230738 0.268335 0.229672 0.267559 0.233875 0.268335 0.229672 0.261668 0.230738 0.277419 0.227939 0.268685 0.227862 0.268335 0.229672 0.276427 0.232465 0.268335 0.229672 0.267559 0.233875 0.257896 0.229624 0.257351 0.232517 0.261668 0.230738 0.260668 0.23615 0.261668 0.230738 0.257351 0.232517 0.262089 0.228419 0.257896 0.229624 0.261668 0.230738 0.268685 0.227862 0.262089 0.228419 0.261668 0.230738 0.267559 0.233875 0.261668 0.230738 0.260668 0.23615 0.256324 0.231552 0.256267 0.231835 0.257351 0.232517 0.257896 0.229624 0.256324 0.231552 0.257351 0.232517 0.260668 0.23615 0.257351 0.232517 0.256007 0.239273 0.275929 0.2354789 0.266293 0.241697 0.275628 0.2383199 0.25969 0.241327 0.258762 0.2462199 0.266293 0.241697 0.266868 0.237899 0.25969 0.241327 0.266293 0.241697 0.275929 0.2354789 0.266868 0.237899 0.266293 0.241697 0.254644 0.245724 0.253293 0.25182 0.258762 0.2462199 0.25969 0.241327 0.254644 0.245724 0.258762 0.2462199 0.256007 0.239273 0.254644 0.245724 0.25969 0.241327 0.260668 0.23615 0.25969 0.241327 0.266868 0.237899 0.260668 0.23615 0.256007 0.239273 0.25969 0.241327 0.267559 0.233875 0.266868 0.237899 0.275929 0.2354789 0.267559 0.233875 0.260668 0.23615 0.266868 0.237899 0.276427 0.232465 0.267559 0.233875 0.275929 0.2354789 0.258991 0.222023 0.258226 0.229869 0.258161 0.229249 0.258569 0.222023 0.258161 0.229249 0.257734 0.22864 0.258991 0.222023 0.258161 0.229249 0.258569 0.222023 0.36576 0.222023 0.392787 0.222023 0.392609 0.209709 0.366 0.236288 0.392787 0.222023 0.36576 0.222023 0.392611 0.234269 0.392787 0.222023 0.366 0.236288 0.366701 0.194167 0.392609 0.209709 0.392076 0.197699 0.365997 0.207836 0.392609 0.209709 0.366701 0.194167 0.36576 0.222023 0.392609 0.209709 0.365997 0.207836 0.367839 0.181545 0.392076 0.197699 0.391201 0.18632 0.366701 0.194167 0.392076 0.197699 0.367839 0.181545 0.369353 0.170467 0.391201 0.18632 0.390011 0.175916 0.367839 0.181545 0.391201 0.18632 0.369353 0.170467 0.371199 0.161169 0.390011 0.175916 0.388517 0.1666499 0.369353 0.170467 0.390011 0.175916 0.371199 0.161169 0.3733 0.153969 0.388517 0.1666499 0.386752 0.158818 0.371199 0.161169 0.388517 0.1666499 0.3733 0.153969 0.3733 0.153969 0.386752 0.158818 0.38476 0.152691 0.37557 0.149075 0.38476 0.152691 0.382587 0.148488 0.3733 0.153969 0.38476 0.152691 0.37557 0.149075 0.377925 0.146558 0.382587 0.148488 0.380288 0.146394 0.37557 0.149075 0.382587 0.148488 0.377925 0.146558 0.392083 0.246232 0.366 0.236288 0.36671 0.250008 0.392611 0.234269 0.366 0.236288 0.392083 0.246232 0.391213 0.257594 0.36671 0.250008 0.367856 0.262644 0.392083 0.246232 0.36671 0.250008 0.391213 0.257594 0.390027 0.268011 0.367856 0.262644 0.369373 0.273702 0.391213 0.257594 0.367856 0.262644 0.390027 0.268011 0.388532 0.277317 0.369373 0.273702 0.371217 0.282953 0.390027 0.268011 0.369373 0.273702 0.388532 0.277317 0.386761 0.285197 0.371217 0.282953 0.373309 0.290103 0.388532 0.277317 0.371217 0.282953 0.386761 0.285197 0.386761 0.285197 0.373309 0.290103 0.375568 0.294968 0.384758 0.291358 0.375568 0.294968 0.377915 0.297482 0.386761 0.285197 0.375568 0.294968 0.384758 0.291358 0.382577 0.295572 0.377915 0.297482 0.380275 0.297657 0.384758 0.291358 0.377915 0.297482 0.382577 0.295572 0.170462 0.201238 0.167105 0.2146919 0.162319 0.2145259 0.170462 0.201238 0.168358 0.216365 0.167758 0.215135 0.170462 0.238758 0.168868 0.235351 0.169259 0.232845 0.170462 0.238758 0.168357 0.237299 0.168868 0.235351 0.170462 0.201238 0.169506 0.229941 0.169591 0.226804 0.1734679 0.238516 0.17214 0.238623 0.1734679 0.201539 0.178842 0.202077 0.178134 0.208952 0.178134 0.202006 0.170462 0.201238 0.169591 0.226804 0.169506 0.223672 0.170462 0.201238 0.168869 0.21829 0.168358 0.216365 0.178842 0.208998 0.175015 0.238391 0.178134 0.208952 0.178842 0.202077 0.178842 0.208998 0.178134 0.208952 0.170462 0.238758 0.169259 0.232845 0.169506 0.229941 0.185954 0.230834 0.180945 0.209136 0.186177 0.209478 0.178842 0.208998 0.183957 0.230926 0.1789219 0.231157 0.185954 0.237509 0.185954 0.230834 0.186177 0.209478 0.170462 0.201238 0.167758 0.215135 0.167105 0.2146919 0.1681939 0.220779 0.168869 0.21829 0.16926 0.220779 0.1681939 0.220779 0.167801 0.21829 0.168869 0.21829 0.171088 0.2014099 0.17214 0.201406 0.17214 0.238623 0.171088 0.2014099 0.169402 0.201243 0.17214 0.201406 0.171088 0.23862 0.17214 0.238623 0.170462 0.238758 0.1684409 0.229938 0.168527 0.226803 0.169506 0.229941 0.1681939 0.232842 0.1684409 0.229938 0.169506 0.229941 0.1779029 0.231155 0.1789219 0.231157 0.183957 0.230926 0.1779029 0.238073 0.1789219 0.238076 0.1789219 0.231157 0.1779029 0.231155 0.1779029 0.238073 0.1789219 0.231157 0.182964 0.230924 0.183957 0.230926 0.178842 0.208998 0.182964 0.230924 0.1779029 0.231155 0.183957 0.230926 0.177823 0.209001 0.178842 0.208998 0.178842 0.202077 0.182964 0.230924 0.178842 0.208998 0.177823 0.209001 0.177823 0.202081 0.178842 0.202077 0.186177 0.202812 0.177823 0.209001 0.178842 0.202077 0.177823 0.202081 0.185194 0.202816 0.186177 0.202812 0.186177 0.209478 0.177823 0.202081 0.186177 0.202812 0.185194 0.202816 0.1684409 0.223671 0.16926 0.220779 0.169506 0.223672 0.1684409 0.223671 0.1681939 0.220779 0.16926 0.220779 0.166029 0.214694 0.167105 0.2146919 0.167758 0.215135 0.16122 0.214528 0.167105 0.2146919 0.166029 0.214694 0.16122 0.20043 0.162319 0.200425 0.162319 0.2145259 0.15948 0.200257 0.160588 0.2002519 0.162319 0.200425 0.16122 0.20043 0.15948 0.200257 0.162319 0.200425 0.1681939 0.232842 0.169506 0.229941 0.169259 0.232845 0.167288 0.237295 0.168868 0.235351 0.168357 0.237299 0.167288 0.237295 0.167801 0.235348 0.168868 0.235351 0.166685 0.238552 0.168357 0.237299 0.167758 0.238556 0.166685 0.238552 0.167288 0.237295 0.168357 0.237299 0.166685 0.238552 0.167758 0.238556 0.167105 0.239028 0.166029 0.2390249 0.167105 0.239028 0.160588 0.239553 0.166685 0.238552 0.167105 0.239028 0.166029 0.2390249 0.15948 0.239548 0.160588 0.239553 0.160588 0.2002519 0.166029 0.2390249 0.160588 0.239553 0.15948 0.239548 0.15948 0.239548 0.160588 0.2002519 0.15948 0.200257 0.169402 0.201243 0.170462 0.201238 0.17214 0.201406 0.169402 0.238755 0.170462 0.238758 0.170462 0.201238 0.169402 0.201243 0.169402 0.238755 0.170462 0.201238 0.185194 0.209481 0.186177 0.209478 0.180945 0.209136 0.15948 0.239548 0.15948 0.200257 0.16122 0.20043 0.16122 0.214528 0.15948 0.239548 0.16122 0.20043 0.166029 0.231697 0.166029 0.2390249 0.15948 0.239548 0.16122 0.222023 0.15948 0.239548 0.16122 0.214528 0.16122 0.222023 0.16122 0.231916 0.15948 0.239548 0.166029 0.231697 0.15948 0.239548 0.16122 0.231916 0.1665869 0.230852 0.166685 0.238552 0.166029 0.2390249 0.166416 0.231306 0.1665869 0.230852 0.166029 0.2390249 0.166231 0.231584 0.166416 0.231306 0.166029 0.2390249 0.166029 0.231697 0.166231 0.231584 0.166029 0.2390249 0.166029 0.222023 0.166029 0.214694 0.166685 0.215136 0.16122 0.222023 0.16122 0.214528 0.166029 0.214694 0.166029 0.222023 0.16122 0.222023 0.166029 0.214694 0.166737 0.223435 0.166685 0.215136 0.167287 0.2163659 0.166231 0.222126 0.166029 0.222023 0.166685 0.215136 0.166416 0.222396 0.166231 0.222126 0.166685 0.215136 0.1665869 0.222842 0.166416 0.222396 0.166685 0.215136 0.166737 0.223435 0.1665869 0.222842 0.166685 0.215136 0.167288 0.237295 0.167287 0.2163659 0.167801 0.21829 0.167008 0.227805 0.167287 0.2163659 0.167288 0.237295 0.16686 0.224157 0.166737 0.223435 0.167287 0.2163659 0.166952 0.224982 0.16686 0.224157 0.167287 0.2163659 0.167008 0.225871 0.166952 0.224982 0.167287 0.2163659 0.167029 0.226837 0.167008 0.225871 0.167287 0.2163659 0.167008 0.227805 0.167029 0.226837 0.167287 0.2163659 0.167801 0.235348 0.167801 0.21829 0.1681939 0.220779 0.167288 0.237295 0.167801 0.21829 0.167801 0.235348 0.1681939 0.232842 0.1681939 0.220779 0.1684409 0.223671 0.167801 0.235348 0.1681939 0.220779 0.1681939 0.232842 0.1684409 0.229938 0.1684409 0.223671 0.168527 0.226803 0.1681939 0.232842 0.1684409 0.223671 0.1684409 0.229938 0.167008 0.227805 0.167288 0.237295 0.166685 0.238552 0.166952 0.228696 0.167008 0.227805 0.166685 0.238552 0.16686 0.229525 0.166952 0.228696 0.166685 0.238552 0.166737 0.230253 0.16686 0.229525 0.166685 0.238552 0.1665869 0.230852 0.166737 0.230253 0.166685 0.238552 0.162319 0.231918 0.16122 0.231916 0.16122 0.222023 0.167105 0.231699 0.166029 0.231697 0.16122 0.231916 0.167105 0.231699 0.16122 0.231916 0.162319 0.231918 0.162319 0.222023 0.16122 0.222023 0.166029 0.222023 0.162319 0.222023 0.162319 0.231918 0.16122 0.222023 0.167105 0.222023 0.166029 0.222023 0.166231 0.222126 0.167105 0.222023 0.162319 0.222023 0.166029 0.222023 0.167306 0.222126 0.166231 0.222126 0.166416 0.222396 0.167105 0.222023 0.166231 0.222126 0.167306 0.222126 0.16749 0.222397 0.166416 0.222396 0.1665869 0.222842 0.167306 0.222126 0.166416 0.222396 0.16749 0.222397 0.167661 0.222843 0.1665869 0.222842 0.166737 0.223435 0.16749 0.222397 0.1665869 0.222842 0.167661 0.222843 0.16781 0.223435 0.166737 0.223435 0.16686 0.224157 0.167661 0.222843 0.166737 0.223435 0.16781 0.223435 0.167932 0.224158 0.16686 0.224157 0.166952 0.224982 0.16781 0.223435 0.16686 0.224157 0.167932 0.224158 0.168024 0.224982 0.166952 0.224982 0.167008 0.225871 0.167932 0.224158 0.166952 0.224982 0.168024 0.224982 0.168079 0.225872 0.167008 0.225871 0.167029 0.226837 0.168024 0.224982 0.167008 0.225871 0.168079 0.225872 0.1680999 0.2268379 0.167029 0.226837 0.167008 0.227805 0.168079 0.225872 0.167029 0.226837 0.1680999 0.2268379 0.168079 0.227806 0.167008 0.227805 0.166952 0.228696 0.1680999 0.2268379 0.167008 0.227805 0.168079 0.227806 0.168024 0.228698 0.166952 0.228696 0.16686 0.229525 0.168079 0.227806 0.166952 0.228696 0.168024 0.228698 0.167932 0.229526 0.16686 0.229525 0.166737 0.230253 0.168024 0.228698 0.16686 0.229525 0.167932 0.229526 0.16781 0.230255 0.166737 0.230253 0.1665869 0.230852 0.167932 0.229526 0.166737 0.230253 0.16781 0.230255 0.167661 0.230854 0.1665869 0.230852 0.166416 0.231306 0.16781 0.230255 0.1665869 0.230852 0.167661 0.230854 0.16749 0.231308 0.166416 0.231306 0.166231 0.231584 0.167661 0.230854 0.166416 0.231306 0.16749 0.231308 0.167306 0.231586 0.166231 0.231584 0.166029 0.231697 0.16749 0.231308 0.166231 0.231584 0.167306 0.231586 0.167306 0.231586 0.166029 0.231697 0.167105 0.231699 0.185194 0.202816 0.186177 0.209478 0.185194 0.209481 0.179936 0.209138 0.180945 0.209136 0.185954 0.230834 0.185194 0.209481 0.180945 0.209136 0.179936 0.209138 0.18497 0.2308329 0.185954 0.230834 0.185954 0.237509 0.179936 0.209138 0.185954 0.230834 0.18497 0.2308329 0.18497 0.237506 0.185954 0.237509 0.1789219 0.238076 0.18497 0.2308329 0.185954 0.237509 0.18497 0.237506 0.18497 0.237506 0.1789219 0.238076 0.1779029 0.238073 0.167801 0.235348 0.169259 0.232845 0.168868 0.235351 0.167801 0.235348 0.1681939 0.232842 0.169259 0.232845 0.171088 0.23862 0.169402 0.238755 0.169402 0.201243 0.171088 0.2014099 0.171088 0.23862 0.169402 0.201243 0.173978 0.238388 0.172423 0.2385129 0.172423 0.201543 0.173978 0.208751 0.173978 0.238388 0.172423 0.201543 0.177112 0.208954 0.173978 0.208751 0.172423 0.201543 0.177112 0.20201 0.177112 0.208954 0.172423 0.201543 0.182964 0.230924 0.1779029 0.238073 0.1779029 0.231155 0.18497 0.2308329 0.18497 0.237506 0.1779029 0.238073 0.182964 0.230924 0.18497 0.2308329 0.1779029 0.238073 0.182964 0.230924 0.179936 0.209138 0.18497 0.2308329 0.185194 0.202816 0.185194 0.209481 0.179936 0.209138 0.177823 0.209001 0.185194 0.202816 0.179936 0.209138 0.182964 0.230924 0.177823 0.209001 0.179936 0.209138 0.177823 0.209001 0.177823 0.202081 0.185194 0.202816 0.167287 0.2163659 0.167758 0.215135 0.168358 0.216365 0.166685 0.215136 0.166029 0.214694 0.167758 0.215135 0.167287 0.2163659 0.166685 0.215136 0.167758 0.215135 0.173978 0.208751 0.175015 0.238391 0.173978 0.238388 0.173978 0.238388 0.1734679 0.238516 0.172423 0.2385129 0.167801 0.21829 0.168358 0.216365 0.168869 0.21829 0.167801 0.21829 0.167287 0.2163659 0.168358 0.216365 0.177112 0.20201 0.178134 0.202006 0.178134 0.208952 0.177112 0.20201 0.172423 0.201543 0.178134 0.202006 0.171088 0.2014099 0.17214 0.238623 0.171088 0.23862 0.171088 0.23862 0.170462 0.238758 0.169402 0.238755 0.172423 0.201543 0.1734679 0.201539 0.178134 0.202006 0.172423 0.2385129 0.1734679 0.238516 0.1734679 0.201539 0.172423 0.201543 0.172423 0.2385129 0.1734679 0.201539 0.1684409 0.223671 0.169506 0.223672 0.169591 0.226804 0.177112 0.20201 0.178134 0.208952 0.177112 0.208954 0.173978 0.208751 0.175015 0.208748 0.175015 0.238391 0.177112 0.208954 0.175015 0.208748 0.173978 0.208751 0.173978 0.238388 0.175015 0.238391 0.1734679 0.238516 0.177112 0.208954 0.178134 0.208952 0.175015 0.208748 0.168527 0.226803 0.169591 0.226804 0.169506 0.229941 0.168527 0.226803 0.1684409 0.223671 0.169591 0.226804 0.16122 0.214528 0.162319 0.2145259 0.167105 0.2146919 0.16122 0.214528 0.16122 0.20043 0.162319 0.2145259 0.112214 0.03107196 0.115394 0.0528469 0.114721 0.05769091 0.134313 0.05737495 0.114721 0.05769091 0.115394 0.0528469 0.09991699 0.06646496 0.112214 0.03107196 0.114721 0.05769091 0.111041 0.091802 0.09991699 0.06646496 0.114721 0.05769091 0.140795 0.1091639 0.111041 0.091802 0.114721 0.05769091 0.140795 0.1091639 0.114721 0.05769091 0.134313 0.05737495 0.112214 0.03107196 0.11585 0.048415 0.115394 0.0528469 0.132905 0.04834693 0.115394 0.0528469 0.11585 0.048415 0.132905 0.04834693 0.134313 0.05737495 0.115394 0.0528469 0.112214 0.03107196 0.116047 0.04084599 0.11585 0.048415 0.131143 0.04082298 0.11585 0.048415 0.116047 0.04084599 0.131143 0.04082298 0.132905 0.04834693 0.11585 0.048415 0.112214 0.03107196 0.1152009 0.03529793 0.116047 0.04084599 0.130153 0.03775393 0.116047 0.04084599 0.1152009 0.03529793 0.130153 0.03775393 0.131143 0.04082298 0.116047 0.04084599 0.112214 0.03107196 0.1132709 0.03198695 0.1152009 0.03529793 0.129102 0.03519892 0.1152009 0.03529793 0.1132709 0.03198695 0.129102 0.03519892 0.130153 0.03775393 0.1152009 0.03529793 0.126879 0.03181093 0.1132709 0.03198695 0.112214 0.03107196 0.126879 0.03181093 0.129102 0.03519892 0.1132709 0.03198695 0.07719498 0.01694995 0.112214 0.03107196 0.09991699 0.06646496 0.09858596 0.01919299 0.112214 0.03107196 0.07719498 0.01694995 0.126879 0.03181093 0.112214 0.03107196 0.09858596 0.01919299 0.111041 0.091802 0.09109801 0.102917 0.09991699 0.06646496 0.06164389 0.06539398 0.09991699 0.06646496 0.09109801 0.102917 0.07441598 0.02429896 0.07719498 0.01694995 0.09991699 0.06646496 0.07259297 0.02935296 0.07441598 0.02429896 0.09991699 0.06646496 0.06739795 0.04511892 0.07259297 0.02935296 0.09991699 0.06646496 0.06164389 0.06539398 0.06739795 0.04511892 0.09991699 0.06646496 0.110477 0.125273 0.08579295 0.140075 0.09109801 0.102917 0.05370193 0.102303 0.09109801 0.102917 0.08579295 0.140075 0.111041 0.091802 0.110477 0.125273 0.09109801 0.102917 0.06139898 0.066347 0.06164389 0.06539398 0.09109801 0.102917 0.056373 0.08808296 0.06139898 0.066347 0.09109801 0.102917 0.05370193 0.102303 0.056373 0.08808296 0.09109801 0.102917 0.113788 0.173361 0.08402198 0.177588 0.08579295 0.140075 0.04897391 0.139806 0.08579295 0.140075 0.08402198 0.177588 0.113669 0.169189 0.113788 0.173361 0.08579295 0.140075 0.113342 0.163245 0.113669 0.169189 0.08579295 0.140075 0.112826 0.157728 0.113342 0.163245 0.08579295 0.140075 0.110477 0.125273 0.112826 0.157728 0.08579295 0.140075 0.05244499 0.11013 0.05370193 0.102303 0.08579295 0.140075 0.04964697 0.132475 0.05244499 0.11013 0.08579295 0.140075 0.04897391 0.139806 0.04964697 0.132475 0.08579295 0.140075 0.112826 0.197448 0.08579295 0.215101 0.08402198 0.177588 0.04739296 0.177588 0.08402198 0.177588 0.08579295 0.215101 0.113342 0.191931 0.112826 0.197448 0.08402198 0.177588 0.113669 0.1859869 0.113342 0.191931 0.08402198 0.177588 0.113788 0.181816 0.113669 0.1859869 0.08402198 0.177588 0.113828 0.1775889 0.113788 0.181816 0.08402198 0.177588 0.113788 0.173361 0.113828 0.1775889 0.08402198 0.177588 0.04795897 0.154999 0.04897391 0.139806 0.08402198 0.177588 0.04739296 0.177588 0.04795897 0.154999 0.08402198 0.177588 0.110477 0.229897 0.09109801 0.252259 0.08579295 0.215101 0.04957598 0.22198 0.08579295 0.215101 0.09109801 0.252259 0.112826 0.197448 0.110477 0.229897 0.08579295 0.215101 0.047957 0.200173 0.04739296 0.177588 0.08579295 0.215101 0.04957598 0.22198 0.047957 0.200173 0.08579295 0.215101 0.111041 0.26337 0.09991699 0.288711 0.09109801 0.252259 0.05611795 0.265904 0.09109801 0.252259 0.09991699 0.288711 0.110477 0.229897 0.111041 0.26337 0.09109801 0.252259 0.049649 0.222714 0.04957598 0.22198 0.09109801 0.252259 0.05245095 0.24502 0.049649 0.222714 0.09109801 0.252259 0.05611795 0.265904 0.05245095 0.24502 0.09109801 0.252259 0.1132709 0.323189 0.112214 0.324104 0.09991699 0.288711 0.066998 0.30889 0.09991699 0.288711 0.112214 0.324104 0.115202 0.319876 0.1132709 0.323189 0.09991699 0.288711 0.116047 0.314324 0.115202 0.319876 0.09991699 0.288711 0.11585 0.306756 0.116047 0.314324 0.09991699 0.288711 0.115393 0.302325 0.11585 0.306756 0.09991699 0.288711 0.114721 0.297485 0.115393 0.302325 0.09991699 0.288711 0.111041 0.26337 0.114721 0.297485 0.09991699 0.288711 0.05636495 0.267129 0.05611795 0.265904 0.09991699 0.288711 0.06133192 0.288781 0.05636495 0.267129 0.09991699 0.288711 0.066998 0.30889 0.06133192 0.288781 0.09991699 0.288711 0.09799897 0.350855 0.112214 0.324104 0.1132709 0.323189 0.06737697 0.310116 0.066998 0.30889 0.112214 0.324104 0.07438397 0.330787 0.06737697 0.310116 0.112214 0.324104 0.09858596 0.335983 0.07438397 0.330787 0.112214 0.324104 0.09799897 0.350855 0.09858596 0.335983 0.112214 0.324104 0.126879 0.323365 0.1132709 0.323189 0.115202 0.319876 0.09799897 0.350855 0.1132709 0.323189 0.126879 0.323365 0.129102 0.319977 0.115202 0.319876 0.116047 0.314324 0.126879 0.323365 0.115202 0.319876 0.129102 0.319977 0.131143 0.314353 0.116047 0.314324 0.11585 0.306756 0.130153 0.317422 0.116047 0.314324 0.131143 0.314353 0.129102 0.319977 0.116047 0.314324 0.130153 0.317422 0.132905 0.30683 0.11585 0.306756 0.115393 0.302325 0.131143 0.314353 0.11585 0.306756 0.132905 0.30683 0.132905 0.30683 0.115393 0.302325 0.114721 0.297485 0.134313 0.297797 0.114721 0.297485 0.111041 0.26337 0.132905 0.30683 0.114721 0.297485 0.134313 0.297797 0.140795 0.246011 0.111041 0.26337 0.110477 0.229897 0.134313 0.297797 0.111041 0.26337 0.140795 0.246011 0.14688 0.197248 0.110477 0.229897 0.112826 0.197448 0.140795 0.246011 0.110477 0.229897 0.14688 0.197248 0.14688 0.197248 0.112826 0.197448 0.113342 0.191931 0.14771 0.187835 0.113342 0.191931 0.113669 0.1859869 0.14688 0.197248 0.113342 0.191931 0.14771 0.187835 0.14771 0.187835 0.113669 0.1859869 0.113788 0.181816 0.14771 0.187835 0.113788 0.181816 0.113828 0.1775889 0.147994 0.177588 0.113828 0.1775889 0.113788 0.173361 0.14771 0.187835 0.113828 0.1775889 0.147994 0.177588 0.147994 0.177588 0.113788 0.173361 0.113669 0.169189 0.14771 0.16734 0.113669 0.169189 0.113342 0.163245 0.147994 0.177588 0.113669 0.169189 0.14771 0.16734 0.14771 0.16734 0.113342 0.163245 0.112826 0.157728 0.146881 0.157932 0.112826 0.157728 0.110477 0.125273 0.14771 0.16734 0.112826 0.157728 0.146881 0.157932 0.140795 0.1091639 0.110477 0.125273 0.111041 0.091802 0.140795 0.1091639 0.146881 0.157932 0.110477 0.125273 0.09858596 0.01919299 0.07719498 0.01694995 0.08217698 0.004699945 0.06573396 0.02092289 0.08217698 0.004699945 0.07719498 0.01694995 0.126879 0.03181093 0.09858596 0.01919299 0.08217698 0.004699945 0.09799998 0.004321992 0.126879 0.03181093 0.08217698 0.004699945 0.09798097 0.004303932 0.09799998 0.004321992 0.08217698 0.004699945 0.08215999 0.004683971 0.09798097 0.004303932 0.08217698 0.004699945 0.06573396 0.02092289 0.08215999 0.004683971 0.08217698 0.004699945 0.06573396 0.02092289 0.07719498 0.01694995 0.07441598 0.02429896 0.05978399 0.04278898 0.07441598 0.02429896 0.07259297 0.02935296 0.05978399 0.04278898 0.06573396 0.02092289 0.07441598 0.02429896 0.05978399 0.04278898 0.07259297 0.02935296 0.06739795 0.04511892 0.06139898 0.066347 0.06739795 0.04511892 0.06164389 0.06539398 0.05501097 0.06498998 0.06739795 0.04511892 0.06139898 0.066347 0.05978399 0.04278898 0.06739795 0.04511892 0.05501097 0.06498998 0.05501097 0.06498998 0.06139898 0.066347 0.056373 0.08808296 0.05128699 0.08742499 0.056373 0.08808296 0.05370193 0.102303 0.05501097 0.06498998 0.056373 0.08808296 0.05128699 0.08742499 0.04865998 0.109996 0.05370193 0.102303 0.05244499 0.11013 0.05128699 0.08742499 0.05370193 0.102303 0.04865998 0.109996 0.04711788 0.1326 0.05244499 0.11013 0.04964697 0.132475 0.04865998 0.109996 0.05244499 0.11013 0.04711788 0.1326 0.04668599 0.155158 0.04964697 0.132475 0.04897391 0.139806 0.04711788 0.1326 0.04964697 0.132475 0.04668599 0.155158 0.04668599 0.155158 0.04897391 0.139806 0.04795897 0.154999 0.04668599 0.155158 0.04795897 0.154999 0.04739296 0.177588 0.04668498 0.199971 0.04739296 0.177588 0.047957 0.200173 0.04539489 0.155928 0.04668599 0.155158 0.04739296 0.177588 0.0440849 0.157171 0.04539489 0.155928 0.04739296 0.177588 0.04278689 0.159045 0.0440849 0.157171 0.04739296 0.177588 0.04162293 0.161677 0.04278689 0.159045 0.04739296 0.177588 0.04070997 0.165009 0.04162293 0.161677 0.04739296 0.177588 0.04002189 0.16894 0.04070997 0.165009 0.04739296 0.177588 0.0395559 0.173215 0.04002189 0.16894 0.04739296 0.177588 0.03939098 0.177586 0.0395559 0.173215 0.04739296 0.177588 0.03956192 0.181963 0.03939098 0.177586 0.04739296 0.177588 0.04002588 0.186241 0.03956192 0.181963 0.04739296 0.177588 0.04071193 0.190171 0.04002588 0.186241 0.04739296 0.177588 0.04162198 0.193516 0.04071193 0.190171 0.04739296 0.177588 0.04278391 0.1961629 0.04162198 0.193516 0.04739296 0.177588 0.04408395 0.198014 0.04278391 0.1961629 0.04739296 0.177588 0.04539597 0.199205 0.04408395 0.198014 0.04739296 0.177588 0.04668498 0.199971 0.04539597 0.199205 0.04739296 0.177588 0.04711788 0.222482 0.047957 0.200173 0.04957598 0.22198 0.04711788 0.222482 0.04668498 0.199971 0.047957 0.200173 0.04711788 0.222482 0.04957598 0.22198 0.049649 0.222714 0.04866397 0.2450399 0.049649 0.222714 0.05245095 0.24502 0.04866397 0.2450399 0.04711788 0.222482 0.049649 0.222714 0.05127096 0.267561 0.05245095 0.24502 0.05611795 0.265904 0.05127096 0.267561 0.04866397 0.2450399 0.05245095 0.24502 0.05127096 0.267561 0.05611795 0.265904 0.05636495 0.267129 0.05494689 0.289948 0.05636495 0.267129 0.06133192 0.288781 0.05494689 0.289948 0.05127096 0.267561 0.05636495 0.267129 0.05973798 0.312105 0.06133192 0.288781 0.066998 0.30889 0.05973798 0.312105 0.05494689 0.289948 0.06133192 0.288781 0.05973798 0.312105 0.066998 0.30889 0.06737697 0.310116 0.06570595 0.333921 0.06737697 0.310116 0.07438397 0.330787 0.05973798 0.312105 0.06737697 0.310116 0.06570595 0.333921 0.09858596 0.335983 0.082179 0.350475 0.07438397 0.330787 0.08215999 0.350492 0.07438397 0.330787 0.082179 0.350475 0.07835298 0.353089 0.07438397 0.330787 0.08215999 0.350492 0.07421398 0.354475 0.07438397 0.330787 0.07835298 0.353089 0.06570595 0.333921 0.07438397 0.330787 0.07421398 0.354475 0.09799897 0.350855 0.082179 0.350475 0.09858596 0.335983 0.08215999 0.350492 0.082179 0.350475 0.09799897 0.350855 0.140795 0.246011 0.140795 0.1091639 0.134313 0.05737495 0.134313 0.297797 0.134313 0.05737495 0.132905 0.04834693 0.134313 0.297797 0.140795 0.246011 0.134313 0.05737495 0.14688 0.197248 0.146881 0.157932 0.140795 0.1091639 0.14771 0.187835 0.14771 0.16734 0.146881 0.157932 0.14688 0.197248 0.14771 0.187835 0.146881 0.157932 0.140795 0.246011 0.14688 0.197248 0.140795 0.1091639 0.132905 0.30683 0.132905 0.04834693 0.131143 0.04082298 0.132905 0.30683 0.134313 0.297797 0.132905 0.04834693 0.131143 0.314353 0.131143 0.04082298 0.130153 0.03775393 0.131143 0.314353 0.132905 0.30683 0.131143 0.04082298 0.130153 0.317422 0.130153 0.03775393 0.129102 0.03519892 0.130153 0.317422 0.131143 0.314353 0.130153 0.03775393 0.129102 0.319977 0.129102 0.03519892 0.126879 0.03181093 0.129102 0.319977 0.130153 0.317422 0.129102 0.03519892 0.126879 0.323365 0.126879 0.03181093 0.09799998 0.004321992 0.126879 0.323365 0.129102 0.319977 0.126879 0.03181093 0.09799897 0.350855 0.126879 0.323365 0.09799998 0.004321992 0.09798097 0.004303932 0.09799897 0.350855 0.09799998 0.004321992 0.14771 0.187835 0.147994 0.177588 0.14771 0.16734 0.09798097 0.004303932 0.09798097 0.350872 0.09799897 0.350855 0.08215999 0.350492 0.09799897 0.350855 0.09798097 0.350872 0.094473 0.001636922 0.094473 0.35354 0.09798097 0.350872 0.08215999 0.350492 0.09798097 0.350872 0.094473 0.35354 0.09798097 0.004303932 0.094473 0.001636922 0.09798097 0.350872 0.09101897 2.4e-4 0.091035 0.354934 0.094473 0.35354 0.07421398 0.354475 0.094473 0.35354 0.091035 0.354934 0.094473 0.001636922 0.09101897 2.4e-4 0.094473 0.35354 0.07835298 0.353089 0.08215999 0.350492 0.094473 0.35354 0.07421398 0.354475 0.07835298 0.353089 0.094473 0.35354 0.09101897 2.4e-4 0.08798098 0.355181 0.091035 0.354934 0.07027399 0.354716 0.091035 0.354934 0.08798098 0.355181 0.07027399 0.354716 0.07421398 0.354475 0.091035 0.354934 0.08794295 0 0.08535999 0.354655 0.08798098 0.355181 0.066711 0.35419 0.08798098 0.355181 0.08535999 0.354655 0.09101897 2.4e-4 0.08794295 0 0.08798098 0.355181 0.066711 0.35419 0.07027399 0.354716 0.08798098 0.355181 0.08530396 5.42e-4 0.08074897 0.352052 0.08535999 0.354655 0.059991 0.351574 0.08535999 0.354655 0.08074897 0.352052 0.08794295 0 0.08530396 5.42e-4 0.08535999 0.354655 0.059991 0.351574 0.066711 0.35419 0.08535999 0.354655 0.07795095 0.005787968 0.07509398 0.345777 0.08074897 0.352052 0.05113697 0.345257 0.08074897 0.352052 0.07509398 0.345777 0.08065199 0.003203988 0.07795095 0.005787968 0.08074897 0.352052 0.08530396 5.42e-4 0.08065199 0.003203988 0.08074897 0.352052 0.05113697 0.345257 0.059991 0.351574 0.08074897 0.352052 0.074907 0.009667992 0.06976795 0.336416 0.07509398 0.345777 0.0423119 0.335802 0.07509398 0.345777 0.06976795 0.336416 0.07795095 0.005787968 0.074907 0.009667992 0.07509398 0.345777 0.0423119 0.335802 0.05113697 0.345257 0.07509398 0.345777 0.06958699 0.01914393 0.065961 0.327292 0.06976795 0.336416 0.03571891 0.326523 0.06976795 0.336416 0.065961 0.327292 0.074907 0.009667992 0.06958699 0.01914393 0.06976795 0.336416 0.03571891 0.326523 0.0423119 0.335802 0.06976795 0.336416 0.06580895 0.02829498 0.06260198 0.31719 0.065961 0.327292 0.03571891 0.326523 0.065961 0.327292 0.06260198 0.31719 0.06958699 0.01914393 0.06580895 0.02829498 0.065961 0.327292 0.0624929 0.03834992 0.06068789 0.310393 0.06260198 0.31719 0.029778 0.316235 0.06260198 0.31719 0.06068789 0.310393 0.06580895 0.02829498 0.0624929 0.03834992 0.06260198 0.31719 0.029778 0.316235 0.03571891 0.326523 0.06260198 0.31719 0.06059789 0.04512488 0.05857998 0.301846 0.06068789 0.310393 0.02643996 0.309456 0.06068789 0.310393 0.05857998 0.301846 0.0624929 0.03834992 0.06059789 0.04512488 0.06068789 0.310393 0.02643996 0.309456 0.029778 0.316235 0.06068789 0.310393 0.05851 0.05363392 0.05633199 0.291236 0.05857998 0.301846 0.02276688 0.300941 0.05857998 0.301846 0.05633199 0.291236 0.06059789 0.04512488 0.05851 0.05363392 0.05857998 0.301846 0.02276688 0.300941 0.02643996 0.309456 0.05857998 0.301846 0.05627495 0.064233 0.05430489 0.27996 0.05633199 0.291236 0.01886695 0.290322 0.05633199 0.291236 0.05430489 0.27996 0.05851 0.05363392 0.05627495 0.064233 0.05633199 0.291236 0.01886695 0.290322 0.02276688 0.300941 0.05633199 0.291236 0.0542699 0.07543098 0.05271697 0.269566 0.05430489 0.27996 0.01537793 0.279116 0.05430489 0.27996 0.05271697 0.269566 0.05627495 0.064233 0.0542699 0.07543098 0.05430489 0.27996 0.01537793 0.279116 0.01886695 0.290322 0.05430489 0.27996 0.05270296 0.08570599 0.05148392 0.260209 0.05271697 0.269566 0.01031392 0.259592 0.05271697 0.269566 0.05148392 0.260209 0.0542699 0.07543098 0.05270296 0.08570599 0.05271697 0.269566 0.01258796 0.268884 0.01537793 0.279116 0.05271697 0.269566 0.01031392 0.259592 0.01258796 0.268884 0.05271697 0.269566 0.04951989 0.11359 0.04949295 0.241289 0.05148392 0.260209 0.01031392 0.259592 0.05148392 0.260209 0.04949295 0.241289 0.05147397 0.09504997 0.04951989 0.11359 0.05148392 0.260209 0.05270296 0.08570599 0.05147397 0.09504997 0.05148392 0.260209 0.04791796 0.135668 0.04786497 0.218566 0.04949295 0.241289 0.006296992 0.240389 0.04949295 0.241289 0.04786497 0.218566 0.04951989 0.11359 0.04791796 0.135668 0.04949295 0.241289 0.006296992 0.240389 0.01031392 0.259592 0.04949295 0.241289 0.0469399 0.161035 0.04691398 0.192902 0.04786497 0.218566 0.002734959 0.217759 0.04786497 0.218566 0.04691398 0.192902 0.04791796 0.135668 0.0469399 0.161035 0.04786497 0.218566 0.002734959 0.217759 0.006296992 0.240389 0.04786497 0.218566 4.49e-4 0.1922219 0.04691398 0.192902 0.0469399 0.161035 4.49e-4 0.1922219 0.002734959 0.217759 0.04691398 0.192902 5.32e-4 0.160679 0.0469399 0.161035 0.04791796 0.135668 5.32e-4 0.160679 4.49e-4 0.1922219 0.0469399 0.161035 0.002908945 0.135704 0.04791796 0.135668 0.04951989 0.11359 0.002908945 0.135704 5.32e-4 0.160679 0.04791796 0.135668 0.006468892 0.113751 0.04951989 0.11359 0.05147397 0.09504997 0.006468892 0.113751 0.002908945 0.135704 0.04951989 0.11359 0.01038491 0.09531295 0.05147397 0.09504997 0.05270296 0.08570599 0.01038491 0.09531295 0.006468892 0.113751 0.05147397 0.09504997 0.01265299 0.08605796 0.05270296 0.08570599 0.0542699 0.07543098 0.01265299 0.08605796 0.01038491 0.09531295 0.05270296 0.08570599 0.01545792 0.07577699 0.0542699 0.07543098 0.05627495 0.064233 0.01545792 0.07577699 0.01265299 0.08605796 0.0542699 0.07543098 0.01896589 0.06455999 0.05627495 0.064233 0.05851 0.05363392 0.01896589 0.06455999 0.01545792 0.07577699 0.05627495 0.064233 0.02288097 0.05396991 0.05851 0.05363392 0.06059789 0.04512488 0.02288097 0.05396991 0.01896589 0.06455999 0.05851 0.05363392 0.026573 0.04548192 0.06059789 0.04512488 0.0624929 0.03834992 0.026573 0.04548192 0.02288097 0.05396991 0.06059789 0.04512488 0.02992188 0.0387389 0.0624929 0.03834992 0.06580895 0.02829498 0.02992188 0.0387389 0.026573 0.04548192 0.0624929 0.03834992 0.03573298 0.02872192 0.06580895 0.02829498 0.06958699 0.01914393 0.03573298 0.02872192 0.02992188 0.0387389 0.06580895 0.02829498 0.04227197 0.01949495 0.06958699 0.01914393 0.074907 0.009667992 0.04227197 0.01949495 0.03573298 0.02872192 0.06958699 0.01914393 0.05111998 0.009937942 0.074907 0.009667992 0.07795095 0.005787968 0.05111998 0.009937942 0.04227197 0.01949495 0.074907 0.009667992 0.05111998 0.009937942 0.07795095 0.005787968 0.08065199 0.003203988 0.05985796 0.003628969 0.08065199 0.003203988 0.08530396 5.42e-4 0.05985796 0.003628969 0.05111998 0.009937942 0.08065199 0.003203988 0.06652599 0.001003921 0.08530396 5.42e-4 0.08794295 0 0.06652599 0.001003921 0.05985796 0.003628969 0.08530396 5.42e-4 0.070158 4.65e-4 0.08794295 0 0.09101897 2.4e-4 0.070158 4.65e-4 0.06652599 0.001003921 0.08794295 0 0.07420796 7.2e-4 0.09101897 2.4e-4 0.094473 0.001636922 0.07420796 7.2e-4 0.070158 4.65e-4 0.09101897 2.4e-4 0.078422 0.002136886 0.094473 0.001636922 0.09798097 0.004303932 0.078422 0.002136886 0.07420796 7.2e-4 0.094473 0.001636922 0.078422 0.002136886 0.09798097 0.004303932 0.08215999 0.004683971 0.06573396 0.02092289 0.078422 0.002136886 0.08215999 0.004683971 0.06570595 0.333921 0.07421398 0.354475 0.07027399 0.354716 0.06570595 0.333921 0.07027399 0.354716 0.066711 0.35419 0.05607998 0.33376 0.066711 0.35419 0.059991 0.351574 0.05607998 0.33376 0.06570595 0.333921 0.066711 0.35419 0.05607998 0.33376 0.059991 0.351574 0.05113697 0.345257 0.04587197 0.329455 0.05113697 0.345257 0.0423119 0.335802 0.04587197 0.329455 0.05607998 0.33376 0.05113697 0.345257 0.0350089 0.3194 0.0423119 0.335802 0.03571891 0.326523 0.0350089 0.3194 0.04587197 0.329455 0.0423119 0.335802 0.0350089 0.3194 0.03571891 0.326523 0.029778 0.316235 0.0350089 0.3194 0.029778 0.316235 0.02643996 0.309456 0.02437895 0.302276 0.02643996 0.309456 0.02276688 0.300941 0.02437895 0.302276 0.0350089 0.3194 0.02643996 0.309456 0.02437895 0.302276 0.02276688 0.300941 0.01886695 0.290322 0.01532596 0.278147 0.01886695 0.290322 0.01537793 0.279116 0.01532596 0.278147 0.02437895 0.302276 0.01886695 0.290322 0.01532596 0.278147 0.01537793 0.279116 0.01258796 0.268884 0.01532596 0.278147 0.01258796 0.268884 0.01031392 0.259592 0.007790923 0.247877 0.01031392 0.259592 0.006296992 0.240389 0.007790923 0.247877 0.01532596 0.278147 0.01031392 0.259592 0.007790923 0.247877 0.006296992 0.240389 0.002734959 0.217759 0.00217998 0.213529 0.002734959 0.217759 4.49e-4 0.1922219 0.00217998 0.213529 0.007790923 0.247877 0.002734959 0.217759 0 0.177599 4.49e-4 0.1922219 5.32e-4 0.160679 0 0.177599 0.00217998 0.213529 4.49e-4 0.1922219 0.002121925 0.141707 5.32e-4 0.160679 0.002908945 0.135704 0.002121925 0.141707 0 0.177599 5.32e-4 0.160679 0.002121925 0.141707 0.002908945 0.135704 0.006468892 0.113751 0.007763922 0.107379 0.006468892 0.113751 0.01038491 0.09531295 0.007763922 0.107379 0.002121925 0.141707 0.006468892 0.113751 0.007763922 0.107379 0.01038491 0.09531295 0.01265299 0.08605796 0.007763922 0.107379 0.01265299 0.08605796 0.01545792 0.07577699 0.01529788 0.07710999 0.01545792 0.07577699 0.01896589 0.06455999 0.01529788 0.07710999 0.007763922 0.107379 0.01545792 0.07577699 0.01529788 0.07710999 0.01896589 0.06455999 0.02288097 0.05396991 0.02433788 0.0530759 0.02288097 0.05396991 0.026573 0.04548192 0.02433788 0.0530759 0.01529788 0.07710999 0.02288097 0.05396991 0.02433788 0.0530759 0.026573 0.04548192 0.02992188 0.0387389 0.02433788 0.0530759 0.02992188 0.0387389 0.03573298 0.02872192 0.034976 0.03605097 0.03573298 0.02872192 0.04227197 0.01949495 0.034976 0.03605097 0.02433788 0.0530759 0.03573298 0.02872192 0.04585492 0.02580398 0.04227197 0.01949495 0.05111998 0.009937942 0.04585492 0.02580398 0.034976 0.03605097 0.04227197 0.01949495 0.04585492 0.02580398 0.05111998 0.009937942 0.05985796 0.003628969 0.05609095 0.02110296 0.05985796 0.003628969 0.06652599 0.001003921 0.05609095 0.02110296 0.04585492 0.02580398 0.05985796 0.003628969 0.05609095 0.02110296 0.06652599 0.001003921 0.070158 4.65e-4 0.06573396 0.02092289 0.070158 4.65e-4 0.07420796 7.2e-4 0.06573396 0.02092289 0.05609095 0.02110296 0.070158 4.65e-4 0.06573396 0.02092289 0.07420796 7.2e-4 0.078422 0.002136886 0.05973798 0.312105 0.06570595 0.333921 0.05607998 0.33376 0.05132395 0.311174 0.05607998 0.33376 0.04587197 0.329455 0.05973798 0.312105 0.05607998 0.33376 0.05132395 0.311174 0.04241997 0.306754 0.04587197 0.329455 0.0350089 0.3194 0.05132395 0.311174 0.04587197 0.329455 0.04241997 0.306754 0.03274995 0.297641 0.0350089 0.3194 0.02437895 0.302276 0.04241997 0.306754 0.0350089 0.3194 0.03274995 0.297641 0.0231319 0.282734 0.02437895 0.302276 0.01532596 0.278147 0.03274995 0.297641 0.02437895 0.302276 0.0231319 0.282734 0.0150299 0.262091 0.01532596 0.278147 0.007790923 0.247877 0.0231319 0.282734 0.01532596 0.278147 0.0150299 0.262091 0.008408963 0.236466 0.007790923 0.247877 0.00217998 0.213529 0.0150299 0.262091 0.007790923 0.247877 0.008408963 0.236466 0.003519952 0.207607 0.00217998 0.213529 0 0.177599 0.008408963 0.236466 0.00217998 0.213529 0.003519952 0.207607 0.001631975 0.177543 0 0.177599 0.002121925 0.141707 0.003519952 0.207607 0 0.177599 0.001631975 0.177543 0.003479957 0.147512 0.002121925 0.141707 0.007763922 0.107379 0.001631975 0.177543 0.002121925 0.141707 0.003479957 0.147512 0.008402943 0.118678 0.007763922 0.107379 0.01529788 0.07710999 0.003479957 0.147512 0.007763922 0.107379 0.008402943 0.118678 0.01503098 0.09306895 0.01529788 0.07710999 0.02433788 0.0530759 0.008402943 0.118678 0.01529788 0.07710999 0.01503098 0.09306895 0.02312994 0.07252496 0.02433788 0.0530759 0.034976 0.03605097 0.01503098 0.09306895 0.02433788 0.0530759 0.02312994 0.07252496 0.03276091 0.05772292 0.034976 0.03605097 0.04585492 0.02580398 0.02312994 0.07252496 0.034976 0.03605097 0.03276091 0.05772292 0.04243993 0.04846888 0.04585492 0.02580398 0.05609095 0.02110296 0.03276091 0.05772292 0.04585492 0.02580398 0.04243993 0.04846888 0.05135893 0.04372495 0.05609095 0.02110296 0.06573396 0.02092289 0.04243993 0.04846888 0.05609095 0.02110296 0.05135893 0.04372495 0.05135893 0.04372495 0.06573396 0.02092289 0.05978399 0.04278898 0.04711788 0.1326 0.04668599 0.155158 0.04539489 0.155928 0.04451292 0.133943 0.04539489 0.155928 0.0440849 0.157171 0.04451292 0.133943 0.04711788 0.1326 0.04539489 0.155928 0.04175895 0.136268 0.0440849 0.157171 0.04278689 0.159045 0.04175895 0.136268 0.04451292 0.133943 0.0440849 0.157171 0.03891396 0.139903 0.04278689 0.159045 0.04162293 0.161677 0.03891396 0.139903 0.04175895 0.136268 0.04278689 0.159045 0.03630089 0.145135 0.04162293 0.161677 0.04070997 0.165009 0.03630089 0.145135 0.03891396 0.139903 0.04162293 0.161677 0.03422999 0.151858 0.04070997 0.165009 0.04002189 0.16894 0.03422999 0.151858 0.03630089 0.145135 0.04070997 0.165009 0.03261095 0.159856 0.04002189 0.16894 0.0395559 0.173215 0.03261095 0.159856 0.03422999 0.151858 0.04002189 0.16894 0.03144598 0.168608 0.0395559 0.173215 0.03939098 0.177586 0.03144598 0.168608 0.03261095 0.159856 0.0395559 0.173215 0.03101789 0.17759 0.03939098 0.177586 0.03956192 0.181963 0.03101789 0.17759 0.03144598 0.168608 0.03939098 0.177586 0.03146398 0.186583 0.03956192 0.181963 0.04002588 0.186241 0.03146398 0.186583 0.03101789 0.17759 0.03956192 0.181963 0.03262192 0.195341 0.04002588 0.186241 0.04071193 0.190171 0.03262192 0.195341 0.03146398 0.186583 0.04002588 0.186241 0.0342369 0.203338 0.04071193 0.190171 0.04162198 0.193516 0.0342369 0.203338 0.03262192 0.195341 0.04071193 0.190171 0.03630393 0.210086 0.04162198 0.193516 0.04278391 0.1961629 0.03630393 0.210086 0.0342369 0.203338 0.04162198 0.193516 0.03891396 0.215345 0.04278391 0.1961629 0.04408395 0.198014 0.03891396 0.215345 0.03630393 0.210086 0.04278391 0.1961629 0.04176098 0.218931 0.04408395 0.198014 0.04539597 0.199205 0.04176098 0.218931 0.03891396 0.215345 0.04408395 0.198014 0.04451698 0.22115 0.04539597 0.199205 0.04668498 0.199971 0.04451698 0.22115 0.04176098 0.218931 0.04539597 0.199205 0.04711788 0.222482 0.04451698 0.22115 0.04668498 0.199971 0.04865998 0.109996 0.04711788 0.1326 0.04451292 0.133943 0.04469794 0.1116639 0.04451292 0.133943 0.04175895 0.136268 0.04469794 0.1116639 0.04865998 0.109996 0.04451292 0.133943 0.040434 0.114928 0.04175895 0.136268 0.03891396 0.139903 0.040434 0.114928 0.04469794 0.1116639 0.04175895 0.136268 0.03587496 0.120204 0.03891396 0.139903 0.03630089 0.145135 0.03587496 0.120204 0.040434 0.114928 0.03891396 0.139903 0.03156691 0.127969 0.03630089 0.145135 0.03422999 0.151858 0.03156691 0.127969 0.03587496 0.120204 0.03630089 0.145135 0.02809095 0.138125 0.03422999 0.151858 0.03261095 0.159856 0.02809095 0.138125 0.03156691 0.127969 0.03422999 0.151858 0.0253179 0.1503289 0.03261095 0.159856 0.03144598 0.168608 0.0253179 0.1503289 0.02809095 0.138125 0.03261095 0.159856 0.02328199 0.163766 0.03144598 0.168608 0.03101789 0.17759 0.02328199 0.163766 0.0253179 0.1503289 0.03144598 0.168608 0.02252596 0.177601 0.03101789 0.17759 0.03146398 0.186583 0.02252596 0.177601 0.02328199 0.163766 0.03101789 0.17759 0.02331393 0.191452 0.03146398 0.186583 0.03262192 0.195341 0.02331393 0.191452 0.02252596 0.177601 0.03146398 0.186583 0.02533888 0.2048979 0.03262192 0.195341 0.0342369 0.203338 0.02533888 0.2048979 0.02331393 0.191452 0.03262192 0.195341 0.02810692 0.217099 0.0342369 0.203338 0.03630393 0.210086 0.02810692 0.217099 0.02533888 0.2048979 0.0342369 0.203338 0.03158193 0.227289 0.03630393 0.210086 0.03891396 0.215345 0.03158193 0.227289 0.02810692 0.217099 0.03630393 0.210086 0.03588396 0.23509 0.03891396 0.215345 0.04176098 0.218931 0.03588396 0.23509 0.03158193 0.227289 0.03891396 0.215345 0.04044389 0.240289 0.04176098 0.218931 0.04451698 0.22115 0.04044389 0.240289 0.03588396 0.23509 0.04176098 0.218931 0.04470795 0.2433879 0.04451698 0.22115 0.04711788 0.222482 0.04470795 0.2433879 0.04044389 0.240289 0.04451698 0.22115 0.04866397 0.2450399 0.04470795 0.2433879 0.04711788 0.222482 0.04586493 0.08913296 0.04865998 0.109996 0.04469794 0.1116639 0.04586493 0.08913296 0.05128699 0.08742499 0.04865998 0.109996 0.040057 0.09314596 0.04469794 0.1116639 0.040434 0.114928 0.040057 0.09314596 0.04586493 0.08913296 0.04469794 0.1116639 0.03372293 0.09991699 0.040434 0.114928 0.03587496 0.120204 0.03372293 0.09991699 0.040057 0.09314596 0.040434 0.114928 0.027565 0.110117 0.03587496 0.120204 0.03156691 0.127969 0.027565 0.110117 0.03372293 0.09991699 0.03587496 0.120204 0.02251189 0.123724 0.03156691 0.127969 0.02809095 0.138125 0.02251189 0.123724 0.027565 0.110117 0.03156691 0.127969 0.01844292 0.1402699 0.02809095 0.138125 0.0253179 0.1503289 0.01844292 0.1402699 0.02251189 0.123724 0.02809095 0.138125 0.01543796 0.158616 0.0253179 0.1503289 0.02328199 0.163766 0.01543796 0.158616 0.01844292 0.1402699 0.0253179 0.1503289 0.01431691 0.177575 0.02328199 0.163766 0.02252596 0.177601 0.01431691 0.177575 0.01543796 0.158616 0.02328199 0.163766 0.01547396 0.196554 0.02252596 0.177601 0.02331393 0.191452 0.01547396 0.196554 0.01431691 0.177575 0.02252596 0.177601 0.01845699 0.214915 0.02331393 0.191452 0.02533888 0.2048979 0.01845699 0.214915 0.01547396 0.196554 0.02331393 0.191452 0.02251899 0.2314659 0.02533888 0.2048979 0.02810692 0.217099 0.02251899 0.2314659 0.01845699 0.214915 0.02533888 0.2048979 0.02756989 0.24513 0.02810692 0.217099 0.03158193 0.227289 0.02756989 0.24513 0.02251899 0.2314659 0.02810692 0.217099 0.033719 0.255392 0.03158193 0.227289 0.03588396 0.23509 0.033719 0.255392 0.02756989 0.24513 0.03158193 0.227289 0.04005193 0.262067 0.03588396 0.23509 0.04044389 0.240289 0.04005193 0.262067 0.033719 0.255392 0.03588396 0.23509 0.0458579 0.265864 0.04044389 0.240289 0.04470795 0.2433879 0.0458579 0.265864 0.04005193 0.262067 0.04044389 0.240289 0.05127096 0.267561 0.04470795 0.2433879 0.04866397 0.2450399 0.05127096 0.267561 0.0458579 0.265864 0.04470795 0.2433879 0.0480619 0.06644099 0.05128699 0.08742499 0.04586493 0.08913296 0.0480619 0.06644099 0.05501097 0.06498998 0.05128699 0.08742499 0.040681 0.070948 0.04586493 0.08913296 0.040057 0.09314596 0.040681 0.070948 0.0480619 0.06644099 0.04586493 0.08913296 0.03259491 0.07903897 0.040057 0.09314596 0.03372293 0.09991699 0.03259491 0.07903897 0.040681 0.070948 0.040057 0.09314596 0.02457499 0.09156996 0.03372293 0.09991699 0.027565 0.110117 0.02457499 0.09156996 0.03259491 0.07903897 0.03372293 0.09991699 0.01790696 0.108632 0.027565 0.110117 0.02251189 0.123724 0.01790696 0.108632 0.02457499 0.09156996 0.027565 0.110117 0.01250797 0.129649 0.02251189 0.123724 0.01844292 0.1402699 0.01250797 0.129649 0.01790696 0.108632 0.02251189 0.123724 0.008507966 0.153133 0.01844292 0.1402699 0.01543796 0.158616 0.008507966 0.153133 0.01250797 0.129649 0.01844292 0.1402699 0.007004976 0.177498 0.01543796 0.158616 0.01431691 0.177575 0.007004976 0.177498 0.008507966 0.153133 0.01543796 0.158616 0.008531987 0.201892 0.01431691 0.177575 0.01547396 0.196554 0.008531987 0.201892 0.007004976 0.177498 0.01431691 0.177575 0.0124939 0.225405 0.01547396 0.196554 0.01845699 0.214915 0.0124939 0.225405 0.008531987 0.201892 0.01547396 0.196554 0.01788097 0.246447 0.01845699 0.214915 0.02251899 0.2314659 0.01788097 0.246447 0.0124939 0.225405 0.01845699 0.214915 0.02454096 0.263608 0.02251899 0.2314659 0.02756989 0.24513 0.02454096 0.263608 0.01788097 0.246447 0.02251899 0.2314659 0.03254497 0.276246 0.02756989 0.24513 0.033719 0.255392 0.03254497 0.276246 0.02454096 0.263608 0.02756989 0.24513 0.04062891 0.284238 0.033719 0.255392 0.04005193 0.262067 0.04062891 0.284238 0.03254497 0.276246 0.033719 0.255392 0.04800593 0.288492 0.04005193 0.262067 0.0458579 0.265864 0.04800593 0.288492 0.04062891 0.284238 0.04005193 0.262067 0.05494689 0.289948 0.0458579 0.265864 0.05127096 0.267561 0.05494689 0.289948 0.04800593 0.288492 0.0458579 0.265864 0.05978399 0.04278898 0.05501097 0.06498998 0.0480619 0.06644099 0.05135893 0.04372495 0.0480619 0.06644099 0.040681 0.070948 0.05135893 0.04372495 0.05978399 0.04278898 0.0480619 0.06644099 0.04243993 0.04846888 0.040681 0.070948 0.03259491 0.07903897 0.04243993 0.04846888 0.05135893 0.04372495 0.040681 0.070948 0.03276091 0.05772292 0.03259491 0.07903897 0.02457499 0.09156996 0.03276091 0.05772292 0.04243993 0.04846888 0.03259491 0.07903897 0.02312994 0.07252496 0.02457499 0.09156996 0.01790696 0.108632 0.02312994 0.07252496 0.03276091 0.05772292 0.02457499 0.09156996 0.01503098 0.09306895 0.01790696 0.108632 0.01250797 0.129649 0.01503098 0.09306895 0.02312994 0.07252496 0.01790696 0.108632 0.008402943 0.118678 0.01250797 0.129649 0.008507966 0.153133 0.008402943 0.118678 0.01503098 0.09306895 0.01250797 0.129649 0.003479957 0.147512 0.008507966 0.153133 0.007004976 0.177498 0.003479957 0.147512 0.008402943 0.118678 0.008507966 0.153133 0.001631975 0.177543 0.007004976 0.177498 0.008531987 0.201892 0.001631975 0.177543 0.003479957 0.147512 0.007004976 0.177498 0.003519952 0.207607 0.008531987 0.201892 0.0124939 0.225405 0.003519952 0.207607 0.001631975 0.177543 0.008531987 0.201892 0.008408963 0.236466 0.0124939 0.225405 0.01788097 0.246447 0.008408963 0.236466 0.003519952 0.207607 0.0124939 0.225405 0.0150299 0.262091 0.01788097 0.246447 0.02454096 0.263608 0.0150299 0.262091 0.008408963 0.236466 0.01788097 0.246447 0.0231319 0.282734 0.02454096 0.263608 0.03254497 0.276246 0.0231319 0.282734 0.0150299 0.262091 0.02454096 0.263608 0.03274995 0.297641 0.03254497 0.276246 0.04062891 0.284238 0.03274995 0.297641 0.0231319 0.282734 0.03254497 0.276246 0.04241997 0.306754 0.04062891 0.284238 0.04800593 0.288492 0.04241997 0.306754 0.03274995 0.297641 0.04062891 0.284238 0.05132395 0.311174 0.04800593 0.288492 0.05494689 0.289948 0.05132395 0.311174 0.04241997 0.306754 0.04800593 0.288492 0.05973798 0.312105 0.05132395 0.311174 0.05494689 0.289948 0.06450098 0.1436859 0.041426 0.137299 0.03551989 0.1313199 0.04228198 0.1316159 0.03551989 0.1313199 0.041426 0.137299 0.03362298 0.128967 0.06450098 0.1436859 0.03551989 0.1313199 0.02934288 0.111016 0.03362298 0.128967 0.03551989 0.1313199 0.02934288 0.111016 0.03551989 0.1313199 0.04228198 0.1316159 0.06450098 0.1436859 0.04771298 0.141435 0.041426 0.137299 0.05232989 0.141616 0.041426 0.137299 0.04771298 0.141435 0.04690599 0.137452 0.04228198 0.1316159 0.041426 0.137299 0.05232989 0.141616 0.04690599 0.137452 0.041426 0.137299 0.06450098 0.1436859 0.05099093 0.14284 0.04771298 0.141435 0.05525398 0.143009 0.04771298 0.141435 0.05099093 0.14284 0.05525398 0.143009 0.05232989 0.141616 0.04771298 0.141435 0.06450098 0.1436859 0.054223 0.1437489 0.05099093 0.14284 0.05826497 0.143922 0.05099093 0.14284 0.054223 0.1437489 0.05826497 0.143922 0.05525398 0.143009 0.05099093 0.14284 0.06450098 0.1436859 0.0603609 0.144102 0.054223 0.1437489 0.06132495 0.14435 0.054223 0.1437489 0.0603609 0.144102 0.06132495 0.14435 0.05826497 0.143922 0.054223 0.1437489 0.06440496 0.144291 0.0603609 0.144102 0.06450098 0.1436859 0.06440496 0.144291 0.06132495 0.14435 0.0603609 0.144102 0.03362298 0.128967 0.06014597 0.123579 0.06450098 0.1436859 0.07831096 0.142305 0.06450098 0.1436859 0.06014597 0.123579 0.06440496 0.144291 0.06450098 0.1436859 0.07831096 0.142305 0.03063398 0.110198 0.05723893 0.103147 0.06014597 0.123579 0.08638197 0.121711 0.06014597 0.123579 0.05723893 0.103147 0.03362298 0.128967 0.03063398 0.110198 0.06014597 0.123579 0.09056395 0.14109 0.07831096 0.142305 0.06014597 0.123579 0.08638197 0.121711 0.09056395 0.14109 0.06014597 0.123579 0.02884596 0.09123295 0.055785 0.08252 0.05723893 0.103147 0.08359098 0.102021 0.05723893 0.103147 0.055785 0.08252 0.03063398 0.110198 0.02884596 0.09123295 0.05723893 0.103147 0.08359098 0.102021 0.08638197 0.121711 0.05723893 0.103147 0.02824896 0.07217496 0.055785 0.06182897 0.055785 0.08252 0.08219397 0.08214396 0.055785 0.08252 0.055785 0.06182897 0.02884596 0.09123295 0.02824896 0.07217496 0.055785 0.08252 0.08219397 0.08214396 0.08359098 0.102021 0.055785 0.08252 0.02884596 0.05311596 0.05723893 0.04120296 0.055785 0.06182897 0.08359098 0.04232895 0.055785 0.06182897 0.05723893 0.04120296 0.02824896 0.07217496 0.02884596 0.05311596 0.055785 0.06182897 0.08219397 0.06220489 0.08219397 0.08214396 0.055785 0.06182897 0.08359098 0.04232895 0.08219397 0.06220489 0.055785 0.06182897 0.03063398 0.03415089 0.06014597 0.0207709 0.05723893 0.04120296 0.08638197 0.02263796 0.05723893 0.04120296 0.06014597 0.0207709 0.02884596 0.05311596 0.03063398 0.03415089 0.05723893 0.04120296 0.08638197 0.02263796 0.08359098 0.04232895 0.05723893 0.04120296 0.05422097 6.01e-4 0.06450098 6.64e-4 0.06014597 0.0207709 0.07831096 0.002044916 0.06014597 0.0207709 0.06450098 6.64e-4 0.05098789 0.001510918 0.05422097 6.01e-4 0.06014597 0.0207709 0.04770892 0.002916932 0.05098789 0.001510918 0.06014597 0.0207709 0.04142391 0.007051885 0.04770892 0.002916932 0.06014597 0.0207709 0.03551989 0.01302999 0.04142391 0.007051885 0.06014597 0.0207709 0.03362697 0.01537793 0.03551989 0.01302999 0.06014597 0.0207709 0.03063398 0.03415089 0.03362697 0.01537793 0.06014597 0.0207709 0.09056395 0.003259897 0.08638197 0.02263796 0.06014597 0.0207709 0.07831096 0.002044916 0.09056395 0.003259897 0.06014597 0.0207709 0.05422097 6.01e-4 0.0603609 2.48e-4 0.06450098 6.64e-4 0.100233 0.003607988 0.06450098 6.64e-4 0.0603609 2.48e-4 0.100233 0.003607988 0.07831096 0.002044916 0.06450098 6.64e-4 0.06440496 5.8e-5 0.0603609 2.48e-4 0.05422097 6.01e-4 0.100233 0.003607988 0.0603609 2.48e-4 0.06440496 5.8e-5 0.05826497 4.28e-4 0.05422097 6.01e-4 0.05098789 0.001510918 0.06132495 0 0.05422097 6.01e-4 0.05826497 4.28e-4 0.06440496 5.8e-5 0.05422097 6.01e-4 0.06132495 0 0.05525398 0.001339972 0.05098789 0.001510918 0.04770892 0.002916932 0.05826497 4.28e-4 0.05098789 0.001510918 0.05525398 0.001339972 0.05232989 0.002733886 0.04770892 0.002916932 0.04142391 0.007051885 0.05525398 0.001339972 0.04770892 0.002916932 0.05232989 0.002733886 0.04690599 0.006897926 0.04142391 0.007051885 0.03551989 0.01302999 0.05232989 0.002733886 0.04142391 0.007051885 0.04690599 0.006897926 0.04228198 0.01273298 0.03551989 0.01302999 0.03362697 0.01537793 0.04690599 0.006897926 0.03551989 0.01302999 0.04228198 0.01273298 0.01981699 0.03337198 0.03362697 0.01537793 0.03063398 0.03415089 0.04228198 0.01273298 0.03362697 0.01537793 0.01981699 0.03337198 0.01981699 0.03337198 0.03063398 0.03415089 0.02884596 0.05311596 0.005089998 0.05449098 0.02884596 0.05311596 0.02824896 0.07217496 0.005089998 0.05449098 0.01981699 0.03337198 0.02884596 0.05311596 0 0.07217496 0.02824896 0.07217496 0.02884596 0.09123295 0.002332985 0.05979496 0.005089998 0.05449098 0.02824896 0.07217496 5.94e-4 0.06580799 0.002332985 0.05979496 0.02824896 0.07217496 0 0.07217496 5.94e-4 0.06580799 0.02824896 0.07217496 0.005088925 0.089859 0.02884596 0.09123295 0.03063398 0.110198 5.94e-4 0.07854199 0 0.07217496 0.02884596 0.09123295 0.002332985 0.08455395 5.94e-4 0.07854199 0.02884596 0.09123295 0.005088925 0.089859 0.002332985 0.08455395 0.02884596 0.09123295 0.01981699 0.110977 0.03063398 0.110198 0.03362298 0.128967 0.01981699 0.110977 0.005088925 0.089859 0.03063398 0.110198 0.02934288 0.111016 0.01981699 0.110977 0.03362298 0.128967 0.06440496 0.144291 0.07831096 0.142305 0.09056395 0.14109 0.09584599 0.140569 0.09056395 0.14109 0.08638197 0.121711 0.06440496 0.144291 0.09056395 0.14109 0.09584599 0.140569 0.110897 0.114822 0.08638197 0.121711 0.08359098 0.102021 0.100005 0.139869 0.09584599 0.140569 0.08638197 0.121711 0.103983 0.138599 0.100005 0.139869 0.08638197 0.121711 0.107767 0.136764 0.103983 0.138599 0.08638197 0.121711 0.111337 0.134362 0.107767 0.136764 0.08638197 0.121711 0.114241 0.1318269 0.111337 0.134362 0.08638197 0.121711 0.110897 0.114822 0.114241 0.1318269 0.08638197 0.121711 0.108766 0.09784799 0.08359098 0.102021 0.08219397 0.08214396 0.108766 0.09784799 0.110897 0.114822 0.08359098 0.102021 0.1077 0.080747 0.08219397 0.08214396 0.08219397 0.06220489 0.1077 0.080747 0.108766 0.09784799 0.08219397 0.08214396 0.108766 0.04650396 0.08219397 0.06220489 0.08359098 0.04232895 0.1077 0.06360399 0.1077 0.080747 0.08219397 0.06220489 0.108766 0.04650396 0.1077 0.06360399 0.08219397 0.06220489 0.110897 0.02952992 0.08359098 0.04232895 0.08638197 0.02263796 0.110897 0.02952992 0.108766 0.04650396 0.08359098 0.04232895 0.114242 0.01252388 0.08638197 0.02263796 0.09056395 0.003259897 0.114242 0.01252388 0.110897 0.02952992 0.08638197 0.02263796 0.100233 0.003607988 0.09056395 0.003259897 0.07831096 0.002044916 0.111398 0.01003599 0.114242 0.01252388 0.09056395 0.003259897 0.10781 0.007610976 0.111398 0.01003599 0.09056395 0.003259897 0.104008 0.005760908 0.10781 0.007610976 0.09056395 0.003259897 0.100015 0.004482984 0.104008 0.005760908 0.09056395 0.003259897 0.09584599 0.003780961 0.100015 0.004482984 0.09056395 0.003259897 0.100233 0.003607988 0.09584599 0.003780961 0.09056395 0.003259897 0.100233 0.140741 0.09584599 0.140569 0.100005 0.139869 0.100233 0.140741 0.06440496 0.144291 0.09584599 0.140569 0.108523 0.138791 0.100005 0.139869 0.103983 0.138599 0.10442 0.1400409 0.100005 0.139869 0.108523 0.138791 0.100233 0.140741 0.100005 0.139869 0.10442 0.1400409 0.1125349 0.137004 0.103983 0.138599 0.107767 0.136764 0.108523 0.138791 0.103983 0.138599 0.1125349 0.137004 0.116406 0.134698 0.107767 0.136764 0.111337 0.134362 0.1125349 0.137004 0.107767 0.136764 0.116406 0.134698 0.116406 0.134698 0.111337 0.134362 0.114241 0.1318269 0.117574 0.128107 0.114241 0.1318269 0.110897 0.114822 0.123594 0.128661 0.114241 0.1318269 0.117574 0.128107 0.116406 0.134698 0.114241 0.1318269 0.123594 0.128661 0.126727 0.110337 0.110897 0.114822 0.108766 0.09784799 0.120276 0.124283 0.117574 0.128107 0.110897 0.114822 0.122706 0.120017 0.120276 0.124283 0.110897 0.114822 0.124855 0.115357 0.122706 0.120017 0.110897 0.114822 0.126727 0.110337 0.124855 0.115357 0.110897 0.114822 0.1306689 0.09371095 0.108766 0.09784799 0.1077 0.080747 0.128322 0.104997 0.126727 0.110337 0.108766 0.09784799 0.1296319 0.09943997 0.128322 0.104997 0.108766 0.09784799 0.1306689 0.09371095 0.1296319 0.09943997 0.108766 0.09784799 0.132073 0.08003699 0.1077 0.080747 0.1077 0.06360399 0.131444 0.08783596 0.1306689 0.09371095 0.1077 0.080747 0.132073 0.08003699 0.131444 0.08783596 0.1077 0.080747 0.131444 0.05651295 0.1077 0.06360399 0.108766 0.04650396 0.132282 0.07217496 0.132073 0.08003699 0.1077 0.06360399 0.132073 0.06431299 0.132282 0.07217496 0.1077 0.06360399 0.131444 0.05651295 0.132073 0.06431299 0.1077 0.06360399 0.129663 0.04506099 0.108766 0.04650396 0.110897 0.02952992 0.130684 0.05072891 0.131444 0.05651295 0.108766 0.04650396 0.129663 0.04506099 0.130684 0.05072891 0.108766 0.04650396 0.124933 0.02918189 0.110897 0.02952992 0.114242 0.01252388 0.128371 0.03953891 0.129663 0.04506099 0.110897 0.02952992 0.126792 0.03420895 0.128371 0.03953891 0.110897 0.02952992 0.124933 0.02918189 0.126792 0.03420895 0.110897 0.02952992 0.123645 0.015742 0.114242 0.01252388 0.111398 0.01003599 0.122791 0.02450096 0.124933 0.02918189 0.114242 0.01252388 0.1203629 0.02020597 0.122791 0.02450096 0.114242 0.01252388 0.117657 0.016348 0.1203629 0.02020597 0.114242 0.01252388 0.123645 0.015742 0.117657 0.016348 0.114242 0.01252388 0.116447 0.009679973 0.111398 0.01003599 0.10781 0.007610976 0.123645 0.015742 0.111398 0.01003599 0.116447 0.009679973 0.112565 0.007361948 0.10781 0.007610976 0.104008 0.005760908 0.116447 0.009679973 0.10781 0.007610976 0.112565 0.007361948 0.108542 0.005565941 0.104008 0.005760908 0.100015 0.004482984 0.112565 0.007361948 0.104008 0.005760908 0.108542 0.005565941 0.104429 0.004310965 0.100015 0.004482984 0.09584599 0.003780961 0.108542 0.005565941 0.100015 0.004482984 0.104429 0.004310965 0.104429 0.004310965 0.09584599 0.003780961 0.100233 0.003607988 0.123594 0.128661 0.117574 0.128107 0.120276 0.124283 0.129908 0.120885 0.120276 0.124283 0.122706 0.120017 0.123594 0.128661 0.120276 0.124283 0.129908 0.120885 0.129908 0.120885 0.122706 0.120017 0.124855 0.115357 0.135173 0.111634 0.124855 0.115357 0.126727 0.110337 0.129908 0.120885 0.124855 0.115357 0.135173 0.111634 0.135173 0.111634 0.126727 0.110337 0.128322 0.104997 0.139239 0.10122 0.128322 0.104997 0.1296319 0.09943997 0.135173 0.111634 0.128322 0.104997 0.139239 0.10122 0.14079 0.09567695 0.1296319 0.09943997 0.1306689 0.09371095 0.139239 0.10122 0.1296319 0.09943997 0.14079 0.09567695 0.1420069 0.08995896 0.1306689 0.09371095 0.131444 0.08783596 0.14079 0.09567695 0.1306689 0.09371095 0.1420069 0.08995896 0.142882 0.084113 0.131444 0.08783596 0.132073 0.08003699 0.1420069 0.08995896 0.131444 0.08783596 0.142882 0.084113 0.14341 0.078188 0.132073 0.08003699 0.132282 0.07217496 0.142882 0.084113 0.132073 0.08003699 0.14341 0.078188 0.143414 0.066235 0.132282 0.07217496 0.132073 0.06431299 0.143588 0.07221096 0.132282 0.07217496 0.143414 0.066235 0.14341 0.078188 0.132282 0.07217496 0.143588 0.07221096 0.142891 0.0603109 0.132073 0.06431299 0.131444 0.05651295 0.143414 0.066235 0.132073 0.06431299 0.142891 0.0603109 0.142021 0.05446696 0.131444 0.05651295 0.130684 0.05072891 0.142891 0.0603109 0.131444 0.05651295 0.142021 0.05446696 0.140808 0.04874789 0.130684 0.05072891 0.129663 0.04506099 0.142021 0.05446696 0.130684 0.05072891 0.140808 0.04874789 0.139262 0.04320293 0.129663 0.04506099 0.128371 0.03953891 0.140808 0.04874789 0.129663 0.04506099 0.139262 0.04320293 0.139262 0.04320293 0.128371 0.03953891 0.126792 0.03420895 0.135205 0.03278297 0.126792 0.03420895 0.124933 0.02918189 0.139262 0.04320293 0.126792 0.03420895 0.135205 0.03278297 0.135205 0.03278297 0.124933 0.02918189 0.122791 0.02450096 0.129953 0.02353 0.122791 0.02450096 0.1203629 0.02020597 0.135205 0.03278297 0.122791 0.02450096 0.129953 0.02353 0.129953 0.02353 0.1203629 0.02020597 0.117657 0.016348 0.129953 0.02353 0.117657 0.016348 0.123645 0.015742 0.02934288 0.03333389 0.01981699 0.03337198 0.005089998 0.05449098 0.04228198 0.01273298 0.01981699 0.03337198 0.02934288 0.03333389 0.01605695 0.05446493 0.005089998 0.05449098 0.002332985 0.05979496 0.02934288 0.03333389 0.005089998 0.05449098 0.01605695 0.05446493 0.01304197 0.06092488 0.002332985 0.05979496 5.94e-4 0.06580799 0.01605695 0.05446493 0.002332985 0.05979496 0.01304197 0.06092488 0.01146394 0.06831496 5.94e-4 0.06580799 0 0.07217496 0.01304197 0.06092488 5.94e-4 0.06580799 0.01146394 0.06831496 0.01146394 0.07603496 0 0.07217496 5.94e-4 0.07854199 0.01146394 0.06831496 0 0.07217496 0.01146394 0.07603496 0.01304197 0.08342498 5.94e-4 0.07854199 0.002332985 0.08455395 0.01146394 0.07603496 5.94e-4 0.07854199 0.01304197 0.08342498 0.01304197 0.08342498 0.002332985 0.08455395 0.005088925 0.089859 0.01605695 0.08988398 0.005088925 0.089859 0.01981699 0.110977 0.01304197 0.08342498 0.005088925 0.089859 0.01605695 0.08988398 0.02934288 0.111016 0.01605695 0.08988398 0.01981699 0.110977 0.04228198 0.01273298 0.04228198 0.1316159 0.04690599 0.137452 0.02934288 0.03333389 0.02934288 0.111016 0.04228198 0.1316159 0.04228198 0.01273298 0.02934288 0.03333389 0.04228198 0.1316159 0.04690599 0.006897926 0.04690599 0.137452 0.05232989 0.141616 0.04690599 0.006897926 0.04228198 0.01273298 0.04690599 0.137452 0.05232989 0.002733886 0.05232989 0.141616 0.05525398 0.143009 0.05232989 0.002733886 0.04690599 0.006897926 0.05232989 0.141616 0.05525398 0.001339972 0.05525398 0.143009 0.05826497 0.143922 0.05525398 0.001339972 0.05232989 0.002733886 0.05525398 0.143009 0.05826497 4.28e-4 0.05826497 0.143922 0.06132495 0.14435 0.05826497 4.28e-4 0.05525398 0.001339972 0.05826497 0.143922 0.06132495 0 0.06132495 0.14435 0.06440496 0.144291 0.06132495 0 0.05826497 4.28e-4 0.06132495 0.14435 0.06440496 5.8e-5 0.06132495 0 0.06440496 0.144291 0.100233 0.140741 0.06440496 5.8e-5 0.06440496 0.144291 0.01605695 0.05446493 0.01605695 0.08988398 0.02934288 0.111016 0.01304197 0.06092488 0.01304197 0.08342498 0.01605695 0.08988398 0.01605695 0.05446493 0.01304197 0.06092488 0.01605695 0.08988398 0.02934288 0.03333389 0.01605695 0.05446493 0.02934288 0.111016 0.01146394 0.06831496 0.01146394 0.07603496 0.01304197 0.08342498 0.01304197 0.06092488 0.01146394 0.06831496 0.01304197 0.08342498 0.100233 0.140741 0.100233 0.003607988 0.06440496 5.8e-5 0.10442 0.1400409 0.104429 0.004310965 0.100233 0.003607988 0.100233 0.140741 0.10442 0.1400409 0.100233 0.003607988 0.108523 0.138791 0.108542 0.005565941 0.104429 0.004310965 0.10442 0.1400409 0.108523 0.138791 0.104429 0.004310965 0.1125349 0.137004 0.112565 0.007361948 0.108542 0.005565941 0.108523 0.138791 0.1125349 0.137004 0.108542 0.005565941 0.116406 0.134698 0.116447 0.009679973 0.112565 0.007361948 0.1125349 0.137004 0.116406 0.134698 0.112565 0.007361948 0.123594 0.128661 0.123645 0.015742 0.116447 0.009679973 0.116406 0.134698 0.123594 0.128661 0.116447 0.009679973 0.129908 0.120885 0.129953 0.02353 0.123645 0.015742 0.123594 0.128661 0.129908 0.120885 0.123645 0.015742 0.135173 0.111634 0.135205 0.03278297 0.129953 0.02353 0.129908 0.120885 0.135173 0.111634 0.129953 0.02353 0.139239 0.10122 0.139262 0.04320293 0.135205 0.03278297 0.135173 0.111634 0.139239 0.10122 0.135205 0.03278297 0.14079 0.09567695 0.140808 0.04874789 0.139262 0.04320293 0.139239 0.10122 0.14079 0.09567695 0.139262 0.04320293 0.1420069 0.08995896 0.142021 0.05446696 0.140808 0.04874789 0.14079 0.09567695 0.1420069 0.08995896 0.140808 0.04874789 0.142882 0.084113 0.142891 0.0603109 0.142021 0.05446696 0.1420069 0.08995896 0.142882 0.084113 0.142021 0.05446696 0.14341 0.078188 0.143414 0.066235 0.142891 0.0603109 0.142882 0.084113 0.14341 0.078188 0.142891 0.0603109 0.14341 0.078188 0.143588 0.07221096 0.143414 0.066235 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 3 3 3 4 3 4 5 3 5 6 4 6 7 5 7 8 6 8 9 7 9 10 7 10 4 7 11 3 8 12 9 8 13 4 8 14 0 0 15 11 9 16 1 1 17 3 10 18 5 10 19 12 10 20 0 0 21 13 11 22 11 9 23 14 12 24 15 13 25 16 14 26 14 12 27 17 15 28 15 13 29 3 16 30 12 16 31 18 16 32 0 0 33 19 17 34 13 11 35 20 18 36 16 14 37 21 19 38 14 12 39 16 14 40 20 18 41 22 20 42 23 21 43 19 17 44 20 18 45 21 19 46 24 22 47 25 23 48 22 20 49 19 17 50 0 0 51 25 23 52 19 17 53 26 24 54 27 25 55 28 26 56 29 27 57 27 25 58 26 24 59 30 28 60 31 29 61 32 30 62 30 28 63 33 31 64 31 29 65 26 24 66 28 26 67 34 32 68 35 33 69 36 34 70 7 5 71 37 35 72 36 34 73 35 33 74 38 36 75 39 37 76 40 38 77 41 39 78 39 37 79 38 36 80 35 33 81 7 5 82 6 4 83 42 40 84 43 41 85 44 42 86 45 43 87 46 43 88 47 43 89 48 44 90 42 40 91 44 42 92 49 45 93 50 46 94 51 47 95 52 48 96 51 47 97 53 49 98 45 50 99 54 50 100 46 50 101 52 48 102 49 45 103 51 47 104 42 40 105 55 51 106 43 41 107 56 52 108 47 52 109 57 52 110 56 53 111 45 53 112 47 53 113 35 33 114 6 4 115 55 51 116 56 54 117 57 54 118 10 54 119 42 40 120 35 33 121 55 51 122 9 55 123 56 55 124 10 55 125 37 35 126 35 33 127 42 40 128 58 56 129 42 40 130 48 44 131 59 57 132 37 35 133 42 40 134 58 56 135 59 57 136 42 40 137 58 56 138 48 44 139 60 58 140 61 59 141 62 60 142 50 46 143 63 61 144 61 59 145 50 46 146 64 62 147 63 61 148 50 46 149 49 45 150 64 62 151 50 46 152 65 63 153 66 64 154 38 36 155 67 65 156 38 36 157 66 64 158 68 66 159 69 67 160 70 68 161 71 69 162 67 65 163 66 64 164 68 66 165 72 70 166 69 67 167 41 39 168 38 36 169 67 65 170 52 48 171 53 49 172 73 71 173 45 72 174 74 72 175 54 72 176 75 73 177 76 74 178 77 75 179 45 76 180 78 76 181 74 76 182 68 66 183 70 68 184 79 77 185 80 78 186 81 79 187 82 80 188 83 81 189 81 79 190 80 78 191 84 82 192 85 83 193 86 84 194 87 85 195 82 80 196 88 86 197 80 78 198 82 80 199 87 85 200 89 87 201 88 86 202 76 74 203 87 85 204 88 86 205 89 87 206 89 87 207 76 74 208 75 73 209 90 88 210 91 89 211 92 90 212 93 91 213 94 91 214 95 91 215 96 92 216 90 88 217 92 90 218 97 93 219 98 94 220 99 95 221 93 96 222 100 96 223 94 96 224 90 88 225 101 97 226 91 89 227 93 98 228 95 98 229 102 98 230 103 99 231 104 100 232 101 97 233 105 101 234 102 101 235 106 101 236 90 88 237 103 99 238 101 97 239 105 102 240 93 102 241 102 102 242 103 99 243 107 103 244 104 100 245 108 104 246 106 104 247 109 104 248 108 105 249 105 105 250 106 105 251 110 106 252 111 107 253 107 103 254 112 108 255 109 108 256 113 108 257 103 99 258 110 106 259 107 103 260 112 109 261 108 109 262 109 109 263 110 106 264 114 110 265 111 107 266 115 111 267 113 111 268 116 111 269 115 112 270 112 112 271 113 112 272 117 113 273 118 114 274 114 110 275 119 115 276 116 115 277 120 115 278 110 106 279 117 113 280 114 110 281 121 116 282 115 116 283 116 116 284 119 117 285 121 117 286 116 117 287 89 87 288 75 73 289 118 114 290 122 118 291 120 118 292 78 118 293 117 113 294 89 87 295 118 114 296 123 119 297 119 119 298 120 119 299 124 120 300 123 120 301 120 120 302 122 121 303 124 121 304 120 121 305 125 122 306 78 122 307 45 122 308 125 123 309 122 123 310 78 123 311 87 85 312 89 87 313 117 113 314 126 124 315 117 113 316 110 106 317 126 124 318 87 85 319 117 113 320 127 125 321 110 106 322 103 99 323 127 125 324 126 124 325 110 106 326 128 126 327 103 99 328 90 88 329 128 126 330 127 125 331 103 99 332 129 127 333 90 88 334 96 92 335 129 127 336 128 126 337 90 88 338 129 127 339 96 92 340 130 128 341 131 129 342 132 130 343 98 94 344 131 129 345 98 94 346 97 93 347 133 131 348 129 127 349 130 128 350 133 131 351 130 128 352 134 132 353 135 133 354 136 134 355 132 130 356 135 133 357 132 130 358 131 129 359 80 78 360 87 85 361 126 124 362 137 135 363 126 124 364 127 125 365 137 135 366 80 78 367 126 124 368 138 136 369 127 125 370 128 126 371 138 136 372 137 135 373 127 125 374 139 137 375 128 126 376 129 127 377 139 137 378 138 136 379 128 126 380 133 131 381 139 137 382 129 127 383 140 138 384 133 131 385 134 132 386 140 138 387 134 132 388 141 139 389 142 140 390 143 141 391 136 134 392 142 140 393 136 134 394 135 133 395 144 142 396 80 78 397 137 135 398 144 142 399 83 81 400 80 78 401 145 143 402 137 135 403 138 136 404 146 144 405 144 142 406 137 135 407 145 143 408 146 144 409 137 135 410 147 145 411 138 136 412 139 137 413 148 146 414 145 143 415 138 136 416 147 145 417 148 146 418 138 136 419 149 147 420 139 137 421 133 131 422 150 148 423 147 145 424 139 137 425 151 149 426 150 148 427 139 137 428 149 147 429 151 149 430 139 137 431 152 150 432 149 147 433 133 131 434 153 151 435 152 150 436 133 131 437 140 138 438 153 151 439 133 131 440 154 152 441 155 153 442 156 154 443 157 155 444 143 141 445 142 140 446 158 156 447 159 157 448 160 158 449 154 152 450 156 154 451 161 159 452 84 82 453 86 84 454 162 160 455 163 161 456 162 160 457 164 162 458 84 82 459 162 160 460 165 163 461 163 161 462 165 163 463 162 160 464 163 161 465 164 162 466 166 164 467 167 165 468 166 164 469 168 166 470 163 161 471 166 164 472 167 165 473 167 165 474 168 166 475 169 167 476 167 165 477 169 167 478 170 168 479 171 169 480 170 168 481 172 170 482 167 165 483 170 168 484 171 169 485 171 169 486 172 170 487 173 171 488 171 169 489 173 171 490 174 172 491 171 169 492 174 172 493 175 173 494 154 152 495 175 173 496 155 153 497 171 169 498 175 173 499 154 152 500 176 174 501 177 175 502 178 176 503 179 177 504 180 177 505 181 177 506 182 178 507 176 174 508 178 176 509 183 179 510 184 180 511 185 181 512 186 182 513 187 182 514 180 182 515 179 183 516 186 183 517 180 183 518 176 174 519 188 184 520 177 175 521 179 185 522 181 185 523 189 185 524 190 186 525 191 187 526 188 184 527 192 188 528 189 188 529 193 188 530 176 174 531 190 186 532 188 184 533 192 189 534 179 189 535 189 189 536 194 190 537 195 191 538 191 187 539 192 192 540 193 192 541 196 192 542 190 186 543 194 190 544 191 187 545 194 190 546 197 193 547 195 191 548 198 194 549 196 194 550 199 194 551 198 195 552 192 195 553 196 195 554 200 196 555 201 197 556 197 193 557 198 198 558 199 198 559 202 198 560 194 190 561 200 196 562 197 193 563 131 129 564 97 93 565 201 197 566 93 199 567 202 199 568 100 199 569 200 196 570 131 129 571 201 197 572 93 200 573 198 200 574 202 200 575 135 133 576 131 129 577 200 196 578 203 201 579 200 196 580 194 190 581 203 201 582 135 133 583 200 196 584 204 202 585 194 190 586 190 186 587 204 202 588 203 201 589 194 190 590 205 203 591 190 186 592 176 174 593 205 203 594 204 202 595 190 186 596 206 204 597 176 174 598 182 178 599 206 204 600 205 203 601 176 174 602 206 204 603 182 178 604 207 205 605 208 206 606 209 207 607 184 180 608 208 206 609 184 180 610 183 179 611 210 208 612 206 204 613 207 205 614 208 206 615 211 209 616 209 207 617 142 140 618 135 133 619 203 201 620 212 210 621 203 201 622 204 202 623 212 210 624 142 140 625 203 201 626 213 211 627 204 202 628 205 203 629 213 211 630 212 210 631 204 202 632 214 212 633 205 203 634 206 204 635 214 212 636 213 211 637 205 203 638 215 213 639 206 204 640 210 208 641 215 213 642 214 212 643 206 204 644 215 213 645 210 208 646 216 214 647 217 215 648 218 216 649 211 209 650 217 215 651 211 209 652 208 206 653 219 217 654 215 213 655 216 214 656 220 218 657 221 219 658 218 216 659 220 218 660 218 216 661 217 215 662 222 220 663 142 140 664 212 210 665 223 221 666 157 155 667 142 140 668 222 220 669 223 221 670 142 140 671 224 222 672 212 210 673 213 211 674 224 222 675 222 220 676 212 210 677 225 223 678 213 211 679 214 212 680 225 223 681 224 222 682 213 211 683 226 224 684 214 212 685 215 213 686 227 225 687 225 223 688 214 212 689 226 224 690 227 225 691 214 212 692 228 226 693 215 213 694 219 217 695 228 226 696 226 224 697 215 213 698 228 226 699 219 217 700 229 227 701 220 218 702 230 228 703 221 219 704 231 229 705 232 230 706 233 231 707 234 232 708 235 233 709 236 234 710 237 235 711 231 229 712 233 231 713 234 232 714 238 236 715 235 233 716 239 237 717 160 158 718 240 238 719 158 156 720 160 158 721 239 237 722 239 237 723 240 238 724 241 239 725 239 237 726 241 239 727 242 240 728 243 241 729 242 240 730 244 242 731 243 241 732 239 237 733 242 240 734 245 243 735 244 242 736 246 244 737 245 243 738 243 241 739 244 242 740 245 243 741 246 244 742 247 245 743 231 229 744 247 245 745 232 230 746 231 229 747 245 243 748 247 245 749 248 246 750 183 179 751 249 247 752 186 248 753 250 248 754 187 248 755 251 249 756 252 250 757 253 251 758 251 249 759 253 251 760 254 252 761 186 253 762 255 253 763 250 253 764 248 246 765 208 206 766 183 179 767 256 254 768 217 215 769 208 206 770 248 246 771 256 254 772 208 206 773 257 255 774 220 218 775 217 215 776 256 254 777 257 255 778 217 215 779 258 256 780 236 234 781 259 257 782 258 256 783 234 232 784 236 234 785 260 258 786 261 259 787 262 260 788 263 261 789 264 262 790 265 263 791 263 261 792 266 264 793 264 262 794 267 265 795 262 260 796 252 250 797 268 266 798 260 258 799 262 260 800 269 267 801 268 266 802 262 260 803 267 265 804 269 267 805 262 260 806 251 249 807 267 265 808 252 250 809 251 249 810 254 252 811 270 268 812 186 269 813 271 269 814 255 269 815 272 270 816 273 271 817 274 272 818 275 273 819 276 273 820 271 273 821 186 274 822 275 274 823 271 274 824 277 275 825 265 263 826 278 276 827 263 261 828 265 263 829 277 275 830 277 275 831 278 276 832 279 277 833 280 278 834 281 279 835 282 280 836 283 281 837 281 279 838 280 278 839 284 282 840 285 283 841 286 284 842 287 285 843 285 283 844 284 282 845 288 286 846 282 280 847 273 271 848 288 286 849 280 278 850 282 280 851 272 270 852 288 286 853 273 271 854 289 287 855 290 288 856 291 289 857 292 290 858 291 289 859 290 288 860 293 291 861 294 292 862 295 293 863 296 294 864 291 289 865 292 290 866 297 295 867 298 295 868 299 295 869 300 296 870 301 297 871 302 298 872 300 296 873 302 298 874 303 299 875 304 300 876 305 301 877 306 302 878 307 302 879 304 300 880 306 302 881 308 303 882 309 304 883 290 288 884 292 290 885 290 288 886 309 304 887 310 305 888 308 303 889 290 288 890 289 287 891 310 305 892 290 288 893 311 306 894 312 307 895 309 304 896 313 308 897 309 304 898 312 307 899 314 309 900 311 306 901 309 304 902 315 310 903 314 309 904 309 304 905 316 311 906 315 310 907 309 304 908 308 303 909 316 311 910 309 304 911 313 308 912 292 290 913 309 304 914 317 312 915 280 278 916 312 307 917 318 313 918 312 307 919 280 278 920 319 314 921 317 312 922 312 307 923 320 315 924 319 314 925 312 307 926 311 306 927 320 315 928 312 307 929 318 313 930 313 308 931 312 307 932 321 316 933 283 281 934 280 278 935 317 312 936 321 316 937 280 278 938 288 286 939 318 313 940 280 278 941 284 282 942 286 284 943 322 317 944 323 318 945 322 317 946 324 319 947 284 282 948 322 317 949 323 318 950 323 318 951 324 319 952 325 320 953 326 321 954 325 320 955 327 322 956 323 318 957 325 320 958 326 321 959 326 321 960 327 322 961 328 323 962 329 324 963 328 323 964 330 325 965 326 321 966 328 323 967 329 324 968 329 324 969 330 325 970 331 326 971 329 324 972 331 326 973 332 327 974 333 328 975 332 327 976 334 329 977 329 324 978 332 327 979 333 328 980 333 328 981 334 329 982 335 330 983 336 331 984 335 330 985 294 292 986 337 332 987 333 328 988 335 330 989 336 331 990 337 332 991 335 330 992 293 291 993 336 331 994 294 292 995 338 333 996 292 290 997 313 308 998 338 333 999 296 294 1000 292 290 1001 339 334 1002 313 308 1003 318 313 1004 339 334 1005 338 333 1006 313 308 1007 340 335 1008 318 313 1009 288 286 1010 341 336 1011 339 334 1012 318 313 1013 340 335 1014 341 336 1015 318 313 1016 272 270 1017 340 335 1018 288 286 1019 275 337 1020 299 337 1021 342 337 1022 343 338 1023 297 338 1024 299 338 1025 275 339 1026 343 339 1027 299 339 1028 275 340 1029 342 340 1030 344 340 1031 275 341 1032 344 341 1033 345 341 1034 275 342 1035 345 342 1036 346 342 1037 275 343 1038 346 343 1039 276 343 1040 347 344 1041 348 345 1042 333 328 1043 329 324 1044 333 328 1045 348 345 1046 337 332 1047 347 344 1048 333 328 1049 349 346 1050 350 347 1051 348 345 1052 351 348 1053 348 345 1054 350 347 1055 347 344 1056 349 346 1057 348 345 1058 351 348 1059 329 324 1060 348 345 1061 352 349 1062 353 350 1063 350 347 1064 354 351 1065 350 347 1066 353 350 1067 349 346 1068 352 349 1069 350 347 1070 354 351 1071 351 348 1072 350 347 1073 355 352 1074 356 353 1075 353 350 1076 357 354 1077 353 350 1078 356 353 1079 352 349 1080 355 352 1081 353 350 1082 357 354 1083 354 351 1084 353 350 1085 358 355 1086 359 356 1087 356 353 1088 360 357 1089 356 353 1090 359 356 1091 355 352 1092 358 355 1093 356 353 1094 360 357 1095 357 354 1096 356 353 1097 361 358 1098 362 359 1099 359 356 1100 363 360 1101 359 356 1102 362 359 1103 364 361 1104 361 358 1105 359 356 1106 358 355 1107 364 361 1108 359 356 1109 363 360 1110 360 357 1111 359 356 1112 365 362 1113 366 363 1114 362 359 1115 367 364 1116 362 359 1117 366 363 1118 368 365 1119 365 362 1120 362 359 1121 361 358 1122 368 365 1123 362 359 1124 367 364 1125 363 360 1126 362 359 1127 369 366 1128 370 367 1129 366 363 1130 371 368 1131 366 363 1132 370 367 1133 365 362 1134 369 366 1135 366 363 1136 371 368 1137 367 364 1138 366 363 1139 372 369 1140 373 370 1141 370 367 1142 374 371 1143 370 367 1144 373 370 1145 375 372 1146 372 369 1147 370 367 1148 369 366 1149 375 372 1150 370 367 1151 374 371 1152 371 368 1153 370 367 1154 376 373 1155 377 374 1156 373 370 1157 374 371 1158 373 370 1159 377 374 1160 378 375 1161 376 373 1162 373 370 1163 372 369 1164 378 375 1165 373 370 1166 379 376 1167 380 377 1168 381 378 1169 382 379 1170 374 371 1171 377 374 1172 379 376 1173 383 380 1174 380 377 1175 384 381 1176 385 382 1177 386 383 1178 384 381 1179 387 384 1180 385 382 1181 379 376 1182 381 378 1183 388 385 1184 389 386 1185 386 383 1186 390 387 1187 389 386 1188 384 381 1189 386 383 1190 389 386 1191 390 387 1192 391 388 1193 389 386 1194 391 388 1195 392 389 1196 393 390 1197 392 389 1198 394 391 1199 393 390 1200 389 386 1201 392 389 1202 393 390 1203 394 391 1204 395 392 1205 396 393 1206 395 392 1207 397 394 1208 396 393 1209 393 390 1210 395 392 1211 396 393 1212 397 394 1213 398 395 1214 399 396 1215 398 395 1216 400 397 1217 399 396 1218 396 393 1219 398 395 1220 399 396 1221 400 397 1222 401 398 1223 402 399 1224 401 398 1225 403 400 1226 402 399 1227 399 396 1228 401 398 1229 404 401 1230 403 400 1231 405 402 1232 404 401 1233 402 399 1234 403 400 1235 404 401 1236 405 402 1237 406 403 1238 407 404 1239 406 403 1240 408 405 1241 407 404 1242 404 401 1243 406 403 1244 300 296 1245 408 405 1246 409 406 1247 300 296 1248 407 404 1249 408 405 1250 300 296 1251 409 406 1252 301 297 1253 326 321 1254 329 324 1255 351 348 1256 410 407 1257 351 348 1258 354 351 1259 410 407 1260 326 321 1261 351 348 1262 411 408 1263 354 351 1264 357 354 1265 411 408 1266 410 407 1267 354 351 1268 412 409 1269 357 354 1270 360 357 1271 412 409 1272 411 408 1273 357 354 1274 413 410 1275 360 357 1276 363 360 1277 413 410 1278 412 409 1279 360 357 1280 414 411 1281 363 360 1282 367 364 1283 414 411 1284 413 410 1285 363 360 1286 415 412 1287 367 364 1288 371 368 1289 415 412 1290 414 411 1291 367 364 1292 416 413 1293 371 368 1294 374 371 1295 416 413 1296 415 412 1297 371 368 1298 417 414 1299 374 371 1300 382 379 1301 417 414 1302 416 413 1303 374 371 1304 418 415 1305 417 414 1306 382 379 1307 419 416 1308 420 417 1309 383 380 1310 419 416 1311 383 380 1312 379 376 1313 323 318 1314 326 321 1315 410 407 1316 421 418 1317 410 407 1318 411 408 1319 421 418 1320 323 318 1321 410 407 1322 422 419 1323 411 408 1324 412 409 1325 422 419 1326 421 418 1327 411 408 1328 423 420 1329 412 409 1330 413 410 1331 423 420 1332 422 419 1333 412 409 1334 424 421 1335 413 410 1336 414 411 1337 424 421 1338 423 420 1339 413 410 1340 425 422 1341 414 411 1342 415 412 1343 425 422 1344 424 421 1345 414 411 1346 426 423 1347 415 412 1348 416 413 1349 426 423 1350 425 422 1351 415 412 1352 427 424 1353 416 413 1354 417 414 1355 427 424 1356 426 423 1357 416 413 1358 427 424 1359 417 414 1360 418 415 1361 428 425 1362 427 424 1363 418 415 1364 429 426 1365 430 427 1366 420 417 1367 429 426 1368 420 417 1369 419 416 1370 284 282 1371 323 318 1372 421 418 1373 431 428 1374 421 418 1375 422 419 1376 431 428 1377 284 282 1378 421 418 1379 432 429 1380 422 419 1381 423 420 1382 432 429 1383 431 428 1384 422 419 1385 433 430 1386 423 420 1387 424 421 1388 433 430 1389 432 429 1390 423 420 1391 434 431 1392 424 421 1393 425 422 1394 434 431 1395 433 430 1396 424 421 1397 435 432 1398 425 422 1399 426 423 1400 435 432 1401 434 431 1402 425 422 1403 436 433 1404 426 423 1405 427 424 1406 436 433 1407 435 432 1408 426 423 1409 436 433 1410 427 424 1411 428 425 1412 437 434 1413 436 433 1414 428 425 1415 438 435 1416 439 436 1417 430 427 1418 438 435 1419 430 427 1420 429 426 1421 287 285 1422 284 282 1423 431 428 1424 440 437 1425 431 428 1426 432 429 1427 440 437 1428 287 285 1429 431 428 1430 441 438 1431 432 429 1432 433 430 1433 441 438 1434 440 437 1435 432 429 1436 442 439 1437 433 430 1438 434 431 1439 443 440 1440 441 438 1441 433 430 1442 442 439 1443 443 440 1444 433 430 1445 444 441 1446 434 431 1447 435 432 1448 445 442 1449 442 439 1450 434 431 1451 444 441 1452 445 442 1453 434 431 1454 446 443 1455 435 432 1456 436 433 1457 447 444 1458 444 441 1459 435 432 1460 448 445 1461 447 444 1462 435 432 1463 446 443 1464 448 445 1465 435 432 1466 449 446 1467 436 433 1468 437 434 1469 450 447 1470 446 443 1471 436 433 1472 449 446 1473 450 447 1474 436 433 1475 451 448 1476 449 446 1477 437 434 1478 452 449 1479 453 450 1480 439 436 1481 454 451 1482 439 436 1483 438 435 1484 455 452 1485 439 436 1486 454 451 1487 452 449 1488 439 436 1489 455 452 1490 263 261 1491 277 275 1492 456 453 1493 263 261 1494 456 453 1495 457 454 1496 263 261 1497 457 454 1498 458 455 1499 459 456 1500 458 455 1501 460 457 1502 263 261 1503 458 455 1504 459 456 1505 459 456 1506 460 457 1507 461 458 1508 459 456 1509 461 458 1510 462 459 1511 463 460 1512 462 459 1513 464 461 1514 465 462 1515 462 459 1516 463 460 1517 466 463 1518 462 459 1519 465 462 1520 467 464 1521 462 459 1522 466 463 1523 468 465 1524 462 459 1525 467 464 1526 469 466 1527 462 459 1528 468 465 1529 470 467 1530 462 459 1531 469 466 1532 459 456 1533 462 459 1534 470 467 1535 471 468 1536 464 461 1537 472 469 1538 463 460 1539 464 461 1540 471 468 1541 473 470 1542 472 469 1543 474 471 1544 475 472 1545 472 469 1546 473 470 1547 471 468 1548 472 469 1549 475 472 1550 476 473 1551 474 471 1552 477 474 1553 478 475 1554 474 471 1555 476 473 1556 479 476 1557 474 471 1558 478 475 1559 473 470 1560 474 471 1561 479 476 1562 480 477 1563 477 474 1564 481 478 1565 482 479 1566 477 474 1567 480 477 1568 483 480 1569 477 474 1570 482 479 1571 476 473 1572 477 474 1573 483 480 1574 484 481 1575 481 478 1576 485 482 1577 486 483 1578 481 478 1579 484 481 1580 487 484 1581 481 478 1582 486 483 1583 488 485 1584 481 478 1585 487 484 1586 480 477 1587 481 478 1588 488 485 1589 489 486 1590 490 487 1591 491 488 1592 489 489 1593 492 489 1594 490 489 1595 493 490 1596 485 482 1597 494 491 1598 484 481 1599 485 482 1600 493 490 1601 495 492 1602 496 492 1603 497 492 1604 304 300 1605 498 493 1606 305 301 1607 384 381 1608 499 494 1609 387 384 1610 379 376 1611 388 385 1612 500 495 1613 384 381 1614 501 496 1615 499 494 1616 502 497 1617 503 498 1618 504 499 1619 502 497 1620 505 500 1621 503 498 1622 506 501 1623 507 502 1624 501 496 1625 502 497 1626 504 499 1627 508 503 1628 384 381 1629 506 501 1630 501 496 1631 506 501 1632 509 504 1633 507 502 1634 510 505 1635 508 503 1636 511 506 1637 510 505 1638 502 497 1639 508 503 1640 506 501 1641 512 507 1642 509 504 1643 510 505 1644 511 506 1645 513 508 1646 506 501 1647 514 509 1648 512 507 1649 515 510 1650 513 508 1651 516 511 1652 510 505 1653 513 508 1654 515 510 1655 517 512 1656 518 513 1657 519 513 1658 520 514 1659 518 513 1660 517 512 1661 521 515 1662 522 516 1663 523 517 1664 524 518 1665 522 516 1666 521 515 1667 525 492 1668 526 492 1669 527 492 1670 528 519 1671 529 519 1672 526 519 1673 525 492 1674 528 492 1675 526 492 1676 530 520 1677 527 520 1678 531 520 1679 530 521 1680 525 521 1681 527 521 1682 532 492 1683 531 492 1684 533 492 1685 532 492 1686 530 492 1687 531 492 1688 534 492 1689 533 492 1690 535 492 1691 534 492 1692 532 492 1693 533 492 1694 536 492 1695 535 492 1696 537 492 1697 536 492 1698 534 492 1699 535 492 1700 538 492 1701 537 492 1702 539 492 1703 538 492 1704 536 492 1705 537 492 1706 540 492 1707 539 492 1708 541 492 1709 542 492 1710 538 492 1711 539 492 1712 540 522 1713 542 522 1714 539 522 1715 543 492 1716 541 492 1717 544 492 1718 543 523 1719 540 523 1720 541 523 1721 545 492 1722 544 492 1723 496 492 1724 545 492 1725 543 492 1726 544 492 1727 495 492 1728 546 492 1729 496 492 1730 545 524 1731 496 524 1732 546 524 1733 528 525 1734 547 525 1735 529 525 1736 520 514 1737 517 512 1738 548 526 1739 528 492 1740 549 492 1741 547 492 1742 550 527 1743 548 526 1744 551 528 1745 552 529 1746 520 514 1747 548 526 1748 550 530 1749 552 530 1750 548 530 1751 528 531 1752 553 531 1753 549 531 1754 554 532 1755 551 528 1756 555 533 1757 556 534 1758 550 527 1759 551 528 1760 557 535 1761 558 535 1762 559 535 1763 554 532 1764 556 534 1765 551 528 1766 560 492 1767 561 492 1768 553 492 1769 562 536 1770 555 533 1771 563 537 1772 528 538 1773 560 538 1774 553 538 1775 564 539 1776 554 532 1777 555 533 1778 565 540 1779 564 539 1780 555 533 1781 562 536 1782 565 540 1783 555 533 1784 560 492 1785 566 492 1786 561 492 1787 567 541 1788 563 537 1789 568 542 1790 567 541 1791 562 536 1792 563 537 1793 569 492 1794 570 492 1795 566 492 1796 571 543 1797 568 542 1798 572 544 1799 560 492 1800 569 492 1801 566 492 1802 571 543 1803 567 541 1804 568 542 1805 569 545 1806 573 545 1807 570 545 1808 574 546 1809 572 544 1810 575 547 1811 574 546 1812 571 543 1813 572 544 1814 576 492 1815 577 492 1816 573 492 1817 578 548 1818 575 547 1819 579 549 1820 569 492 1821 576 492 1822 573 492 1823 580 550 1824 574 546 1825 575 547 1826 578 548 1827 580 550 1828 575 547 1829 581 492 1830 582 492 1831 577 492 1832 583 551 1833 579 549 1834 584 552 1835 576 492 1836 581 492 1837 577 492 1838 583 551 1839 578 548 1840 579 549 1841 581 492 1842 585 492 1843 582 492 1844 586 553 1845 584 552 1846 587 554 1847 586 553 1848 583 551 1849 584 552 1850 588 492 1851 589 492 1852 585 492 1853 590 555 1854 587 554 1855 591 556 1856 581 492 1857 588 492 1858 585 492 1859 590 555 1860 586 553 1861 587 554 1862 588 492 1863 592 492 1864 589 492 1865 593 557 1866 591 556 1867 594 558 1868 593 557 1869 590 555 1870 591 556 1871 595 492 1872 596 492 1873 592 492 1874 593 557 1875 594 558 1876 597 559 1877 588 492 1878 595 492 1879 592 492 1880 595 492 1881 598 492 1882 596 492 1883 599 560 1884 597 559 1885 600 561 1886 599 560 1887 593 557 1888 597 559 1889 601 492 1890 602 492 1891 598 492 1892 603 562 1893 600 561 1894 604 563 1895 595 564 1896 601 564 1897 598 564 1898 603 562 1899 599 560 1900 600 561 1901 605 492 1902 606 492 1903 602 492 1904 607 565 1905 604 563 1906 608 566 1907 601 492 1908 605 492 1909 602 492 1910 607 565 1911 603 562 1912 604 563 1913 609 492 1914 610 492 1915 606 492 1916 611 567 1917 608 566 1918 612 568 1919 613 492 1920 609 492 1921 606 492 1922 605 492 1923 613 492 1924 606 492 1925 611 567 1926 607 565 1927 608 566 1928 614 492 1929 615 492 1930 610 492 1931 611 567 1932 612 568 1933 616 569 1934 609 492 1935 614 492 1936 610 492 1937 617 492 1938 618 492 1939 615 492 1940 619 570 1941 616 569 1942 620 571 1943 614 492 1944 617 492 1945 615 492 1946 619 570 1947 611 567 1948 616 569 1949 617 492 1950 621 492 1951 618 492 1952 622 572 1953 620 571 1954 623 573 1955 622 572 1956 619 570 1957 620 571 1958 624 574 1959 623 573 1960 625 575 1961 624 574 1962 622 572 1963 623 573 1964 626 576 1965 625 575 1966 627 577 1967 626 576 1968 624 574 1969 625 575 1970 628 578 1971 627 577 1972 629 579 1973 628 578 1974 626 576 1975 627 577 1976 613 492 1977 630 492 1978 609 492 1979 628 578 1980 629 579 1981 631 580 1982 632 492 1983 633 492 1984 630 492 1985 634 581 1986 631 580 1987 635 582 1988 613 492 1989 632 492 1990 630 492 1991 634 581 1992 628 578 1993 631 580 1994 636 583 1995 637 583 1996 633 583 1997 634 581 1998 635 582 1999 638 584 2000 632 492 2001 636 492 2002 633 492 2003 639 585 2004 640 585 2005 637 585 2006 641 586 2007 638 584 2008 642 587 2009 636 588 2010 639 588 2011 637 588 2012 641 586 2013 634 581 2014 638 584 2015 639 492 2016 643 492 2017 640 492 2018 641 586 2019 642 587 2020 644 589 2021 645 492 2022 646 492 2023 643 492 2024 647 590 2025 644 589 2026 648 591 2027 639 492 2028 645 492 2029 643 492 2030 647 590 2031 641 586 2032 644 589 2033 645 492 2034 649 492 2035 646 492 2036 647 590 2037 648 591 2038 650 592 2039 651 593 2040 652 593 2041 649 593 2042 653 594 2043 650 592 2044 654 595 2045 645 492 2046 651 492 2047 649 492 2048 653 594 2049 647 590 2050 650 592 2051 651 596 2052 655 596 2053 652 596 2054 653 594 2055 654 595 2056 656 597 2057 657 492 2058 658 492 2059 655 492 2060 659 598 2061 656 597 2062 660 599 2063 651 600 2064 657 600 2065 655 600 2066 659 598 2067 653 594 2068 656 597 2069 657 492 2070 661 492 2071 658 492 2072 659 598 2073 660 599 2074 662 601 2075 663 492 2076 664 492 2077 661 492 2078 665 602 2079 662 601 2080 666 603 2081 657 492 2082 663 492 2083 661 492 2084 665 602 2085 659 598 2086 662 601 2087 663 492 2088 667 492 2089 664 492 2090 668 604 2091 666 603 2092 669 605 2093 668 604 2094 665 602 2095 666 603 2096 670 492 2097 671 492 2098 667 492 2099 668 604 2100 669 605 2101 672 606 2102 663 607 2103 670 607 2104 667 607 2105 670 492 2106 673 492 2107 671 492 2108 674 608 2109 672 606 2110 675 609 2111 674 608 2112 668 604 2113 672 606 2114 676 492 2115 677 492 2116 673 492 2117 678 610 2118 675 609 2119 679 611 2120 670 612 2121 676 612 2122 673 612 2123 678 610 2124 674 608 2125 675 609 2126 680 613 2127 681 613 2128 677 613 2129 678 610 2130 679 611 2131 682 614 2132 680 492 2133 677 492 2134 676 492 2135 680 615 2136 683 615 2137 681 615 2138 678 610 2139 682 614 2140 684 616 2141 680 492 2142 685 492 2143 683 492 2144 686 617 2145 684 616 2146 687 618 2147 686 617 2148 678 610 2149 684 616 2150 688 492 2151 689 492 2152 685 492 2153 690 619 2154 687 618 2155 691 620 2156 680 492 2157 688 492 2158 685 492 2159 692 621 2160 686 617 2161 687 618 2162 690 619 2163 692 621 2164 687 618 2165 693 492 2166 694 492 2167 689 492 2168 695 622 2169 691 620 2170 696 623 2171 688 624 2172 693 624 2173 689 624 2174 697 625 2175 690 619 2176 691 620 2177 695 622 2178 697 625 2179 691 620 2180 698 492 2181 699 492 2182 694 492 2183 700 626 2184 696 623 2185 701 627 2186 693 492 2187 698 492 2188 694 492 2189 702 628 2190 695 622 2191 696 623 2192 700 626 2193 702 628 2194 696 623 2195 703 492 2196 704 492 2197 699 492 2198 705 629 2199 701 627 2200 706 630 2201 698 492 2202 703 492 2203 699 492 2204 707 631 2205 700 626 2206 701 627 2207 705 629 2208 707 631 2209 701 627 2210 708 492 2211 709 492 2212 704 492 2213 710 632 2214 706 630 2215 711 633 2216 703 492 2217 708 492 2218 704 492 2219 712 634 2220 705 629 2221 706 630 2222 710 632 2223 712 634 2224 706 630 2225 713 492 2226 714 492 2227 709 492 2228 715 635 2229 711 633 2230 716 636 2231 708 637 2232 713 637 2233 709 637 2234 717 638 2235 710 632 2236 711 633 2237 715 635 2238 717 638 2239 711 633 2240 718 492 2241 546 492 2242 714 492 2243 719 639 2244 716 636 2245 720 640 2246 721 492 2247 718 492 2248 714 492 2249 713 641 2250 721 641 2251 714 641 2252 722 642 2253 715 635 2254 716 636 2255 719 639 2256 722 642 2257 716 636 2258 723 643 2259 720 640 2260 498 493 2261 718 492 2262 545 492 2263 546 492 2264 723 643 2265 719 639 2266 720 640 2267 304 300 2268 723 643 2269 498 493 2270 724 644 2271 725 645 2272 726 646 2273 727 647 2274 728 648 2275 729 649 2276 727 647 2277 729 649 2278 730 650 2279 731 651 2280 726 646 2281 732 652 2282 731 651 2283 724 644 2284 726 646 2285 733 653 2286 732 652 2287 734 654 2288 733 653 2289 731 651 2290 732 652 2291 735 655 2292 734 654 2293 736 656 2294 735 655 2295 733 653 2296 734 654 2297 737 657 2298 736 656 2299 738 658 2300 737 657 2301 735 655 2302 736 656 2303 739 659 2304 738 658 2305 740 660 2306 739 659 2307 737 657 2308 738 658 2309 741 661 2310 740 660 2311 742 662 2312 741 661 2313 739 659 2314 740 660 2315 743 663 2316 742 662 2317 744 664 2318 745 665 2319 741 661 2320 742 662 2321 743 663 2322 745 665 2323 742 662 2324 746 666 2325 744 664 2326 747 667 2327 746 666 2328 743 663 2329 744 664 2330 748 668 2331 747 667 2332 749 669 2333 748 668 2334 746 666 2335 747 667 2336 750 670 2337 749 669 2338 751 671 2339 750 670 2340 748 668 2341 749 669 2342 752 672 2343 751 671 2344 753 673 2345 752 672 2346 750 670 2347 751 671 2348 752 672 2349 753 673 2350 754 674 2351 755 675 2352 754 674 2353 756 676 2354 755 675 2355 752 672 2356 754 674 2357 757 677 2358 756 676 2359 758 678 2360 757 677 2361 755 675 2362 756 676 2363 759 679 2364 758 678 2365 760 680 2366 759 679 2367 757 677 2368 758 678 2369 761 681 2370 760 680 2371 762 682 2372 761 681 2373 759 679 2374 760 680 2375 763 683 2376 762 682 2377 764 684 2378 763 683 2379 761 681 2380 762 682 2381 765 685 2382 764 684 2383 766 686 2384 765 685 2385 763 683 2386 764 684 2387 767 687 2388 768 688 2389 769 689 2390 770 690 2391 765 685 2392 766 686 2393 771 691 2394 769 689 2395 772 692 2396 771 691 2397 767 687 2398 769 689 2399 773 693 2400 772 692 2401 774 694 2402 773 693 2403 771 691 2404 772 692 2405 775 695 2406 774 694 2407 776 696 2408 775 695 2409 773 693 2410 774 694 2411 777 697 2412 776 696 2413 778 698 2414 777 697 2415 775 695 2416 776 696 2417 779 699 2418 778 698 2419 780 700 2420 779 699 2421 777 697 2422 778 698 2423 781 701 2424 780 700 2425 782 702 2426 781 701 2427 779 699 2428 780 700 2429 783 703 2430 782 702 2431 784 704 2432 785 705 2433 781 701 2434 782 702 2435 783 703 2436 785 705 2437 782 702 2438 786 706 2439 784 704 2440 787 707 2441 786 706 2442 783 703 2443 784 704 2444 788 708 2445 787 707 2446 789 709 2447 788 708 2448 786 706 2449 787 707 2450 790 710 2451 789 709 2452 791 711 2453 790 710 2454 788 708 2455 789 709 2456 792 712 2457 791 711 2458 793 713 2459 792 712 2460 790 710 2461 791 711 2462 792 712 2463 793 713 2464 794 714 2465 795 715 2466 794 714 2467 796 716 2468 795 715 2469 792 712 2470 794 714 2471 797 717 2472 796 716 2473 798 718 2474 797 717 2475 795 715 2476 796 716 2477 799 719 2478 798 718 2479 800 720 2480 799 719 2481 797 717 2482 798 718 2483 801 721 2484 800 720 2485 802 722 2486 801 721 2487 799 719 2488 800 720 2489 803 723 2490 802 722 2491 728 648 2492 803 723 2493 801 721 2494 802 722 2495 727 647 2496 803 723 2497 728 648 2498 521 515 2499 523 517 2500 804 724 2501 805 725 2502 804 724 2503 806 726 2504 805 725 2505 521 515 2506 804 724 2507 805 725 2508 806 726 2509 807 727 2510 808 728 2511 809 728 2512 557 728 2513 810 729 2514 805 725 2515 807 727 2516 810 729 2517 807 727 2518 811 730 2519 812 731 2520 813 732 2521 814 733 2522 812 731 2523 815 734 2524 813 732 2525 812 731 2526 814 733 2527 816 735 2528 817 736 2529 818 737 2530 819 738 2531 820 739 2532 819 738 2533 821 740 2534 820 739 2535 817 736 2536 819 738 2537 820 739 2538 821 740 2539 822 741 2540 823 742 2541 822 741 2542 824 743 2543 823 742 2544 820 739 2545 822 741 2546 825 744 2547 824 743 2548 826 745 2549 825 744 2550 823 742 2551 824 743 2552 825 744 2553 826 745 2554 827 746 2555 828 747 2556 827 746 2557 829 748 2558 828 747 2559 825 744 2560 827 746 2561 828 747 2562 829 748 2563 830 749 2564 831 750 2565 830 749 2566 832 751 2567 831 750 2568 828 747 2569 830 749 2570 833 752 2571 832 751 2572 834 753 2573 833 752 2574 831 750 2575 832 751 2576 835 754 2577 834 753 2578 836 755 2579 835 754 2580 833 752 2581 834 753 2582 837 756 2583 836 755 2584 838 757 2585 837 756 2586 835 754 2587 836 755 2588 839 758 2589 838 757 2590 840 759 2591 839 758 2592 837 756 2593 838 757 2594 841 760 2595 840 759 2596 842 761 2597 841 760 2598 839 758 2599 840 759 2600 843 762 2601 842 761 2602 844 763 2603 841 760 2604 842 761 2605 843 762 2606 845 764 2607 844 763 2608 846 765 2609 847 492 2610 848 492 2611 808 492 2612 845 764 2613 849 766 2614 844 763 2615 850 767 2616 844 763 2617 849 766 2618 851 768 2619 844 763 2620 850 767 2621 852 769 2622 844 763 2623 851 768 2624 853 770 2625 844 763 2626 852 769 2627 854 771 2628 844 763 2629 853 770 2630 855 772 2631 844 763 2632 854 771 2633 856 773 2634 844 763 2635 855 772 2636 857 774 2637 844 763 2638 856 773 2639 858 775 2640 844 763 2641 857 774 2642 843 762 2643 844 763 2644 858 775 2645 859 776 2646 860 776 2647 861 776 2648 862 777 2649 860 777 2650 859 777 2651 863 778 2652 864 778 2653 847 778 2654 865 779 2655 866 780 2656 867 781 2657 868 782 2658 866 780 2659 865 779 2660 869 783 2661 866 780 2662 868 782 2663 870 784 2664 871 785 2665 872 786 2666 873 787 2667 874 788 2668 875 789 2669 876 790 2670 872 786 2671 877 791 2672 878 792 2673 872 786 2674 876 790 2675 870 784 2676 872 786 2677 878 792 2678 879 793 2679 877 791 2680 880 794 2681 876 790 2682 877 791 2683 879 793 2684 881 795 2685 880 794 2686 882 796 2687 879 793 2688 880 794 2689 881 795 2690 883 797 2691 882 796 2692 884 798 2693 881 795 2694 882 796 2695 883 797 2696 885 799 2697 884 798 2698 886 800 2699 883 797 2700 884 798 2701 885 799 2702 887 801 2703 886 800 2704 888 802 2705 885 799 2706 886 800 2707 887 801 2708 889 803 2709 888 802 2710 890 804 2711 887 801 2712 888 802 2713 889 803 2714 891 805 2715 890 804 2716 892 806 2717 889 803 2718 890 804 2719 891 805 2720 893 807 2721 892 806 2722 894 808 2723 891 805 2724 892 806 2725 893 807 2726 893 807 2727 894 808 2728 895 809 2729 896 810 2730 895 809 2731 897 811 2732 893 807 2733 895 809 2734 896 810 2735 896 810 2736 897 811 2737 898 812 2738 899 813 2739 898 812 2740 900 814 2741 896 810 2742 898 812 2743 899 813 2744 901 815 2745 900 814 2746 902 816 2747 899 813 2748 900 814 2749 901 815 2750 901 815 2751 902 816 2752 903 817 2753 904 818 2754 903 817 2755 905 819 2756 901 815 2757 903 817 2758 904 818 2759 904 818 2760 905 819 2761 906 820 2762 907 821 2763 906 820 2764 908 822 2765 904 818 2766 906 820 2767 907 821 2768 907 821 2769 908 822 2770 909 823 2771 910 824 2772 909 823 2773 911 825 2774 907 821 2775 909 823 2776 910 824 2777 910 824 2778 911 825 2779 912 826 2780 913 827 2781 912 826 2782 914 828 2783 910 824 2784 912 826 2785 913 827 2786 913 827 2787 914 828 2788 915 829 2789 916 830 2790 915 829 2791 917 831 2792 913 827 2793 915 829 2794 916 830 2795 916 830 2796 917 831 2797 918 832 2798 919 833 2799 918 832 2800 920 834 2801 916 830 2802 918 832 2803 919 833 2804 921 835 2805 920 834 2806 922 836 2807 919 833 2808 920 834 2809 921 835 2810 923 837 2811 922 836 2812 924 838 2813 921 835 2814 922 836 2815 923 837 2816 925 839 2817 926 840 2818 927 841 2819 928 842 2820 926 840 2821 925 839 2822 923 837 2823 924 838 2824 929 843 2825 930 844 2826 931 845 2827 521 515 2828 932 846 2829 521 515 2830 931 845 2831 805 725 2832 930 844 2833 521 515 2834 932 846 2835 524 518 2836 521 515 2837 933 847 2838 934 848 2839 931 845 2840 932 846 2841 931 845 2842 934 848 2843 930 844 2844 933 847 2845 931 845 2846 935 849 2847 936 850 2848 934 848 2849 937 851 2850 934 848 2851 936 850 2852 933 847 2853 935 849 2854 934 848 2855 937 851 2856 932 846 2857 934 848 2858 938 852 2859 939 853 2860 936 850 2861 940 854 2862 936 850 2863 939 853 2864 935 849 2865 938 852 2866 936 850 2867 940 854 2868 937 851 2869 936 850 2870 941 855 2871 942 856 2872 939 853 2873 943 857 2874 939 853 2875 942 856 2876 944 858 2877 941 855 2878 939 853 2879 938 852 2880 944 858 2881 939 853 2882 943 857 2883 940 854 2884 939 853 2885 945 859 2886 946 860 2887 947 861 2888 948 862 2889 943 857 2890 942 856 2891 945 859 2892 949 863 2893 946 860 2894 950 864 2895 947 861 2896 951 865 2897 950 864 2898 945 859 2899 947 861 2900 952 866 2901 944 858 2902 938 852 2903 953 867 2904 951 865 2905 954 868 2906 955 869 2907 950 864 2908 951 865 2909 953 867 2910 955 869 2911 951 865 2912 956 870 2913 938 852 2914 935 849 2915 957 871 2916 952 866 2917 938 852 2918 956 870 2919 957 871 2920 938 852 2921 958 872 2922 935 849 2923 933 847 2924 958 872 2925 956 870 2926 935 849 2927 958 872 2928 933 847 2929 930 844 2930 959 873 2931 930 844 2932 805 725 2933 959 873 2934 958 872 2935 930 844 2936 810 729 2937 959 873 2938 805 725 2939 960 874 2940 961 875 2941 962 876 2942 963 877 2943 964 877 2944 965 877 2945 966 878 2946 965 879 2947 964 880 2948 967 881 2949 954 868 2950 968 882 2951 969 883 2952 953 867 2953 954 868 2954 970 884 2955 969 883 2956 954 868 2957 967 881 2958 970 884 2959 954 868 2960 966 878 2961 964 880 2962 971 885 2963 972 886 2964 962 876 2965 973 887 2966 960 874 2967 962 876 2968 974 888 2969 972 886 2970 974 888 2971 962 876 2972 975 889 2973 973 887 2974 976 890 2975 975 889 2976 972 886 2977 973 887 2978 977 891 2979 976 890 2980 978 892 2981 975 889 2982 976 890 2983 977 891 2984 979 893 2985 978 892 2986 815 734 2987 977 891 2988 978 892 2989 979 893 2990 979 893 2991 815 734 2992 812 731 2993 510 505 2994 515 510 2995 980 894 2996 981 895 2997 980 894 2998 982 896 2999 510 505 3000 980 894 3001 981 895 3002 983 897 3003 982 896 3004 984 898 3005 985 899 3006 982 896 3007 983 897 3008 981 895 3009 982 896 3010 985 899 3011 986 900 3012 984 898 3013 987 901 3014 983 897 3015 984 898 3016 986 900 3017 986 900 3018 987 901 3019 988 902 3020 986 900 3021 988 902 3022 989 903 3023 990 904 3024 991 905 3025 949 863 3026 992 906 3027 990 904 3028 949 863 3029 945 859 3030 992 906 3031 949 863 3032 502 497 3033 993 907 3034 505 500 3035 994 908 3036 995 909 3037 993 907 3038 996 910 3039 994 908 3040 993 907 3041 502 497 3042 996 910 3043 993 907 3044 997 911 3045 998 912 3046 995 909 3047 994 908 3048 997 911 3049 995 909 3050 999 913 3051 1000 914 3052 998 912 3053 997 911 3054 999 913 3055 998 912 3056 1001 915 3057 1002 916 3058 1000 914 3059 999 913 3060 1001 915 3061 1000 914 3062 1003 917 3063 1004 918 3064 1005 919 3065 1006 920 3066 491 488 3067 1007 921 3068 1008 922 3069 1009 922 3070 1007 922 3071 1010 923 3072 1007 921 3073 1009 924 3074 1003 917 3075 1011 925 3076 1004 918 3077 1012 926 3078 1006 920 3079 1007 921 3080 1010 923 3081 1012 926 3082 1007 921 3083 1013 927 3084 1001 915 3085 999 913 3086 1014 928 3087 1005 919 3088 1015 929 3089 1016 930 3090 1003 917 3091 1005 919 3092 1017 931 3093 1016 930 3094 1005 919 3095 1018 932 3096 1017 931 3097 1005 919 3098 1014 928 3099 1018 932 3100 1005 919 3101 986 900 3102 999 913 3103 997 911 3104 989 903 3105 1013 927 3106 999 913 3107 986 900 3108 989 903 3109 999 913 3110 983 897 3111 997 911 3112 994 908 3113 983 897 3114 986 900 3115 997 911 3116 985 899 3117 994 908 3118 996 910 3119 985 899 3120 983 897 3121 994 908 3122 981 895 3123 996 910 3124 502 497 3125 981 895 3126 985 899 3127 996 910 3128 510 505 3129 981 895 3130 502 497 3131 1019 933 3132 1015 929 3133 991 905 3134 1019 933 3135 1014 928 3136 1015 929 3137 990 904 3138 1019 933 3139 991 905 3140 847 934 3141 864 934 3142 848 934 3143 1020 935 3144 489 486 3145 491 488 3146 863 936 3147 1021 936 3148 864 936 3149 1022 937 3150 1020 935 3151 491 488 3152 1006 920 3153 1022 937 3154 491 488 3155 1003 917 3156 1023 938 3157 1011 925 3158 1024 939 3159 1025 940 3160 1026 941 3161 1027 942 3162 1028 943 3163 1029 944 3164 1024 939 3165 1026 941 3166 1030 945 3167 1031 946 3168 1032 947 3169 1033 948 3170 1034 949 3171 1032 947 3172 1031 946 3173 1035 950 3174 1036 951 3175 1037 952 3176 1038 953 3177 1036 951 3178 1035 950 3179 1039 492 3180 1021 492 3181 863 492 3182 1031 946 3183 1033 948 3184 1040 954 3185 1041 955 3186 1033 948 3187 1042 956 3188 1040 954 3189 1033 948 3190 1041 955 3191 1043 957 3192 1044 957 3193 1045 957 3194 1041 955 3195 1042 956 3196 1046 958 3197 1047 959 3198 1048 960 3199 1049 961 3200 1050 962 3201 1046 958 3202 1042 956 3203 1051 963 3204 1049 961 3205 1052 964 3206 1047 959 3207 1049 961 3208 1053 965 3209 1054 966 3210 1053 965 3211 1049 961 3212 1051 963 3213 1054 966 3214 1049 961 3215 1055 967 3216 1052 964 3217 1056 968 3218 1055 967 3219 1051 963 3220 1052 964 3221 1024 939 3222 1056 968 3223 1025 940 3224 1057 969 3225 1055 967 3226 1056 968 3227 1024 939 3228 1057 969 3229 1056 968 3230 967 881 3231 968 882 3232 1058 970 3233 1059 971 3234 1060 972 3235 1061 973 3236 1062 974 3237 1063 975 3238 1064 976 3239 1059 971 3240 1061 973 3241 1065 977 3242 1066 978 3243 1029 944 3244 1067 979 3245 1068 980 3246 1027 942 3247 1029 944 3248 1069 981 3249 1068 980 3250 1029 944 3251 1066 978 3252 1069 981 3253 1029 944 3254 1070 982 3255 1067 979 3256 1071 983 3257 1070 982 3258 1066 978 3259 1067 979 3260 1072 984 3261 1071 983 3262 1073 985 3263 1072 984 3264 1070 982 3265 1071 983 3266 1074 986 3267 1073 985 3268 1075 987 3269 1074 986 3270 1072 984 3271 1073 985 3272 1074 986 3273 1075 987 3274 1076 988 3275 1077 989 3276 1078 990 3277 1079 991 3278 1074 986 3279 1076 988 3280 1080 992 3281 1081 993 3282 1079 991 3283 1082 994 3284 1081 993 3285 1077 989 3286 1079 991 3287 1083 995 3288 1082 994 3289 1084 996 3290 1083 995 3291 1081 993 3292 1082 994 3293 1083 995 3294 1084 996 3295 1085 997 3296 1086 998 3297 1087 999 3298 1088 1000 3299 1083 995 3300 1085 997 3301 1089 1001 3302 1090 1002 3303 1088 1000 3304 1091 1003 3305 1092 1004 3306 1086 998 3307 1088 1000 3308 1090 1002 3309 1092 1004 3310 1088 1000 3311 1093 1005 3312 1091 1003 3313 1094 1006 3314 1093 1005 3315 1090 1002 3316 1091 1003 3317 1095 1007 3318 1094 1006 3319 1096 1008 3320 1095 1007 3321 1093 1005 3322 1094 1006 3323 1097 1009 3324 1096 1008 3325 1060 972 3326 1097 1009 3327 1095 1007 3328 1096 1008 3329 1059 971 3330 1097 1009 3331 1060 972 3332 1098 1010 3333 1099 1011 3334 1100 1012 3335 1101 1013 3336 1102 1014 3337 1103 1015 3338 1104 1016 3339 1105 1017 3340 1106 1018 3341 1101 1013 3342 1107 1019 3343 1102 1014 3344 1108 1020 3345 1109 1021 3346 1110 1022 3347 1104 1016 3348 1106 1018 3349 1111 1023 3350 1112 1024 3351 971 885 3352 1099 1011 3353 1113 1025 3354 1112 1024 3355 1099 1011 3356 1045 1026 3357 1044 1026 3358 1039 1026 3359 1098 1010 3360 1113 1025 3361 1099 1011 3362 1114 492 3363 1115 492 3364 1043 492 3365 1116 1027 3366 1117 1028 3367 1118 1029 3368 1119 1030 3369 1116 1027 3370 1118 1029 3371 1120 1031 3372 966 878 3373 971 885 3374 1112 1024 3375 1120 1031 3376 971 885 3377 1121 1032 3378 1064 976 3379 1122 1033 3380 1123 1034 3381 1062 974 3382 1064 976 3383 1124 1035 3384 1123 1034 3385 1064 976 3386 1121 1032 3387 1124 1035 3388 1064 976 3389 1121 1032 3390 1122 1033 3391 1125 1036 3392 1126 1037 3393 1125 1036 3394 1127 1038 3395 1126 1037 3396 1121 1032 3397 1125 1036 3398 1039 1039 3399 1044 1039 3400 1021 1039 3401 1126 1037 3402 1127 1038 3403 1128 1040 3404 1129 1041 3405 1130 1042 3406 1105 1017 3407 1131 1043 3408 1130 1042 3409 1129 1041 3410 1132 1044 3411 1130 1042 3412 1131 1043 3413 1133 1045 3414 1130 1042 3415 1132 1044 3416 1043 1046 3417 1115 1046 3418 1044 1046 3419 1129 1041 3420 1105 1017 3421 1104 1016 3422 1101 1013 3423 1134 1047 3424 1107 1019 3425 1135 1048 3426 1110 1022 3427 1136 1049 3428 1108 1020 3429 1110 1022 3430 1135 1048 3431 1101 1013 3432 1137 1050 3433 1134 1047 3434 1135 1048 3435 1136 1049 3436 1138 1051 3437 1101 1013 3438 1139 1052 3439 1137 1050 3440 1140 1053 3441 1138 1051 3442 1141 1054 3443 1135 1048 3444 1138 1051 3445 1140 1053 3446 1142 1055 3447 1143 1056 3448 1139 1052 3449 1144 1057 3450 1141 1054 3451 1145 1058 3452 1101 1013 3453 1142 1055 3454 1139 1052 3455 1140 1053 3456 1141 1054 3457 1144 1057 3458 1142 1055 3459 1146 1059 3460 1143 1056 3461 1147 1060 3462 1145 1058 3463 1148 1061 3464 1144 1057 3465 1145 1058 3466 1147 1060 3467 1142 1055 3468 1149 1062 3469 1146 1059 3470 1150 1063 3471 1148 1061 3472 1151 1064 3473 1147 1060 3474 1148 1061 3475 1150 1063 3476 1152 1065 3477 1153 1066 3478 1149 1062 3479 1150 1063 3480 1151 1064 3481 1154 1067 3482 1142 1055 3483 1152 1065 3484 1149 1062 3485 1152 1065 3486 1155 1068 3487 1153 1066 3488 1156 1069 3489 1154 1067 3490 1157 1070 3491 1150 1063 3492 1154 1067 3493 1156 1069 3494 1158 1071 3495 1159 1072 3496 1155 1068 3497 1160 1073 3498 1157 1070 3499 1161 1074 3500 1152 1065 3501 1158 1071 3502 1155 1068 3503 1156 1069 3504 1157 1070 3505 1160 1073 3506 1158 1071 3507 1162 1075 3508 1159 1072 3509 1163 1076 3510 1161 1074 3511 1164 1077 3512 1160 1073 3513 1161 1074 3514 1163 1076 3515 1165 1078 3516 1166 1079 3517 1162 1075 3518 1167 1080 3519 1164 1077 3520 1168 1081 3521 1158 1071 3522 1165 1078 3523 1162 1075 3524 1163 1076 3525 1164 1077 3526 1167 1080 3527 1165 1078 3528 1169 1082 3529 1166 1079 3530 1167 1080 3531 1168 1081 3532 1170 1083 3533 1165 1078 3534 1171 1084 3535 1169 1082 3536 1172 1085 3537 1170 1083 3538 1173 1086 3539 1167 1080 3540 1170 1083 3541 1172 1085 3542 1174 1087 3543 1175 1088 3544 1171 1084 3545 1176 1089 3546 1173 1086 3547 1177 1090 3548 1165 1078 3549 1174 1087 3550 1171 1084 3551 1172 1085 3552 1173 1086 3553 1176 1089 3554 1174 1087 3555 1178 1091 3556 1175 1088 3557 1179 1092 3558 1177 1090 3559 1180 1093 3560 1176 1089 3561 1177 1090 3562 1179 1092 3563 1174 1087 3564 1181 1094 3565 1178 1091 3566 1182 1095 3567 1180 1093 3568 1183 1096 3569 1179 1092 3570 1180 1093 3571 1182 1095 3572 1174 1087 3573 1184 1097 3574 1181 1094 3575 1182 1095 3576 1183 1096 3577 1185 1098 3578 1174 1087 3579 1186 1099 3580 1184 1097 3581 1187 1100 3582 1185 1098 3583 1188 1101 3584 1182 1095 3585 1185 1098 3586 1187 1100 3587 1174 1087 3588 1189 1102 3589 1186 1099 3590 1190 1103 3591 1188 1101 3592 1191 1104 3593 1187 1100 3594 1188 1101 3595 1190 1103 3596 1192 1105 3597 1193 1106 3598 1189 1102 3599 1194 1107 3600 1191 1104 3601 1195 1108 3602 1174 1087 3603 1192 1105 3604 1189 1102 3605 1190 1103 3606 1191 1104 3607 1194 1107 3608 1192 1105 3609 1196 1109 3610 1193 1106 3611 1197 1110 3612 1195 1108 3613 1198 1111 3614 1194 1107 3615 1195 1108 3616 1197 1110 3617 1192 1105 3618 1199 1112 3619 1196 1109 3620 1200 1113 3621 1198 1111 3622 1201 1114 3623 1197 1110 3624 1198 1111 3625 1200 1113 3626 1192 1105 3627 1202 1115 3628 1199 1112 3629 1203 1116 3630 1201 1114 3631 1204 1117 3632 1200 1113 3633 1201 1114 3634 1203 1116 3635 1192 1105 3636 1205 1118 3637 1202 1115 3638 1203 1116 3639 1204 1117 3640 1206 1119 3641 1207 1120 3642 1208 1121 3643 1205 1118 3644 1209 1122 3645 1206 1119 3646 1210 1123 3647 1192 1105 3648 1207 1120 3649 1205 1118 3650 1203 1116 3651 1206 1119 3652 1209 1122 3653 1207 1120 3654 1211 1124 3655 1208 1121 3656 1212 1125 3657 1210 1123 3658 1213 1126 3659 1209 1122 3660 1210 1123 3661 1212 1125 3662 1207 1120 3663 1214 1127 3664 1211 1124 3665 1215 1128 3666 1213 1126 3667 1216 1129 3668 1212 1125 3669 1213 1126 3670 1215 1128 3671 1207 1120 3672 1217 1130 3673 1214 1127 3674 1218 1131 3675 1216 1129 3676 1219 1132 3677 1215 1128 3678 1216 1129 3679 1218 1131 3680 1207 1120 3681 1220 1133 3682 1217 1130 3683 1218 1131 3684 1219 1132 3685 1221 1134 3686 1222 1135 3687 1223 1136 3688 1224 1137 3689 1218 1131 3690 1221 1134 3691 1225 1138 3692 1226 1139 3693 1227 1140 3694 1228 1141 3695 1229 1142 3696 1226 1139 3697 1228 1141 3698 1230 1143 3699 1231 1144 3700 1223 1136 3701 1222 1135 3702 1230 1143 3703 1223 1136 3704 1232 1145 3705 1207 1120 3706 1192 1105 3707 1233 1146 3708 1207 1120 3709 1232 1145 3710 1222 1135 3711 1224 1137 3712 1234 1147 3713 1232 1145 3714 1235 1148 3715 1233 1146 3716 1236 1149 3717 1192 1105 3718 1174 1087 3719 1236 1149 3720 1232 1145 3721 1192 1105 3722 1237 1150 3723 1174 1087 3724 1165 1078 3725 1238 1151 3726 1236 1149 3727 1174 1087 3728 1239 1152 3729 1238 1151 3730 1174 1087 3731 1240 1153 3732 1239 1152 3733 1174 1087 3734 1237 1150 3735 1240 1153 3736 1174 1087 3737 1241 1154 3738 1242 1155 3739 1243 1156 3740 1241 1154 3741 1244 1157 3742 1242 1155 3743 1245 1158 3744 1243 1156 3745 1246 1159 3746 1245 1158 3747 1241 1154 3748 1243 1156 3749 1245 1158 3750 1246 1159 3751 1247 1160 3752 1116 1027 3753 1247 1160 3754 1117 1028 3755 1116 1027 3756 1245 1158 3757 1247 1160 3758 1222 1135 3759 1234 1147 3760 1248 1161 3761 1249 1162 3762 1250 1163 3763 1251 1164 3764 1252 1165 3765 1253 1166 3766 1254 1167 3767 1249 1162 3768 1255 1168 3769 1250 1163 3770 1256 1169 3771 1251 1164 3772 1257 1170 3773 1256 1169 3774 1249 1162 3775 1251 1164 3776 1258 1171 3777 1257 1170 3778 1259 1172 3779 1258 1171 3780 1256 1169 3781 1257 1170 3782 1258 1171 3783 1259 1172 3784 1260 1173 3785 1261 1174 3786 1260 1173 3787 1262 1175 3788 1261 1174 3789 1258 1171 3790 1260 1173 3791 1261 1174 3792 1262 1175 3793 1244 1157 3794 1241 1154 3795 1261 1174 3796 1244 1157 3797 1218 1131 3798 1225 1138 3799 1263 1176 3800 1226 1139 3801 1264 1177 3802 1227 1140 3803 1265 1178 3804 1218 1131 3805 1263 1176 3806 1266 1179 3807 1267 1180 3808 1268 1181 3809 1269 1182 3810 1264 1177 3811 1226 1139 3812 1270 1183 3813 1271 1184 3814 1272 1185 3815 1273 1186 3816 1271 1184 3817 1270 1183 3818 1274 1187 3819 1215 1128 3820 1218 1131 3821 1265 1178 3822 1274 1187 3823 1218 1131 3824 1275 1188 3825 1212 1125 3826 1215 1128 3827 1274 1187 3828 1275 1188 3829 1215 1128 3830 1276 1189 3831 1209 1122 3832 1212 1125 3833 1275 1188 3834 1276 1189 3835 1212 1125 3836 1277 1190 3837 1203 1116 3838 1209 1122 3839 1276 1189 3840 1277 1190 3841 1209 1122 3842 1278 1191 3843 1200 1113 3844 1203 1116 3845 1277 1190 3846 1278 1191 3847 1203 1116 3848 1279 1192 3849 1197 1110 3850 1200 1113 3851 1280 1193 3852 1279 1192 3853 1200 1113 3854 1281 1194 3855 1280 1193 3856 1200 1113 3857 1278 1191 3858 1281 1194 3859 1200 1113 3860 1282 1195 3861 1194 1107 3862 1197 1110 3863 1279 1192 3864 1282 1195 3865 1197 1110 3866 1283 1196 3867 1190 1103 3868 1194 1107 3869 1282 1195 3870 1283 1196 3871 1194 1107 3872 1284 1197 3873 1187 1100 3874 1190 1103 3875 1285 1198 3876 1284 1197 3877 1190 1103 3878 1283 1196 3879 1285 1198 3880 1190 1103 3881 1286 1199 3882 1182 1095 3883 1187 1100 3884 1284 1197 3885 1286 1199 3886 1187 1100 3887 1287 1200 3888 1179 1092 3889 1182 1095 3890 1286 1199 3891 1287 1200 3892 1182 1095 3893 1288 1201 3894 1176 1089 3895 1179 1092 3896 1289 1202 3897 1288 1201 3898 1179 1092 3899 1287 1200 3900 1289 1202 3901 1179 1092 3902 1290 1203 3903 1172 1085 3904 1176 1089 3905 1288 1201 3906 1290 1203 3907 1176 1089 3908 1291 1204 3909 1167 1080 3910 1172 1085 3911 1290 1203 3912 1291 1204 3913 1172 1085 3914 1292 1205 3915 1163 1076 3916 1167 1080 3917 1291 1204 3918 1292 1205 3919 1167 1080 3920 1293 1206 3921 1160 1073 3922 1163 1076 3923 1294 1207 3924 1293 1206 3925 1163 1076 3926 1292 1205 3927 1294 1207 3928 1163 1076 3929 1295 1208 3930 1156 1069 3931 1160 1073 3932 1293 1206 3933 1295 1208 3934 1160 1073 3935 1296 1209 3936 1150 1063 3937 1156 1069 3938 1297 1210 3939 1296 1209 3940 1156 1069 3941 1295 1208 3942 1297 1210 3943 1156 1069 3944 1298 1211 3945 1147 1060 3946 1150 1063 3947 1299 1212 3948 1298 1211 3949 1150 1063 3950 1296 1209 3951 1299 1212 3952 1150 1063 3953 1300 1213 3954 1144 1057 3955 1147 1060 3956 1298 1211 3957 1300 1213 3958 1147 1060 3959 1301 1214 3960 1140 1053 3961 1144 1057 3962 1302 1215 3963 1301 1214 3964 1144 1057 3965 1300 1213 3966 1302 1215 3967 1144 1057 3968 1303 1216 3969 1135 1048 3970 1140 1053 3971 1304 1217 3972 1303 1216 3973 1140 1053 3974 1301 1214 3975 1304 1217 3976 1140 1053 3977 1305 1218 3978 1108 1020 3979 1135 1048 3980 1303 1216 3981 1305 1218 3982 1135 1048 3983 1104 1016 3984 1111 1023 3985 1306 1219 3986 1307 1220 3987 1308 1221 3988 1309 1222 3989 1310 1223 3990 1308 1221 3991 1307 1220 3992 1307 1220 3993 1309 1222 3994 1311 1224 3995 1312 1225 3996 1311 1224 3997 1313 1226 3998 1307 1220 3999 1311 1224 4000 1312 1225 4001 1314 1227 4002 1313 1226 4003 1315 1228 4004 1316 1229 4005 1313 1226 4006 1314 1227 4007 1312 1225 4008 1313 1226 4009 1316 1229 4010 1317 1230 4011 1315 1228 4012 1318 1231 4013 1314 1227 4014 1315 1228 4015 1317 1230 4016 1319 1232 4017 1312 1225 4018 1320 1233 4019 1321 1234 4020 1312 1225 4021 1319 1232 4022 1322 1235 4023 1312 1225 4024 1321 1234 4025 1323 1236 4026 1312 1225 4027 1322 1235 4028 1324 1237 4029 1312 1225 4030 1323 1236 4031 1325 1238 4032 1312 1225 4033 1324 1237 4034 1326 1239 4035 1312 1225 4036 1325 1238 4037 1307 1220 4038 1312 1225 4039 1326 1239 4040 1327 1240 4041 1326 1239 4042 1328 1241 4043 1329 1242 4044 1326 1239 4045 1327 1240 4046 1330 1243 4047 1326 1239 4048 1329 1242 4049 1331 1244 4050 1326 1239 4051 1330 1243 4052 1332 1245 4053 1326 1239 4054 1331 1244 4055 1307 1220 4056 1326 1239 4057 1332 1245 4058 1332 1245 4059 1331 1244 4060 1333 1246 4061 1332 1245 4062 1333 1246 4063 1334 1247 4064 1332 1245 4065 1334 1247 4066 1335 1248 4067 1266 1179 4068 1335 1248 4069 1336 1249 4070 1337 1250 4071 1335 1248 4072 1266 1179 4073 1332 1245 4074 1335 1248 4075 1337 1250 4076 1266 1179 4077 1336 1249 4078 1338 1251 4079 1266 1179 4080 1338 1251 4081 1339 1252 4082 1266 1179 4083 1339 1252 4084 1340 1253 4085 1266 1179 4086 1340 1253 4087 1341 1254 4088 1266 1179 4089 1341 1254 4090 1342 1255 4091 1266 1179 4092 1342 1255 4093 1267 1180 4094 1343 1256 4095 1344 1257 4096 1345 1258 4097 1346 1259 4098 1347 1259 4099 1348 1259 4100 1349 1260 4101 1350 1261 4102 1351 1262 4103 1346 1263 4104 1352 1263 4105 1347 1263 4106 1353 1264 4107 1354 1265 4108 1344 1257 4109 1355 1266 4110 1344 1257 4111 1354 1265 4112 1343 1256 4113 1353 1264 4114 1344 1257 4115 1356 1267 4116 1348 1267 4117 1357 1267 4118 1356 1268 4119 1346 1268 4120 1348 1268 4121 1358 1269 4122 1226 1139 4123 1354 1265 4124 1359 1270 4125 1354 1265 4126 1226 1139 4127 1353 1264 4128 1358 1269 4129 1354 1265 4130 1359 1270 4131 1355 1266 4132 1354 1265 4133 1360 1271 4134 1269 1182 4135 1226 1139 4136 1358 1269 4137 1360 1271 4138 1226 1139 4139 1229 1142 4140 1359 1270 4141 1226 1139 4142 1361 1272 4143 1272 1185 4144 1362 1273 4145 1270 1183 4146 1272 1185 4147 1361 1272 4148 1361 1272 4149 1362 1273 4150 1363 1274 4151 1364 1275 4152 1363 1274 4153 1365 1276 4154 1361 1272 4155 1363 1274 4156 1364 1275 4157 1364 1275 4158 1365 1276 4159 1350 1261 4160 1364 1275 4161 1350 1261 4162 1349 1260 4163 1366 1277 4164 1367 1278 4165 1368 1279 4166 1369 1280 4167 1356 1280 4168 1357 1280 4169 1230 1143 4170 1368 1279 4171 1231 1144 4172 1366 1277 4173 1368 1279 4174 1370 1281 4175 1371 1282 4176 1370 1281 4177 1368 1279 4178 1114 1283 4179 1372 1283 4180 1115 1283 4181 1230 1143 4182 1371 1282 4183 1368 1279 4184 1373 1284 4185 1374 1284 4186 1372 1284 4187 1375 1285 4188 1376 1286 4189 1377 1287 4190 1378 1288 4191 1379 1288 4192 1380 1288 4193 1381 1289 4194 1375 1285 4195 1377 1287 4196 1382 1290 4197 1383 1291 4198 1384 1292 4199 1378 1293 4200 1385 1293 4201 1379 1293 4202 1375 1285 4203 1386 1294 4204 1376 1286 4205 1387 1295 4206 1380 1295 4207 1388 1295 4208 1387 1296 4209 1378 1296 4210 1380 1296 4211 1389 1297 4212 1390 1298 4213 1386 1294 4214 1387 1299 4215 1388 1299 4216 1391 1299 4217 1375 1285 4218 1389 1297 4219 1386 1294 4220 1392 1300 4221 1393 1301 4222 1390 1298 4223 1394 1302 4224 1391 1302 4225 1395 1302 4226 1389 1297 4227 1392 1300 4228 1390 1298 4229 1394 1303 4230 1387 1303 4231 1391 1303 4232 1396 1304 4233 1397 1305 4234 1393 1301 4235 1394 1306 4236 1395 1306 4237 1398 1306 4238 1392 1300 4239 1396 1304 4240 1393 1301 4241 1396 1304 4242 1399 1307 4243 1397 1305 4244 1400 1308 4245 1398 1308 4246 1401 1308 4247 1400 1309 4248 1394 1309 4249 1398 1309 4250 1364 1275 4251 1349 1260 4252 1399 1307 4253 1400 1310 4254 1401 1310 4255 1352 1310 4256 1396 1304 4257 1364 1275 4258 1399 1307 4259 1346 1311 4260 1400 1311 4261 1352 1311 4262 1361 1272 4263 1364 1275 4264 1396 1304 4265 1402 1312 4266 1396 1304 4267 1392 1300 4268 1402 1312 4269 1361 1272 4270 1396 1304 4271 1403 1313 4272 1392 1300 4273 1389 1297 4274 1403 1313 4275 1402 1312 4276 1392 1300 4277 1404 1314 4278 1389 1297 4279 1375 1285 4280 1404 1314 4281 1403 1313 4282 1389 1297 4283 1405 1315 4284 1375 1285 4285 1381 1289 4286 1405 1315 4287 1404 1314 4288 1375 1285 4289 1405 1315 4290 1381 1289 4291 1406 1316 4292 1407 1317 4293 1408 1318 4294 1383 1291 4295 1407 1317 4296 1383 1291 4297 1382 1290 4298 1409 1319 4299 1405 1315 4300 1406 1316 4301 1409 1319 4302 1406 1316 4303 1410 1320 4304 1411 1321 4305 1412 1322 4306 1408 1318 4307 1411 1321 4308 1408 1318 4309 1407 1317 4310 1270 1183 4311 1361 1272 4312 1402 1312 4313 1413 1323 4314 1402 1312 4315 1403 1313 4316 1413 1323 4317 1270 1183 4318 1402 1312 4319 1414 1324 4320 1403 1313 4321 1404 1314 4322 1414 1324 4323 1413 1323 4324 1403 1313 4325 1415 1325 4326 1404 1314 4327 1405 1315 4328 1415 1325 4329 1414 1324 4330 1404 1314 4331 1409 1319 4332 1415 1325 4333 1405 1315 4334 1416 1326 4335 1409 1319 4336 1410 1320 4337 1417 1327 4338 1410 1320 4339 1418 1328 4340 1419 1329 4341 1420 1330 4342 1412 1322 4343 1417 1327 4344 1416 1326 4345 1410 1320 4346 1419 1329 4347 1412 1322 4348 1411 1321 4349 1421 1331 4350 1270 1183 4351 1413 1323 4352 1421 1331 4353 1273 1186 4354 1270 1183 4355 1422 1332 4356 1413 1323 4357 1414 1324 4358 1422 1332 4359 1421 1331 4360 1413 1323 4361 1423 1333 4362 1414 1324 4363 1415 1325 4364 1424 1334 4365 1422 1332 4366 1414 1324 4367 1423 1333 4368 1424 1334 4369 1414 1324 4370 1425 1335 4371 1415 1325 4372 1409 1319 4373 1425 1335 4374 1423 1333 4375 1415 1325 4376 1416 1326 4377 1425 1335 4378 1409 1319 4379 1426 1336 4380 1427 1337 4381 1428 1338 4382 1429 1339 4383 1420 1330 4384 1419 1329 4385 1430 1340 4386 1431 1341 4387 1432 1342 4388 1433 1343 4389 1431 1341 4390 1430 1340 4391 1337 1250 4392 1266 1179 4393 1434 1344 4394 1337 1250 4395 1434 1344 4396 1435 1345 4397 1436 1346 4398 1435 1345 4399 1437 1347 4400 1337 1250 4401 1435 1345 4402 1436 1346 4403 1438 1348 4404 1437 1347 4405 1439 1349 4406 1436 1346 4407 1437 1347 4408 1438 1348 4409 1438 1348 4410 1439 1349 4411 1440 1350 4412 1441 1351 4413 1440 1350 4414 1442 1352 4415 1438 1348 4416 1440 1350 4417 1441 1351 4418 1441 1351 4419 1442 1352 4420 1427 1337 4421 1443 1353 4422 1427 1337 4423 1426 1336 4424 1441 1351 4425 1427 1337 4426 1443 1353 4427 1444 1354 4428 1445 1355 4429 1446 1356 4430 1447 1357 4431 1448 1357 4432 1449 1357 4433 1450 1358 4434 1444 1354 4435 1446 1356 4436 1451 1359 4437 1452 1360 4438 1453 1361 4439 1451 1359 4440 1453 1361 4441 1454 1362 4442 1455 1363 4443 1456 1363 4444 1448 1363 4445 1447 1364 4446 1455 1364 4447 1448 1364 4448 1457 1365 4449 1458 1366 4450 1445 1355 4451 1459 1367 4452 1449 1367 4453 1460 1367 4454 1444 1354 4455 1457 1365 4456 1445 1355 4457 1459 1368 4458 1447 1368 4459 1449 1368 4460 1461 1369 4461 1462 1370 4462 1458 1366 4463 1463 1371 4464 1460 1371 4465 1464 1371 4466 1457 1365 4467 1461 1369 4468 1458 1366 4469 1465 1372 4470 1459 1372 4471 1460 1372 4472 1463 1373 4473 1465 1373 4474 1460 1373 4475 1466 1374 4476 1467 1375 4477 1462 1370 4478 1468 1376 4479 1464 1376 4480 1469 1376 4481 1461 1369 4482 1466 1374 4483 1462 1370 4484 1470 1377 4485 1463 1377 4486 1464 1377 4487 1471 1378 4488 1470 1378 4489 1464 1378 4490 1468 1379 4491 1471 1379 4492 1464 1379 4493 1466 1374 4494 1472 1380 4495 1467 1375 4496 1473 1381 4497 1469 1381 4498 1474 1381 4499 1475 1382 4500 1468 1382 4501 1469 1382 4502 1473 1383 4503 1475 1383 4504 1469 1383 4505 1476 1384 4506 1477 1385 4507 1472 1380 4508 1478 1386 4509 1474 1386 4510 1479 1386 4511 1466 1374 4512 1476 1384 4513 1472 1380 4514 1478 1387 4515 1473 1387 4516 1474 1387 4517 1407 1317 4518 1480 1388 4519 1477 1385 4520 1378 1389 4521 1479 1389 4522 1481 1389 4523 1476 1384 4524 1407 1317 4525 1477 1385 4526 1378 1390 4527 1478 1390 4528 1479 1390 4529 1407 1317 4530 1382 1290 4531 1480 1388 4532 1378 1391 4533 1481 1391 4534 1385 1391 4535 1411 1321 4536 1407 1317 4537 1476 1384 4538 1482 1392 4539 1476 1384 4540 1466 1374 4541 1482 1392 4542 1411 1321 4543 1476 1384 4544 1483 1393 4545 1466 1374 4546 1461 1369 4547 1483 1393 4548 1482 1392 4549 1466 1374 4550 1484 1394 4551 1461 1369 4552 1457 1365 4553 1484 1394 4554 1483 1393 4555 1461 1369 4556 1485 1395 4557 1457 1365 4558 1444 1354 4559 1485 1395 4560 1484 1394 4561 1457 1365 4562 1486 1396 4563 1444 1354 4564 1450 1358 4565 1486 1396 4566 1485 1395 4567 1444 1354 4568 1486 1396 4569 1450 1358 4570 1487 1397 4571 1451 1359 4572 1488 1398 4573 1452 1360 4574 1489 1399 4575 1486 1396 4576 1487 1397 4577 1489 1399 4578 1487 1397 4579 1490 1400 4580 1451 1359 4581 1491 1401 4582 1488 1398 4583 1419 1329 4584 1411 1321 4585 1482 1392 4586 1492 1402 4587 1482 1392 4588 1483 1393 4589 1492 1402 4590 1419 1329 4591 1482 1392 4592 1493 1403 4593 1483 1393 4594 1484 1394 4595 1493 1403 4596 1492 1402 4597 1483 1393 4598 1494 1404 4599 1484 1394 4600 1485 1395 4601 1494 1404 4602 1493 1403 4603 1484 1394 4604 1495 1405 4605 1485 1395 4606 1486 1396 4607 1495 1405 4608 1494 1404 4609 1485 1395 4610 1489 1399 4611 1495 1405 4612 1486 1396 4613 1496 1406 4614 1489 1399 4615 1490 1400 4616 1496 1406 4617 1490 1400 4618 1497 1407 4619 1498 1408 4620 1499 1409 4621 1491 1401 4622 1500 1410 4623 1498 1408 4624 1491 1401 4625 1451 1359 4626 1500 1410 4627 1491 1401 4628 1501 1411 4629 1419 1329 4630 1492 1402 4631 1501 1411 4632 1429 1339 4633 1419 1329 4634 1502 1412 4635 1492 1402 4636 1493 1403 4637 1503 1413 4638 1501 1411 4639 1492 1402 4640 1504 1414 4641 1503 1413 4642 1492 1402 4643 1502 1412 4644 1504 1414 4645 1492 1402 4646 1505 1415 4647 1493 1403 4648 1494 1404 4649 1506 1416 4650 1502 1412 4651 1493 1403 4652 1505 1415 4653 1506 1416 4654 1493 1403 4655 1507 1417 4656 1494 1404 4657 1495 1405 4658 1508 1418 4659 1505 1415 4660 1494 1404 4661 1507 1417 4662 1508 1418 4663 1494 1404 4664 1509 1419 4665 1495 1405 4666 1489 1399 4667 1510 1420 4668 1507 1417 4669 1495 1405 4670 1509 1419 4671 1510 1420 4672 1495 1405 4673 1496 1406 4674 1509 1419 4675 1489 1399 4676 1511 1421 4677 1512 1422 4678 1513 1423 4679 1514 1424 4680 1515 1425 4681 1516 1426 4682 1517 1427 4683 1515 1425 4684 1514 1424 4685 1430 1340 4686 1432 1342 4687 1518 1428 4688 1519 1429 4689 1518 1428 4690 1520 1430 4691 1430 1340 4692 1518 1428 4693 1519 1429 4694 1519 1429 4695 1520 1430 4696 1521 1431 4697 1519 1429 4698 1521 1431 4699 1522 1432 4700 1519 1429 4701 1522 1432 4702 1523 1433 4703 1524 1434 4704 1523 1433 4705 1525 1435 4706 1519 1429 4707 1523 1433 4708 1524 1434 4709 1524 1434 4710 1525 1435 4711 1526 1436 4712 1524 1434 4713 1526 1436 4714 1527 1437 4715 1528 1438 4716 1527 1437 4717 1529 1439 4718 1524 1434 4719 1527 1437 4720 1528 1438 4721 1528 1438 4722 1529 1439 4723 1530 1440 4724 1511 1421 4725 1530 1440 4726 1512 1422 4727 1531 1441 4728 1530 1440 4729 1511 1421 4730 1532 1442 4731 1530 1440 4732 1531 1441 4733 1528 1438 4734 1530 1440 4735 1532 1442 4736 1451 1359 4737 1454 1362 4738 1533 1443 4739 1455 1444 4740 1534 1444 4741 1456 1444 4742 1535 1445 4743 1536 1446 4744 1537 1447 4745 1455 1448 4746 1538 1448 4747 1534 1448 4748 1539 1449 4749 1540 1450 4750 1536 1446 4751 1541 1451 4752 1540 1450 4753 1539 1449 4754 1542 1452 4755 1543 1453 4756 1544 1454 4757 1545 1455 4758 1543 1453 4759 1542 1452 4760 1517 1427 4761 1514 1424 4762 1546 1456 4763 1539 1449 4764 1536 1446 4765 1535 1445 4766 1547 1457 4767 1548 1458 4768 1549 1459 4769 1550 1460 4770 1551 1460 4771 1552 1460 4772 1553 1461 4773 1547 1457 4774 1549 1459 4775 1554 1462 4776 1555 1463 4777 1556 1464 4778 1554 1462 4779 1556 1464 4780 1557 1465 4781 1558 1466 4782 1559 1466 4783 1551 1466 4784 1550 1467 4785 1558 1467 4786 1551 1467 4787 1560 1468 4788 1561 1469 4789 1548 1458 4790 1550 1470 4791 1552 1470 4792 1562 1470 4793 1547 1457 4794 1560 1468 4795 1548 1458 4796 1539 1449 4797 1535 1445 4798 1561 1469 4799 1455 1471 4800 1562 1471 4801 1538 1471 4802 1560 1468 4803 1539 1449 4804 1561 1469 4805 1455 1472 4806 1550 1472 4807 1562 1472 4808 1541 1451 4809 1539 1449 4810 1560 1468 4811 1563 1473 4812 1560 1468 4813 1547 1457 4814 1563 1473 4815 1541 1451 4816 1560 1468 4817 1564 1474 4818 1547 1457 4819 1553 1461 4820 1564 1474 4821 1563 1473 4822 1547 1457 4823 1564 1474 4824 1553 1461 4825 1565 1475 4826 1566 1476 4827 1567 1477 4828 1555 1463 4829 1568 1478 4830 1566 1476 4831 1555 1463 4832 1554 1462 4833 1568 1478 4834 1555 1463 4835 1569 1479 4836 1570 1480 4837 1571 1481 4838 1572 1482 4839 1571 1481 4840 1570 1480 4841 1573 1483 4842 1574 1484 4843 1575 1485 4844 1576 1486 4845 1574 1484 4846 1573 1483 4847 1542 1452 4848 1544 1454 4849 1571 1481 4850 1572 1482 4851 1542 1452 4852 1571 1481 4853 1554 1462 4854 1557 1465 4855 1577 1487 4856 1578 1488 4857 1579 1488 4858 1559 1488 4859 1580 1489 4860 1581 1490 4861 1582 1491 4862 1578 1492 4863 1583 1492 4864 1579 1492 4865 1558 1493 4866 1578 1493 4867 1559 1493 4868 1584 1494 4869 1585 1495 4870 1581 1490 4871 1586 1496 4872 1585 1495 4873 1584 1494 4874 1587 1497 4875 1588 1498 4876 1589 1499 4877 1590 1500 4878 1588 1498 4879 1587 1497 4880 1591 1501 4881 1588 1498 4882 1590 1500 4883 1576 1486 4884 1573 1483 4885 1592 1502 4886 1580 1489 4887 1584 1494 4888 1581 1490 4889 1593 1503 4890 1594 1504 4891 1595 1505 4892 1596 1506 4893 1595 1505 4894 1594 1504 4895 1597 1507 4896 1598 1508 4897 1599 1509 4898 1578 1510 4899 1600 1510 4900 1601 1510 4901 1602 1511 4902 1603 1512 4903 1604 1513 4904 1605 1514 4905 1602 1511 4906 1604 1513 4907 1606 1515 4908 1605 1514 4909 1604 1513 4910 1607 1516 4911 1606 1515 4912 1604 1513 4913 1608 1517 4914 1609 1518 4915 1594 1504 4916 1610 1519 4917 1594 1504 4918 1609 1518 4919 1593 1503 4920 1608 1517 4921 1594 1504 4922 1610 1519 4923 1596 1506 4924 1594 1504 4925 1611 1520 4926 1612 1521 4927 1609 1518 4928 1613 1522 4929 1609 1518 4930 1612 1521 4931 1614 1523 4932 1611 1520 4933 1609 1518 4934 1608 1517 4935 1614 1523 4936 1609 1518 4937 1613 1522 4938 1610 1519 4939 1609 1518 4940 1615 1524 4941 1584 1494 4942 1612 1521 4943 1616 1525 4944 1612 1521 4945 1584 1494 4946 1617 1526 4947 1615 1524 4948 1612 1521 4949 1611 1520 4950 1617 1526 4951 1612 1521 4952 1616 1525 4953 1613 1522 4954 1612 1521 4955 1615 1524 4956 1586 1496 4957 1584 1494 4958 1580 1489 4959 1616 1525 4960 1584 1494 4961 1587 1497 4962 1589 1499 4963 1618 1527 4964 1619 1528 4965 1618 1527 4966 1620 1529 4967 1587 1497 4968 1618 1527 4969 1619 1528 4970 1621 1530 4971 1620 1529 4972 1622 1531 4973 1619 1528 4974 1620 1529 4975 1621 1530 4976 1621 1530 4977 1622 1531 4978 1623 1532 4979 1624 1533 4980 1623 1532 4981 1625 1534 4982 1626 1535 4983 1621 1530 4984 1623 1532 4985 1624 1533 4986 1626 1535 4987 1623 1532 4988 1627 1536 4989 1625 1534 4990 1598 1508 4991 1627 1536 4992 1624 1533 4993 1625 1534 4994 1597 1507 4995 1627 1536 4996 1598 1508 4997 1578 1537 4998 1601 1537 4999 1628 1537 5000 1578 1538 5001 1628 1538 5002 1629 1538 5003 1578 1539 5004 1629 1539 5005 1630 1539 5006 1578 1540 5007 1630 1540 5008 1583 1540 5009 1631 1541 5010 1619 1528 5011 1621 1530 5012 1626 1535 5013 1631 1541 5014 1621 1530 5015 1632 1542 5016 1633 1543 5017 1619 1528 5018 1587 1497 5019 1619 1528 5020 1633 1543 5021 1631 1541 5022 1632 1542 5023 1619 1528 5024 1634 1544 5025 1635 1545 5026 1633 1543 5027 1590 1500 5028 1633 1543 5029 1635 1545 5030 1632 1542 5031 1634 1544 5032 1633 1543 5033 1590 1500 5034 1587 1497 5035 1633 1543 5036 1636 1546 5037 1637 1547 5038 1635 1545 5039 1638 1548 5040 1635 1545 5041 1637 1547 5042 1634 1544 5043 1636 1546 5044 1635 1545 5045 1638 1548 5046 1590 1500 5047 1635 1545 5048 1639 1549 5049 1640 1550 5050 1637 1547 5051 1641 1551 5052 1637 1547 5053 1640 1550 5054 1636 1546 5055 1639 1549 5056 1637 1547 5057 1641 1551 5058 1638 1548 5059 1637 1547 5060 1642 1552 5061 1643 1553 5062 1640 1550 5063 1644 1554 5064 1640 1550 5065 1643 1553 5066 1645 1555 5067 1642 1552 5068 1640 1550 5069 1639 1549 5070 1645 1555 5071 1640 1550 5072 1644 1554 5073 1641 1551 5074 1640 1550 5075 1646 1556 5076 1647 1557 5077 1643 1553 5078 1648 1558 5079 1643 1553 5080 1647 1557 5081 1649 1559 5082 1646 1556 5083 1643 1553 5084 1642 1552 5085 1649 1559 5086 1643 1553 5087 1648 1558 5088 1644 1554 5089 1643 1553 5090 1650 1560 5091 1651 1561 5092 1647 1557 5093 1652 1562 5094 1647 1557 5095 1651 1561 5096 1653 1563 5097 1650 1560 5098 1647 1557 5099 1654 1564 5100 1653 1563 5101 1647 1557 5102 1646 1556 5103 1654 1564 5104 1647 1557 5105 1652 1562 5106 1648 1558 5107 1647 1557 5108 1655 1565 5109 1656 1566 5110 1657 1567 5111 1658 1568 5112 1652 1562 5113 1651 1561 5114 1659 1569 5115 1660 1570 5116 1656 1566 5117 1659 1569 5118 1656 1566 5119 1655 1565 5120 1655 1565 5121 1657 1567 5122 1661 1571 5123 1662 1572 5124 1663 1573 5125 1664 1574 5126 1662 1572 5127 1665 1575 5128 1663 1573 5129 1655 1565 5130 1661 1571 5131 1666 1576 5132 1667 1577 5133 1664 1574 5134 1668 1578 5135 1667 1577 5136 1662 1572 5137 1664 1574 5138 1667 1577 5139 1668 1578 5140 1669 1579 5141 1667 1577 5142 1669 1579 5143 1670 1580 5144 1667 1577 5145 1670 1580 5146 1671 1581 5147 1672 1582 5148 1671 1581 5149 1673 1583 5150 1672 1582 5151 1667 1577 5152 1671 1581 5153 1672 1582 5154 1673 1583 5155 1674 1584 5156 1675 1585 5157 1674 1584 5158 1676 1586 5159 1675 1585 5160 1672 1582 5161 1674 1584 5162 1675 1585 5163 1676 1586 5164 1677 1587 5165 1675 1585 5166 1677 1587 5167 1678 1588 5168 1679 1589 5169 1678 1588 5170 1680 1590 5171 1679 1589 5172 1675 1585 5173 1678 1588 5174 1679 1589 5175 1680 1590 5176 1681 1591 5177 1602 1511 5178 1681 1591 5179 1682 1592 5180 1679 1589 5181 1681 1591 5182 1602 1511 5183 1602 1511 5184 1682 1592 5185 1603 1512 5186 1591 1501 5187 1590 1500 5188 1638 1548 5189 1683 1593 5190 1638 1548 5191 1641 1551 5192 1683 1593 5193 1591 1501 5194 1638 1548 5195 1684 1594 5196 1641 1551 5197 1644 1554 5198 1684 1594 5199 1683 1593 5200 1641 1551 5201 1685 1595 5202 1644 1554 5203 1648 1558 5204 1686 1596 5205 1684 1594 5206 1644 1554 5207 1685 1595 5208 1686 1596 5209 1644 1554 5210 1687 1597 5211 1648 1558 5212 1652 1562 5213 1688 1598 5214 1685 1595 5215 1648 1558 5216 1687 1597 5217 1688 1598 5218 1648 1558 5219 1658 1568 5220 1689 1599 5221 1652 1562 5222 1690 1600 5223 1652 1562 5224 1689 1599 5225 1690 1600 5226 1687 1597 5227 1652 1562 5228 1691 1601 5229 1692 1602 5230 1660 1570 5231 1693 1603 5232 1690 1600 5233 1689 1599 5234 1694 1604 5235 1695 1605 5236 1692 1602 5237 1694 1604 5238 1692 1602 5239 1691 1601 5240 1691 1601 5241 1660 1570 5242 1659 1569 5243 1696 1606 5244 1592 1502 5245 1697 1607 5246 1576 1486 5247 1592 1502 5248 1696 1606 5249 1698 1608 5250 1697 1607 5251 1699 1609 5252 1696 1606 5253 1697 1607 5254 1698 1608 5255 1700 1610 5256 1699 1609 5257 1701 1611 5258 1698 1608 5259 1699 1609 5260 1700 1610 5261 1702 1612 5262 1701 1611 5263 1703 1613 5264 1700 1610 5265 1701 1611 5266 1702 1612 5267 1702 1612 5268 1703 1613 5269 1704 1614 5270 1705 1615 5271 1704 1614 5272 1706 1616 5273 1702 1612 5274 1704 1614 5275 1705 1615 5276 1707 1617 5277 1706 1616 5278 1708 1618 5279 1705 1615 5280 1706 1616 5281 1707 1617 5282 1693 1603 5283 1709 1619 5284 1690 1600 5285 1710 1620 5286 1708 1618 5287 1711 1621 5288 1707 1617 5289 1708 1618 5290 1710 1620 5291 1712 1622 5292 1713 1623 5293 1695 1605 5294 1714 1624 5295 1715 1625 5296 1716 1626 5297 1717 1627 5298 1716 1626 5299 1715 1625 5300 1718 1628 5301 1714 1624 5302 1716 1626 5303 1712 1622 5304 1695 1605 5305 1719 1629 5306 1694 1604 5307 1719 1629 5308 1695 1605 5309 1720 1630 5310 1721 1630 5311 1722 1630 5312 1723 1631 5313 1721 1631 5314 1720 1631 5315 1606 1515 5316 1724 1632 5317 1605 1514 5318 1725 1633 5319 1726 1634 5320 1724 1632 5321 1723 492 5322 1720 492 5323 1727 492 5324 1606 1515 5325 1725 1633 5326 1724 1632 5327 1728 1635 5328 1729 1636 5329 1726 1634 5330 1723 1637 5331 1727 1637 5332 1730 1637 5333 1725 1633 5334 1728 1635 5335 1726 1634 5336 1728 1635 5337 1731 1638 5338 1729 1636 5339 1732 492 5340 1730 492 5341 1733 492 5342 1732 492 5343 1723 492 5344 1730 492 5345 1734 1639 5346 1735 1640 5347 1731 1638 5348 1736 492 5349 1733 492 5350 1737 492 5351 1728 1635 5352 1734 1639 5353 1731 1638 5354 1738 492 5355 1732 492 5356 1733 492 5357 1736 1641 5358 1738 1641 5359 1733 1641 5360 1739 1642 5361 1740 1643 5362 1735 1640 5363 1736 1644 5364 1737 1644 5365 1741 1644 5366 1734 1639 5367 1739 1642 5368 1735 1640 5369 1739 1642 5370 1742 1645 5371 1740 1643 5372 1743 492 5373 1741 492 5374 1744 492 5375 1743 1646 5376 1736 1646 5377 1741 1646 5378 1745 1647 5379 1746 1648 5380 1742 1645 5381 1747 492 5382 1744 492 5383 1748 492 5384 1739 1642 5385 1745 1647 5386 1742 1645 5387 1747 1649 5388 1743 1649 5389 1744 1649 5390 1745 1647 5391 1749 1650 5392 1746 1648 5393 1747 1651 5394 1748 1651 5395 1750 1651 5396 1751 1652 5397 1752 1653 5398 1749 1650 5399 1753 1654 5400 1750 1654 5401 1754 1654 5402 1745 1647 5403 1751 1652 5404 1749 1650 5405 1753 492 5406 1747 492 5407 1750 492 5408 1751 1652 5409 1755 1655 5410 1752 1653 5411 1753 492 5412 1754 492 5413 1756 492 5414 1757 1656 5415 1758 1657 5416 1755 1655 5417 1759 1658 5418 1756 1658 5419 1760 1658 5420 1751 1652 5421 1757 1656 5422 1755 1655 5423 1759 492 5424 1753 492 5425 1756 492 5426 1761 1659 5427 1762 1660 5428 1758 1657 5429 1759 1661 5430 1760 1661 5431 1763 1661 5432 1757 1656 5433 1761 1659 5434 1758 1657 5435 1761 1659 5436 1764 1662 5437 1762 1660 5438 1765 492 5439 1763 492 5440 1766 492 5441 1765 1663 5442 1759 1663 5443 1763 1663 5444 1767 1664 5445 1768 1665 5446 1764 1662 5447 1765 492 5448 1766 492 5449 1769 492 5450 1761 1659 5451 1767 1664 5452 1764 1662 5453 1767 1664 5454 1770 1666 5455 1768 1665 5456 1771 492 5457 1769 492 5458 1772 492 5459 1771 492 5460 1765 492 5461 1769 492 5462 1773 1667 5463 1774 1668 5464 1770 1666 5465 1771 492 5466 1772 492 5467 1775 492 5468 1767 1664 5469 1773 1667 5470 1770 1666 5471 1776 1669 5472 1777 1670 5473 1774 1668 5474 1778 492 5475 1775 492 5476 1779 492 5477 1773 1667 5478 1776 1669 5479 1774 1668 5480 1771 492 5481 1775 492 5482 1778 492 5483 1780 1671 5484 1781 1672 5485 1777 1670 5486 1782 1673 5487 1779 1673 5488 1783 1673 5489 1776 1669 5490 1780 1671 5491 1777 1670 5492 1784 1674 5493 1778 1674 5494 1779 1674 5495 1782 1675 5496 1784 1675 5497 1779 1675 5498 1785 1676 5499 1786 1677 5500 1781 1672 5501 1787 492 5502 1783 492 5503 1788 492 5504 1780 1671 5505 1785 1676 5506 1781 1672 5507 1787 1678 5508 1782 1678 5509 1783 1678 5510 1789 1679 5511 1790 1680 5512 1786 1677 5513 1791 1681 5514 1788 1681 5515 1792 1681 5516 1785 1676 5517 1789 1679 5518 1786 1677 5519 1791 1682 5520 1787 1682 5521 1788 1682 5522 1793 1683 5523 1794 1684 5524 1790 1680 5525 1795 1685 5526 1792 1685 5527 1796 1685 5528 1789 1679 5529 1793 1683 5530 1790 1680 5531 1795 492 5532 1791 492 5533 1792 492 5534 1797 1686 5535 1798 1687 5536 1794 1684 5537 1799 492 5538 1796 492 5539 1800 492 5540 1793 1683 5541 1797 1686 5542 1794 1684 5543 1799 1688 5544 1795 1688 5545 1796 1688 5546 1801 1689 5547 1802 1690 5548 1798 1687 5549 1803 1691 5550 1800 1691 5551 1804 1691 5552 1797 1686 5553 1801 1689 5554 1798 1687 5555 1803 492 5556 1799 492 5557 1800 492 5558 1805 1692 5559 1806 1693 5560 1802 1690 5561 1807 492 5562 1804 492 5563 1808 492 5564 1801 1689 5565 1805 1692 5566 1802 1690 5567 1809 1694 5568 1803 1694 5569 1804 1694 5570 1807 1695 5571 1809 1695 5572 1804 1695 5573 1810 1696 5574 1811 1696 5575 1806 1693 5576 1812 492 5577 1808 492 5578 1813 492 5579 1814 1697 5580 1810 1696 5581 1806 1693 5582 1815 1698 5583 1814 1697 5584 1806 1693 5585 1816 1699 5586 1815 1698 5587 1806 1693 5588 1805 1692 5589 1816 1699 5590 1806 1693 5591 1812 1700 5592 1817 1700 5593 1808 1700 5594 1807 492 5595 1808 492 5596 1817 492 5597 1818 1701 5598 1819 1702 5599 1820 1703 5600 1821 1704 5601 1822 1705 5602 1819 1702 5603 1823 1706 5604 1821 1704 5605 1819 1702 5606 1818 1701 5607 1823 1706 5608 1819 1702 5609 1824 1707 5610 1825 1707 5611 1826 1707 5612 1827 1708 5613 1828 1709 5614 1829 1710 5615 1830 1711 5616 1831 1712 5617 1832 1713 5618 1830 1711 5619 1832 1713 5620 1833 1714 5621 1834 1715 5622 1835 1716 5623 1836 1717 5624 1837 1718 5625 1826 1718 5626 1838 1718 5627 3 1719 5628 1838 1719 5629 1826 1719 5630 1839 1720 5631 1826 1720 5632 1837 1720 5633 1840 1721 5634 1826 1721 5635 1839 1721 5636 1841 1722 5637 1826 1722 5638 1840 1722 5639 1842 1723 5640 1826 1723 5641 1841 1723 5642 1824 1724 5643 1826 1724 5644 1842 1724 5645 1843 1725 5646 1844 1726 5647 1845 1727 5648 1846 1728 5649 1836 1717 5650 1847 1729 5651 1846 1728 5652 1834 1715 5653 1836 1717 5654 1848 1730 5655 1847 1729 5656 1849 1731 5657 1846 1728 5658 1847 1729 5659 1848 1730 5660 1850 1732 5661 1849 1731 5662 1851 1733 5663 1848 1730 5664 1849 1731 5665 1850 1732 5666 1850 1732 5667 1851 1733 5668 1852 1734 5669 1853 1735 5670 1852 1734 5671 1854 1736 5672 1850 1732 5673 1852 1734 5674 1853 1735 5675 1855 1737 5676 1854 1736 5677 1856 1738 5678 1853 1735 5679 1854 1736 5680 1855 1737 5681 1857 1739 5682 1856 1738 5683 1858 1740 5684 1855 1737 5685 1856 1738 5686 1857 1739 5687 1859 1741 5688 1858 1740 5689 1860 1742 5690 1857 1739 5691 1858 1740 5692 1859 1741 5693 1861 1743 5694 1860 1742 5695 1862 1744 5696 1859 1741 5697 1860 1742 5698 1861 1743 5699 1863 1745 5700 1862 1744 5701 1864 1746 5702 1861 1743 5703 1862 1744 5704 1863 1745 5705 1865 1747 5706 1864 1746 5707 1866 1748 5708 1863 1745 5709 1864 1746 5710 1865 1747 5711 1867 1749 5712 1866 1748 5713 1868 1750 5714 1865 1747 5715 1866 1748 5716 1867 1749 5717 1869 1751 5718 1868 1750 5719 1870 1752 5720 1867 1749 5721 1868 1750 5722 1869 1751 5723 1871 1753 5724 1870 1752 5725 1872 1754 5726 1869 1751 5727 1870 1752 5728 1871 1753 5729 1873 1755 5730 1872 1754 5731 1874 1756 5732 1871 1753 5733 1872 1754 5734 1873 1755 5735 1875 1757 5736 1874 1756 5737 1876 1758 5738 1873 1755 5739 1874 1756 5740 1875 1757 5741 1875 1757 5742 1876 1758 5743 1877 1759 5744 1878 1760 5745 1877 1759 5746 1879 1761 5747 1875 1757 5748 1877 1759 5749 1878 1760 5750 1880 1762 5751 1879 1761 5752 1881 1763 5753 1878 1760 5754 1879 1761 5755 1880 1762 5756 1882 1764 5757 1881 1763 5758 1883 1765 5759 1880 1762 5760 1881 1763 5761 1882 1764 5762 1882 1764 5763 1883 1765 5764 1884 1766 5765 1885 1767 5766 1886 1768 5767 1887 1769 5768 1888 1770 5769 1886 1768 5770 1885 1767 5771 1882 1764 5772 1884 1766 5773 1889 1771 5774 1662 1572 5775 1890 1772 5776 1665 1575 5777 1891 1773 5778 1666 1576 5779 1892 1774 5780 1655 1565 5781 1666 1576 5782 1891 1773 5783 1662 1572 5784 1893 1775 5785 1890 1772 5786 1891 1773 5787 1892 1774 5788 1894 1776 5789 1895 1777 5790 1896 1778 5791 1893 1775 5792 1897 1779 5793 1898 1780 5794 1899 1781 5795 1662 1572 5796 1895 1777 5797 1893 1775 5798 1900 1782 5799 1898 1780 5800 1897 1779 5801 1901 1783 5802 1902 1784 5803 1896 1778 5804 1903 1785 5805 1899 1781 5806 1904 1786 5807 1895 1777 5808 1901 1783 5809 1896 1778 5810 1897 1779 5811 1899 1781 5812 1903 1785 5813 1901 1783 5814 1905 1787 5815 1902 1784 5816 1903 1785 5817 1904 1786 5818 1906 1788 5819 1901 1783 5820 1907 1789 5821 1905 1787 5822 1908 1790 5823 1906 1788 5824 1909 1791 5825 1903 1785 5826 1906 1788 5827 1908 1790 5828 1901 1783 5829 1910 1792 5830 1907 1789 5831 1908 1790 5832 1909 1791 5833 1911 1793 5834 1912 1794 5835 1913 1795 5836 1910 1792 5837 1914 1796 5838 1915 1797 5839 1916 1798 5840 1901 1783 5841 1912 1794 5842 1910 1792 5843 1917 1799 5844 1915 1797 5845 1914 1796 5846 1912 1794 5847 1918 1800 5848 1913 1795 5849 1914 1796 5850 1916 1798 5851 1919 1801 5852 1912 1794 5853 1920 1802 5854 1918 1800 5855 1921 1803 5856 1922 1804 5857 1923 1805 5858 1921 1803 5859 1924 1806 5860 1922 1804 5861 1925 1807 5862 1926 1808 5863 1920 1802 5864 1927 1809 5865 1923 1805 5866 1928 1810 5867 1912 1794 5868 1925 1807 5869 1920 1802 5870 1921 1803 5871 1923 1805 5872 1927 1809 5873 1925 1807 5874 1929 1811 5875 1926 1808 5876 1927 1809 5877 1928 1810 5878 1930 1812 5879 1925 1807 5880 1931 1813 5881 1929 1811 5882 1932 1814 5883 1930 1812 5884 1933 1815 5885 1927 1809 5886 1930 1812 5887 1932 1814 5888 1925 1807 5889 1934 1816 5890 1931 1813 5891 1932 1814 5892 1933 1815 5893 1935 1817 5894 1936 1818 5895 1937 1819 5896 1938 1820 5897 1939 1821 5898 1937 1819 5899 1936 1818 5900 1940 1822 5901 1941 1823 5902 1942 1824 5903 1943 1825 5904 1941 1823 5905 1940 1822 5906 1944 492 5907 1945 492 5908 1946 492 5909 1947 492 5910 1948 492 5911 1945 492 5912 1944 492 5913 1947 492 5914 1945 492 5915 1949 1826 5916 1946 1826 5917 1950 1826 5918 1951 1827 5919 1944 1827 5920 1946 1827 5921 1949 1828 5922 1951 1828 5923 1946 1828 5924 1952 492 5925 1950 492 5926 1953 492 5927 1952 1829 5928 1949 1829 5929 1950 1829 5930 1954 1830 5931 1953 1830 5932 1955 1830 5933 1954 1831 5934 1952 1831 5935 1953 1831 5936 1956 1832 5937 1955 1832 5938 1957 1832 5939 1956 492 5940 1954 492 5941 1955 492 5942 1958 492 5943 1957 492 5944 1959 492 5945 1958 1833 5946 1956 1833 5947 1957 1833 5948 1960 1834 5949 1959 1834 5950 1961 1834 5951 1960 492 5952 1958 492 5953 1959 492 5954 1732 492 5955 1961 492 5956 1723 492 5957 1962 1835 5958 1960 1835 5959 1961 1835 5960 1732 1836 5961 1962 1836 5962 1961 1836 5963 1963 492 5964 1964 492 5965 1948 492 5966 1965 1837 5967 1936 1818 5968 1966 1838 5969 1947 492 5970 1963 492 5971 1948 492 5972 1967 1839 5973 1939 1821 5974 1936 1818 5975 1968 1840 5976 1967 1839 5977 1936 1818 5978 1969 1841 5979 1968 1840 5980 1936 1818 5981 1965 1837 5982 1969 1841 5983 1936 1818 5984 1970 492 5985 1971 492 5986 1964 492 5987 1972 1842 5988 1966 1838 5989 1973 1843 5990 1963 1844 5991 1970 1844 5992 1964 1844 5993 1974 1845 5994 1965 1837 5995 1966 1838 5996 1975 1846 5997 1974 1845 5998 1966 1838 5999 1976 1847 6000 1975 1846 6001 1966 1838 6002 1972 1842 6003 1976 1847 6004 1966 1838 6005 1977 492 6006 1978 492 6007 1971 492 6008 1979 1848 6009 1973 1843 6010 1980 1849 6011 1970 492 6012 1977 492 6013 1971 492 6014 1979 1848 6015 1972 1842 6016 1973 1843 6017 1981 492 6018 1982 492 6019 1978 492 6020 1983 1850 6021 1980 1849 6022 1984 1851 6023 1977 492 6024 1981 492 6025 1978 492 6026 1985 1852 6027 1979 1848 6028 1980 1849 6029 1986 1853 6030 1985 1852 6031 1980 1849 6032 1983 1850 6033 1986 1853 6034 1980 1849 6035 1987 1854 6036 1988 1854 6037 1982 1854 6038 1989 1855 6039 1984 1851 6040 1990 1856 6041 1981 1857 6042 1987 1857 6043 1982 1857 6044 1991 1858 6045 1983 1850 6046 1984 1851 6047 1989 1855 6048 1991 1858 6049 1984 1851 6050 1992 492 6051 1817 492 6052 1988 492 6053 1993 1859 6054 1990 1856 6055 1994 1860 6056 1995 1861 6057 1992 1861 6058 1988 1861 6059 1987 1862 6060 1995 1862 6061 1988 1862 6062 1996 1863 6063 1989 1855 6064 1990 1856 6065 1997 1864 6066 1996 1863 6067 1990 1856 6068 1998 1865 6069 1997 1864 6070 1990 1856 6071 1993 1859 6072 1998 1865 6073 1990 1856 6074 1999 1866 6075 1994 1860 6076 1822 1705 6077 1992 1867 6078 1807 1867 6079 1817 1867 6080 2000 1868 6081 1993 1859 6082 1994 1860 6083 2001 1869 6084 2000 1868 6085 1994 1860 6086 2002 1870 6087 2001 1869 6088 1994 1860 6089 1999 1866 6090 2002 1870 6091 1994 1860 6092 2003 1871 6093 1999 1866 6094 1822 1705 6095 1821 1704 6096 2003 1871 6097 1822 1705 6098 2004 1872 6099 2005 1873 6100 2006 1874 6101 2007 1875 6102 2008 1876 6103 2009 1877 6104 2007 1875 6105 2009 1877 6106 2010 1878 6107 2011 1879 6108 2006 1874 6109 2012 1880 6110 2011 1879 6111 2004 1872 6112 2006 1874 6113 2013 1881 6114 2012 1880 6115 2014 1882 6116 2013 1881 6117 2011 1879 6118 2012 1880 6119 2015 1883 6120 2014 1882 6121 2016 1884 6122 2015 1883 6123 2013 1881 6124 2014 1882 6125 2017 1885 6126 2016 1884 6127 2018 1886 6128 2017 1885 6129 2015 1883 6130 2016 1884 6131 2019 1887 6132 2018 1886 6133 2020 1888 6134 2019 1887 6135 2017 1885 6136 2018 1886 6137 2021 1889 6138 2020 1888 6139 2022 1890 6140 2021 1889 6141 2019 1887 6142 2020 1888 6143 2023 1891 6144 2022 1890 6145 2024 1892 6146 2025 1893 6147 2021 1889 6148 2022 1890 6149 2023 1891 6150 2025 1893 6151 2022 1890 6152 2026 1894 6153 2024 1892 6154 2027 1895 6155 2026 1894 6156 2023 1891 6157 2024 1892 6158 2028 1896 6159 2027 1895 6160 2029 1897 6161 2028 1896 6162 2026 1894 6163 2027 1895 6164 2030 1898 6165 2029 1897 6166 2031 1899 6167 2030 1898 6168 2028 1896 6169 2029 1897 6170 2030 1898 6171 2031 1899 6172 2032 1900 6173 2033 1901 6174 2032 1900 6175 2034 1902 6176 2033 1901 6177 2030 1898 6178 2032 1900 6179 2035 1903 6180 2034 1902 6181 2036 1904 6182 2035 1903 6183 2033 1901 6184 2034 1902 6185 2037 1905 6186 2036 1904 6187 2038 1906 6188 2037 1905 6189 2035 1903 6190 2036 1904 6191 2039 1907 6192 2038 1906 6193 2040 1908 6194 2039 1907 6195 2037 1905 6196 2038 1906 6197 2041 1909 6198 2040 1908 6199 2042 1910 6200 2041 1909 6201 2039 1907 6202 2040 1908 6203 2043 1911 6204 2042 1910 6205 2044 1912 6206 2043 1911 6207 2041 1909 6208 2042 1910 6209 2045 1913 6210 2046 1914 6211 2047 1915 6212 2048 1916 6213 2043 1911 6214 2044 1912 6215 2049 1917 6216 2047 1915 6217 2050 1918 6218 2049 1917 6219 2045 1913 6220 2047 1915 6221 2051 1919 6222 2050 1918 6223 2052 1920 6224 2051 1919 6225 2049 1917 6226 2050 1918 6227 2053 1921 6228 2052 1920 6229 2054 1922 6230 2053 1921 6231 2051 1919 6232 2052 1920 6233 2055 1923 6234 2054 1922 6235 2056 1924 6236 2055 1923 6237 2053 1921 6238 2054 1922 6239 2057 1925 6240 2056 1924 6241 2058 1926 6242 2057 1925 6243 2055 1923 6244 2056 1924 6245 2059 1927 6246 2058 1926 6247 2060 1928 6248 2059 1927 6249 2057 1925 6250 2058 1926 6251 2061 1929 6252 2060 1928 6253 2062 1930 6254 2063 1931 6255 2059 1927 6256 2060 1928 6257 2061 1929 6258 2063 1931 6259 2060 1928 6260 2064 1932 6261 2062 1930 6262 2065 1933 6263 2064 1932 6264 2061 1929 6265 2062 1930 6266 2066 1934 6267 2065 1933 6268 2067 1935 6269 2066 1934 6270 2064 1932 6271 2065 1933 6272 2068 1936 6273 2067 1935 6274 2069 1937 6275 2068 1936 6276 2066 1934 6277 2067 1935 6278 2068 1936 6279 2069 1937 6280 2070 1938 6281 2071 1939 6282 2070 1938 6283 2072 1940 6284 2071 1939 6285 2068 1936 6286 2070 1938 6287 2073 1941 6288 2072 1940 6289 2074 1942 6290 2073 1941 6291 2071 1939 6292 2072 1940 6293 2075 1943 6294 2074 1942 6295 2076 1944 6296 2075 1943 6297 2073 1941 6298 2074 1942 6299 2077 1945 6300 2076 1944 6301 2078 1946 6302 2077 1945 6303 2075 1943 6304 2076 1944 6305 2079 1947 6306 2078 1946 6307 2008 1876 6308 2079 1947 6309 2077 1945 6310 2078 1946 6311 2007 1875 6312 2079 1947 6313 2008 1876 6314 2080 1948 6315 1942 1824 6316 2081 1949 6317 1940 1822 6318 1942 1824 6319 2080 1948 6320 2080 1948 6321 2081 1949 6322 2082 1950 6323 2083 1951 6324 2082 1950 6325 2084 1952 6326 2080 1948 6327 2082 1950 6328 2083 1951 6329 2083 1951 6330 2084 1952 6331 2085 1953 6332 2086 1954 6333 2085 1953 6334 2087 1955 6335 2083 1951 6336 2085 1953 6337 2086 1954 6338 2088 1956 6339 2089 1957 6340 2090 1958 6341 2088 1956 6342 2091 1959 6343 2089 1957 6344 2088 1956 6345 2090 1958 6346 2092 1960 6347 2093 1961 6348 2094 1962 6349 2095 1963 6350 2096 1964 6351 2094 1962 6352 2093 1961 6353 2097 1965 6354 2095 1963 6355 2098 1966 6356 2093 1961 6357 2095 1963 6358 2097 1965 6359 2099 1967 6360 2100 1968 6361 2101 1969 6362 2102 1970 6363 2100 1968 6364 2099 1967 6365 2099 1967 6366 2101 1969 6367 2103 1971 6368 2104 1972 6369 2103 1971 6370 2105 1973 6371 2099 1967 6372 2103 1971 6373 2104 1972 6374 2106 1974 6375 2107 1975 6376 2108 1976 6377 2109 1977 6378 2108 1976 6379 2110 1978 6380 2111 1979 6381 2108 1976 6382 2109 1977 6383 2106 1974 6384 2108 1976 6385 2111 1979 6386 2112 1980 6387 2110 1978 6388 2113 1981 6389 2109 1977 6390 2110 1978 6391 2112 1980 6392 2112 1980 6393 2113 1981 6394 2114 1982 6395 2115 1983 6396 2114 1982 6397 2116 1984 6398 2112 1980 6399 2114 1982 6400 2115 1983 6401 2115 1983 6402 2116 1984 6403 2117 1985 6404 2118 1986 6405 2117 1985 6406 2119 1987 6407 2115 1983 6408 2117 1985 6409 2118 1986 6410 2118 1986 6411 2119 1987 6412 2120 1988 6413 2121 1989 6414 2120 1988 6415 2122 1990 6416 2118 1986 6417 2120 1988 6418 2121 1989 6419 2123 1991 6420 2122 1990 6421 2124 1992 6422 2121 1989 6423 2122 1990 6424 2123 1991 6425 2125 1993 6426 2124 1992 6427 2126 1994 6428 2123 1991 6429 2124 1992 6430 2125 1993 6431 2127 1995 6432 2126 1994 6433 2128 1996 6434 2125 1993 6435 2126 1994 6436 2127 1995 6437 2129 1997 6438 2128 1996 6439 2130 1998 6440 2127 1995 6441 2128 1996 6442 2129 1997 6443 2131 1999 6444 2130 1998 6445 1828 1709 6446 2131 1999 6447 2129 1997 6448 2130 1998 6449 2132 2000 6450 2131 1999 6451 1828 1709 6452 2133 2001 6453 2132 2000 6454 1828 1709 6455 1827 1708 6456 2133 2001 6457 1828 1709 6458 2134 2002 6459 2135 2003 6460 2136 2004 6461 2137 2005 6462 2138 2006 6463 2139 2007 6464 2140 2008 6465 2134 2002 6466 2136 2004 6467 2141 2009 6468 2142 2010 6469 2143 2011 6470 2141 2009 6471 2143 2011 6472 2144 2012 6473 2145 2013 6474 2146 2014 6475 2147 2015 6476 2148 2016 6477 2149 2017 6478 2135 2003 6479 2150 2018 6480 2139 2007 6481 2151 2019 6482 2134 2002 6483 2148 2016 6484 2135 2003 6485 2137 2005 6486 2139 2007 6487 2152 2020 6488 2150 2018 6489 2152 2020 6490 2139 2007 6491 2153 2021 6492 2154 2022 6493 2149 2017 6494 2155 2023 6495 2151 2019 6496 2156 2024 6497 2148 2016 6498 2153 2021 6499 2149 2017 6500 2150 2018 6501 2151 2019 6502 2155 2023 6503 2157 2025 6504 2086 1954 6505 2154 2022 6506 2088 1956 6507 2156 2024 6508 2091 1959 6509 2153 2021 6510 2157 2025 6511 2154 2022 6512 2158 2026 6513 2156 2024 6514 2088 1956 6515 2155 2023 6516 2156 2024 6517 2158 2026 6518 2157 2025 6519 2083 1951 6520 2086 1954 6521 2080 1948 6522 2083 1951 6523 2157 2025 6524 2159 2027 6525 2157 2025 6526 2153 2021 6527 2159 2027 6528 2080 1948 6529 2157 2025 6530 2160 2028 6531 2153 2021 6532 2148 2016 6533 2160 2028 6534 2159 2027 6535 2153 2021 6536 2161 2029 6537 2148 2016 6538 2134 2002 6539 2161 2029 6540 2160 2028 6541 2148 2016 6542 2162 2030 6543 2134 2002 6544 2140 2008 6545 2162 2030 6546 2161 2029 6547 2134 2002 6548 2162 2030 6549 2140 2008 6550 2163 2031 6551 2141 2009 6552 2164 2032 6553 2142 2010 6554 2165 2033 6555 2162 2030 6556 2163 2031 6557 2141 2009 6558 2166 2034 6559 2164 2032 6560 1940 1822 6561 2080 1948 6562 2159 2027 6563 2167 2035 6564 2159 2027 6565 2160 2028 6566 2167 2035 6567 1940 1822 6568 2159 2027 6569 2168 2036 6570 2160 2028 6571 2161 2029 6572 2168 2036 6573 2167 2035 6574 2160 2028 6575 2169 2037 6576 2161 2029 6577 2162 2030 6578 2169 2037 6579 2168 2036 6580 2161 2029 6581 2170 2038 6582 2162 2030 6583 2165 2033 6584 2170 2038 6585 2169 2037 6586 2162 2030 6587 2170 2038 6588 2165 2033 6589 2171 2039 6590 2172 2040 6591 2173 2041 6592 2166 2034 6593 2141 2009 6594 2172 2040 6595 2166 2034 6596 2174 2042 6597 2170 2038 6598 2171 2039 6599 2172 2040 6600 2175 2043 6601 2173 2041 6602 1943 1825 6603 1940 1822 6604 2167 2035 6605 2176 2044 6606 2167 2035 6607 2168 2036 6608 2176 2044 6609 1943 1825 6610 2167 2035 6611 2177 2045 6612 2168 2036 6613 2169 2037 6614 2177 2045 6615 2176 2044 6616 2168 2036 6617 2178 2046 6618 2169 2037 6619 2170 2038 6620 2178 2046 6621 2177 2045 6622 2169 2037 6623 2178 2046 6624 2170 2038 6625 2174 2042 6626 2178 2046 6627 2174 2042 6628 2179 2047 6629 2180 2048 6630 2181 2049 6631 2175 2043 6632 2172 2040 6633 2180 2048 6634 2175 2043 6635 2182 2050 6636 2183 2051 6637 2184 2052 6638 2185 2053 6639 2186 2054 6640 2181 2049 6641 2182 2050 6642 2184 2052 6643 2187 2055 6644 2180 2048 6645 2185 2053 6646 2181 2049 6647 2188 2056 6648 1932 1814 6649 2189 2057 6650 2188 2056 6651 1927 1809 6652 1932 1814 6653 2190 2058 6654 2189 2057 6655 2191 2059 6656 2190 2058 6657 2188 2056 6658 2189 2057 6659 2192 2060 6660 2191 2059 6661 2183 2051 6662 2192 2060 6663 2190 2058 6664 2191 2059 6665 2182 2050 6666 2192 2060 6667 2183 2051 6668 2141 2009 6669 2144 2012 6670 2193 2061 6671 2145 2013 6672 2194 2062 6673 2146 2014 6674 2195 2063 6675 2196 2064 6676 2197 2065 6677 2198 2066 6678 2194 2062 6679 2145 2013 6680 2199 2067 6681 2200 2068 6682 2201 2069 6683 2202 2070 6684 2200 2068 6685 2199 2067 6686 2203 2071 6687 2195 2063 6688 2197 2065 6689 2204 2072 6690 2200 2068 6691 2202 2070 6692 2205 2073 6693 2206 2074 6694 2186 2054 6695 2207 2075 6696 2187 2055 6697 2208 2076 6698 2185 2053 6699 2205 2073 6700 2186 2054 6701 2207 2075 6702 2182 2050 6703 2187 2055 6704 2209 2077 6705 2210 2078 6706 2206 2074 6707 2211 2079 6708 2208 2076 6709 2212 2080 6710 2213 2081 6711 2209 2077 6712 2206 2074 6713 2205 2073 6714 2213 2081 6715 2206 2074 6716 2207 2075 6717 2208 2076 6718 2211 2079 6719 2214 2082 6720 2215 2083 6721 2216 2084 6722 2217 2085 6723 2215 2083 6724 2214 2082 6725 2218 2086 6726 2215 2083 6727 2217 2085 6728 2218 2086 6729 2219 2087 6730 2215 2083 6731 2220 2088 6732 2221 2089 6733 2222 2090 6734 2220 2088 6735 2223 2091 6736 2221 2089 6737 2214 2082 6738 2216 2084 6739 2224 2092 6740 2225 2093 6741 2226 2094 6742 2227 2095 6743 2228 2096 6744 2229 2097 6745 2230 2098 6746 2231 2099 6747 2232 2100 6748 2229 2097 6749 2228 2096 6750 2231 2099 6751 2229 2097 6752 2233 2101 6753 2227 2095 6754 2234 2102 6755 2235 2103 6756 2227 2095 6757 2233 2101 6758 2225 2093 6759 2227 2095 6760 2235 2103 6761 2236 2104 6762 2234 2102 6763 2237 2105 6764 2233 2101 6765 2234 2102 6766 2236 2104 6767 2238 2106 6768 2237 2105 6769 2239 2107 6770 2236 2104 6771 2237 2105 6772 2238 2106 6773 2195 2063 6774 2239 2107 6775 2196 2064 6776 2238 2106 6777 2239 2107 6778 2195 2063 6779 2240 2108 6780 2241 2109 6781 2242 2110 6782 2243 2111 6783 2244 2112 6784 2245 2113 6785 2246 2114 6786 2247 2115 6787 2248 2116 6788 2243 2111 6789 2249 2117 6790 2244 2112 6791 2250 2118 6792 2251 2119 6793 2252 2120 6794 2246 2114 6795 2248 2116 6796 2253 2121 6797 2240 2108 6798 2254 2122 6799 2241 2109 6800 2243 2111 6801 2245 2113 6802 2255 2123 6803 2256 2124 6804 2145 2013 6805 2254 2122 6806 2257 2125 6807 2256 2124 6808 2254 2122 6809 2258 2126 6810 2257 2125 6811 2254 2122 6812 2259 2127 6813 2258 2126 6814 2254 2122 6815 2260 2128 6816 2259 2127 6817 2254 2122 6818 2261 2129 6819 2260 2128 6820 2254 2122 6821 2240 2108 6822 2261 2129 6823 2254 2122 6824 2262 2130 6825 2263 2131 6826 2264 2132 6827 2265 2133 6828 2198 2066 6829 2145 2013 6830 2266 2134 6831 2265 2133 6832 2145 2013 6833 2256 2124 6834 2266 2134 6835 2145 2013 6836 2267 2135 6837 2268 2136 6838 2269 2137 6839 2270 2138 6840 2269 2137 6841 2271 2139 6842 2272 2140 6843 2269 2137 6844 2270 2138 6845 2267 2135 6846 2269 2137 6847 2272 2140 6848 2273 2141 6849 2274 2142 6850 2275 2143 6851 2270 2138 6852 2271 2139 6853 2276 2144 6854 2277 2145 6855 2275 2143 6856 2278 2146 6857 2279 2147 6858 2273 2141 6859 2275 2143 6860 2280 2148 6861 2279 2147 6862 2275 2143 6863 2277 2145 6864 2280 2148 6865 2275 2143 6866 2277 2145 6867 2278 2146 6868 2281 2149 6869 2282 2150 6870 2281 2149 6871 2283 2151 6872 2282 2150 6873 2277 2145 6874 2281 2149 6875 2284 2152 6876 2283 2151 6877 2285 2153 6878 2284 2152 6879 2282 2150 6880 2283 2151 6881 2246 2114 6882 2285 2153 6883 2247 2115 6884 2246 2114 6885 2284 2152 6886 2285 2153 6887 2243 2111 6888 2286 2154 6889 2249 2117 6890 2287 2155 6891 2252 2120 6892 2288 2156 6893 2250 2118 6894 2252 2120 6895 2287 2155 6896 2243 2111 6897 2289 2157 6898 2286 2154 6899 2290 2158 6900 2288 2156 6901 2291 2159 6902 2287 2155 6903 2288 2156 6904 2290 2158 6905 2243 2111 6906 2292 2160 6907 2289 2157 6908 2293 2161 6909 2291 2159 6910 2294 2162 6911 2290 2158 6912 2291 2159 6913 2293 2161 6914 2295 2163 6915 2296 2164 6916 2292 2160 6917 2297 2165 6918 2294 2162 6919 2298 2166 6920 2243 2111 6921 2295 2163 6922 2292 2160 6923 2293 2161 6924 2294 2162 6925 2297 2165 6926 2299 2167 6927 2300 2168 6928 2296 2164 6929 2297 2165 6930 2298 2166 6931 2301 2169 6932 2295 2163 6933 2299 2167 6934 2296 2164 6935 2299 2167 6936 2302 2170 6937 2300 2168 6938 2303 2171 6939 2301 2169 6940 2304 2172 6941 2297 2165 6942 2301 2169 6943 2303 2171 6944 2299 2167 6945 2305 2173 6946 2302 2170 6947 2306 2174 6948 2304 2172 6949 2307 2175 6950 2303 2171 6951 2304 2172 6952 2306 2174 6953 2299 2167 6954 2308 2176 6955 2305 2173 6956 2309 2177 6957 2307 2175 6958 2310 2178 6959 2306 2174 6960 2307 2175 6961 2309 2177 6962 2311 2179 6963 2312 2180 6964 2313 2181 6965 2309 2177 6966 2310 2178 6967 2314 2182 6968 2315 2183 6969 2314 2182 6970 2310 2178 6971 2316 2184 6972 2317 2185 6973 2318 2186 6974 2311 2179 6975 2319 2187 6976 2312 2180 6977 2311 2179 6978 2313 2181 6979 2320 2188 6980 2262 2130 6981 2320 2188 6982 2263 2131 6983 2262 2130 6984 2311 2179 6985 2320 2188 6986 71 69 6987 2321 2189 6988 67 65 6989 2322 2190 6990 67 65 6991 2321 2189 6992 2322 2190 6993 41 39 6994 67 65 6995 2323 2191 6996 2324 2192 6997 2321 2189 6998 2325 2193 6999 2321 2189 7000 2324 2192 7001 71 69 7002 2323 2191 7003 2321 2189 7004 2325 2193 7005 2322 2190 7006 2321 2189 7007 2326 2194 7008 2327 2195 7009 2324 2192 7010 2328 2196 7011 2324 2192 7012 2327 2195 7013 2323 2191 7014 2326 2194 7015 2324 2192 7016 2328 2196 7017 2325 2193 7018 2324 2192 7019 2329 2197 7020 2330 2198 7021 2327 2195 7022 2331 2199 7023 2327 2195 7024 2330 2198 7025 2326 2194 7026 2329 2197 7027 2327 2195 7028 2331 2199 7029 2328 2196 7030 2327 2195 7031 2332 2200 7032 2333 2201 7033 2330 2198 7034 2334 2202 7035 2330 2198 7036 2333 2201 7037 2335 2203 7038 2332 2200 7039 2330 2198 7040 2329 2197 7041 2335 2203 7042 2330 2198 7043 2334 2202 7044 2331 2199 7045 2330 2198 7046 2336 2204 7047 2337 2205 7048 2333 2201 7049 2338 2206 7050 2333 2201 7051 2337 2205 7052 2332 2200 7053 2336 2204 7054 2333 2201 7055 2338 2206 7056 2334 2202 7057 2333 2201 7058 2339 2207 7059 2340 2208 7060 2337 2205 7061 2341 2209 7062 2337 2205 7063 2340 2208 7064 2342 2210 7065 2339 2207 7066 2337 2205 7067 2336 2204 7068 2342 2210 7069 2337 2205 7070 2341 2209 7071 2338 2206 7072 2337 2205 7073 2343 2211 7074 2344 2212 7075 2340 2208 7076 2345 2213 7077 2340 2208 7078 2344 2212 7079 2339 2207 7080 2343 2211 7081 2340 2208 7082 2345 2213 7083 2341 2209 7084 2340 2208 7085 2346 2214 7086 2347 2215 7087 2344 2212 7088 2348 2216 7089 2344 2212 7090 2347 2215 7091 2349 2217 7092 2346 2214 7093 2344 2212 7094 2343 2211 7095 2349 2217 7096 2344 2212 7097 2348 2216 7098 2345 2213 7099 2344 2212 7100 2350 2218 7101 2351 2219 7102 2347 2215 7103 2352 2220 7104 2347 2215 7105 2351 2219 7106 2346 2214 7107 2350 2218 7108 2347 2215 7109 2352 2220 7110 2348 2216 7111 2347 2215 7112 2353 2221 7113 2314 2182 7114 2351 2219 7115 2315 2183 7116 2351 2219 7117 2314 2182 7118 2354 2222 7119 2353 2221 7120 2351 2219 7121 2350 2218 7122 2354 2222 7123 2351 2219 7124 2355 2223 7125 2352 2220 7126 2351 2219 7127 2356 2224 7128 2355 2223 7129 2351 2219 7130 2315 2183 7131 2356 2224 7132 2351 2219 7133 2357 2225 7134 2309 2177 7135 2314 2182 7136 2353 2221 7137 2357 2225 7138 2314 2182 7139 2358 2226 7140 2306 2174 7141 2309 2177 7142 2357 2225 7143 2358 2226 7144 2309 2177 7145 2359 2227 7146 2303 2171 7147 2306 2174 7148 2358 2226 7149 2359 2227 7150 2306 2174 7151 2360 2228 7152 2297 2165 7153 2303 2171 7154 2361 2229 7155 2360 2228 7156 2303 2171 7157 2359 2227 7158 2361 2229 7159 2303 2171 7160 2362 2230 7161 2293 2161 7162 2297 2165 7163 2360 2228 7164 2362 2230 7165 2297 2165 7166 2363 2231 7167 2290 2158 7168 2293 2161 7169 2362 2230 7170 2363 2231 7171 2293 2161 7172 2364 2232 7173 2287 2155 7174 2290 2158 7175 2363 2231 7176 2364 2232 7177 2290 2158 7178 2365 2233 7179 2250 2118 7180 2287 2155 7181 2366 2234 7182 2365 2233 7183 2287 2155 7184 2364 2232 7185 2366 2234 7186 2287 2155 7187 2246 2114 7188 2253 2121 7189 2367 2235 7190 2368 2236 7191 2369 2237 7192 2370 2238 7193 2368 2236 7194 2371 2239 7195 2369 2237 7196 2368 2236 7197 2370 2238 7198 2372 2240 7199 2368 2236 7200 2372 2240 7201 2373 2241 7202 2374 2242 7203 2373 2241 7204 2375 2243 7205 2374 2242 7206 2368 2236 7207 2373 2241 7208 2374 2242 7209 2375 2243 7210 2376 2244 7211 2374 2242 7212 2376 2244 7213 2377 2245 7214 2374 2242 7215 2377 2245 7216 2378 2246 7217 2379 2247 7218 2378 2246 7219 2380 2248 7220 2379 2247 7221 2374 2242 7222 2378 2246 7223 2379 2247 7224 2380 2248 7225 2381 2249 7226 2379 2247 7227 2381 2249 7228 2382 2250 7229 2379 2247 7230 2382 2250 7231 2383 2251 7232 2379 2247 7233 2383 2251 7234 2384 2252 7235 2385 2253 7236 2384 2252 7237 2386 2254 7238 2385 2253 7239 2379 2247 7240 2384 2252 7241 2385 2253 7242 2386 2254 7243 2387 2255 7244 2385 2253 7245 2387 2255 7246 2388 2256 7247 2385 2253 7248 2388 2256 7249 2389 2257 7250 2390 2258 7251 2389 2257 7252 2391 2259 7253 2390 2258 7254 2385 2253 7255 2389 2257 7256 2390 2258 7257 2391 2259 7258 2392 2260 7259 2390 2258 7260 2392 2260 7261 2393 2261 7262 2394 2262 7263 2393 2261 7264 2395 2263 7265 2394 2262 7266 2390 2258 7267 2393 2261 7268 2394 2262 7269 2395 2263 7270 2396 2264 7271 2397 2265 7272 2396 2264 7273 2398 2266 7274 2397 2265 7275 2394 2262 7276 2396 2264 7277 2399 2267 7278 2398 2266 7279 2400 2268 7280 2399 2267 7281 2397 2265 7282 2398 2266 7283 2399 2267 7284 2400 2268 7285 72 70 7286 68 66 7287 2399 2267 7288 72 70 7289 29 27 7290 26 24 7291 2401 2269 7292 2402 2270 7293 2401 2269 7294 2403 2271 7295 2404 2272 7296 29 27 7297 2401 2269 7298 2402 2270 7299 2404 2272 7300 2401 2269 7301 2405 2273 7302 2403 2271 7303 2406 2274 7304 2407 2275 7305 2402 2270 7306 2403 2271 7307 2405 2273 7308 2407 2275 7309 2403 2271 7310 2408 2276 7311 2406 2274 7312 2409 2277 7313 2408 2276 7314 2405 2273 7315 2406 2274 7316 2410 2278 7317 2409 2277 7318 2411 2279 7319 2410 2278 7320 2408 2276 7321 2409 2277 7322 2412 2280 7323 2411 2279 7324 2413 2281 7325 2412 2280 7326 2410 2278 7327 2411 2279 7328 2414 2282 7329 2413 2281 7330 2415 2283 7331 2414 2282 7332 2412 2280 7333 2413 2281 7334 2414 2282 7335 2415 2283 7336 2416 2284 7337 2417 2285 7338 2418 2286 7339 2419 2287 7340 2420 2288 7341 2421 2289 7342 2422 2290 7343 2423 2291 7344 2420 2288 7345 2422 2290 7346 2417 2285 7347 2424 2292 7348 2418 2286 7349 2417 2285 7350 2419 2287 7351 2425 2293 7352 2417 2285 7353 2425 2293 7354 2426 2294 7355 2316 2184 7356 2426 2294 7357 2427 2295 7358 2316 2184 7359 2417 2285 7360 2426 2294 7361 2316 2184 7362 2427 2295 7363 2317 2185 7364 2428 2296 7365 32 30 7366 2429 2297 7367 2428 2296 7368 30 28 7369 32 30 7370 2428 2296 7371 2429 2297 7372 2430 2298 7373 2431 2299 7374 2430 2298 7375 2432 2300 7376 2431 2299 7377 2428 2296 7378 2430 2298 7379 2433 2301 7380 2432 2300 7381 2434 2302 7382 2433 2301 7383 2431 2299 7384 2432 2300 7385 2433 2301 7386 2434 2302 7387 2435 2303 7388 2436 2304 7389 2435 2303 7390 2437 2305 7391 2436 2304 7392 2433 2301 7393 2435 2303 7394 2438 2306 7395 2437 2305 7396 2439 2307 7397 2438 2306 7398 2436 2304 7399 2437 2305 7400 2420 2288 7401 2439 2307 7402 2421 2289 7403 2420 2288 7404 2438 2306 7405 2439 2307 7406 30 28 7407 2440 2308 7408 33 31 7409 14 12 7410 20 18 7411 2441 2309 7412 30 28 7413 2442 2310 7414 2440 2308 7415 2443 2311 7416 2441 2309 7417 2444 2312 7418 14 12 7419 2441 2309 7420 2443 2311 7421 2125 1993 7422 2442 2310 7423 30 28 7424 2127 1995 7425 2445 2313 7426 2442 2310 7427 2446 2314 7428 2444 2312 7429 2447 2315 7430 2125 1993 7431 2127 1995 7432 2442 2310 7433 2443 2311 7434 2444 2312 7435 2446 2314 7436 2123 1991 7437 30 28 7438 2428 2296 7439 2123 1991 7440 2125 1993 7441 30 28 7442 2121 1989 7443 2428 2296 7444 2431 2299 7445 2121 1989 7446 2123 1991 7447 2428 2296 7448 2118 1986 7449 2431 2299 7450 2433 2301 7451 2118 1986 7452 2121 1989 7453 2431 2299 7454 2115 1983 7455 2433 2301 7456 2436 2304 7457 2115 1983 7458 2118 1986 7459 2433 2301 7460 2112 1980 7461 2436 2304 7462 2438 2306 7463 2112 1980 7464 2115 1983 7465 2436 2304 7466 2109 1977 7467 2438 2306 7468 2420 2288 7469 2109 1977 7470 2112 1980 7471 2438 2306 7472 2423 2291 7473 2448 2316 7474 2420 2288 7475 2109 1977 7476 2420 2288 7477 2448 2316 7478 2417 2285 7479 2449 2317 7480 2424 2292 7481 2450 2318 7482 2109 1977 7483 2448 2316 7484 2451 2319 7485 2452 2320 7486 2449 2317 7487 2417 2285 7488 2451 2319 7489 2449 2317 7490 2127 1995 7491 2453 2321 7492 2445 2313 7493 2446 2314 7494 2447 2315 7495 2454 2322 7496 2127 1995 7497 2455 2323 7498 2453 2321 7499 2456 2324 7500 2454 2322 7501 2457 2325 7502 2446 2314 7503 2454 2322 7504 2456 2324 7505 2127 1995 7506 2129 1997 7507 2455 2323 7508 2458 2326 7509 2457 2325 7510 2459 2327 7511 2456 2324 7512 2457 2325 7513 2458 2326 7514 2460 2328 7515 2459 2327 7516 2461 2329 7517 2458 2326 7518 2459 2327 7519 2460 2328 7520 2450 2318 7521 2111 1979 7522 2109 1977 7523 2462 2330 7524 2463 2331 7525 2452 2320 7526 2099 1967 7527 2104 1972 7528 2463 2331 7529 2462 2330 7530 2099 1967 7531 2463 2331 7532 2451 2319 7533 2462 2330 7534 2452 2320 7535 2464 2332 7536 2461 2329 7537 2465 2333 7538 2460 2328 7539 2461 2329 7540 2464 2332 7541 2466 2334 7542 2465 2333 7543 2467 2335 7544 2464 2332 7545 2465 2333 7546 2466 2334 7547 1830 1711 7548 2467 2335 7549 1831 1712 7550 2466 2334 7551 2467 2335 7552 1830 1711 7553 2443 2311 7554 2468 2336 7555 17 15 7556 3 2337 7557 18 2337 7558 2469 2337 7559 14 12 7560 2443 2311 7561 17 15 7562 2443 2311 7563 2470 2338 7564 2468 2336 7565 3 2339 7566 2469 2339 7567 2471 2339 7568 2446 2314 7569 2472 2340 7570 2470 2338 7571 3 2341 7572 2471 2341 7573 1838 2341 7574 2443 2311 7575 2446 2314 7576 2470 2338 7577 2458 2326 7578 2473 2342 7579 2472 2340 7580 2456 2324 7581 2458 2326 7582 2472 2340 7583 2446 2314 7584 2456 2324 7585 2472 2340 7586 2460 2328 7587 2474 2343 7588 2473 2342 7589 2458 2326 7590 2460 2328 7591 2473 2342 7592 2460 2328 7593 2475 2344 7594 2474 2343 7595 2464 2332 7596 2476 2345 7597 2475 2344 7598 2460 2328 7599 2464 2332 7600 2475 2344 7601 2466 2334 7602 2477 2346 7603 2476 2345 7604 2464 2332 7605 2466 2334 7606 2476 2345 7607 1830 1711 7608 1833 1714 7609 2477 2346 7610 2466 2334 7611 1830 1711 7612 2477 2346 7613 2478 2347 7614 2479 2348 7615 2480 2349 7616 2481 2350 7617 2482 2351 7618 2483 2352 7619 2484 2353 7620 2479 2348 7621 2478 2347 7622 2485 2354 7623 2480 2349 7624 2486 2355 7625 2485 2354 7626 2478 2347 7627 2480 2349 7628 2485 2354 7629 2486 2355 7630 1844 1726 7631 2485 2354 7632 1844 1726 7633 1843 1725 7634 925 839 7635 927 841 7636 2487 2356 7637 2488 2357 7638 2489 2358 7639 2490 2359 7640 2491 2360 7641 2490 2359 7642 2492 2361 7643 2488 2357 7644 2490 2359 7645 2491 2360 7646 2493 2362 7647 2492 2361 7648 2494 2363 7649 2491 2360 7650 2492 2361 7651 2493 2362 7652 2495 2364 7653 2494 2363 7654 2496 2365 7655 2493 2362 7656 2494 2363 7657 2495 2364 7658 2497 2366 7659 2496 2365 7660 2498 2367 7661 2495 2364 7662 2496 2365 7663 2497 2366 7664 2497 2366 7665 2498 2367 7666 2499 2368 7667 2500 2369 7668 2501 2370 7669 2502 2371 7670 2497 2366 7671 2499 2368 7672 2503 2372 7673 2504 2373 7674 2502 2371 7675 2505 2374 7676 2504 2373 7677 2500 2369 7678 2502 2371 7679 2504 2373 7680 2505 2374 7681 2506 2375 7682 2507 2376 7683 2506 2375 7684 2508 2377 7685 2504 2373 7686 2506 2375 7687 2507 2376 7688 2509 2378 7689 2508 2377 7690 2510 2379 7691 2507 2376 7692 2508 2377 7693 2509 2378 7694 2509 2378 7695 2510 2379 7696 2511 2380 7697 2512 2381 7698 2511 2380 7699 2513 2382 7700 2509 2378 7701 2511 2380 7702 2512 2381 7703 2512 2381 7704 2513 2382 7705 2514 2383 7706 2515 2384 7707 2514 2383 7708 2482 2351 7709 2512 2381 7710 2514 2383 7711 2515 2384 7712 2515 2384 7713 2482 2351 7714 2481 2350 7715 2516 2385 7716 2517 2386 7717 2518 2387 7718 2519 2388 7719 2520 2389 7720 2521 2390 7721 2522 2391 7722 2523 2392 7723 2524 2393 7724 2525 2394 7725 2520 2389 7726 2519 2388 7727 2526 2395 7728 2527 2396 7729 2528 2397 7730 2529 2398 7731 2528 2397 7732 2527 2396 7733 2522 2391 7734 2524 2393 7735 2530 2399 7736 2531 2400 7737 2520 2389 7738 2525 2394 7739 2532 2401 7740 2533 2402 7741 2520 2389 7742 2529 2398 7743 2527 2396 7744 2534 2403 7745 2535 2404 7746 2532 2401 7747 2520 2389 7748 2531 2400 7749 2535 2404 7750 2520 2389 7751 2516 2385 7752 2536 2405 7753 2517 2386 7754 2537 2406 7755 2517 2386 7756 2536 2405 7757 2516 2385 7758 2538 2407 7759 2536 2405 7760 2539 2408 7761 2536 2405 7762 2538 2407 7763 2540 2409 7764 2536 2405 7765 2539 2408 7766 2541 2410 7767 2536 2405 7768 2540 2409 7769 2537 2406 7770 2536 2405 7771 2541 2410 7772 2542 2411 7773 2543 2412 7774 2538 2407 7775 2544 2413 7776 2538 2407 7777 2543 2412 7778 2516 2385 7779 2542 2411 7780 2538 2407 7781 2539 2408 7782 2538 2407 7783 2544 2413 7784 2484 2353 7785 2478 2347 7786 2543 2412 7787 2545 2414 7788 2543 2412 7789 2478 2347 7790 2542 2411 7791 2484 2353 7792 2543 2412 7793 2544 2413 7794 2543 2412 7795 2545 2414 7796 2545 2414 7797 2478 2347 7798 2485 2354 7799 2515 2384 7800 2481 2350 7801 2546 2415 7802 2547 2416 7803 2546 2415 7804 2523 2392 7805 2515 2384 7806 2546 2415 7807 2547 2416 7808 2547 2416 7809 2523 2392 7810 2522 2391 7811 2539 2408 7812 2548 2417 7813 2549 2418 7814 2550 2419 7815 2551 2420 7816 2552 2421 7817 2553 2422 7818 2539 2408 7819 2549 2418 7820 2554 2423 7821 2555 2424 7822 2556 2425 7823 2550 2419 7824 2557 2426 7825 2551 2420 7826 2544 2413 7827 2558 2427 7828 2548 2417 7829 2559 2428 7830 2552 2421 7831 2560 2429 7832 2539 2408 7833 2544 2413 7834 2548 2417 7835 2559 2428 7836 2550 2419 7837 2552 2421 7838 2545 2414 7839 1843 1725 7840 2558 2427 7841 1846 1728 7842 2560 2429 7843 1834 1715 7844 2544 2413 7845 2545 2414 7846 2558 2427 7847 1846 1728 7848 2559 2428 7849 2560 2429 7850 2545 2414 7851 2485 2354 7852 1843 1725 7853 2553 2422 7854 2540 2409 7855 2539 2408 7856 2561 2430 7857 2562 2431 7858 2555 2424 7859 2561 2430 7860 2563 2432 7861 2562 2431 7862 2564 2433 7863 2555 2424 7864 2554 2423 7865 2565 2434 7866 2555 2424 7867 2564 2433 7868 2566 2435 7869 2555 2424 7870 2565 2434 7871 2567 2436 7872 2555 2424 7873 2566 2435 7874 2568 2437 7875 2555 2424 7876 2567 2436 7877 2569 2438 7878 2555 2424 7879 2568 2437 7880 2569 2438 7881 2561 2430 7882 2555 2424 7883 2561 2430 7884 2519 2388 7885 2563 2432 7886 2570 2439 7887 2525 2394 7888 2519 2388 7889 2561 2430 7890 2570 2439 7891 2519 2388 7892 2571 2440 7893 2572 2441 7894 2573 2442 7895 2574 2443 7896 2575 2444 7897 2576 2445 7898 2577 2446 7899 2578 2447 7900 2579 2448 7901 2580 2449 7902 2581 2450 7903 2582 2451 7904 2583 2452 7905 2584 2453 7906 2572 2441 7907 2574 2443 7908 2576 2445 7909 2585 2454 7910 2571 2440 7911 2583 2452 7912 2572 2441 7913 2586 2455 7914 2587 2456 7915 2584 2453 7916 2588 2457 7917 2585 2454 7918 2589 2458 7919 2583 2452 7920 2586 2455 7921 2584 2453 7922 2588 2457 7923 2574 2443 7924 2585 2454 7925 2586 2455 7926 2590 2459 7927 2587 2456 7928 2588 2457 7929 2589 2458 7930 2591 2460 7931 2592 2461 7932 2593 2462 7933 2590 2459 7934 2594 2463 7935 2591 2460 7936 2595 2464 7937 2586 2455 7938 2592 2461 7939 2590 2459 7940 2588 2457 7941 2591 2460 7942 2594 2463 7943 2592 2461 7944 2596 2465 7945 2593 2462 7946 2597 2466 7947 2595 2464 7948 2598 2467 7949 2594 2463 7950 2595 2464 7951 2597 2466 7952 2528 2397 7953 2598 2467 7954 2599 2468 7955 2600 2469 7956 2601 2470 7957 2596 2465 7958 2602 2471 7959 2598 2467 7960 2528 2397 7961 2592 2461 7962 2600 2469 7963 2596 2465 7964 2597 2466 7965 2598 2467 7966 2602 2471 7967 2600 2469 7968 2603 2472 7969 2601 2470 7970 2522 2391 7971 2530 2399 7972 2603 2472 7973 2600 2469 7974 2522 2391 7975 2603 2472 7976 2602 2471 7977 2528 2397 7978 2529 2398 7979 2604 2473 7980 2522 2391 7981 2600 2469 7982 2604 2473 7983 2547 2416 7984 2522 2391 7985 2605 2474 7986 2600 2469 7987 2592 2461 7988 2605 2474 7989 2604 2473 7990 2600 2469 7991 2606 2475 7992 2592 2461 7993 2586 2455 7994 2606 2475 7995 2605 2474 7996 2592 2461 7997 2607 2476 7998 2586 2455 7999 2583 2452 8000 2607 2476 8001 2606 2475 8002 2586 2455 8003 2608 2477 8004 2583 2452 8005 2571 2440 8006 2607 2476 8007 2583 2452 8008 2608 2477 8009 2609 2478 8010 2610 2479 8011 2578 2447 8012 2611 2480 8013 2578 2447 8014 2577 2446 8015 2611 2480 8016 2609 2478 8017 2578 2447 8018 2500 2369 8019 2607 2476 8020 2608 2477 8021 2612 2481 8022 2503 2372 8023 2610 2479 8024 2612 2481 8025 2610 2479 8026 2609 2478 8027 2512 2381 8028 2547 2416 8029 2604 2473 8030 2512 2381 8031 2515 2384 8032 2547 2416 8033 2509 2378 8034 2604 2473 8035 2605 2474 8036 2509 2378 8037 2512 2381 8038 2604 2473 8039 2507 2376 8040 2605 2474 8041 2606 2475 8042 2507 2376 8043 2509 2378 8044 2605 2474 8045 2504 2373 8046 2606 2475 8047 2607 2476 8048 2504 2373 8049 2507 2376 8050 2606 2475 8051 2504 2373 8052 2607 2476 8053 2500 2369 8054 2497 2366 8055 2503 2372 8056 2612 2481 8057 2613 2482 8058 2581 2450 8059 2614 2483 8060 2580 2449 8061 2614 2483 8062 2581 2450 8063 2615 2484 8064 2616 2485 8065 2609 2478 8066 2612 2481 8067 2609 2478 8068 2616 2485 8069 2617 2486 8070 2615 2484 8071 2609 2478 8072 2611 2480 8073 2617 2486 8074 2609 2478 8075 2618 2487 8076 2619 2488 8077 2616 2485 8078 2620 2489 8079 2616 2485 8080 2619 2488 8081 2621 2490 8082 2618 2487 8083 2616 2485 8084 2615 2484 8085 2621 2490 8086 2616 2485 8087 2620 2489 8088 2612 2481 8089 2616 2485 8090 2622 2491 8091 2623 2492 8092 2619 2488 8093 2624 2493 8094 2619 2488 8095 2623 2492 8096 2625 2494 8097 2622 2491 8098 2619 2488 8099 2618 2487 8100 2625 2494 8101 2619 2488 8102 2624 2493 8103 2620 2489 8104 2619 2488 8105 2626 2495 8106 2627 2496 8107 2623 2492 8108 2628 2497 8109 2623 2492 8110 2627 2496 8111 2629 2498 8112 2626 2495 8113 2623 2492 8114 2630 2499 8115 2629 2498 8116 2623 2492 8117 2622 2491 8118 2630 2499 8119 2623 2492 8120 2628 2497 8121 2624 2493 8122 2623 2492 8123 2631 2500 8124 2632 2501 8125 2633 2502 8126 2634 2503 8127 2628 2497 8128 2627 2496 8129 2631 2500 8130 2635 2504 8131 2632 2501 8132 2636 2505 8133 2637 2506 8134 2638 2507 8135 2639 2508 8136 2637 2506 8137 2636 2505 8138 2640 2509 8139 2641 2510 8140 2642 2511 8141 2631 2500 8142 2633 2502 8143 2643 2512 8144 2644 2513 8145 2636 2505 8146 2645 2514 8147 2646 2515 8148 2636 2505 8149 2644 2513 8150 2647 2516 8151 2636 2505 8152 2646 2515 8153 2648 2517 8154 2639 2508 8155 2636 2505 8156 2649 2518 8157 2648 2517 8158 2636 2505 8159 2647 2516 8160 2649 2518 8161 2636 2505 8162 2650 2519 8163 2644 2513 8164 2651 2520 8165 2652 2521 8166 2644 2513 8167 2650 2519 8168 2646 2515 8169 2644 2513 8170 2653 2522 8171 2652 2521 8172 2653 2522 8173 2644 2513 8174 2614 2483 8175 2650 2519 8176 2654 2523 8177 2652 2521 8178 2650 2519 8179 2614 2483 8180 2655 2524 8181 2652 2521 8182 2614 2483 8183 2655 2524 8184 2614 2483 8185 2580 2449 8186 2497 2366 8187 2612 2481 8188 2620 2489 8189 2495 2364 8190 2620 2489 8191 2624 2493 8192 2495 2364 8193 2497 2366 8194 2620 2489 8195 2493 2362 8196 2624 2493 8197 2628 2497 8198 2493 2362 8199 2495 2364 8200 2624 2493 8201 2491 2360 8202 2628 2497 8203 2634 2503 8204 2491 2360 8205 2493 2362 8206 2628 2497 8207 2488 2357 8208 2491 2360 8209 2634 2503 8210 2656 2525 8211 925 839 8212 2635 2504 8213 2631 2500 8214 2656 2525 8215 2635 2504 8216 2656 2525 8217 928 842 8218 925 839 8219 2657 2526 8220 2658 2527 8221 2659 2528 8222 2660 2529 8223 2661 2529 8224 2662 2529 8225 2663 2530 8226 2657 2526 8227 2659 2528 8228 2664 2531 8229 2663 2530 8230 2659 2528 8231 2665 2532 8232 2666 2533 8233 2667 2534 8234 2665 2532 8235 2667 2534 8236 2668 2535 8237 2669 2536 8238 2670 2537 8239 2658 2527 8240 2660 2538 8241 2662 2538 8242 2671 2538 8243 2657 2526 8244 2669 2536 8245 2658 2527 8246 2669 2536 8247 2672 2539 8248 2670 2537 8249 2660 2540 8250 2671 2540 8251 2673 2540 8252 2674 2541 8253 2675 2542 8254 2672 2539 8255 2676 2543 8256 2677 2544 8257 2678 2545 8258 2669 2536 8259 2674 2541 8260 2672 2539 8261 2679 2546 8262 2660 2546 8263 2673 2546 8264 2680 2547 8265 2681 2548 8266 2675 2542 8267 2682 2549 8268 2678 2545 8269 2683 2550 8270 2674 2541 8271 2680 2547 8272 2675 2542 8273 2682 2549 8274 2676 2543 8275 2678 2545 8276 2680 2547 8277 2684 2551 8278 2681 2548 8279 2682 2549 8280 2683 2550 8281 2685 2552 8282 2686 2553 8283 2687 2554 8284 2684 2551 8285 2688 2555 8286 2684 2551 8287 2687 2554 8288 2680 2547 8289 2686 2553 8290 2684 2551 8291 2689 2556 8292 2685 2552 8293 2690 2557 8294 2689 2556 8295 2682 2549 8296 2685 2552 8297 2691 2558 8298 2692 2559 8299 2693 2560 8300 2694 2561 8301 2688 2555 8302 2687 2554 8303 2695 2562 8304 2694 2561 8305 2687 2554 8306 2696 2563 8307 2695 2562 8308 2687 2554 8309 2697 2564 8310 2696 2563 8311 2687 2554 8312 2698 2565 8313 2697 2564 8314 2687 2554 8315 2699 2566 8316 2698 2565 8317 2687 2554 8318 2700 2567 8319 2701 2568 8320 2692 2559 8321 2691 2558 8322 2700 2567 8323 2692 2559 8324 2691 2558 8325 2693 2560 8326 2702 2569 8327 2703 2570 8328 2680 2547 8329 2674 2541 8330 2704 2571 8331 2702 2569 8332 2705 2572 8333 2704 2571 8334 2691 2558 8335 2702 2569 8336 2706 2573 8337 2674 2541 8338 2669 2536 8339 2707 2574 8340 2703 2570 8341 2674 2541 8342 2706 2573 8343 2707 2574 8344 2674 2541 8345 2708 2575 8346 2669 2536 8347 2657 2526 8348 2709 2576 8349 2706 2573 8350 2669 2536 8351 2710 2577 8352 2709 2576 8353 2669 2536 8354 2711 2578 8355 2710 2577 8356 2669 2536 8357 2708 2575 8358 2711 2578 8359 2669 2536 8360 2712 2579 8361 2657 2526 8362 2663 2530 8363 2713 2580 8364 2708 2575 8365 2657 2526 8366 2714 2581 8367 2713 2580 8368 2657 2526 8369 2715 2582 8370 2714 2581 8371 2657 2526 8372 2712 2579 8373 2715 2582 8374 2657 2526 8375 2716 2583 8376 2717 2584 8377 2663 2530 8378 2718 2585 8379 2663 2530 8380 2717 2584 8381 2719 2586 8382 2716 2583 8383 2663 2530 8384 2720 2587 8385 2719 2586 8386 2663 2530 8387 2721 2588 8388 2720 2587 8389 2663 2530 8390 2664 2531 8391 2721 2588 8392 2663 2530 8393 2722 2589 8394 2712 2579 8395 2663 2530 8396 2723 2590 8397 2722 2589 8398 2663 2530 8399 2718 2585 8400 2723 2590 8401 2663 2530 8402 2724 2591 8403 2725 2592 8404 2717 2584 8405 2726 2593 8406 2717 2584 8407 2725 2592 8408 2716 2583 8409 2724 2591 8410 2717 2584 8411 2726 2593 8412 2718 2585 8413 2717 2584 8414 2727 2594 8415 2728 2595 8416 2725 2592 8417 2729 2596 8418 2725 2592 8419 2728 2595 8420 2730 2597 8421 2727 2594 8422 2725 2592 8423 2724 2591 8424 2730 2597 8425 2725 2592 8426 2731 2598 8427 2726 2593 8428 2725 2592 8429 2732 2599 8430 2731 2598 8431 2725 2592 8432 2729 2596 8433 2732 2599 8434 2725 2592 8435 2733 2600 8436 2653 2522 8437 2728 2595 8438 2734 2601 8439 2728 2595 8440 2653 2522 8441 2727 2594 8442 2733 2600 8443 2728 2595 8444 2735 2602 8445 2729 2596 8446 2728 2595 8447 2736 2603 8448 2735 2602 8449 2728 2595 8450 2737 2604 8451 2736 2603 8452 2728 2595 8453 2738 2605 8454 2737 2604 8455 2728 2595 8456 2739 2606 8457 2738 2605 8458 2728 2595 8459 2740 2607 8460 2739 2606 8461 2728 2595 8462 2734 2601 8463 2740 2607 8464 2728 2595 8465 2741 2608 8466 2646 2515 8467 2653 2522 8468 2742 2609 8469 2741 2608 8470 2653 2522 8471 2733 2600 8472 2742 2609 8473 2653 2522 8474 2652 2521 8475 2734 2601 8476 2653 2522 8477 2743 2610 8478 2744 2611 8479 2745 2612 8480 2743 2610 8481 2746 2613 8482 2744 2611 8483 2747 2614 8484 2745 2612 8485 2748 2615 8486 2747 2614 8487 2743 2610 8488 2745 2612 8489 2747 2614 8490 2748 2615 8491 2749 2616 8492 2750 2617 8493 2751 2617 8494 2752 2617 8495 2747 2614 8496 2749 2616 8497 2753 2618 8498 2750 2619 8499 2752 2619 8500 2754 2619 8501 2750 2620 8502 2754 2620 8503 2755 2620 8504 2756 2621 8505 2757 2622 8506 2758 2623 8507 2750 2624 8508 2755 2624 8509 2759 2624 8510 2760 2625 8511 2758 2623 8512 2761 2626 8513 2760 2625 8514 2756 2621 8515 2758 2623 8516 2762 2627 8517 2761 2626 8518 2763 2628 8519 2762 2627 8520 2760 2625 8521 2761 2626 8522 2764 2629 8523 2763 2628 8524 2765 2630 8525 2764 2629 8526 2762 2627 8527 2763 2628 8528 2665 2532 8529 2765 2630 8530 2666 2533 8531 2665 2532 8532 2764 2629 8533 2765 2630 8534 2766 2631 8535 2690 2557 8536 2767 2632 8537 2766 2631 8538 2689 2556 8539 2690 2557 8540 2766 2631 8541 2767 2632 8542 2768 2633 8543 2769 2634 8544 2770 2634 8545 2771 2634 8546 2766 2631 8547 2768 2633 8548 2772 2635 8549 2769 2636 8550 2771 2636 8551 2773 2636 8552 2774 2637 8553 2775 2638 8554 2776 2639 8555 2777 2640 8556 2778 2641 8557 2779 2642 8558 2769 2643 8559 2773 2643 8560 2780 2643 8561 2781 2644 8562 2776 2639 8563 2782 2645 8564 2774 2637 8565 2776 2639 8566 2783 2646 8567 2781 2644 8568 2783 2646 8569 2776 2639 8570 2784 2647 8571 2781 2644 8572 2782 2645 8573 2785 2648 8574 2786 2649 8575 2787 2650 8576 2788 2651 8577 2703 2570 8578 2707 2574 8579 2789 2652 8580 2705 2572 8581 2790 2653 8582 2789 2652 8583 2704 2571 8584 2705 2572 8585 2791 2654 8586 2707 2574 8587 2706 2573 8588 2792 2655 8589 2788 2651 8590 2707 2574 8591 2791 2654 8592 2792 2655 8593 2707 2574 8594 2793 2656 8595 2706 2573 8596 2709 2576 8597 2793 2656 8598 2791 2654 8599 2706 2573 8600 2794 2657 8601 2795 2658 8602 2796 2659 8603 2797 2660 8604 2798 2661 8605 2795 2658 8606 2794 2657 8607 2797 2660 8608 2795 2658 8609 2799 2662 8610 2800 2663 8611 2801 2664 8612 2794 2657 8613 2796 2659 8614 2802 2665 8615 2803 2666 8616 2801 2664 8617 2804 2667 8618 2803 2666 8619 2799 2662 8620 2801 2664 8621 2805 2668 8622 2804 2667 8623 2806 2669 8624 2805 2668 8625 2803 2666 8626 2804 2667 8627 2807 2670 8628 2806 2669 8629 2808 2671 8630 2807 2670 8631 2805 2668 8632 2806 2669 8633 2809 2672 8634 2808 2671 8635 2810 2673 8636 2809 2672 8637 2807 2670 8638 2808 2671 8639 2811 2674 8640 2810 2673 8641 2812 2675 8642 2811 2674 8643 2809 2672 8644 2810 2673 8645 2813 2676 8646 2812 2675 8647 2814 2677 8648 2813 2676 8649 2811 2674 8650 2812 2675 8651 2815 2678 8652 2816 2679 8653 2817 2680 8654 2818 2681 8655 2817 2680 8656 2819 2682 8657 2818 2681 8658 2815 2678 8659 2817 2680 8660 2820 2683 8661 2819 2682 8662 2821 2684 8663 2822 2685 8664 2818 2681 8665 2819 2682 8666 2820 2683 8667 2822 2685 8668 2819 2682 8669 2820 2683 8670 2821 2684 8671 2823 2686 8672 2824 2687 8673 2825 2688 8674 2826 2689 8675 2827 2690 8676 2820 2683 8677 2823 2686 8678 2828 2691 8679 2826 2689 8680 2829 2692 8681 2828 2691 8682 2824 2687 8683 2826 2689 8684 2830 2693 8685 2829 2692 8686 2831 2694 8687 2830 2693 8688 2828 2691 8689 2829 2692 8690 2832 2695 8691 2831 2694 8692 2833 2696 8693 2832 2695 8694 2830 2693 8695 2831 2694 8696 2834 2697 8697 2833 2696 8698 2835 2698 8699 2834 2697 8700 2832 2695 8701 2833 2696 8702 2836 2699 8703 2835 2698 8704 2837 2700 8705 2836 2699 8706 2834 2697 8707 2835 2698 8708 2836 2699 8709 2837 2700 8710 2838 2701 8711 2839 2702 8712 2840 2703 8713 2841 2704 8714 2842 2705 8715 2836 2699 8716 2838 2701 8717 2843 2706 8718 2740 2607 8719 2734 2601 8720 2844 2707 8721 2841 2704 8722 2845 2708 8723 2844 2707 8724 2839 2702 8725 2841 2704 8726 2655 2524 8727 2734 2601 8728 2652 2521 8729 2846 2709 8730 2734 2601 8731 2655 2524 8732 2843 2706 8733 2734 2601 8734 2846 2709 8735 2789 2652 8736 2790 2653 8737 2847 2710 8738 2848 2711 8739 2792 2655 8740 2791 2654 8741 2849 2712 8742 2847 2710 8743 2850 2713 8744 2849 2712 8745 2789 2652 8746 2847 2710 8747 2793 2656 8748 2851 2714 8749 2791 2654 8750 2852 2715 8751 2791 2654 8752 2851 2714 8753 2853 2716 8754 2848 2711 8755 2791 2654 8756 2854 2717 8757 2853 2716 8758 2791 2654 8759 2852 2715 8760 2854 2717 8761 2791 2654 8762 2855 2718 8763 2856 2719 8764 2798 2661 8765 2857 2720 8766 2852 2715 8767 2851 2714 8768 2858 2721 8769 2859 2722 8770 2856 2719 8771 2855 2718 8772 2858 2721 8773 2856 2719 8774 2797 2660 8775 2855 2718 8776 2798 2661 8777 2860 2723 8778 2850 2713 8779 2861 2724 8780 2849 2712 8781 2850 2713 8782 2860 2723 8783 2862 2725 8784 2863 2726 8785 2864 2727 8786 2865 2728 8787 2866 2729 8788 2867 2730 8789 2868 2731 8790 2864 2727 8791 2869 2732 8792 2870 2733 8793 2864 2727 8794 2868 2731 8795 2862 2725 8796 2864 2727 8797 2870 2733 8798 2871 2734 8799 2872 2735 8800 2852 2715 8801 2873 2736 8802 2869 2732 8803 2874 2737 8804 2875 2738 8805 2871 2734 8806 2852 2715 8807 2876 2739 8808 2875 2738 8809 2852 2715 8810 2857 2720 8811 2876 2739 8812 2852 2715 8813 2868 2731 8814 2869 2732 8815 2873 2736 8816 2877 2740 8817 2878 2741 8818 2872 2735 8819 2879 2742 8820 2874 2737 8821 2880 2743 8822 2881 2744 8823 2877 2740 8824 2872 2735 8825 2882 2745 8826 2881 2744 8827 2872 2735 8828 2883 2746 8829 2882 2745 8830 2872 2735 8831 2871 2734 8832 2883 2746 8833 2872 2735 8834 2873 2736 8835 2874 2737 8836 2879 2742 8837 2884 2747 8838 2885 2748 8839 2878 2741 8840 2886 2749 8841 2880 2743 8842 2887 2750 8843 2888 2751 8844 2884 2747 8845 2878 2741 8846 2889 2752 8847 2888 2751 8848 2878 2741 8849 2877 2740 8850 2889 2752 8851 2878 2741 8852 2879 2742 8853 2880 2743 8854 2886 2749 8855 2890 2753 8856 2891 2754 8857 2885 2748 8858 2886 2749 8859 2887 2750 8860 2892 2755 8861 2884 2747 8862 2890 2753 8863 2885 2748 8864 2890 2753 8865 2893 2756 8866 2891 2754 8867 2886 2749 8868 2892 2755 8869 2894 2757 8870 2895 2758 8871 2896 2759 8872 2893 2756 8873 2897 2760 8874 2894 2757 8875 2898 2761 8876 2890 2753 8877 2895 2758 8878 2893 2756 8879 2886 2749 8880 2894 2757 8881 2897 2760 8882 2899 2762 8883 2900 2763 8884 2896 2759 8885 2901 2764 8886 2898 2761 8887 2902 2765 8888 2903 2766 8889 2899 2762 8890 2896 2759 8891 2904 2767 8892 2903 2766 8893 2896 2759 8894 2905 2768 8895 2904 2767 8896 2896 2759 8897 2895 2758 8898 2905 2768 8899 2896 2759 8900 2897 2760 8901 2898 2761 8902 2901 2764 8903 2906 2769 8904 2907 2770 8905 2900 2763 8906 2588 2457 8907 2902 2765 8908 2908 2771 8909 2909 2772 8910 2906 2769 8911 2900 2763 8912 2910 2773 8913 2909 2772 8914 2900 2763 8915 2911 2774 8916 2910 2773 8917 2900 2763 8918 2912 2775 8919 2911 2774 8920 2900 2763 8921 2899 2762 8922 2912 2775 8923 2900 2763 8924 2901 2764 8925 2902 2765 8926 2588 2457 8927 2655 2524 8928 2580 2449 8929 2907 2770 8930 2588 2457 8931 2908 2771 8932 2574 2443 8933 2846 2709 8934 2655 2524 8935 2907 2770 8936 2906 2769 8937 2846 2709 8938 2907 2770 8939 2913 2776 8940 2914 2777 8941 2915 2778 8942 2913 2776 8943 2845 2708 8944 2914 2777 8945 2916 2779 8946 2917 2780 8947 2918 2781 8948 2919 2782 8949 2913 2776 8950 2915 2778 8951 2920 2783 8952 2918 2781 8953 2921 2784 8954 2920 2783 8955 2916 2779 8956 2918 2781 8957 2920 2783 8958 2921 2784 8959 2922 2785 8960 2923 2786 8961 2922 2785 8962 2924 2787 8963 2923 2786 8964 2920 2783 8965 2922 2785 8966 2925 2788 8967 2924 2787 8968 2926 2789 8969 2925 2788 8970 2923 2786 8971 2924 2787 8972 2927 2790 8973 2926 2789 8974 2928 2791 8975 2927 2790 8976 2925 2788 8977 2926 2789 8978 2929 2792 8979 2928 2791 8980 2930 2793 8981 2929 2792 8982 2927 2790 8983 2928 2791 8984 2931 2794 8985 2930 2793 8986 2932 2795 8987 2931 2794 8988 2929 2792 8989 2930 2793 8990 2933 2796 8991 2934 2797 8992 2935 2798 8993 2936 2799 8994 2935 2798 8995 2937 2800 8996 2936 2799 8997 2933 2796 8998 2935 2798 8999 2938 2801 9000 2937 2800 9001 2939 2802 9002 2938 2801 9003 2936 2799 9004 2937 2800 9005 2940 2803 9006 2939 2802 9007 2941 2804 9008 2940 2803 9009 2938 2801 9010 2939 2802 9011 2942 2805 9012 2941 2804 9013 2943 2806 9014 2942 2805 9015 2940 2803 9016 2941 2804 9017 2942 2805 9018 2943 2806 9019 2944 2807 9020 2945 2808 9021 2946 2809 9022 2947 2810 9023 2948 2811 9024 2942 2805 9025 2944 2807 9026 2949 2812 9027 2947 2810 9028 2950 2813 9029 2949 2812 9030 2945 2808 9031 2947 2810 9032 2951 2814 9033 2950 2813 9034 2952 2815 9035 2951 2814 9036 2949 2812 9037 2950 2813 9038 2953 2816 9039 2952 2815 9040 2954 2817 9041 2953 2816 9042 2951 2814 9043 2952 2815 9044 2955 2818 9045 2954 2817 9046 2956 2819 9047 2955 2818 9048 2953 2816 9049 2954 2817 9050 2957 2820 9051 2956 2819 9052 2958 2821 9053 2957 2820 9054 2955 2818 9055 2956 2819 9056 2957 2820 9057 2958 2821 9058 2959 2822 9059 2960 2823 9060 2957 2820 9061 2959 2822 9062 2961 2824 9063 2844 2707 9064 2845 2708 9065 2913 2776 9066 2961 2824 9067 2845 2708 9068 2648 2517 9069 2962 2825 9070 2639 2508 9071 2963 2826 9072 2642 2511 9073 2964 2827 9074 2965 2828 9075 2642 2511 9076 2963 2826 9077 2966 2829 9078 2642 2511 9079 2965 2828 9080 2967 2830 9081 2642 2511 9082 2966 2829 9083 2640 2509 9084 2642 2511 9085 2967 2830 9086 2648 2517 9087 2968 2831 9088 2962 2825 9089 2969 2832 9090 2970 2832 9091 2971 2832 9092 2972 2833 9093 2973 2834 9094 2974 2835 9095 2975 2836 9096 2973 2834 9097 2972 2833 9098 2969 2837 9099 2971 2837 9100 2976 2837 9101 2977 2838 9102 2978 2839 9103 2979 2840 9104 2969 2841 9105 2976 2841 9106 2980 2841 9107 2981 2842 9108 2979 2840 9109 2746 2613 9110 2981 2842 9111 2977 2838 9112 2979 2840 9113 2743 2610 9114 2981 2842 9115 2746 2613 9116 2982 2843 9117 2983 2843 9118 2984 2843 9119 2985 2844 9120 2983 2844 9121 2982 2844 9122 2986 2845 9123 2983 2845 9124 2985 2845 9125 2987 2846 9126 2982 2846 9127 2984 2846 9128 2988 2847 9129 2987 2847 9130 2984 2847 9131 2986 2848 9132 2985 2848 9133 2989 2848 9134 2986 2849 9135 2989 2849 9136 2990 2849 9137 2988 2850 9138 2991 2850 9139 2987 2850 9140 2992 2851 9141 2993 2851 9142 2994 2851 9143 2995 2852 9144 2996 2852 9145 2993 2852 9146 2992 2853 9147 2995 2853 9148 2993 2853 9149 2997 2854 9150 2994 2854 9151 2998 2854 9152 2997 2855 9153 2992 2855 9154 2994 2855 9155 2999 2856 9156 2998 2856 9157 2991 2856 9158 2997 2857 9159 2998 2857 9160 2999 2857 9161 2999 2858 9162 2991 2858 9163 2988 2858 9164 3000 2859 9165 2996 2859 9166 2995 2859 9167 3001 2860 9168 2996 2860 9169 3000 2860 9170 2777 2640 9171 3002 2861 9172 2778 2641 9173 3001 2862 9174 3000 2862 9175 3003 2862 9176 3004 2863 9177 3005 2864 9178 3002 2861 9179 3006 2865 9180 3004 2863 9181 3002 2861 9182 3007 2866 9183 3006 2865 9184 3002 2861 9185 2777 2640 9186 3007 2866 9187 3002 2861 9188 3008 2867 9189 3003 2867 9190 3009 2867 9191 3010 2868 9192 3011 2869 9193 3005 2864 9194 3001 2870 9195 3003 2870 9196 3008 2870 9197 3004 2863 9198 3010 2868 9199 3005 2864 9200 3012 2871 9201 3009 2871 9202 3013 2871 9203 3010 2868 9204 3014 2872 9205 3011 2869 9206 3015 2873 9207 3009 2873 9208 3012 2873 9209 3008 2874 9210 3009 2874 9211 3015 2874 9212 3016 2875 9213 3013 2875 9214 3017 2875 9215 3018 2876 9216 3019 2877 9217 3014 2872 9218 3012 2878 9219 3013 2878 9220 3016 2878 9221 3010 2868 9222 3018 2876 9223 3014 2872 9224 3020 2879 9225 3017 2879 9226 3021 2879 9227 3022 2880 9228 3023 2881 9229 3019 2877 9230 3016 2882 9231 3017 2882 9232 3020 2882 9233 3018 2876 9234 3022 2880 9235 3019 2877 9236 3024 2883 9237 3021 2883 9238 3025 2883 9239 3026 2884 9240 3027 2885 9241 3023 2881 9242 3020 2886 9243 3021 2886 9244 3024 2886 9245 3022 2880 9246 3026 2884 9247 3023 2881 9248 3028 2887 9249 3025 2887 9250 3029 2887 9251 3030 2888 9252 3031 2889 9253 3027 2885 9254 3024 2890 9255 3025 2890 9256 3028 2890 9257 3026 2884 9258 3030 2888 9259 3027 2885 9260 3032 2891 9261 3029 2891 9262 3033 2891 9263 3034 2892 9264 3035 2893 9265 3031 2889 9266 3028 2894 9267 3029 2894 9268 3032 2894 9269 3030 2888 9270 3034 2892 9271 3031 2889 9272 3036 2895 9273 3033 2895 9274 3037 2895 9275 3038 2896 9276 3039 2897 9277 3035 2893 9278 3032 2898 9279 3033 2898 9280 3036 2898 9281 3034 2892 9282 3038 2896 9283 3035 2893 9284 3040 2899 9285 3037 2899 9286 3041 2899 9287 3042 2900 9288 3043 2901 9289 3039 2897 9290 3036 2902 9291 3037 2902 9292 3040 2902 9293 3038 2896 9294 3042 2900 9295 3039 2897 9296 3044 2903 9297 3041 2903 9298 3045 2903 9299 3046 2904 9300 3047 2905 9301 3043 2901 9302 3040 2906 9303 3041 2906 9304 3044 2906 9305 3042 2900 9306 3046 2904 9307 3043 2901 9308 3048 2907 9309 3045 2907 9310 3049 2907 9311 3050 2908 9312 3051 2909 9313 3047 2905 9314 3044 2910 9315 3045 2910 9316 3048 2910 9317 3046 2904 9318 3050 2908 9319 3047 2905 9320 3052 2911 9321 3049 2911 9322 3053 2911 9323 3054 2912 9324 3055 2913 9325 3051 2909 9326 3048 2914 9327 3049 2914 9328 3052 2914 9329 3050 2908 9330 3054 2912 9331 3051 2909 9332 3052 2915 9333 3053 2915 9334 3056 2915 9335 3057 2916 9336 3058 2917 9337 3055 2913 9338 3054 2912 9339 3057 2916 9340 3055 2913 9341 3059 2918 9342 3056 2918 9343 3060 2918 9344 3061 2919 9345 3062 2920 9346 3058 2917 9347 3052 2921 9348 3056 2921 9349 3059 2921 9350 3057 2916 9351 3061 2919 9352 3058 2917 9353 3063 2922 9354 3060 2922 9355 3064 2922 9356 3065 2923 9357 3066 2924 9358 3062 2920 9359 3059 2925 9360 3060 2925 9361 3063 2925 9362 3061 2919 9363 3065 2923 9364 3062 2920 9365 3067 2926 9366 3064 2926 9367 3068 2926 9368 3069 2927 9369 3070 2928 9370 3066 2924 9371 3063 2929 9372 3064 2929 9373 3067 2929 9374 3065 2923 9375 3069 2927 9376 3066 2924 9377 3071 2930 9378 3068 2930 9379 3072 2930 9380 3073 2931 9381 3074 2932 9382 3070 2928 9383 3067 2933 9384 3068 2933 9385 3071 2933 9386 3069 2927 9387 3073 2931 9388 3070 2928 9389 3075 2934 9390 3072 2934 9391 3076 2934 9392 3077 2935 9393 3078 2936 9394 3074 2932 9395 3071 2937 9396 3072 2937 9397 3075 2937 9398 3073 2931 9399 3077 2935 9400 3074 2932 9401 3079 2938 9402 3080 2939 9403 3078 2936 9404 3081 2940 9405 3079 2938 9406 3078 2936 9407 3077 2935 9408 3081 2940 9409 3078 2936 9410 3082 2941 9411 3083 2942 9412 3080 2939 9413 3079 2938 9414 3082 2941 9415 3080 2939 9416 3084 2943 9417 3085 2944 9418 3083 2942 9419 3082 2941 9420 3084 2943 9421 3083 2942 9422 3086 2945 9423 3087 2946 9424 3085 2944 9425 3084 2943 9426 3086 2945 9427 3085 2944 9428 3088 2947 9429 3089 2948 9430 3087 2946 9431 3086 2945 9432 3088 2947 9433 3087 2946 9434 3090 2949 9435 3091 2950 9436 3089 2948 9437 3088 2947 9438 3090 2949 9439 3089 2948 9440 3092 2951 9441 3093 2952 9442 3091 2950 9443 3090 2949 9444 3092 2951 9445 3091 2950 9446 3094 2953 9447 3095 2954 9448 3093 2952 9449 3092 2951 9450 3094 2953 9451 3093 2952 9452 3096 2955 9453 3097 2956 9454 3095 2954 9455 3094 2953 9456 3096 2955 9457 3095 2954 9458 3098 2957 9459 3099 2958 9460 3097 2956 9461 3096 2955 9462 3098 2957 9463 3097 2956 9464 3100 2959 9465 3101 2960 9466 3099 2958 9467 3098 2957 9468 3100 2959 9469 3099 2958 9470 3102 2961 9471 3103 2962 9472 3101 2960 9473 3100 2959 9474 3102 2961 9475 3101 2960 9476 3104 2963 9477 3105 2964 9478 3103 2962 9479 3102 2961 9480 3104 2963 9481 3103 2962 9482 3106 2965 9483 3107 2966 9484 3105 2964 9485 3104 2963 9486 3106 2965 9487 3105 2964 9488 3108 2967 9489 3109 2968 9490 3107 2966 9491 3106 2965 9492 3108 2967 9493 3107 2966 9494 3110 2969 9495 3111 2970 9496 3109 2968 9497 3108 2967 9498 3110 2969 9499 3109 2968 9500 3112 2971 9501 3113 2972 9502 3111 2970 9503 3110 2969 9504 3112 2971 9505 3111 2970 9506 3114 2973 9507 3115 2974 9508 3113 2972 9509 3116 2975 9510 3114 2973 9511 3113 2972 9512 3112 2971 9513 3116 2975 9514 3113 2972 9515 3117 2976 9516 2972 2833 9517 3115 2974 9518 3118 2977 9519 3117 2976 9520 3115 2974 9521 3114 2973 9522 3118 2977 9523 3115 2974 9524 3117 2976 9525 2975 2836 9526 2972 2833 9527 3119 2978 9528 3120 2979 9529 3121 2980 9530 3122 2981 9531 3121 2980 9532 3123 2982 9533 3122 2981 9534 3119 2978 9535 3121 2980 9536 3122 2981 9537 3123 2982 9538 3124 2983 9539 3125 2984 9540 3124 2983 9541 3126 2985 9542 3125 2984 9543 3122 2981 9544 3124 2983 9545 3125 2984 9546 3126 2985 9547 3127 2986 9548 3128 2987 9549 3127 2986 9550 3129 2988 9551 3128 2987 9552 3125 2984 9553 3127 2986 9554 3130 2989 9555 3129 2988 9556 3131 2990 9557 3132 2991 9558 3128 2987 9559 3129 2988 9560 3133 2992 9561 3132 2991 9562 3129 2988 9563 3130 2989 9564 3133 2992 9565 3129 2988 9566 3134 2993 9567 3131 2990 9568 3135 2994 9569 3134 2993 9570 3130 2989 9571 3131 2990 9572 3136 2995 9573 3135 2994 9574 3137 2996 9575 3138 2997 9576 3134 2993 9577 3135 2994 9578 3139 2998 9579 3138 2997 9580 3135 2994 9581 3136 2995 9582 3139 2998 9583 3135 2994 9584 3140 2999 9585 3137 2996 9586 3141 3000 9587 3140 2999 9588 3136 2995 9589 3137 2996 9590 3142 3001 9591 3141 3000 9592 3143 3002 9593 3144 3003 9594 3140 2999 9595 3141 3000 9596 3142 3001 9597 3144 3003 9598 3141 3000 9599 3145 3004 9600 3143 3002 9601 3146 3005 9602 3145 3004 9603 3142 3001 9604 3143 3002 9605 3145 3004 9606 3146 3005 9607 3147 3006 9608 3148 3007 9609 3147 3006 9610 3149 3008 9611 3148 3007 9612 3145 3004 9613 3147 3006 9614 3150 3009 9615 3149 3008 9616 3151 3010 9617 3150 3009 9618 3148 3007 9619 3149 3008 9620 3150 3009 9621 3151 3010 9622 3152 3011 9623 3153 3012 9624 3152 3011 9625 3154 3013 9626 3153 3012 9627 3150 3009 9628 3152 3011 9629 3153 3012 9630 3154 3013 9631 3155 3014 9632 3156 3015 9633 3155 3014 9634 3157 3016 9635 3156 3015 9636 3153 3012 9637 3155 3014 9638 3158 3017 9639 3157 3016 9640 3159 3018 9641 3158 3017 9642 3156 3015 9643 3157 3016 9644 3158 3017 9645 3159 3018 9646 3160 3019 9647 3161 3020 9648 3160 3019 9649 3162 3021 9650 3161 3020 9651 3158 3017 9652 3160 3019 9653 3163 3022 9654 3162 3021 9655 3164 3023 9656 3163 3022 9657 3161 3020 9658 3162 3021 9659 3165 3024 9660 3164 3023 9661 3166 3025 9662 3165 3024 9663 3163 3022 9664 3164 3023 9665 3165 3024 9666 3166 3025 9667 3167 3026 9668 3168 3027 9669 3167 3026 9670 3169 3028 9671 3168 3027 9672 3165 3024 9673 3167 3026 9674 3170 3029 9675 3169 3028 9676 3171 3030 9677 3170 3029 9678 3168 3027 9679 3169 3028 9680 3172 3031 9681 3171 3030 9682 3173 3032 9683 3172 3031 9684 3170 3029 9685 3171 3030 9686 3174 3033 9687 3173 3032 9688 3175 3034 9689 3176 3035 9690 3172 3031 9691 3173 3032 9692 3177 3036 9693 3176 3035 9694 3173 3032 9695 3174 3033 9696 3177 3036 9697 3173 3032 9698 3178 3037 9699 3175 3034 9700 3179 3038 9701 3178 3037 9702 3174 3033 9703 3175 3034 9704 3180 3039 9705 3179 3038 9706 3181 3040 9707 3180 3039 9708 3178 3037 9709 3179 3038 9710 3182 3041 9711 3181 3040 9712 3183 3042 9713 3182 3041 9714 3180 3039 9715 3181 3040 9716 3184 3043 9717 3183 3042 9718 3185 3044 9719 3184 3043 9720 3182 3041 9721 3183 3042 9722 3186 3045 9723 3185 3044 9724 3187 3046 9725 3186 3045 9726 3184 3043 9727 3185 3044 9728 3188 3047 9729 3187 3046 9730 3189 3048 9731 3188 3047 9732 3186 3045 9733 3187 3046 9734 3190 3049 9735 3189 3048 9736 3191 3050 9737 3190 3049 9738 3188 3047 9739 3189 3048 9740 3192 3051 9741 3191 3050 9742 3193 3052 9743 3192 3051 9744 3190 3049 9745 3191 3050 9746 3194 3053 9747 3193 3052 9748 3195 3054 9749 3194 3053 9750 3192 3051 9751 3193 3052 9752 3196 3055 9753 3195 3054 9754 3197 3056 9755 3196 3055 9756 3194 3053 9757 3195 3054 9758 3196 3055 9759 3197 3056 9760 3198 3057 9761 3196 3055 9762 3198 3057 9763 3199 3058 9764 3196 3055 9765 3199 3058 9766 3200 3059 9767 2784 2647 9768 3201 3060 9769 2781 2644 9770 3196 3055 9771 3200 3059 9772 3202 3061 9773 2785 2648 9774 3203 3062 9775 2786 2649 9776 3204 3063 9777 3205 3064 9778 3206 3065 9779 3207 3066 9780 3204 3063 9781 3206 3065 9782 2785 2648 9783 3208 3067 9784 3203 3062 9785 3209 3068 9786 3210 3069 9787 3211 3070 9788 2631 2500 9789 2643 2512 9790 3212 3071 9791 3213 3072 9792 3211 3070 9793 3214 3073 9794 3213 3072 9795 3209 3068 9796 3211 3070 9797 3215 3074 9798 3214 3073 9799 3216 3075 9800 3215 3074 9801 3213 3072 9802 3214 3073 9803 3215 3074 9804 3216 3075 9805 3217 3076 9806 3215 3074 9807 3217 3076 9808 3218 3077 9809 3219 3078 9810 3218 3077 9811 3220 3079 9812 3219 3078 9813 3215 3074 9814 3218 3077 9815 3219 3078 9816 3220 3079 9817 3221 3080 9818 3219 3078 9819 3221 3080 9820 3222 3081 9821 3219 3078 9822 3222 3081 9823 3223 3082 9824 3224 3083 9825 3223 3082 9826 3225 3084 9827 3224 3083 9828 3219 3078 9829 3223 3082 9830 3224 3083 9831 3225 3084 9832 3226 3085 9833 3224 3083 9834 3226 3085 9835 3227 3086 9836 3228 3087 9837 3227 3086 9838 3229 3088 9839 3228 3087 9840 3224 3083 9841 3227 3086 9842 3230 3089 9843 3229 3088 9844 3231 3090 9845 3230 3089 9846 3228 3087 9847 3229 3088 9848 3232 3091 9849 3231 3090 9850 3233 3092 9851 3232 3091 9852 3230 3089 9853 3231 3090 9854 3234 3093 9855 3233 3092 9856 3235 3094 9857 3234 3093 9858 3232 3091 9859 3233 3092 9860 3236 3095 9861 3235 3094 9862 3237 3096 9863 3236 3095 9864 3234 3093 9865 3235 3094 9866 3238 3097 9867 3237 3096 9868 3239 3098 9869 3238 3097 9870 3236 3095 9871 3237 3096 9872 3240 3099 9873 3239 3098 9874 3241 3100 9875 3240 3099 9876 3238 3097 9877 3239 3098 9878 3240 3099 9879 3241 3100 9880 3242 3101 9881 3243 3102 9882 3242 3101 9883 3244 3103 9884 3243 3102 9885 3240 3099 9886 3242 3101 9887 3245 3104 9888 3244 3103 9889 3246 3105 9890 3245 3104 9891 3243 3102 9892 3244 3103 9893 3247 3106 9894 3246 3105 9895 3248 3107 9896 3247 3106 9897 3245 3104 9898 3246 3105 9899 3247 3106 9900 3248 3107 9901 3249 3108 9902 3247 3106 9903 3249 3108 9904 3250 3109 9905 3251 3110 9906 3250 3109 9907 3252 3111 9908 3251 3110 9909 3247 3106 9910 3250 3109 9911 3251 3110 9912 3252 3111 9913 3253 3112 9914 3254 3113 9915 3253 3112 9916 3255 3114 9917 3254 3113 9918 3251 3110 9919 3253 3112 9920 3254 3113 9921 3255 3114 9922 3256 3115 9923 3257 3116 9924 3256 3115 9925 3258 3117 9926 3257 3116 9927 3254 3113 9928 3256 3115 9929 3257 3116 9930 3258 3117 9931 3259 3118 9932 3260 3119 9933 3259 3118 9934 3261 3120 9935 3260 3119 9936 3257 3116 9937 3259 3118 9938 3260 3119 9939 3261 3120 9940 3262 3121 9941 3263 3122 9942 3262 3121 9943 3264 3123 9944 3263 3122 9945 3260 3119 9946 3262 3121 9947 3263 3122 9948 3264 3123 9949 3265 3124 9950 3266 3125 9951 3265 3124 9952 3267 3126 9953 3266 3125 9954 3263 3122 9955 3265 3124 9956 3266 3125 9957 3267 3126 9958 3205 3064 9959 3204 3063 9960 3266 3125 9961 3205 3064 9962 3268 3127 9963 929 843 9964 3269 3128 9965 923 837 9966 929 843 9967 3268 3127 9968 3213 3072 9969 3269 3128 9970 3209 3068 9971 3268 3127 9972 3269 3128 9973 3213 3072 9974 3268 3127 9975 3213 3072 9976 3215 3074 9977 3270 3129 9978 3215 3074 9979 3219 3078 9980 3270 3129 9981 3268 3127 9982 3215 3074 9983 3271 3130 9984 3219 3078 9985 3224 3083 9986 3271 3130 9987 3270 3129 9988 3219 3078 9989 3272 3131 9990 3224 3083 9991 3228 3087 9992 3272 3131 9993 3271 3130 9994 3224 3083 9995 3273 3132 9996 3228 3087 9997 3230 3089 9998 3273 3132 9999 3272 3131 10000 3228 3087 10001 3274 3133 10002 3230 3089 10003 3232 3091 10004 3274 3133 10005 3273 3132 10006 3230 3089 10007 3275 3134 10008 3232 3091 10009 3234 3093 10010 3275 3134 10011 3274 3133 10012 3232 3091 10013 3276 3135 10014 3234 3093 10015 3236 3095 10016 3276 3135 10017 3275 3134 10018 3234 3093 10019 3277 3136 10020 3236 3095 10021 3238 3097 10022 3277 3136 10023 3276 3135 10024 3236 3095 10025 3278 3137 10026 3238 3097 10027 3240 3099 10028 3278 3137 10029 3277 3136 10030 3238 3097 10031 3279 3138 10032 3240 3099 10033 3243 3102 10034 3279 3138 10035 3278 3137 10036 3240 3099 10037 3280 3139 10038 3243 3102 10039 3245 3104 10040 3280 3139 10041 3279 3138 10042 3243 3102 10043 3281 3140 10044 3245 3104 10045 3247 3106 10046 3281 3140 10047 3280 3139 10048 3245 3104 10049 3282 3141 10050 3247 3106 10051 3251 3110 10052 3282 3141 10053 3281 3140 10054 3247 3106 10055 3283 3142 10056 3251 3110 10057 3254 3113 10058 3283 3142 10059 3282 3141 10060 3251 3110 10061 3284 3143 10062 3254 3113 10063 3257 3116 10064 3284 3143 10065 3283 3142 10066 3254 3113 10067 3285 3144 10068 3257 3116 10069 3260 3119 10070 3285 3144 10071 3284 3143 10072 3257 3116 10073 3286 3145 10074 3260 3119 10075 3263 3122 10076 3286 3145 10077 3285 3144 10078 3260 3119 10079 3287 3146 10080 3263 3122 10081 3266 3125 10082 3287 3146 10083 3286 3145 10084 3263 3122 10085 3288 3147 10086 3266 3125 10087 3204 3063 10088 3288 3147 10089 3287 3146 10090 3266 3125 10091 3289 3148 10092 3204 3063 10093 3207 3066 10094 3289 3148 10095 3288 3147 10096 3204 3063 10097 3290 3149 10098 3289 3148 10099 3207 3066 10100 3291 3150 10101 3292 3151 10102 3208 3067 10103 2785 2648 10104 3291 3150 10105 3208 3067 10106 923 837 10107 3268 3127 10108 3270 3129 10109 921 835 10110 3270 3129 10111 3271 3130 10112 921 835 10113 923 837 10114 3270 3129 10115 919 833 10116 3271 3130 10117 3272 3131 10118 919 833 10119 921 835 10120 3271 3130 10121 916 830 10122 3272 3131 10123 3273 3132 10124 916 830 10125 919 833 10126 3272 3131 10127 913 827 10128 3273 3132 10129 3274 3133 10130 913 827 10131 916 830 10132 3273 3132 10133 910 824 10134 3274 3133 10135 3275 3134 10136 910 824 10137 913 827 10138 3274 3133 10139 907 821 10140 3275 3134 10141 3276 3135 10142 907 821 10143 910 824 10144 3275 3134 10145 904 818 10146 3276 3135 10147 3277 3136 10148 904 818 10149 907 821 10150 3276 3135 10151 901 815 10152 3277 3136 10153 3278 3137 10154 901 815 10155 904 818 10156 3277 3136 10157 899 813 10158 3278 3137 10159 3279 3138 10160 899 813 10161 901 815 10162 3278 3137 10163 896 810 10164 3279 3138 10165 3280 3139 10166 896 810 10167 899 813 10168 3279 3138 10169 893 807 10170 3280 3139 10171 3281 3140 10172 893 807 10173 896 810 10174 3280 3139 10175 891 805 10176 3281 3140 10177 3282 3141 10178 891 805 10179 893 807 10180 3281 3140 10181 889 803 10182 3282 3141 10183 3283 3142 10184 889 803 10185 891 805 10186 3282 3141 10187 887 801 10188 3283 3142 10189 3284 3143 10190 887 801 10191 889 803 10192 3283 3142 10193 885 799 10194 3284 3143 10195 3285 3144 10196 885 799 10197 887 801 10198 3284 3143 10199 883 797 10200 3285 3144 10201 3286 3145 10202 883 797 10203 885 799 10204 3285 3144 10205 881 795 10206 3286 3145 10207 3287 3146 10208 881 795 10209 883 797 10210 3286 3145 10211 879 793 10212 3287 3146 10213 3288 3147 10214 879 793 10215 881 795 10216 3287 3146 10217 876 790 10218 3288 3147 10219 3289 3148 10220 876 790 10221 879 793 10222 3288 3147 10223 878 792 10224 3289 3148 10225 3290 3149 10226 878 792 10227 876 790 10228 3289 3148 10229 870 784 10230 878 792 10231 3290 3149 10232 3293 3152 10233 875 789 10234 3292 3151 10235 3291 3150 10236 3293 3152 10237 3292 3151 10238 3294 3153 10239 873 787 10240 875 789 10241 3293 3152 10242 3294 3153 10243 875 789 10244 3295 3154 10245 859 3154 10246 3296 3154 10247 3295 3155 10248 862 3155 10249 859 3155 10250 3297 3156 10251 3298 3157 10252 3299 3158 10253 3300 3159 10254 3296 3159 10255 1356 3159 10256 3297 3156 10257 3301 3160 10258 3298 3157 10259 3302 3161 10260 3295 3161 10261 3296 3161 10262 3303 3162 10263 3302 3162 10264 3296 3162 10265 3304 3163 10266 3303 3163 10267 3296 3163 10268 3305 3164 10269 3304 3164 10270 3296 3164 10271 3306 3165 10272 3305 3165 10273 3296 3165 10274 3307 3166 10275 3306 3166 10276 3296 3166 10277 3308 3167 10278 3307 3167 10279 3296 3167 10280 3309 3168 10281 3308 3168 10282 3296 3168 10283 3310 3169 10284 3309 3169 10285 3296 3169 10286 3311 3170 10287 3310 3170 10288 3296 3170 10289 3312 3171 10290 3311 3171 10291 3296 3171 10292 3313 3172 10293 3312 3172 10294 3296 3172 10295 3314 3173 10296 3313 3173 10297 3296 3173 10298 3315 3174 10299 3314 3174 10300 3296 3174 10301 3316 3175 10302 3315 3175 10303 3296 3175 10304 3317 3176 10305 3316 3176 10306 3296 3176 10307 3318 3177 10308 3317 3177 10309 3296 3177 10310 3319 3178 10311 3318 3178 10312 3296 3178 10313 3320 3179 10314 3319 3179 10315 3296 3179 10316 3321 3180 10317 3320 3180 10318 3296 3180 10319 3300 3181 10320 3321 3181 10321 3296 3181 10322 3322 3182 10323 3299 3158 10324 3323 3183 10325 3297 3156 10326 3299 3158 10327 3322 3182 10328 2691 2558 10329 3323 3183 10330 2700 2567 10331 3322 3182 10332 3323 3183 10333 2691 2558 10334 3324 3184 10335 1887 1769 10336 3325 3185 10337 3324 3184 10338 1885 1767 10339 1887 1769 10340 3324 3184 10341 3325 3185 10342 3326 3186 10343 3327 3187 10344 3326 3186 10345 3328 3188 10346 3324 3184 10347 3326 3186 10348 3327 3187 10349 3329 3189 10350 3330 3190 10351 3331 3191 10352 3332 3192 10353 3331 3191 10354 3333 3193 10355 3332 3192 10356 3329 3189 10357 3331 3191 10358 3332 3192 10359 3333 3193 10360 3334 3194 10361 3335 3195 10362 3334 3194 10363 3336 3196 10364 3335 3195 10365 3332 3192 10366 3334 3194 10367 3335 3195 10368 3336 3196 10369 3337 3197 10370 3338 3198 10371 3337 3197 10372 3339 3199 10373 3338 3198 10374 3335 3195 10375 3337 3197 10376 3340 3200 10377 3339 3199 10378 3341 3201 10379 3340 3200 10380 3338 3198 10381 3339 3199 10382 3340 3200 10383 3341 3201 10384 3342 3202 10385 3343 3203 10386 3342 3202 10387 3344 3204 10388 3343 3203 10389 3340 3200 10390 3342 3202 10391 3343 3203 10392 3344 3204 10393 3345 3205 10394 3346 3206 10395 3347 3207 10396 3348 3208 10397 3349 3209 10398 3343 3203 10399 3345 3205 10400 3350 3210 10401 3348 3208 10402 3351 3211 10403 3350 3210 10404 3346 3206 10405 3348 3208 10406 3352 3212 10407 3351 3211 10408 3353 3213 10409 3350 3210 10410 3351 3211 10411 3352 3212 10412 3354 3214 10413 3353 3213 10414 3355 3215 10415 3352 3212 10416 3353 3213 10417 3354 3214 10418 3297 3156 10419 3355 3215 10420 3301 3160 10421 3354 3214 10422 3355 3215 10423 3297 3156 10424 3356 3216 10425 3300 3216 10426 1356 3216 10427 3357 3217 10428 3356 3217 10429 1356 3217 10430 3358 3218 10431 3357 3218 10432 1356 3218 10433 3359 3219 10434 3358 3219 10435 1356 3219 10436 3360 3220 10437 3359 3220 10438 1356 3220 10439 3361 3221 10440 3360 3221 10441 1356 3221 10442 3362 3222 10443 3361 3222 10444 1356 3222 10445 3363 3223 10446 3362 3223 10447 1356 3223 10448 3364 3224 10449 3363 3224 10450 1356 3224 10451 3365 3225 10452 3364 3225 10453 1356 3225 10454 3366 3226 10455 3365 3226 10456 1356 3226 10457 3367 3227 10458 3366 3227 10459 1356 3227 10460 3368 3228 10461 3367 3228 10462 1356 3228 10463 3369 3229 10464 3368 3229 10465 1356 3229 10466 1369 3230 10467 3369 3230 10468 1356 3230 10469 3370 3231 10470 867 781 10471 3371 3232 10472 808 3233 10473 848 3233 10474 809 3233 10475 3372 3234 10476 3371 3232 10477 3373 3235 10478 3372 3234 10479 3370 3231 10480 3371 3232 10481 3374 3236 10482 3373 3235 10483 3375 3237 10484 3374 3236 10485 3372 3234 10486 3373 3235 10487 3376 3238 10488 3375 3237 10489 3377 3239 10490 3376 3238 10491 3374 3236 10492 3375 3237 10493 3378 3240 10494 3377 3239 10495 3379 3241 10496 3378 3240 10497 3376 3238 10498 3377 3239 10499 3380 3242 10500 3379 3241 10501 3381 3243 10502 3380 3242 10503 3378 3240 10504 3379 3241 10505 3382 3244 10506 3381 3243 10507 3383 3245 10508 3382 3244 10509 3380 3242 10510 3381 3243 10511 3382 3244 10512 3383 3245 10513 3384 3246 10514 3385 3247 10515 3384 3246 10516 3386 3248 10517 3385 3247 10518 3382 3244 10519 3384 3246 10520 3387 3249 10521 3386 3248 10522 3388 3250 10523 3387 3249 10524 3385 3247 10525 3386 3248 10526 3389 3251 10527 3388 3250 10528 3390 3252 10529 3389 3251 10530 3387 3249 10531 3388 3250 10532 3391 3253 10533 3390 3252 10534 3392 3254 10535 3391 3253 10536 3389 3251 10537 3390 3252 10538 3393 3255 10539 3392 3254 10540 3394 3256 10541 3393 3255 10542 3391 3253 10543 3392 3254 10544 3395 3257 10545 3394 3256 10546 3396 3258 10547 3395 3257 10548 3393 3255 10549 3394 3256 10550 3397 3259 10551 3396 3258 10552 3398 3260 10553 3397 3259 10554 3395 3257 10555 3396 3258 10556 3399 3261 10557 3398 3260 10558 3400 3262 10559 3399 3261 10560 3397 3259 10561 3398 3260 10562 3401 3263 10563 3400 3262 10564 3402 3264 10565 3401 3263 10566 3399 3261 10567 3400 3262 10568 3403 3265 10569 3402 3264 10570 3404 3266 10571 3403 3265 10572 3401 3263 10573 3402 3264 10574 3405 3267 10575 3404 3266 10576 3406 3268 10577 3405 3267 10578 3403 3265 10579 3404 3266 10580 3407 3269 10581 3406 3268 10582 3408 3270 10583 3407 3269 10584 3405 3267 10585 3406 3268 10586 3409 3271 10587 3408 3270 10588 3410 3272 10589 3409 3271 10590 3407 3269 10591 3408 3270 10592 3411 3273 10593 3410 3272 10594 3412 3274 10595 3411 3273 10596 3409 3271 10597 3410 3272 10598 3413 3275 10599 3412 3274 10600 3414 3276 10601 3413 3275 10602 3411 3273 10603 3412 3274 10604 3415 3277 10605 3414 3276 10606 3416 3278 10607 3415 3277 10608 3413 3275 10609 3414 3276 10610 3417 3279 10611 3416 3278 10612 3418 3280 10613 3417 3279 10614 3415 3277 10615 3416 3278 10616 3419 3281 10617 3418 3280 10618 3420 3282 10619 3419 3281 10620 3417 3279 10621 3418 3280 10622 3421 3283 10623 3420 3282 10624 3422 3284 10625 3421 3283 10626 3419 3281 10627 3420 3282 10628 3423 3285 10629 3422 3284 10630 3424 3286 10631 3423 3285 10632 3421 3283 10633 3422 3284 10634 3425 3287 10635 3424 3286 10636 3426 3288 10637 3425 3287 10638 3423 3285 10639 3424 3286 10640 3427 3289 10641 3426 3288 10642 3428 3290 10643 3427 3289 10644 3425 3287 10645 3426 3288 10646 3429 3291 10647 3428 3290 10648 3430 3292 10649 3429 3291 10650 3427 3289 10651 3428 3290 10652 3431 3293 10653 3430 3292 10654 3432 3294 10655 3431 3293 10656 3429 3291 10657 3430 3292 10658 3433 3295 10659 3432 3294 10660 3434 3296 10661 3433 3295 10662 3431 3293 10663 3432 3294 10664 3435 3297 10665 3434 3296 10666 3436 3298 10667 3435 3297 10668 3433 3295 10669 3434 3296 10670 3437 3299 10671 3436 3298 10672 3438 3300 10673 3437 3299 10674 3435 3297 10675 3436 3298 10676 3437 3299 10677 3438 3300 10678 3439 3301 10679 3440 3302 10680 3437 3299 10681 3439 3301 10682 3441 3303 10683 3442 3304 10684 3443 3305 10685 3444 3306 10686 3445 3307 10687 3446 3308 10688 3447 3309 10689 3448 3310 10690 3449 3311 10691 3444 3306 10692 3450 3312 10693 3445 3307 10694 3441 3303 10695 3451 3313 10696 3442 3304 10697 3452 3314 10698 3446 3308 10699 3453 3315 10700 3452 3314 10701 3454 3316 10702 3446 3308 10703 3455 3317 10704 3446 3308 10705 3454 3316 10706 3455 3317 10707 3444 3306 10708 3446 3308 10709 3441 3303 10710 3456 3318 10711 3451 3313 10712 3457 3319 10713 3451 3313 10714 3456 3318 10715 3458 3320 10716 3453 3315 10717 3459 3321 10718 3458 3320 10719 3452 3314 10720 3453 3315 10721 3441 3303 10722 3460 3322 10723 3456 3318 10724 3461 3323 10725 3456 3318 10726 3460 3322 10727 3462 3324 10728 3456 3318 10729 3461 3323 10730 3463 3325 10731 3456 3318 10732 3462 3324 10733 3457 3319 10734 3456 3318 10735 3463 3325 10736 3464 3326 10737 3465 3327 10738 3460 3322 10739 3466 3328 10740 3460 3322 10741 3465 3327 10742 3441 3303 10743 3464 3326 10744 3460 3322 10745 3461 3323 10746 3460 3322 10747 3466 3328 10748 1888 1770 10749 1885 1767 10750 3465 3327 10751 3467 3329 10752 3465 3327 10753 1885 1767 10754 3464 3326 10755 1888 1770 10756 3465 3327 10757 3466 3328 10758 3465 3327 10759 3467 3329 10760 3467 3329 10761 1885 1767 10762 3324 3184 10763 3468 3330 10764 1889 1771 10765 3469 3331 10766 1882 1764 10767 1889 1771 10768 3468 3330 10769 3470 3332 10770 3469 3331 10771 3448 3310 10772 3468 3330 10773 3469 3331 10774 3470 3332 10775 3470 3332 10776 3448 3310 10777 3447 3309 10778 3461 3323 10779 3471 3333 10780 3472 3334 10781 3473 3335 10782 3474 3336 10783 3475 3337 10784 3462 3324 10785 3461 3323 10786 3472 3334 10787 3476 3338 10788 3477 3339 10789 3478 3340 10790 3479 3341 10791 3480 3342 10792 3481 3343 10793 3482 3344 10794 3479 3341 10795 3481 3343 10796 3473 3335 10797 3483 3345 10798 3474 3336 10799 3466 3328 10800 3484 3346 10801 3471 3333 10802 3485 3347 10803 3475 3337 10804 3486 3348 10805 3461 3323 10806 3466 3328 10807 3471 3333 10808 3473 3335 10809 3475 3337 10810 3485 3347 10811 3467 3329 10812 3327 3187 10813 3484 3346 10814 3332 3192 10815 3486 3348 10816 3329 3189 10817 3466 3328 10818 3467 3329 10819 3484 3346 10820 3485 3347 10821 3486 3348 10822 3332 3192 10823 3467 3329 10824 3324 3184 10825 3327 3187 10826 3476 3338 10827 3487 3349 10828 3477 3339 10829 3458 3320 10830 3459 3321 10831 3487 3349 10832 3476 3338 10833 3458 3320 10834 3487 3349 10835 2550 2419 10836 3488 3350 10837 2557 2426 10838 3489 3351 10839 3490 3352 10840 3488 3350 10841 2550 2419 10842 3489 3351 10843 3488 3350 10844 3489 3351 10845 3491 3353 10846 3490 3352 10847 3492 3354 10848 3493 3355 10849 3491 3353 10850 3489 3351 10851 3492 3354 10852 3491 3353 10853 3494 3356 10854 2567 2436 10855 3495 3357 10856 3492 3354 10857 3496 3358 10858 3493 3355 10859 3497 3359 10860 2567 2436 10861 3494 3356 10862 3498 3360 10863 2567 2436 10864 3497 3359 10865 3499 3361 10866 2568 2437 10867 2567 2436 10868 3500 3362 10869 3499 3361 10870 2567 2436 10871 3498 3360 10872 3500 3362 10873 2567 2436 10874 3492 3354 10875 3501 3363 10876 3496 3358 10877 3502 3364 10878 3503 3365 10879 3501 3363 10880 3497 3359 10881 3494 3356 10882 3504 3366 10883 3492 3354 10884 3502 3364 10885 3501 3363 10886 3502 3364 10887 3505 3367 10888 3503 3365 10889 3506 3368 10890 3504 3366 10891 3507 3369 10892 3506 3368 10893 3497 3359 10894 3504 3366 10895 3508 3370 10896 3509 3371 10897 3505 3367 10898 3506 3368 10899 3507 3369 10900 3510 3372 10901 3502 3364 10902 3508 3370 10903 3505 3367 10904 3508 3370 10905 3511 3373 10906 3509 3371 10907 3512 3374 10908 3510 3372 10909 3513 3375 10910 3512 3374 10911 3506 3368 10912 3510 3372 10913 3514 3376 10914 3515 3377 10915 3511 3373 10916 3516 3378 10917 3513 3375 10918 3517 3379 10919 3508 3370 10920 3514 3376 10921 3511 3373 10922 3516 3378 10923 3512 3374 10924 3513 3375 10925 3514 3376 10926 3518 3380 10927 3515 3377 10928 3516 3378 10929 3517 3379 10930 3519 3381 10931 3520 3382 10932 3521 3383 10933 3518 3380 10934 3522 3384 10935 3519 3381 10936 3523 3385 10937 3514 3376 10938 3520 3382 10939 3518 3380 10940 3522 3384 10941 3516 3378 10942 3519 3381 10943 3520 3382 10944 3524 3386 10945 3521 3383 10946 3522 3384 10947 3523 3385 10948 3525 3387 10949 3526 3388 10950 3527 3389 10951 3524 3386 10952 3528 3390 10953 3525 3387 10954 3529 3391 10955 3520 3382 10956 3526 3388 10957 3524 3386 10958 3528 3390 10959 3522 3384 10960 3525 3387 10961 3526 3388 10962 3530 3392 10963 3527 3389 10964 3528 3390 10965 3529 3391 10966 3531 3393 10967 3532 3394 10968 3533 3395 10969 3530 3392 10970 3534 3396 10971 3531 3393 10972 3535 3397 10973 3526 3388 10974 3532 3394 10975 3530 3392 10976 3534 3396 10977 3528 3390 10978 3531 3393 10979 3532 3394 10980 3536 3398 10981 3533 3395 10982 3534 3396 10983 3535 3397 10984 3537 3399 10985 3538 3400 10986 3539 3401 10987 3536 3398 10988 3540 3402 10989 3537 3399 10990 3541 3403 10991 3532 3394 10992 3538 3400 10993 3536 3398 10994 3540 3402 10995 3534 3396 10996 3537 3399 10997 3542 3404 10998 3543 3405 10999 3539 3401 11000 3544 3406 11001 3541 3403 11002 3545 3407 11003 3538 3400 11004 3542 3404 11005 3539 3401 11006 3544 3406 11007 3540 3402 11008 3541 3403 11009 3542 3404 11010 3546 3408 11011 3543 3405 11012 3544 3406 11013 3545 3407 11014 3547 3409 11015 3548 3410 11016 3549 3411 11017 3546 3408 11018 3550 3412 11019 3547 3409 11020 3551 3413 11021 3542 3404 11022 3548 3410 11023 3546 3408 11024 3550 3412 11025 3544 3406 11026 3547 3409 11027 3548 3410 11028 3552 3414 11029 3549 3411 11030 3550 3412 11031 3551 3413 11032 3553 3415 11033 3554 3416 11034 3555 3417 11035 3552 3414 11036 3556 3418 11037 3553 3415 11038 3557 3419 11039 3548 3410 11040 3554 3416 11041 3552 3414 11042 3556 3418 11043 3550 3412 11044 3553 3415 11045 3554 3416 11046 3558 3420 11047 3555 3417 11048 3556 3418 11049 3557 3419 11050 3559 3421 11051 3560 3422 11052 3561 3423 11053 3558 3420 11054 3562 3424 11055 3559 3421 11056 3563 3425 11057 3554 3416 11058 3560 3422 11059 3558 3420 11060 3562 3424 11061 3556 3418 11062 3559 3421 11063 3560 3422 11064 3564 3426 11065 3561 3423 11066 3565 3427 11067 3563 3425 11068 3566 3428 11069 3565 3427 11070 3562 3424 11071 3563 3425 11072 3567 3429 11073 3568 3430 11074 3564 3426 11075 3565 3427 11076 3566 3428 11077 3569 3431 11078 3560 3422 11079 3567 3429 11080 3564 3426 11081 3567 3429 11082 3570 3432 11083 3568 3430 11084 3571 3433 11085 3569 3431 11086 3572 3434 11087 3571 3433 11088 3565 3427 11089 3569 3431 11090 3573 3435 11091 3574 3436 11092 3570 3432 11093 3575 3437 11094 3572 3434 11095 3576 3438 11096 3567 3429 11097 3573 3435 11098 3570 3432 11099 3571 3433 11100 3572 3434 11101 3575 3437 11102 3573 3435 11103 3577 3439 11104 3574 3436 11105 3575 3437 11106 3576 3438 11107 3578 3440 11108 3579 3441 11109 3580 3442 11110 3577 3439 11111 3575 3437 11112 3578 3440 11113 3581 3443 11114 3573 3435 11115 3579 3441 11116 3577 3439 11117 3579 3441 11118 3582 3444 11119 3580 3442 11120 3444 3306 11121 3581 3443 11122 3583 3445 11123 3584 3446 11124 3581 3443 11125 3444 3306 11126 3585 3447 11127 3575 3437 11128 3581 3443 11129 3586 3448 11130 3585 3447 11131 3581 3443 11132 3584 3446 11133 3586 3448 11134 3581 3443 11135 3579 3441 11136 3587 3449 11137 3582 3444 11138 3444 3306 11139 3583 3445 11140 3588 3450 11141 3470 3332 11142 3589 3451 11143 3587 3449 11144 3444 3306 11145 3588 3450 11146 3590 3452 11147 3579 3441 11148 3470 3332 11149 3587 3449 11150 3470 3332 11151 3447 3309 11152 3589 3451 11153 3444 3306 11154 3590 3452 11155 3450 3312 11156 3468 3330 11157 3470 3332 11158 3579 3441 11159 3591 3453 11160 3579 3441 11161 3573 3435 11162 3591 3453 11163 3468 3330 11164 3579 3441 11165 3592 3454 11166 3573 3435 11167 3567 3429 11168 3592 3454 11169 3591 3453 11170 3573 3435 11171 3593 3455 11172 3567 3429 11173 3560 3422 11174 3593 3455 11175 3592 3454 11176 3567 3429 11177 3594 3456 11178 3560 3422 11179 3554 3416 11180 3594 3456 11181 3593 3455 11182 3560 3422 11183 3595 3457 11184 3554 3416 11185 3548 3410 11186 3595 3457 11187 3594 3456 11188 3554 3416 11189 3596 3458 11190 3548 3410 11191 3542 3404 11192 3596 3458 11193 3595 3457 11194 3548 3410 11195 3597 3459 11196 3542 3404 11197 3538 3400 11198 3597 3459 11199 3596 3458 11200 3542 3404 11201 3598 3460 11202 3538 3400 11203 3532 3394 11204 3598 3460 11205 3597 3459 11206 3538 3400 11207 3599 3461 11208 3532 3394 11209 3526 3388 11210 3599 3461 11211 3598 3460 11212 3532 3394 11213 3600 3462 11214 3526 3388 11215 3520 3382 11216 3600 3462 11217 3599 3461 11218 3526 3388 11219 3601 3463 11220 3520 3382 11221 3514 3376 11222 3601 3463 11223 3600 3462 11224 3520 3382 11225 3602 3464 11226 3514 3376 11227 3508 3370 11228 3602 3464 11229 3601 3463 11230 3514 3376 11231 3603 3465 11232 3508 3370 11233 3502 3364 11234 3603 3465 11235 3602 3464 11236 3508 3370 11237 3604 3466 11238 3502 3364 11239 3492 3354 11240 3604 3466 11241 3603 3465 11242 3502 3364 11243 3605 3467 11244 3492 3354 11245 3489 3351 11246 3605 3467 11247 3604 3466 11248 3492 3354 11249 3606 3468 11250 3489 3351 11251 2550 2419 11252 3606 3468 11253 3605 3467 11254 3489 3351 11255 2559 2428 11256 3606 3468 11257 2550 2419 11258 1882 1764 11259 3468 3330 11260 3591 3453 11261 1880 1762 11262 3591 3453 11263 3592 3454 11264 1880 1762 11265 1882 1764 11266 3591 3453 11267 1878 1760 11268 3592 3454 11269 3593 3455 11270 1878 1760 11271 1880 1762 11272 3592 3454 11273 1875 1757 11274 3593 3455 11275 3594 3456 11276 1875 1757 11277 1878 1760 11278 3593 3455 11279 1873 1755 11280 3594 3456 11281 3595 3457 11282 1873 1755 11283 1875 1757 11284 3594 3456 11285 1871 1753 11286 3595 3457 11287 3596 3458 11288 1871 1753 11289 1873 1755 11290 3595 3457 11291 1869 1751 11292 3596 3458 11293 3597 3459 11294 1869 1751 11295 1871 1753 11296 3596 3458 11297 1867 1749 11298 3597 3459 11299 3598 3460 11300 1867 1749 11301 1869 1751 11302 3597 3459 11303 1865 1747 11304 3598 3460 11305 3599 3461 11306 1865 1747 11307 1867 1749 11308 3598 3460 11309 1863 1745 11310 3599 3461 11311 3600 3462 11312 1863 1745 11313 1865 1747 11314 3599 3461 11315 1861 1743 11316 3600 3462 11317 3601 3463 11318 1861 1743 11319 1863 1745 11320 3600 3462 11321 1859 1741 11322 3601 3463 11323 3602 3464 11324 1859 1741 11325 1861 1743 11326 3601 3463 11327 1857 1739 11328 3602 3464 11329 3603 3465 11330 1857 1739 11331 1859 1741 11332 3602 3464 11333 1855 1737 11334 3603 3465 11335 3604 3466 11336 1855 1737 11337 1857 1739 11338 3603 3465 11339 1853 1735 11340 3604 3466 11341 3605 3467 11342 1853 1735 11343 1855 1737 11344 3604 3466 11345 1850 1732 11346 3605 3467 11347 3606 3468 11348 1850 1732 11349 1853 1735 11350 3605 3467 11351 1848 1730 11352 3606 3468 11353 2559 2428 11354 1848 1730 11355 1850 1732 11356 3606 3468 11357 1846 1728 11358 1848 1730 11359 2559 2428 11360 3607 3469 11361 3608 3470 11362 3609 3471 11363 3610 3472 11364 3611 3472 11365 3612 3472 11366 3610 3473 11367 3612 3473 11368 3613 3473 11369 3614 3474 11370 3609 3471 11371 3615 3475 11372 3614 3474 11373 3607 3469 11374 3609 3471 11375 3476 3338 11376 3616 3476 11377 3458 3320 11378 3614 3474 11379 3615 3475 11380 3617 3477 11381 3610 3478 11382 3618 3478 11383 3611 3478 11384 3610 3479 11385 3619 3479 11386 3618 3479 11387 3476 3338 11388 3620 3480 11389 3616 3476 11390 3621 3481 11391 3617 3477 11392 3622 3482 11393 3621 3481 11394 3614 3474 11395 3617 3477 11396 3476 3338 11397 3623 3483 11398 3620 3480 11399 3624 3484 11400 3622 3482 11401 3625 3485 11402 3624 3484 11403 3621 3481 11404 3622 3482 11405 3476 3338 11406 3626 3486 11407 3623 3483 11408 3627 3487 11409 3625 3485 11410 3628 3488 11411 3627 3487 11412 3624 3484 11413 3625 3485 11414 3629 3489 11415 3630 3490 11416 3626 3486 11417 3627 3487 11418 3628 3488 11419 3631 3491 11420 3476 3338 11421 3629 3489 11422 3626 3486 11423 3629 3489 11424 3632 3492 11425 3630 3490 11426 3633 3493 11427 3634 3493 11428 3635 3493 11429 3636 3494 11430 3627 3487 11431 3631 3491 11432 3629 3489 11433 3637 3495 11434 3632 3492 11435 3633 3496 11436 3635 3496 11437 3638 3496 11438 3639 3497 11439 3640 3498 11440 3641 3499 11441 3642 3500 11442 3633 3500 11443 3638 3500 11444 3643 3501 11445 3644 3502 11446 3640 3498 11447 3639 3497 11448 3643 3501 11449 3640 3498 11450 3639 3497 11451 3641 3499 11452 3480 3342 11453 3479 3341 11454 3639 3497 11455 3480 3342 11456 3645 3503 11457 3646 3504 11458 3647 3505 11459 3648 3506 11460 3649 3507 11461 3646 3504 11462 3645 3503 11463 3648 3506 11464 3646 3504 11465 3650 3508 11466 3647 3505 11467 3651 3509 11468 3650 3508 11469 3645 3503 11470 3647 3505 11471 3650 3508 11472 3651 3509 11473 3652 3510 11474 3650 3508 11475 3652 3510 11476 3653 3511 11477 3654 3512 11478 3655 3513 11479 3656 3514 11480 3654 3512 11481 3657 3515 11482 3655 3513 11483 3658 3516 11484 3656 3514 11485 3659 3517 11486 3658 3516 11487 3654 3512 11488 3656 3514 11489 3660 3518 11490 3659 3517 11491 3661 3519 11492 3660 3518 11493 3658 3516 11494 3659 3517 11495 3662 3520 11496 3661 3519 11497 3663 3521 11498 3662 3520 11499 3660 3518 11500 3661 3519 11501 3664 3522 11502 3663 3521 11503 3665 3523 11504 3664 3522 11505 3662 3520 11506 3663 3521 11507 3666 3524 11508 3665 3523 11509 3667 3525 11510 3666 3524 11511 3664 3522 11512 3665 3523 11513 3668 3526 11514 3667 3525 11515 3669 3527 11516 3668 3526 11517 3666 3524 11518 3667 3525 11519 3670 3528 11520 3669 3527 11521 3671 3529 11522 3670 3528 11523 3668 3526 11524 3669 3527 11525 3672 3530 11526 3671 3529 11527 3673 3531 11528 3672 3530 11529 3670 3528 11530 3671 3529 11531 3674 3532 11532 3673 3531 11533 3675 3533 11534 3674 3532 11535 3672 3530 11536 3673 3531 11537 3676 3534 11538 3675 3533 11539 3677 3535 11540 3676 3534 11541 3674 3532 11542 3675 3533 11543 3678 3536 11544 3677 3535 11545 3679 3537 11546 3678 3536 11547 3676 3534 11548 3677 3535 11549 3648 3506 11550 3679 3537 11551 3649 3507 11552 3680 3538 11553 3678 3536 11554 3679 3537 11555 3648 3506 11556 3680 3538 11557 3679 3537 11558 3681 3539 11559 3682 3539 11560 3683 3539 11561 3681 3540 11562 3684 3540 11563 3682 3540 11564 3685 3541 11565 3686 3542 11566 3687 3543 11567 3681 3544 11568 3683 3544 11569 3688 3544 11570 3689 3545 11571 3687 3543 11572 3657 3515 11573 3689 3545 11574 3685 3541 11575 3687 3543 11576 3654 3512 11577 3689 3545 11578 3657 3515 11579 3690 3546 11580 3691 3547 11581 3692 3548 11582 3693 3549 11583 3694 3550 11584 3691 3547 11585 3690 3546 11586 3693 3549 11587 3691 3547 11588 3690 3546 11589 3692 3548 11590 3695 3551 11591 3681 3552 11592 3696 3552 11593 3684 3552 11594 3690 3546 11595 3695 3551 11596 3697 3553 11597 3698 3554 11598 3699 3555 11599 2533 2402 11600 2529 2398 11601 2534 2403 11602 3700 3556 11603 3701 3557 11604 3698 3554 11605 2533 2402 11606 2532 2401 11607 3701 3557 11608 2533 2402 11609 3702 3558 11610 3703 3559 11611 3699 3555 11612 3704 3560 11613 3700 3556 11614 3705 3561 11615 3698 3554 11616 3702 3558 11617 3699 3555 11618 3704 3560 11619 2529 2398 11620 3700 3556 11621 3706 3562 11622 3707 3562 11623 3708 3562 11624 3709 3563 11625 3707 3563 11626 3706 3563 11627 3710 3564 11628 3705 3561 11629 3711 3565 11630 3710 3564 11631 3704 3560 11632 3705 3561 11633 3706 3566 11634 3708 3566 11635 3712 3566 11636 3713 3567 11637 3714 3568 11638 3715 3569 11639 3706 3570 11640 3712 3570 11641 3716 3570 11642 3717 3571 11643 3715 3569 11644 3718 3572 11645 3717 3571 11646 3713 3567 11647 3715 3569 11648 3719 3573 11649 3718 3572 11650 3720 3574 11651 3719 3573 11652 3717 3571 11653 3718 3572 11654 3693 3549 11655 3720 3574 11656 3694 3550 11657 3693 3549 11658 3719 3573 11659 3720 3574 11660 3721 3575 11661 3722 3575 11662 3723 3575 11663 3724 3576 11664 3725 3576 11665 3722 3576 11666 3721 3577 11667 3724 3577 11668 3722 3577 11669 3726 3578 11670 3723 3578 11671 3727 3578 11672 3726 3579 11673 3721 3579 11674 3723 3579 11675 3728 3580 11676 3727 3580 11677 3729 3580 11678 3726 3581 11679 3727 3581 11680 3728 3581 11681 3730 3582 11682 3729 3582 11683 3731 3582 11684 3728 3583 11685 3729 3583 11686 3730 3583 11687 3732 3584 11688 3731 3584 11689 3733 3584 11690 3730 3585 11691 3731 3585 11692 3732 3585 11693 3732 3586 11694 3733 3586 11695 3734 3586 11696 3735 3587 11697 3734 3587 11698 3733 3587 11699 3736 3588 11700 3633 3588 11701 3642 3588 11702 3737 3589 11703 3633 3589 11704 3736 3589 11705 3738 3590 11706 3725 3590 11707 3724 3590 11708 3739 3591 11709 3725 3591 11710 3738 3591 11711 3739 3592 11712 3738 3592 11713 3740 3592 11714 3741 3593 11715 3740 3593 11716 3742 3593 11717 3739 3594 11718 3740 3594 11719 3741 3594 11720 3743 3595 11721 3742 3595 11722 3744 3595 11723 3741 3596 11724 3742 3596 11725 3743 3596 11726 3745 3597 11727 3744 3597 11728 3746 3597 11729 3743 3598 11730 3744 3598 11731 3745 3598 11732 3747 3599 11733 3746 3599 11734 3748 3599 11735 3745 3600 11736 3746 3600 11737 3747 3600 11738 3749 3601 11739 3748 3601 11740 3750 3601 11741 3747 3602 11742 3748 3602 11743 3749 3602 11744 3751 3603 11745 3750 3603 11746 3752 3603 11747 3749 3604 11748 3750 3604 11749 3751 3604 11750 3753 3605 11751 3752 3605 11752 3754 3605 11753 3751 3606 11754 3752 3606 11755 3753 3606 11756 3735 3607 11757 3755 3607 11758 3734 3607 11759 3709 3608 11760 3706 3608 11761 3756 3608 11762 3757 3609 11763 3758 3610 11764 3759 3611 11765 3710 3564 11766 3711 3565 11767 3760 3612 11768 3710 3564 11769 3760 3612 11770 3761 3613 11771 3757 3609 11772 3762 3614 11773 3758 3610 11774 3763 3615 11775 3755 3615 11776 3735 3615 11777 3763 3616 11778 3764 3616 11779 3755 3616 11780 3643 3501 11781 3765 3617 11782 3644 3502 11783 3643 3501 11784 3766 3618 11785 3765 3617 11786 3767 3619 11787 3768 3620 11788 3769 3621 11789 3770 3622 11790 3771 3623 11791 3766 3618 11792 3772 3624 11793 3769 3621 11794 3773 3625 11795 3643 3501 11796 3770 3622 11797 3766 3618 11798 3774 3626 11799 3767 3619 11800 3769 3621 11801 3774 3626 11802 3769 3621 11803 3772 3624 11804 3770 3622 11805 3775 3627 11806 3771 3623 11807 3772 3624 11808 3773 3625 11809 3776 3628 11810 3710 3564 11811 3777 3629 11812 3775 3627 11813 3778 3630 11814 3776 3628 11815 3779 3631 11816 3770 3622 11817 3710 3564 11818 3775 3627 11819 3772 3624 11820 3776 3628 11821 3778 3630 11822 3710 3564 11823 3761 3613 11824 3777 3629 11825 3780 3632 11826 3779 3631 11827 3762 3614 11828 3778 3630 11829 3779 3631 11830 3780 3632 11831 3780 3632 11832 3762 3614 11833 3757 3609 11834 3781 3633 11835 2529 2398 11836 3704 3560 11837 3781 3633 11838 2602 2471 11839 2529 2398 11840 3782 3634 11841 3704 3560 11842 3710 3564 11843 3782 3634 11844 3781 3633 11845 3704 3560 11846 3782 3634 11847 3710 3564 11848 3770 3622 11849 3783 3635 11850 3770 3622 11851 3643 3501 11852 3783 3635 11853 3782 3634 11854 3770 3622 11855 3784 3636 11856 3643 3501 11857 3639 3497 11858 3784 3636 11859 3783 3635 11860 3643 3501 11861 3785 3637 11862 3639 3497 11863 3479 3341 11864 3785 3637 11865 3784 3636 11866 3639 3497 11867 3786 3638 11868 3787 3639 11869 3479 3341 11870 3788 3640 11871 3479 3341 11872 3787 3639 11873 3482 3344 11874 3786 3638 11875 3479 3341 11876 3788 3640 11877 3785 3637 11878 3479 3341 11879 3789 3641 11880 3790 3642 11881 3791 3643 11882 3792 3644 11883 3788 3640 11884 3787 3639 11885 3789 3641 11886 3793 3645 11887 3790 3642 11888 3473 3335 11889 3791 3643 11890 3483 3345 11891 3789 3641 11892 3791 3643 11893 3473 3335 11894 3794 3646 11895 2602 2471 11896 3781 3633 11897 3794 3646 11898 2597 2466 11899 2602 2471 11900 3795 3647 11901 3781 3633 11902 3782 3634 11903 3795 3647 11904 3794 3646 11905 3781 3633 11906 3796 3648 11907 3782 3634 11908 3783 3635 11909 3796 3648 11910 3795 3647 11911 3782 3634 11912 3796 3648 11913 3783 3635 11914 3784 3636 11915 3797 3649 11916 3784 3636 11917 3785 3637 11918 3797 3649 11919 3796 3648 11920 3784 3636 11921 3798 3650 11922 3785 3637 11923 3788 3640 11924 3798 3650 11925 3797 3649 11926 3785 3637 11927 3792 3644 11928 3799 3651 11929 3788 3640 11930 3800 3652 11931 3788 3640 11932 3799 3651 11933 3800 3652 11934 3798 3650 11935 3788 3640 11936 3801 3653 11937 3802 3654 11938 3793 3645 11939 3803 3655 11940 3800 3652 11941 3799 3651 11942 3801 3653 11943 3804 3656 11944 3802 3654 11945 3801 3653 11946 3793 3645 11947 3789 3641 11948 3805 3657 11949 2597 2466 11950 3794 3646 11951 3805 3657 11952 2594 2463 11953 2597 2466 11954 3806 3658 11955 3794 3646 11956 3795 3647 11957 3806 3658 11958 3805 3657 11959 3794 3646 11960 3806 3658 11961 3795 3647 11962 3796 3648 11963 3807 3659 11964 3796 3648 11965 3797 3649 11966 3807 3659 11967 3806 3658 11968 3796 3648 11969 3808 3660 11970 3797 3649 11971 3798 3650 11972 3808 3660 11973 3807 3659 11974 3797 3649 11975 3809 3661 11976 3798 3650 11977 3800 3652 11978 3809 3661 11979 3808 3660 11980 3798 3650 11981 3810 3662 11982 3800 3652 11983 3803 3655 11984 3810 3662 11985 3809 3661 11986 3800 3652 11987 3811 3663 11988 3810 3662 11989 3803 3655 11990 3812 3664 11991 3813 3665 11992 3804 3656 11993 3812 3664 11994 3804 3656 11995 3801 3653 11996 2901 2764 11997 2594 2463 11998 3805 3657 11999 2901 2764 12000 2588 2457 12001 2594 2463 12002 2897 2760 12003 3805 3657 12004 3806 3658 12005 2897 2760 12006 2901 2764 12007 3805 3657 12008 2897 2760 12009 3806 3658 12010 3807 3659 12011 2886 2749 12012 3807 3659 12013 3808 3660 12014 2886 2749 12015 2897 2760 12016 3807 3659 12017 2879 2742 12018 3808 3660 12019 3809 3661 12020 2879 2742 12021 2886 2749 12022 3808 3660 12023 2873 2736 12024 3809 3661 12025 3810 3662 12026 2873 2736 12027 2879 2742 12028 3809 3661 12029 3811 3663 12030 3814 3666 12031 3810 3662 12032 2868 2731 12033 3810 3662 12034 3814 3666 12035 2868 2731 12036 2873 2736 12037 3810 3662 12038 3812 3664 12039 3815 3667 12040 3813 3665 12041 3816 3668 12042 2868 2731 12043 3814 3666 12044 3812 3664 12045 3817 3669 12046 3815 3667 12047 3816 3668 12048 2870 2733 12049 2868 2731 12050 3818 3670 12051 3819 3671 12052 3817 3669 12053 3818 3670 12054 2867 2730 12055 3819 3671 12056 3818 3670 12057 3817 3669 12058 3812 3664 12059 2865 2728 12060 2867 2730 12061 3818 3670 12062 3820 3672 12063 3821 3672 12064 3764 3672 12065 3763 3673 12066 3820 3673 12067 3764 3673 12068 3820 3674 12069 3822 3674 12070 3821 3674 12071 3485 3347 12072 3332 3192 12073 3335 3195 12074 3823 3675 12075 3335 3195 12076 3338 3198 12077 3823 3675 12078 3485 3347 12079 3335 3195 12080 3824 3676 12081 3338 3198 12082 3340 3200 12083 3824 3676 12084 3823 3675 12085 3338 3198 12086 3825 3677 12087 3340 3200 12088 3343 3203 12089 3825 3677 12090 3824 3676 12091 3340 3200 12092 3826 3678 12093 3343 3203 12094 3349 3209 12095 3826 3678 12096 3825 3677 12097 3343 3203 12098 3827 3679 12099 3826 3678 12100 3349 3209 12101 3350 3210 12102 3828 3680 12103 3346 3206 12104 3473 3335 12105 3485 3347 12106 3823 3675 12107 3789 3641 12108 3823 3675 12109 3824 3676 12110 3789 3641 12111 3473 3335 12112 3823 3675 12113 3801 3653 12114 3824 3676 12115 3825 3677 12116 3801 3653 12117 3789 3641 12118 3824 3676 12119 3812 3664 12120 3825 3677 12121 3826 3678 12122 3812 3664 12123 3801 3653 12124 3825 3677 12125 3818 3670 12126 3826 3678 12127 3827 3679 12128 3818 3670 12129 3812 3664 12130 3826 3678 12131 2865 2728 12132 3818 3670 12133 3827 3679 12134 3829 3681 12135 2860 2723 12136 3828 3680 12137 3350 3210 12138 3829 3681 12139 3828 3680 12140 3829 3681 12141 2849 2712 12142 2860 2723 12143 3322 3182 12144 2691 2558 12145 2704 2571 12146 3830 3682 12147 2704 2571 12148 2789 2652 12149 3830 3682 12150 3322 3182 12151 2704 2571 12152 3831 3683 12153 2789 2652 12154 2849 2712 12155 3831 3683 12156 3830 3682 12157 2789 2652 12158 3829 3681 12159 3831 3683 12160 2849 2712 12161 3297 3156 12162 3322 3182 12163 3830 3682 12164 3354 3214 12165 3830 3682 12166 3831 3683 12167 3354 3214 12168 3297 3156 12169 3830 3682 12170 3352 3212 12171 3831 3683 12172 3829 3681 12173 3352 3212 12174 3354 3214 12175 3831 3683 12176 3350 3210 12177 3352 3212 12178 3829 3681 12179 865 779 12180 867 781 12181 3370 3231 12182 3832 3684 12183 3370 3231 12184 3372 3234 12185 3832 3684 12186 865 779 12187 3370 3231 12188 3833 3685 12189 3372 3234 12190 3374 3236 12191 3833 3685 12192 3832 3684 12193 3372 3234 12194 3834 3686 12195 3374 3236 12196 3376 3238 12197 3834 3686 12198 3833 3685 12199 3374 3236 12200 3835 3687 12201 3376 3238 12202 3378 3240 12203 3835 3687 12204 3834 3686 12205 3376 3238 12206 3836 3688 12207 3378 3240 12208 3380 3242 12209 3836 3688 12210 3835 3687 12211 3378 3240 12212 3837 3689 12213 3380 3242 12214 3382 3244 12215 3837 3689 12216 3836 3688 12217 3380 3242 12218 3838 3690 12219 3382 3244 12220 3385 3247 12221 3838 3690 12222 3837 3689 12223 3382 3244 12224 3839 3691 12225 3385 3247 12226 3387 3249 12227 3839 3691 12228 3838 3690 12229 3385 3247 12230 3840 3692 12231 3387 3249 12232 3389 3251 12233 3840 3692 12234 3839 3691 12235 3387 3249 12236 3841 3693 12237 3389 3251 12238 3391 3253 12239 3841 3693 12240 3840 3692 12241 3389 3251 12242 3842 3694 12243 3391 3253 12244 3393 3255 12245 3842 3694 12246 3841 3693 12247 3391 3253 12248 3843 3695 12249 3393 3255 12250 3395 3257 12251 3843 3695 12252 3842 3694 12253 3393 3255 12254 3844 3696 12255 3395 3257 12256 3397 3259 12257 3844 3696 12258 3843 3695 12259 3395 3257 12260 3845 3697 12261 3397 3259 12262 3399 3261 12263 3845 3697 12264 3844 3696 12265 3397 3259 12266 3846 3698 12267 3399 3261 12268 3401 3263 12269 3846 3698 12270 3845 3697 12271 3399 3261 12272 3847 3699 12273 3401 3263 12274 3403 3265 12275 3847 3699 12276 3846 3698 12277 3401 3263 12278 3848 3700 12279 3403 3265 12280 3405 3267 12281 3848 3700 12282 3847 3699 12283 3403 3265 12284 3849 3701 12285 3405 3267 12286 3407 3269 12287 3849 3701 12288 3848 3700 12289 3405 3267 12290 3850 3702 12291 3407 3269 12292 3409 3271 12293 3850 3702 12294 3849 3701 12295 3407 3269 12296 3851 3703 12297 3409 3271 12298 3411 3273 12299 3851 3703 12300 3850 3702 12301 3409 3271 12302 3852 3704 12303 3411 3273 12304 3413 3275 12305 3852 3704 12306 3851 3703 12307 3411 3273 12308 3853 3705 12309 3413 3275 12310 3415 3277 12311 3853 3705 12312 3852 3704 12313 3413 3275 12314 3854 3706 12315 3415 3277 12316 3417 3279 12317 3854 3706 12318 3853 3705 12319 3415 3277 12320 3855 3707 12321 3417 3279 12322 3419 3281 12323 3855 3707 12324 3854 3706 12325 3417 3279 12326 3856 3708 12327 3419 3281 12328 3421 3283 12329 3856 3708 12330 3855 3707 12331 3419 3281 12332 3857 3709 12333 3421 3283 12334 3423 3285 12335 3857 3709 12336 3856 3708 12337 3421 3283 12338 3858 3710 12339 3423 3285 12340 3425 3287 12341 3858 3710 12342 3857 3709 12343 3423 3285 12344 3859 3711 12345 3425 3287 12346 3427 3289 12347 3859 3711 12348 3858 3710 12349 3425 3287 12350 3860 3712 12351 3427 3289 12352 3429 3291 12353 3860 3712 12354 3859 3711 12355 3427 3289 12356 3861 3713 12357 3429 3291 12358 3431 3293 12359 3861 3713 12360 3860 3712 12361 3429 3291 12362 3862 3714 12363 3431 3293 12364 3433 3295 12365 3862 3714 12366 3861 3713 12367 3431 3293 12368 3863 3715 12369 3433 3295 12370 3435 3297 12371 3863 3715 12372 3862 3714 12373 3433 3295 12374 3864 3716 12375 3435 3297 12376 3437 3299 12377 3864 3716 12378 3863 3715 12379 3435 3297 12380 3865 3717 12381 3437 3299 12382 3440 3302 12383 3865 3717 12384 3864 3716 12385 3437 3299 12386 1373 3718 12387 1372 3718 12388 1114 3718 12389 3866 3719 12390 3865 3717 12391 3440 3302 12392 3867 3720 12393 865 779 12394 3832 3684 12395 3867 3720 12396 868 782 12397 865 779 12398 3868 3721 12399 3832 3684 12400 3833 3685 12401 557 492 12402 809 492 12403 558 492 12404 3869 3722 12405 3867 3720 12406 3832 3684 12407 3868 3721 12408 3869 3722 12409 3832 3684 12410 3870 3723 12411 3833 3685 12412 3834 3686 12413 3870 3723 12414 3868 3721 12415 3833 3685 12416 3871 3724 12417 3834 3686 12418 3835 3687 12419 3871 3724 12420 3870 3723 12421 3834 3686 12422 3872 3725 12423 3835 3687 12424 3836 3688 12425 3872 3725 12426 3871 3724 12427 3835 3687 12428 3873 3726 12429 3836 3688 12430 3837 3689 12431 3873 3726 12432 3872 3725 12433 3836 3688 12434 3874 3727 12435 3837 3689 12436 3838 3690 12437 3874 3727 12438 3873 3726 12439 3837 3689 12440 3875 3728 12441 3838 3690 12442 3839 3691 12443 3875 3728 12444 3874 3727 12445 3838 3690 12446 3876 3729 12447 3839 3691 12448 3840 3692 12449 3876 3729 12450 3875 3728 12451 3839 3691 12452 3877 3730 12453 3840 3692 12454 3841 3693 12455 3877 3730 12456 3876 3729 12457 3840 3692 12458 3878 3731 12459 3841 3693 12460 3842 3694 12461 3878 3731 12462 3877 3730 12463 3841 3693 12464 3879 3732 12465 3842 3694 12466 3843 3695 12467 3879 3732 12468 3878 3731 12469 3842 3694 12470 3880 3733 12471 3843 3695 12472 3844 3696 12473 3880 3733 12474 3879 3732 12475 3843 3695 12476 3881 3734 12477 3844 3696 12478 3845 3697 12479 3881 3734 12480 3880 3733 12481 3844 3696 12482 3882 3735 12483 3845 3697 12484 3846 3698 12485 3882 3735 12486 3881 3734 12487 3845 3697 12488 3883 3736 12489 3846 3698 12490 3847 3699 12491 3883 3736 12492 3882 3735 12493 3846 3698 12494 3884 3737 12495 3847 3699 12496 3848 3700 12497 3884 3737 12498 3883 3736 12499 3847 3699 12500 3885 3738 12501 3848 3700 12502 3849 3701 12503 3885 3738 12504 3884 3737 12505 3848 3700 12506 3886 3739 12507 3849 3701 12508 3850 3702 12509 3886 3739 12510 3885 3738 12511 3849 3701 12512 3887 3740 12513 3850 3702 12514 3851 3703 12515 3887 3740 12516 3886 3739 12517 3850 3702 12518 3888 3741 12519 3851 3703 12520 3852 3704 12521 3888 3741 12522 3887 3740 12523 3851 3703 12524 3889 3742 12525 3852 3704 12526 3853 3705 12527 3889 3742 12528 3888 3741 12529 3852 3704 12530 3890 3743 12531 3853 3705 12532 3854 3706 12533 3890 3743 12534 3889 3742 12535 3853 3705 12536 3891 3744 12537 3854 3706 12538 3855 3707 12539 3891 3744 12540 3890 3743 12541 3854 3706 12542 3892 3745 12543 3855 3707 12544 3856 3708 12545 3892 3745 12546 3891 3744 12547 3855 3707 12548 3893 3746 12549 3856 3708 12550 3857 3709 12551 3893 3746 12552 3892 3745 12553 3856 3708 12554 3894 3747 12555 3857 3709 12556 3858 3710 12557 3894 3747 12558 3893 3746 12559 3857 3709 12560 3895 3748 12561 3858 3710 12562 3859 3711 12563 3895 3748 12564 3894 3747 12565 3858 3710 12566 3896 3749 12567 3859 3711 12568 3860 3712 12569 3896 3749 12570 3895 3748 12571 3859 3711 12572 3897 3750 12573 3860 3712 12574 3861 3713 12575 3897 3750 12576 3896 3749 12577 3860 3712 12578 3898 3751 12579 3861 3713 12580 3862 3714 12581 3898 3751 12582 3897 3750 12583 3861 3713 12584 3899 3752 12585 3862 3714 12586 3863 3715 12587 3899 3752 12588 3898 3751 12589 3862 3714 12590 3900 3753 12591 3863 3715 12592 3864 3716 12593 3900 3753 12594 3899 3752 12595 3863 3715 12596 3901 3754 12597 3864 3716 12598 3865 3717 12599 3901 3754 12600 3900 3753 12601 3864 3716 12602 3901 3754 12603 3865 3717 12604 3866 3719 12605 3902 3755 12606 1374 3755 12607 1373 3755 12608 1253 1166 12609 3901 3754 12610 3866 3719 12611 869 783 12612 868 782 12613 3867 3720 12614 3903 3756 12615 3869 3722 12616 3868 3721 12617 3904 3757 12618 3868 3721 12619 3870 3723 12620 3904 3757 12621 3903 3756 12622 3868 3721 12623 3902 3758 12624 3905 3758 12625 1374 3758 12626 3906 492 12627 3905 492 12628 3902 492 12629 3907 3759 12630 3908 3759 12631 3906 3759 12632 3906 3760 12633 3908 3760 12634 3905 3760 12635 3909 3761 12636 3872 3725 12637 3873 3726 12638 3909 3761 12639 3871 3724 12640 3872 3725 12641 3910 3762 12642 3873 3726 12643 3874 3727 12644 3911 3763 12645 3909 3761 12646 3873 3726 12647 3910 3762 12648 3911 3763 12649 3873 3726 12650 3912 3764 12651 3874 3727 12652 3875 3728 12653 3912 3764 12654 3910 3762 12655 3874 3727 12656 3913 3765 12657 3875 3728 12658 3876 3729 12659 3914 3766 12660 3912 3764 12661 3875 3728 12662 3913 3765 12663 3914 3766 12664 3875 3728 12665 3915 3767 12666 3876 3729 12667 3877 3730 12668 3915 3767 12669 3913 3765 12670 3876 3729 12671 3916 3768 12672 3917 3768 12673 3907 3768 12674 3907 3769 12675 3917 3769 12676 3908 3769 12677 3918 3770 12678 3878 3731 12679 3879 3732 12680 3919 3771 12681 3877 3730 12682 3878 3731 12683 3918 3770 12684 3919 3771 12685 3878 3731 12686 3920 3772 12687 3879 3732 12688 3880 3733 12689 3920 3772 12690 3918 3770 12691 3879 3732 12692 3921 3773 12693 3880 3733 12694 3881 3734 12695 3921 3773 12696 3920 3772 12697 3880 3733 12698 3922 3774 12699 3881 3734 12700 3882 3735 12701 3923 3775 12702 3924 3775 12703 3916 3775 12704 3916 3776 12705 3925 3776 12706 3917 3776 12707 3926 3777 12708 3882 3735 12709 3883 3736 12710 3927 3778 12711 3922 3774 12712 3882 3735 12713 3926 3777 12714 3927 3778 12715 3882 3735 12716 3928 3779 12717 3883 3736 12718 3884 3737 12719 3928 3779 12720 3926 3777 12721 3883 3736 12722 3929 3780 12723 3884 3737 12724 3885 3738 12725 3929 3780 12726 3928 3779 12727 3884 3737 12728 3930 3781 12729 3885 3738 12730 3886 3739 12731 3930 3781 12732 3929 3780 12733 3885 3738 12734 3931 3782 12735 3886 3739 12736 3887 3740 12737 3931 3782 12738 3930 3781 12739 3886 3739 12740 3932 3783 12741 3887 3740 12742 3888 3741 12743 3932 3783 12744 3931 3782 12745 3887 3740 12746 3933 3784 12747 3888 3741 12748 3889 3742 12749 3934 3785 12750 3932 3783 12751 3888 3741 12752 3933 3784 12753 3934 3785 12754 3888 3741 12755 3935 3786 12756 3889 3742 12757 3890 3743 12758 3935 3786 12759 3933 3784 12760 3889 3742 12761 3936 3787 12762 3890 3743 12763 3891 3744 12764 3936 3787 12765 3935 3786 12766 3890 3743 12767 3937 3788 12768 3891 3744 12769 3892 3745 12770 3938 3789 12771 3936 3787 12772 3891 3744 12773 3937 3788 12774 3938 3789 12775 3891 3744 12776 3939 3790 12777 3892 3745 12778 3893 3746 12779 3939 3790 12780 3937 3788 12781 3892 3745 12782 3940 3791 12783 3893 3746 12784 3894 3747 12785 3941 3792 12786 3939 3790 12787 3893 3746 12788 3940 3791 12789 3941 3792 12790 3893 3746 12791 3942 3793 12792 3894 3747 12793 3895 3748 12794 3942 3793 12795 3940 3791 12796 3894 3747 12797 3943 3794 12798 3895 3748 12799 3896 3749 12800 3943 3794 12801 3942 3793 12802 3895 3748 12803 3944 3795 12804 3896 3749 12805 3897 3750 12806 3944 3795 12807 3943 3794 12808 3896 3749 12809 3945 3796 12810 3897 3750 12811 3898 3751 12812 3945 3796 12813 3944 3795 12814 3897 3750 12815 3946 3797 12816 3898 3751 12817 3899 3752 12818 3947 3798 12819 3945 3796 12820 3898 3751 12821 3946 3797 12822 3947 3798 12823 3898 3751 12824 3948 3799 12825 3899 3752 12826 3900 3753 12827 3948 3799 12828 3946 3797 12829 3899 3752 12830 1252 1165 12831 3900 3753 12832 3901 3754 12833 1252 1165 12834 3948 3799 12835 3900 3753 12836 1252 1165 12837 3901 3754 12838 1253 1166 12839 841 760 12840 843 762 12841 3949 3800 12842 841 760 12843 3949 3800 12844 3950 3801 12845 841 760 12846 3950 3801 12847 3951 3802 12848 841 760 12849 3951 3802 12850 3952 3803 12851 841 760 12852 3952 3803 12853 3953 3804 12854 841 760 12855 3953 3804 12856 3954 3805 12857 841 760 12858 3954 3805 12859 3955 3806 12860 841 760 12861 3955 3806 12862 3956 3807 12863 841 760 12864 3956 3807 12865 3957 3808 12866 3958 3809 12867 3957 3808 12868 3959 3810 12869 3958 3809 12870 841 760 12871 3957 3808 12872 3958 3809 12873 3959 3810 12874 3960 3811 12875 3958 3809 12876 3960 3811 12877 3961 3812 12878 3958 3809 12879 3961 3812 12880 3962 3813 12881 3958 3809 12882 3962 3813 12883 3963 3814 12884 3958 3809 12885 3963 3814 12886 3964 3815 12887 3958 3809 12888 3964 3815 12889 3965 3816 12890 3966 3817 12891 3965 3816 12892 3967 3818 12893 3966 3817 12894 3958 3809 12895 3965 3816 12896 3966 3817 12897 3967 3818 12898 3968 3819 12899 3966 3817 12900 3968 3819 12901 3969 3820 12902 3966 3817 12903 3969 3820 12904 3970 3821 12905 3966 3817 12906 3970 3821 12907 3971 3822 12908 3966 3817 12909 3971 3822 12910 3972 3823 12911 3966 3817 12912 3972 3823 12913 3973 3824 12914 3974 3825 12915 3973 3824 12916 3975 3826 12917 3974 3825 12918 3966 3817 12919 3973 3824 12920 3974 3825 12921 3975 3826 12922 3976 3827 12923 3974 3825 12924 3976 3827 12925 3977 3828 12926 3974 3825 12927 3977 3828 12928 3978 3829 12929 3974 3825 12930 3978 3829 12931 3979 3830 12932 3974 3825 12933 3979 3830 12934 3980 3831 12935 1249 1162 12936 3980 3831 12937 3981 3832 12938 3974 3825 12939 3980 3831 12940 1249 1162 12941 1249 1162 12942 3981 3832 12943 3982 3833 12944 1249 1162 12945 3982 3833 12946 3983 3834 12947 1249 1162 12948 3983 3834 12949 1255 1168 12950 3984 3835 12951 1249 1162 12952 1256 1169 12953 3974 3825 12954 1249 1162 12955 3984 3835 12956 3985 3836 12957 1256 1169 12958 1258 1171 12959 3984 3835 12960 1256 1169 12961 3985 3836 12962 3986 3837 12963 1258 1171 12964 1261 1174 12965 3985 3836 12966 1258 1171 12967 3986 3837 12968 3987 3838 12969 1261 1174 12970 1241 1154 12971 3986 3837 12972 1261 1174 12973 3987 3838 12974 3988 3839 12975 1241 1154 12976 1245 1158 12977 3987 3838 12978 1241 1154 12979 3988 3839 12980 3989 3840 12981 1245 1158 12982 1116 1027 12983 3988 3839 12984 1245 1158 12985 3989 3840 12986 3990 3841 12987 1116 1027 12988 1119 1030 12989 3989 3840 12990 1116 1027 12991 3990 3841 12992 3990 3841 12993 1119 1030 12994 3991 3842 12995 3992 3843 12996 817 736 12997 820 739 12998 3993 3844 12999 820 739 13000 823 742 13001 3993 3844 13002 3992 3843 13003 820 739 13004 3994 3845 13005 823 742 13006 825 744 13007 3994 3845 13008 3993 3844 13009 823 742 13010 3995 3846 13011 825 744 13012 828 747 13013 3995 3846 13014 3994 3845 13015 825 744 13016 3996 3847 13017 828 747 13018 831 750 13019 3996 3847 13020 3995 3846 13021 828 747 13022 3997 3848 13023 831 750 13024 833 752 13025 3997 3848 13026 3996 3847 13027 831 750 13028 3998 3849 13029 833 752 13030 835 754 13031 3998 3849 13032 3997 3848 13033 833 752 13034 3999 3850 13035 835 754 13036 837 756 13037 3999 3850 13038 3998 3849 13039 835 754 13040 4000 3851 13041 837 756 13042 839 758 13043 4000 3851 13044 3999 3850 13045 837 756 13046 3958 3809 13047 839 758 13048 841 760 13049 3958 3809 13050 4000 3851 13051 839 758 13052 4001 3852 13053 3992 3843 13054 3993 3844 13055 4002 3853 13056 3993 3844 13057 3994 3845 13058 4003 3854 13059 4001 3852 13060 3993 3844 13061 4002 3853 13062 4003 3854 13063 3993 3844 13064 4004 3855 13065 3994 3845 13066 3995 3846 13067 4004 3855 13068 4002 3853 13069 3994 3845 13070 4005 3856 13071 3995 3846 13072 3996 3847 13073 4005 3856 13074 4004 3855 13075 3995 3846 13076 4006 3857 13077 3996 3847 13078 3997 3848 13079 4006 3857 13080 4005 3856 13081 3996 3847 13082 4007 3858 13083 3997 3848 13084 3998 3849 13085 4007 3858 13086 4006 3857 13087 3997 3848 13088 4008 3859 13089 3998 3849 13090 3999 3850 13091 4008 3859 13092 4007 3858 13093 3998 3849 13094 4009 3860 13095 3999 3850 13096 4000 3851 13097 4009 3860 13098 4008 3859 13099 3999 3850 13100 3966 3817 13101 4000 3851 13102 3958 3809 13103 3966 3817 13104 4009 3860 13105 4000 3851 13106 3991 3842 13107 4001 3852 13108 4003 3854 13109 3990 3841 13110 4003 3854 13111 4002 3853 13112 3990 3841 13113 3991 3842 13114 4003 3854 13115 3989 3840 13116 4002 3853 13117 4004 3855 13118 3989 3840 13119 3990 3841 13120 4002 3853 13121 3988 3839 13122 4004 3855 13123 4005 3856 13124 3988 3839 13125 3989 3840 13126 4004 3855 13127 3987 3838 13128 4005 3856 13129 4006 3857 13130 3987 3838 13131 3988 3839 13132 4005 3856 13133 3986 3837 13134 4006 3857 13135 4007 3858 13136 3986 3837 13137 3987 3838 13138 4006 3857 13139 3985 3836 13140 4007 3858 13141 4008 3859 13142 3985 3836 13143 3986 3837 13144 4007 3858 13145 3984 3835 13146 4008 3859 13147 4009 3860 13148 3984 3835 13149 3985 3836 13150 4008 3859 13151 3974 3825 13152 4009 3860 13153 3966 3817 13154 3974 3825 13155 3984 3835 13156 4009 3860 13157 4010 3861 13158 2799 2662 13159 2803 2666 13160 4011 3862 13161 2802 2665 13162 4012 3863 13163 4011 3862 13164 2794 2657 13165 2802 2665 13166 4013 3864 13167 2803 2666 13168 2805 2668 13169 4013 3864 13170 4010 3861 13171 2803 2666 13172 4014 3865 13173 2805 2668 13174 2807 2670 13175 4015 3866 13176 4013 3864 13177 2805 2668 13178 4014 3865 13179 4015 3866 13180 2805 2668 13181 4016 3867 13182 2807 2670 13183 2809 2672 13184 4016 3867 13185 4014 3865 13186 2807 2670 13187 4017 3868 13188 2809 2672 13189 2811 2674 13190 4017 3868 13191 4016 3867 13192 2809 2672 13193 4018 3869 13194 2811 2674 13195 2813 2676 13196 4018 3869 13197 4017 3868 13198 2811 2674 13199 4018 3869 13200 2813 2676 13201 4019 3870 13202 4020 3871 13203 4021 3872 13204 2815 2678 13205 4020 3871 13206 2815 2678 13207 2818 2681 13208 4022 3873 13209 4023 3874 13210 4024 3875 13211 4025 3876 13212 4026 3877 13213 4027 3878 13214 4028 3879 13215 4022 3873 13216 4024 3875 13217 4029 3880 13218 4030 3881 13219 4031 3882 13220 4032 3883 13221 4033 3884 13222 4034 3885 13223 4035 3886 13224 4032 3883 13225 4034 3885 13226 4036 3887 13227 4031 3882 13228 4037 3888 13229 4038 3889 13230 4029 3880 13231 4031 3882 13232 4036 3887 13233 4038 3889 13234 4031 3882 13235 4039 3890 13236 4037 3888 13237 4040 3891 13238 4041 3892 13239 4036 3887 13240 4037 3888 13241 4039 3890 13242 4041 3892 13243 4037 3888 13244 4042 3893 13245 4040 3891 13246 4043 3894 13247 4044 3895 13248 4039 3890 13249 4040 3891 13250 4042 3893 13251 4044 3895 13252 4040 3891 13253 4045 3896 13254 4043 3894 13255 4046 3897 13256 4045 3896 13257 4042 3893 13258 4043 3894 13259 4022 3873 13260 4046 3897 13261 4023 3874 13262 4022 3873 13263 4045 3896 13264 4046 3897 13265 4047 3898 13266 2818 2681 13267 2822 2685 13268 4047 3898 13269 4020 3871 13270 2818 2681 13271 4048 3899 13272 2822 2685 13273 2820 2683 13274 4048 3899 13275 4047 3898 13276 2822 2685 13277 4048 3899 13278 2820 2683 13279 2827 2690 13280 4048 3899 13281 2827 2690 13282 4049 3900 13283 2828 2691 13284 4050 3901 13285 2824 2687 13286 4051 3902 13287 4052 3903 13288 4053 3904 13289 4054 3905 13290 4050 3901 13291 2828 2691 13292 4055 3906 13293 4056 3907 13294 4057 3908 13295 4058 3909 13296 4051 3902 13297 4053 3904 13298 4059 3910 13299 4027 3878 13300 4060 3911 13301 4025 3876 13302 4027 3878 13303 4061 3912 13304 4059 3910 13305 4061 3912 13306 4027 3878 13307 4062 3913 13308 4060 3911 13309 4052 3903 13310 4059 3910 13311 4060 3911 13312 4062 3913 13313 4062 3913 13314 4052 3903 13315 4051 3902 13316 4063 3914 13317 2828 2691 13318 2830 2693 13319 4063 3914 13320 4054 3905 13321 2828 2691 13322 4064 3915 13323 2830 2693 13324 2832 2695 13325 4065 3916 13326 4063 3914 13327 2830 2693 13328 4064 3915 13329 4065 3916 13330 2830 2693 13331 4066 3917 13332 2832 2695 13333 2834 2697 13334 4067 3918 13335 4064 3915 13336 2832 2695 13337 4066 3917 13338 4067 3918 13339 2832 2695 13340 4068 3919 13341 2834 2697 13342 2836 2699 13343 4069 3920 13344 4066 3917 13345 2834 2697 13346 4068 3919 13347 4069 3920 13348 2834 2697 13349 4070 3921 13350 2836 2699 13351 2842 2705 13352 4071 3922 13353 4068 3919 13354 2836 2699 13355 4072 3923 13356 4071 3922 13357 2836 2699 13358 4070 3921 13359 4072 3923 13360 2836 2699 13361 4070 3921 13362 2842 2705 13363 4073 3924 13364 2844 2707 13365 4074 3925 13366 2839 2702 13367 4075 3926 13368 4076 3927 13369 4077 3928 13370 4078 3929 13371 4074 3925 13372 2844 2707 13373 4079 3930 13374 4080 3931 13375 4081 3932 13376 4082 3933 13377 4075 3926 13378 4077 3928 13379 4083 3934 13380 4057 3908 13381 4084 3935 13382 4055 3906 13383 4057 3908 13384 4085 3936 13385 4086 3937 13386 4085 3936 13387 4057 3908 13388 4083 3934 13389 4086 3937 13390 4057 3908 13391 4087 3938 13392 4084 3935 13393 4088 3939 13394 4087 3938 13395 4083 3934 13396 4084 3935 13397 4089 3940 13398 4088 3939 13399 4090 3941 13400 4089 3940 13401 4087 3938 13402 4088 3939 13403 4091 3942 13404 4090 3941 13405 4092 3943 13406 4091 3942 13407 4089 3940 13408 4090 3941 13409 4093 3944 13410 4092 3943 13411 4094 3945 13412 4093 3944 13413 4091 3942 13414 4092 3943 13415 4095 3946 13416 4094 3945 13417 4096 3947 13418 4095 3946 13419 4093 3944 13420 4094 3945 13421 4097 3948 13422 4096 3947 13423 4098 3949 13424 4097 3948 13425 4095 3946 13426 4096 3947 13427 4099 3950 13428 4098 3949 13429 4100 3951 13430 4099 3950 13431 4097 3948 13432 4098 3949 13433 4101 3952 13434 4100 3951 13435 4102 3953 13436 4101 3952 13437 4099 3950 13438 4100 3951 13439 4075 3926 13440 4102 3953 13441 4076 3927 13442 4075 3926 13443 4101 3952 13444 4102 3953 13445 4078 3929 13446 2844 2707 13447 2961 2824 13448 4103 3954 13449 2961 2824 13450 2913 2776 13451 4103 3954 13452 4078 3929 13453 2961 2824 13454 4104 3955 13455 2913 2776 13456 2919 2782 13457 4104 3955 13458 4103 3954 13459 2913 2776 13460 4104 3955 13461 2919 2782 13462 4105 3956 13463 2920 2783 13464 4106 3957 13465 2916 2779 13466 4107 3958 13467 4108 3959 13468 4109 3960 13469 4110 3961 13470 4106 3957 13471 2920 2783 13472 4111 3962 13473 4112 3963 13474 4113 3964 13475 4107 3958 13476 4109 3960 13477 4114 3965 13478 4115 3966 13479 4081 3932 13480 4116 3967 13481 4117 3968 13482 4079 3930 13483 4081 3932 13484 4117 3968 13485 4081 3932 13486 4115 3966 13487 4107 3958 13488 4116 3967 13489 4108 3959 13490 4115 3966 13491 4116 3967 13492 4107 3958 13493 4118 3969 13494 2920 2783 13495 2923 2786 13496 4118 3969 13497 4110 3961 13498 2920 2783 13499 4119 3970 13500 2923 2786 13501 2925 2788 13502 4120 3971 13503 4118 3969 13504 2923 2786 13505 4119 3970 13506 4120 3971 13507 2923 2786 13508 4121 3972 13509 2925 2788 13510 2927 2790 13511 4122 3973 13512 4119 3970 13513 2925 2788 13514 4123 3974 13515 4122 3973 13516 2925 2788 13517 4121 3972 13518 4123 3974 13519 2925 2788 13520 4124 3975 13521 2927 2790 13522 2929 2792 13523 4125 3976 13524 4121 3972 13525 2927 2790 13526 4124 3975 13527 4125 3976 13528 2927 2790 13529 4126 3977 13530 2929 2792 13531 2931 2794 13532 4127 3978 13533 4124 3975 13534 2929 2792 13535 4126 3977 13536 4127 3978 13537 2929 2792 13538 4126 3977 13539 2931 2794 13540 4128 3979 13541 4129 3980 13542 4130 3981 13543 2933 2796 13544 4129 3980 13545 2933 2796 13546 2936 2799 13547 4131 3982 13548 4132 3983 13549 4133 3984 13550 4134 3985 13551 4135 3986 13552 4136 3987 13553 4137 3988 13554 4131 3982 13555 4133 3984 13556 4138 3989 13557 4113 3964 13558 4139 3990 13559 4140 3991 13560 4111 3962 13561 4113 3964 13562 4140 3991 13563 4113 3964 13564 4138 3989 13565 4141 3992 13566 4139 3990 13567 4142 3993 13568 4138 3989 13569 4139 3990 13570 4141 3992 13571 4141 3992 13572 4142 3993 13573 4143 3994 13574 4144 3995 13575 4143 3994 13576 4145 3996 13577 4141 3992 13578 4143 3994 13579 4144 3995 13580 4146 3997 13581 4145 3996 13582 4147 3998 13583 4144 3995 13584 4145 3996 13585 4146 3997 13586 4148 3999 13587 4147 3998 13588 4149 4000 13589 4146 3997 13590 4147 3998 13591 4148 3999 13592 4150 4001 13593 4149 4000 13594 4151 4002 13595 4148 3999 13596 4149 4000 13597 4150 4001 13598 4152 4003 13599 4151 4002 13600 4153 4004 13601 4150 4001 13602 4151 4002 13603 4152 4003 13604 4154 4005 13605 4153 4004 13606 4155 4006 13607 4152 4003 13608 4153 4004 13609 4154 4005 13610 4156 4007 13611 4155 4006 13612 4132 3983 13613 4154 4005 13614 4155 4006 13615 4156 4007 13616 4156 4007 13617 4132 3983 13618 4131 3982 13619 4157 4008 13620 2936 2799 13621 2938 2801 13622 4157 4008 13623 4129 3980 13624 2936 2799 13625 4158 4009 13626 2938 2801 13627 2940 2803 13628 4158 4009 13629 4157 4008 13630 2938 2801 13631 4159 4010 13632 2940 2803 13633 2942 2805 13634 4159 4010 13635 4158 4009 13636 2940 2803 13637 4159 4010 13638 2942 2805 13639 2948 2811 13640 4159 4010 13641 2948 2811 13642 4160 4011 13643 2949 2812 13644 4161 4012 13645 2945 2808 13646 4162 4013 13647 4163 4014 13648 4164 4015 13649 4165 4016 13650 4161 4012 13651 2949 2812 13652 4166 4017 13653 4167 4018 13654 4168 4019 13655 4169 4020 13656 4162 4013 13657 4164 4015 13658 4170 4021 13659 4136 4021 13660 4171 4021 13661 4170 4022 13662 4172 4023 13663 4136 3987 13664 4134 3985 13665 4136 3987 13666 4172 4023 13667 4173 4024 13668 4171 4024 13669 4174 4024 13670 4170 4025 13671 4171 4025 13672 4173 4025 13673 4175 4026 13674 4174 4026 13675 4163 4026 13676 4173 4027 13677 4174 4027 13678 4175 4027 13679 4175 4028 13680 4163 4028 13681 4162 4028 13682 4165 4016 13683 2949 2812 13684 2951 2814 13685 4176 4029 13686 2951 2814 13687 2953 2816 13688 4176 4029 13689 4165 4016 13690 2951 2814 13691 4177 4030 13692 2953 2816 13693 2955 2818 13694 4178 4031 13695 4176 4029 13696 2953 2816 13697 4177 4030 13698 4178 4031 13699 2953 2816 13700 4179 4032 13701 2955 2818 13702 2957 2820 13703 4179 4032 13704 4177 4030 13705 2955 2818 13706 4180 4033 13707 2957 2820 13708 2960 2823 13709 4180 4033 13710 4179 4032 13711 2957 2820 13712 4180 4033 13713 2960 2823 13714 4181 4034 13715 2855 2718 13716 4182 4035 13717 2858 2721 13718 4183 4036 13719 4184 4037 13720 4185 4038 13721 4186 4039 13722 4182 4035 13723 2855 2718 13724 4187 4040 13725 4188 4041 13726 4189 4042 13727 4183 4036 13728 4185 4038 13729 4190 4043 13730 4191 4044 13731 4168 4019 13732 4192 4045 13733 4193 4046 13734 4194 4047 13735 4168 4019 13736 4166 4017 13737 4168 4019 13738 4194 4047 13739 4193 4046 13740 4168 4019 13741 4191 4044 13742 4195 4048 13743 4192 4045 13744 4196 4049 13745 4191 4044 13746 4192 4045 13747 4195 4048 13748 4197 4050 13749 4196 4049 13750 4198 4051 13751 4199 4052 13752 4196 4049 13753 4197 4050 13754 4195 4048 13755 4196 4049 13756 4199 4052 13757 4200 4053 13758 4198 4051 13759 4201 4054 13760 4197 4050 13761 4198 4051 13762 4200 4053 13763 4183 4036 13764 4201 4054 13765 4184 4037 13766 4202 4055 13767 4201 4054 13768 4183 4036 13769 4200 4053 13770 4201 4054 13771 4202 4055 13772 4203 4056 13773 2855 2718 13774 2797 2660 13775 4203 4056 13776 4186 4039 13777 2855 2718 13778 4011 3862 13779 2797 2660 13780 2794 2657 13781 4011 3862 13782 4203 4056 13783 2797 2660 13784 4204 4057 13785 4189 4042 13786 4205 4058 13787 4204 4057 13788 4187 4040 13789 4189 4042 13790 4206 4059 13791 4205 4058 13792 4033 3884 13793 4206 4059 13794 4204 4057 13795 4205 4058 13796 4032 3883 13797 4206 4059 13798 4033 3884 13799 4207 4060 13800 4208 4061 13801 4209 4062 13802 4210 4063 13803 4208 4061 13804 4207 4060 13805 4211 4064 13806 4208 4061 13807 4210 4063 13808 4212 4065 13809 4213 4066 13810 4214 4067 13811 4215 4068 13812 4213 4066 13813 4212 4065 13814 4207 4060 13815 4209 4062 13816 4216 4069 13817 4207 4060 13818 4216 4069 13819 4217 4070 13820 4207 4060 13821 4217 4070 13822 4218 4071 13823 4219 4072 13824 4220 4073 13825 4221 4074 13826 4222 4075 13827 4221 4074 13828 4223 4076 13829 4222 4075 13830 4219 4072 13831 4221 4074 13832 4222 4075 13833 4223 4076 13834 4224 4077 13835 4225 4078 13836 4224 4077 13837 4226 4079 13838 4225 4078 13839 4222 4075 13840 4224 4077 13841 4227 4080 13842 4226 4079 13843 4228 4081 13844 4227 4080 13845 4225 4078 13846 4226 4079 13847 4227 4080 13848 4228 4081 13849 4229 4082 13850 4230 4083 13851 4229 4082 13852 4231 4084 13853 4230 4083 13854 4227 4080 13855 4229 4082 13856 4232 4085 13857 4231 4084 13858 4233 4086 13859 4232 4085 13860 4230 4083 13861 4231 4084 13862 4028 3879 13863 4234 4087 13864 4022 3873 13865 4235 4088 13866 4233 4086 13867 4236 4089 13868 4235 4088 13869 4232 4085 13870 4233 4086 13871 4237 4090 13872 4235 4088 13873 4236 4089 13874 4238 4091 13875 4239 4092 13876 4240 4093 13877 4241 4094 13878 4238 4091 13879 4240 4093 13880 4242 4095 13881 4219 4072 13882 4222 4075 13883 4243 4096 13884 4222 4075 13885 4225 4078 13886 4243 4096 13887 4242 4095 13888 4222 4075 13889 4244 4097 13890 4225 4078 13891 4227 4080 13892 4244 4097 13893 4243 4096 13894 4225 4078 13895 4245 4098 13896 4227 4080 13897 4230 4083 13898 4245 4098 13899 4244 4097 13900 4227 4080 13901 4246 4099 13902 4230 4083 13903 4232 4085 13904 4246 4099 13905 4245 4098 13906 4230 4083 13907 4247 4100 13908 4232 4085 13909 4235 4088 13910 4247 4100 13911 4246 4099 13912 4232 4085 13913 4247 4100 13914 4235 4088 13915 4237 4090 13916 4248 4101 13917 4247 4100 13918 4237 4090 13919 4249 4102 13920 4250 4103 13921 4239 4092 13922 4249 4102 13923 4239 4092 13924 4251 4104 13925 4238 4091 13926 4251 4104 13927 4239 4092 13928 4252 4105 13929 4253 4105 13930 4254 4105 13931 4255 4106 13932 4211 4064 13933 4210 4063 13934 4256 4107 13935 4257 4107 13936 4253 4107 13937 4258 4108 13938 4253 4108 13939 4252 4108 13940 4259 4109 13941 4260 4109 13942 4253 4109 13943 4261 4110 13944 4253 4110 13945 4260 4110 13946 4262 4111 13947 4259 4111 13948 4253 4111 13949 4263 4112 13950 4262 4112 13951 4253 4112 13952 4258 4113 13953 4263 4113 13954 4253 4113 13955 4261 4114 13956 4264 4114 13957 4253 4114 13958 4265 4115 13959 4253 4115 13960 4264 4115 13961 4265 4116 13962 4266 4116 13963 4253 4116 13964 4267 4117 13965 4253 4117 13966 4266 4117 13967 4267 4118 13968 4256 4118 13969 4253 4118 13970 4268 4119 13971 4254 4119 13972 4269 4119 13973 4268 4120 13974 4252 4120 13975 4254 4120 13976 4270 4121 13977 4269 4121 13978 4271 4121 13979 4270 4122 13980 4268 4122 13981 4269 4122 13982 4272 4123 13983 4271 4123 13984 4273 4123 13985 4272 4124 13986 4270 4124 13987 4271 4124 13988 4274 4125 13989 4273 4125 13990 4275 4125 13991 4274 4126 13992 4272 4126 13993 4273 4126 13994 4276 4127 13995 4275 4127 13996 4277 4127 13997 4276 4128 13998 4274 4128 13999 4275 4128 14000 4278 4129 14001 4279 4129 14002 4277 4129 14003 4276 4130 14004 4277 4130 14005 4279 4130 14006 4212 4065 14007 4214 4067 14008 4280 4131 14009 4281 4132 14010 4282 4132 14011 4257 4132 14012 4283 4133 14013 4281 4133 14014 4257 4133 14015 4256 4134 14016 4283 4134 14017 4257 4134 14018 4284 4135 14019 4285 4136 14020 4286 4137 14021 4284 4135 14022 4286 4137 14023 4287 4138 14024 4288 4139 14025 4289 4139 14026 4282 4139 14027 4215 4068 14028 4212 4065 14029 4290 4140 14030 4281 4141 14031 4288 4141 14032 4282 4141 14033 4291 4142 14034 4292 4142 14035 4289 4142 14036 4293 4143 14037 4290 4140 14038 4294 4144 14039 4288 4145 14040 4291 4145 14041 4289 4145 14042 4295 4146 14043 4215 4068 14044 4290 4140 14045 4293 4143 14046 4295 4146 14047 4290 4140 14048 4296 4147 14049 4297 4147 14050 4292 4147 14051 4298 4148 14052 4294 4144 14053 4299 4149 14054 4300 4150 14055 4296 4150 14056 4292 4150 14057 4291 4151 14058 4300 4151 14059 4292 4151 14060 4301 4152 14061 4293 4143 14062 4294 4144 14063 4298 4148 14064 4301 4152 14065 4294 4144 14066 4302 4153 14067 4303 4153 14068 4297 4153 14069 4304 4154 14070 4299 4149 14071 4305 4155 14072 4296 4156 14073 4302 4156 14074 4297 4156 14075 4306 4157 14076 4298 4148 14077 4299 4149 14078 4304 4154 14079 4306 4157 14080 4299 4149 14081 4307 4158 14082 4308 4158 14083 4303 4158 14084 4309 4159 14085 4305 4155 14086 4310 4160 14087 4302 4161 14088 4307 4161 14089 4303 4161 14090 4309 4159 14091 4304 4154 14092 4305 4155 14093 4307 4162 14094 4311 4162 14095 4308 4162 14096 4312 4163 14097 4313 4164 14098 4314 4165 14099 4315 4166 14100 4313 4164 14101 4312 4163 14102 4309 4159 14103 4310 4160 14104 4316 4167 14105 4312 4163 14106 4314 4165 14107 4317 4168 14108 4318 4169 14109 4319 4170 14110 4320 4171 14111 4321 4172 14112 4320 4171 14113 4322 4173 14114 4323 4174 14115 4318 4169 14116 4320 4171 14117 4324 4175 14118 4323 4174 14119 4320 4171 14120 4325 4176 14121 4324 4175 14122 4320 4171 14123 4321 4172 14124 4325 4176 14125 4320 4171 14126 4326 4177 14127 4322 4173 14128 4327 4178 14129 4328 4179 14130 4321 4172 14131 4322 4173 14132 4326 4177 14133 4328 4179 14134 4322 4173 14135 4329 4180 14136 4327 4178 14137 4330 4181 14138 4331 4182 14139 4326 4177 14140 4327 4178 14141 4329 4180 14142 4331 4182 14143 4327 4178 14144 4332 4183 14145 4330 4181 14146 4333 4184 14147 4334 4185 14148 4329 4180 14149 4330 4181 14150 4332 4183 14151 4334 4185 14152 4330 4181 14153 4335 4186 14154 4333 4184 14155 4336 4187 14156 4337 4188 14157 4332 4183 14158 4333 4184 14159 4335 4186 14160 4337 4188 14161 4333 4184 14162 4258 4189 14163 4252 4189 14164 4281 4189 14165 4338 4190 14166 4339 4191 14167 4340 4192 14168 4258 4193 14169 4281 4193 14170 4341 4193 14171 4342 4194 14172 4341 4194 14173 4281 4194 14174 4343 4195 14175 4342 4195 14176 4281 4195 14177 4344 4196 14178 4343 4196 14179 4281 4196 14180 4345 4197 14181 4344 4197 14182 4281 4197 14183 4346 4198 14184 4345 4198 14185 4281 4198 14186 4347 4199 14187 4346 4199 14188 4281 4199 14189 4283 4200 14190 4347 4200 14191 4281 4200 14192 4348 4201 14193 4339 4191 14194 4338 4190 14195 4335 4186 14196 4336 4187 14197 4349 4202 14198 4350 4203 14199 4351 4204 14200 4352 4205 14201 4353 4206 14202 4352 4205 14203 4354 4207 14204 4355 4208 14205 4350 4203 14206 4352 4205 14207 4353 4206 14208 4355 4208 14209 4352 4205 14210 4356 4209 14211 4354 4207 14212 4357 4210 14213 4356 4209 14214 4353 4206 14215 4354 4207 14216 4358 4211 14217 4357 4210 14218 4359 4212 14219 4358 4211 14220 4356 4209 14221 4357 4210 14222 4360 4213 14223 4359 4212 14224 4285 4136 14225 4360 4213 14226 4358 4211 14227 4359 4212 14228 4284 4135 14229 4360 4213 14230 4285 4136 14231 4342 4214 14232 4361 4214 14233 4341 4214 14234 4362 4215 14235 4363 4215 14236 4364 4215 14237 4369 4216 14238 4370 4216 14239 4371 4216 14240 4408 4217 14241 4409 4217 14242 4410 4217 14243 4411 4218 14244 4412 4218 14245 4413 4218 14246 4424 4219 14247 4425 4219 14248 4426 4219 14249 4434 4220 14250 4435 4220 14251 4436 4220 14252 4437 4221 14253 4436 4221 14254 4435 4221 14255 4441 4222 14256 4442 4222 14257 4443 4222 14258 4441 4223 14259 4444 4223 14260 4442 4223 14261 4445 4224 14262 4446 4224 14263 4444 4224 14264 4441 4225 14265 4445 4225 14266 4444 4225 14267 4447 4226 14268 4448 4226 14269 4446 4226 14270 4445 4227 14271 4447 4227 14272 4446 4227 14273 4449 4228 14274 4450 4228 14275 4448 4228 14276 4447 4229 14277 4449 4229 14278 4448 4229 14279 4451 4230 14280 4452 4230 14281 4450 4230 14282 4449 4231 14283 4451 4231 14284 4450 4231 14285 4453 4232 14286 4454 4232 14287 4452 4232 14288 4451 4233 14289 4453 4233 14290 4452 4233 14291 4455 4234 14292 4456 4234 14293 4454 4234 14294 4453 4235 14295 4455 4235 14296 4454 4235 14297 4457 4236 14298 4458 4236 14299 4456 4236 14300 4455 4237 14301 4457 4237 14302 4456 4237 14303 4457 4238 14304 4459 4238 14305 4458 4238 14306 4483 4239 14307 4484 4240 14308 4485 4241 14309 4486 4242 14310 4487 4243 14311 4488 4244 14312 4489 4245 14313 4483 4239 14314 4485 4241 14315 4490 4246 14316 4489 4245 14317 4485 4241 14318 4491 4247 14319 4487 4243 14320 4486 4242 14321 4492 4248 14322 4493 4248 14323 4494 4248 14324 4491 4247 14325 4486 4242 14326 4495 4249 14327 4491 4247 14328 4495 4249 14329 4496 4250 14330 4497 4251 14331 4496 4250 14332 4498 4252 14333 4491 4247 14334 4496 4250 14335 4497 4251 14336 4497 4251 14337 4498 4252 14338 4499 4253 14339 4500 4254 14340 4499 4253 14341 4501 4255 14342 4497 4251 14343 4499 4253 14344 4500 4254 14345 4500 4254 14346 4501 4255 14347 4502 4256 14348 4503 4257 14349 4502 4256 14350 4504 4258 14351 4500 4254 14352 4502 4256 14353 4503 4257 14354 4505 4259 14355 4504 4258 14356 4506 4260 14357 4503 4257 14358 4504 4258 14359 4505 4259 14360 4505 4259 14361 4506 4260 14362 4507 4261 14363 4508 4262 14364 4507 4261 14365 4509 4263 14366 4505 4259 14367 4507 4261 14368 4508 4262 14369 4508 4262 14370 4509 4263 14371 4510 4264 14372 4508 4262 14373 4510 4264 14374 4511 4265 14375 4512 4266 14376 4513 4267 14377 4514 4268 14378 4515 4269 14379 4516 4270 14380 4512 4266 14381 4514 4268 14382 4515 4269 14383 4512 4266 14384 4516 4270 14385 4517 4271 14386 4512 4266 14387 4518 4272 14388 4512 4266 14389 4517 4271 14390 4519 4273 14391 4520 4273 14392 4521 4273 14393 4522 4274 14394 4523 4275 14395 4524 4276 14396 4525 4277 14397 4526 4277 14398 4527 4277 14399 4528 4278 14400 4522 4274 14401 4524 4276 14402 4529 4279 14403 4530 4280 14404 4522 4274 14405 4531 4281 14406 4532 4281 14407 4533 4281 14408 4534 4282 14409 4529 4279 14410 4522 4274 14411 4535 4283 14412 4534 4282 14413 4522 4274 14414 4528 4278 14415 4535 4283 14416 4522 4274 14417 4536 4284 14418 4537 4284 14419 4538 4284 14420 4624 4285 14421 4625 4286 14422 4626 4287 14423 4624 4285 14424 4627 4288 14425 4625 4286 14426 4628 4289 14427 4626 4287 14428 4629 4290 14429 4630 4291 14430 4624 4285 14431 4626 4287 14432 4628 4289 14433 4630 4291 14434 4626 4287 14435 4631 4292 14436 4629 4290 14437 4632 4293 14438 4631 4292 14439 4628 4289 14440 4629 4290 14441 4633 4294 14442 4631 4292 14443 4632 4293 14444 4634 4295 14445 4633 4294 14446 4632 4293 14447 4635 4296 14448 4636 4297 14449 4637 4298 14450 4638 4299 14451 4637 4298 14452 4639 4300 14453 4638 4299 14454 4635 4296 14455 4637 4298 14456 4638 4299 14457 4639 4300 14458 4640 4301 14459 4641 4302 14460 4640 4301 14461 4642 4303 14462 4641 4302 14463 4638 4299 14464 4640 4301 14465 4643 4304 14466 4642 4303 14467 4644 4305 14468 4643 4304 14469 4641 4302 14470 4642 4303 14471 4645 4306 14472 4644 4305 14473 4646 4307 14474 4645 4306 14475 4643 4304 14476 4644 4305 14477 4647 4308 14478 4635 4296 14479 4638 4299 14480 4648 4309 14481 4638 4299 14482 4641 4302 14483 4648 4309 14484 4647 4308 14485 4638 4299 14486 4649 4310 14487 4641 4302 14488 4643 4304 14489 4649 4310 14490 4648 4309 14491 4641 4302 14492 4650 4311 14493 4643 4304 14494 4645 4306 14495 4650 4311 14496 4649 4310 14497 4643 4304 14498 4651 4312 14499 4652 4312 14500 4653 4312 14501 4654 4313 14502 4655 4314 14503 4656 4315 14504 4657 4316 14505 4658 4317 14506 4659 4318 14507 4654 4313 14508 4656 4315 14509 4660 4319 14510 4654 4313 14511 4660 4319 14512 4661 4320 14513 4654 4313 14514 4661 4320 14515 4662 4321 14516 4654 4313 14517 4662 4321 14518 4663 4322 14519 4664 4323 14520 4665 4324 14521 4666 4325 14522 4657 4316 14523 4659 4318 14524 4667 4326 14525 4668 4327 14526 4669 4328 14527 4670 4329 14528 4671 4330 14529 4666 4325 14530 4672 4331 14531 4673 4332 14532 4664 4323 14533 4666 4325 14534 4673 4332 14535 4666 4325 14536 4671 4330 14537 4674 4333 14538 4672 4331 14539 4675 4334 14540 4671 4330 14541 4672 4331 14542 4674 4333 14543 4676 4335 14544 4675 4334 14545 4677 4336 14546 4674 4333 14547 4675 4334 14548 4676 4335 14549 4678 4337 14550 4677 4336 14551 4679 4338 14552 4676 4335 14553 4677 4336 14554 4678 4337 14555 4680 4339 14556 4679 4338 14557 4681 4340 14558 4678 4337 14559 4679 4338 14560 4680 4339 14561 4680 4339 14562 4681 4340 14563 4682 4341 14564 4657 4316 14565 4667 4326 14566 4683 4342 14567 4668 4327 14568 4684 4343 14569 4669 4328 14570 4685 4344 14571 4657 4316 14572 4683 4342 14573 4686 4345 14574 4687 4346 14575 4688 4347 14576 4689 4348 14577 4684 4343 14578 4668 4327 14579 4690 4349 14580 4691 4350 14581 4692 4351 14582 4693 4352 14583 4687 4346 14584 4686 4345 14585 4694 4353 14586 4695 4354 14587 4696 4355 14588 4694 4353 14589 4697 4356 14590 4695 4354 14591 4698 4357 14592 4699 4358 14593 4700 4359 14594 4701 4360 14595 4702 4361 14596 4703 4362 14597 4704 4363 14598 4698 4357 14599 4700 4359 14600 4705 4364 14601 4706 4365 14602 4707 4366 14603 4705 4364 14604 4707 4366 14605 4708 4367 14606 4701 4360 14607 4709 4368 14608 4702 4361 14609 4710 4369 14610 4711 4370 14611 4699 4358 14612 4712 4371 14613 4703 4362 14614 4713 4372 14615 4698 4357 14616 4710 4369 14617 4699 4358 14618 4712 4371 14619 4701 4360 14620 4703 4362 14621 4714 4373 14622 4715 4374 14623 4711 4370 14624 4716 4375 14625 4713 4372 14626 4717 4376 14627 4710 4369 14628 4714 4373 14629 4711 4370 14630 4716 4375 14631 4712 4371 14632 4713 4372 14633 4689 4348 14634 4668 4327 14635 4715 4374 14636 4673 4332 14637 4717 4376 14638 4664 4323 14639 4714 4373 14640 4689 4348 14641 4715 4374 14642 4673 4332 14643 4716 4375 14644 4717 4376 14645 4718 4377 14646 4692 4351 14647 4719 4378 14648 4718 4377 14649 4690 4349 14650 4692 4351 14651 4720 4379 14652 4719 4378 14653 4721 4380 14654 4718 4377 14655 4719 4378 14656 4720 4379 14657 4722 4381 14658 4721 4380 14659 4723 4382 14660 4724 4383 14661 4721 4380 14662 4722 4381 14663 4720 4379 14664 4721 4380 14665 4724 4383 14666 4704 4363 14667 4725 4384 14668 4698 4357 14669 4726 4385 14670 4723 4382 14671 4727 4386 14672 4722 4381 14673 4723 4382 14674 4726 4385 14675 4705 4364 14676 4728 4387 14677 4706 4365 14678 4729 4388 14679 4728 4387 14680 4705 4364 14681 4730 4389 14682 4731 4390 14683 4732 4391 14684 4733 4392 14685 4734 4393 14686 4731 4390 14687 4735 4394 14688 4733 4392 14689 4731 4390 14690 4730 4389 14691 4735 4394 14692 4731 4390 14693 4736 4395 14694 4732 4391 14695 4737 4396 14696 4736 4395 14697 4730 4389 14698 4732 4391 14699 4738 4397 14700 4737 4396 14701 4739 4398 14702 4738 4397 14703 4736 4395 14704 4737 4396 14705 4740 4399 14706 4741 4400 14707 4739 4398 14708 4742 4401 14709 4739 4398 14710 4741 4400 14711 4743 4402 14712 4740 4399 14713 4739 4398 14714 4744 4403 14715 4743 4402 14716 4739 4398 14717 4745 4404 14718 4744 4403 14719 4739 4398 14720 4746 4405 14721 4745 4404 14722 4739 4398 14723 4747 4406 14724 4746 4405 14725 4739 4398 14726 4748 4407 14727 4747 4406 14728 4739 4398 14729 4749 4408 14730 4748 4407 14731 4739 4398 14732 4742 4401 14733 4738 4397 14734 4739 4398 14735 4750 4409 14736 4751 4410 14737 4752 4411 14738 4753 4412 14739 4742 4401 14740 4741 4400 14741 4750 4409 14742 4754 4413 14743 4751 4410 14744 4755 4414 14745 4752 4411 14746 4756 4415 14747 4750 4409 14748 4752 4411 14749 4755 4414 14750 4757 4416 14751 4756 4415 14752 4758 4417 14753 4755 4414 14754 4756 4415 14755 4757 4416 14756 4759 4418 14757 4758 4417 14758 4760 4419 14759 4757 4416 14760 4758 4417 14761 4759 4418 14762 4761 4420 14763 4760 4419 14764 4762 4421 14765 4759 4418 14766 4760 4419 14767 4761 4420 14768 4761 4420 14769 4762 4421 14770 4763 4422 14771 4764 4423 14772 4763 4422 14773 4765 4424 14774 4761 4420 14775 4763 4422 14776 4764 4423 14777 4766 4425 14778 4765 4424 14779 4767 4426 14780 4764 4423 14781 4765 4424 14782 4766 4425 14783 4766 4425 14784 4767 4426 14785 4768 4427 14786 4769 4428 14787 4770 4429 14788 4771 4430 14789 4769 4428 14790 4772 4431 14791 4770 4429 14792 4769 4428 14793 4771 4430 14794 4773 4432 14795 4774 4433 14796 4735 4394 14797 4730 4389 14798 4775 4434 14799 4773 4432 14800 4776 4435 14801 4775 4434 14802 4769 4428 14803 4773 4432 14804 4705 4364 14805 4730 4389 14806 4736 4395 14807 4708 4367 14808 4774 4433 14809 4730 4389 14810 4705 4364 14811 4708 4367 14812 4730 4389 14813 4777 4436 14814 4736 4395 14815 4738 4397 14816 4777 4436 14817 4705 4364 14818 4736 4395 14819 4778 4437 14820 4738 4397 14821 4742 4401 14822 4778 4437 14823 4777 4436 14824 4738 4397 14825 4779 4438 14826 4780 4439 14827 4742 4401 14828 4781 4440 14829 4742 4401 14830 4780 4439 14831 4782 4441 14832 4779 4438 14833 4742 4401 14834 4783 4442 14835 4782 4441 14836 4742 4401 14837 4784 4443 14838 4783 4442 14839 4742 4401 14840 4785 4444 14841 4784 4443 14842 4742 4401 14843 4786 4445 14844 4785 4444 14845 4742 4401 14846 4753 4412 14847 4786 4445 14848 4742 4401 14849 4781 4440 14850 4778 4437 14851 4742 4401 14852 4787 4446 14853 4788 4447 14854 4789 4448 14855 4790 4449 14856 4781 4440 14857 4780 4439 14858 4791 4450 14859 4792 4451 14860 4788 4447 14861 4791 4450 14862 4788 4447 14863 4787 4446 14864 4793 4452 14865 4789 4448 14866 4794 4453 14867 4787 4446 14868 4789 4448 14869 4793 4452 14870 4793 4452 14871 4794 4453 14872 4795 4454 14873 4796 4455 14874 4795 4454 14875 4797 4456 14876 4793 4452 14877 4795 4454 14878 4796 4455 14879 4798 4457 14880 4797 4456 14881 4799 4458 14882 4796 4455 14883 4797 4456 14884 4798 4457 14885 4800 4459 14886 4799 4458 14887 4801 4460 14888 4798 4457 14889 4799 4458 14890 4800 4459 14891 4802 4461 14892 4801 4460 14893 4754 4413 14894 4800 4459 14895 4801 4460 14896 4802 4461 14897 4802 4461 14898 4754 4413 14899 4750 4409 14900 4701 4360 14901 4776 4435 14902 4709 4368 14903 4701 4360 14904 4775 4434 14905 4776 4435 14906 4803 4462 14907 4705 4364 14908 4777 4436 14909 4804 4463 14910 4729 4388 14911 4705 4364 14912 4805 4464 14913 4804 4463 14914 4705 4364 14915 4806 4465 14916 4805 4464 14917 4705 4364 14918 4803 4462 14919 4806 4465 14920 4705 4364 14921 4807 4466 14922 4777 4436 14923 4778 4437 14924 4807 4466 14925 4803 4462 14926 4777 4436 14927 4808 4467 14928 4778 4437 14929 4781 4440 14930 4808 4467 14931 4807 4466 14932 4778 4437 14933 4809 4468 14934 4810 4469 14935 4781 4440 14936 4811 4470 14937 4781 4440 14938 4810 4469 14939 4812 4471 14940 4809 4468 14941 4781 4440 14942 4813 4472 14943 4812 4471 14944 4781 4440 14945 4814 4473 14946 4813 4472 14947 4781 4440 14948 4815 4474 14949 4814 4473 14950 4781 4440 14951 4816 4475 14952 4815 4474 14953 4781 4440 14954 4817 4476 14955 4816 4475 14956 4781 4440 14957 4818 4477 14958 4817 4476 14959 4781 4440 14960 4790 4449 14961 4818 4477 14962 4781 4440 14963 4811 4470 14964 4808 4467 14965 4781 4440 14966 4819 4478 14967 4820 4479 14968 4821 4480 14969 4822 4481 14970 4811 4470 14971 4810 4469 14972 4823 4482 14973 4822 4481 14974 4810 4469 14975 4824 4483 14976 4823 4482 14977 4810 4469 14978 4825 4484 14979 4824 4483 14980 4810 4469 14981 4826 4485 14982 4825 4484 14983 4810 4469 14984 4827 4486 14985 4826 4485 14986 4810 4469 14987 4828 4487 14988 4827 4486 14989 4810 4469 14990 4829 4488 14991 4828 4487 14992 4810 4469 14993 4819 4478 14994 4830 4489 14995 4820 4479 14996 4831 4490 14997 4821 4480 14998 4832 4491 14999 4819 4478 15000 4821 4480 15001 4831 4490 15002 4833 4492 15003 4832 4491 15004 4834 4493 15005 4831 4490 15006 4832 4491 15007 4833 4492 15008 4835 4494 15009 4834 4493 15010 4836 4495 15011 4833 4492 15012 4834 4493 15013 4835 4494 15014 4835 4494 15015 4836 4495 15016 4837 4496 15017 4838 4497 15018 4837 4496 15019 4839 4498 15020 4835 4494 15021 4837 4496 15022 4838 4497 15023 4840 4499 15024 4839 4498 15025 4841 4500 15026 4838 4497 15027 4839 4498 15028 4840 4499 15029 4840 4499 15030 4841 4500 15031 4842 4501 15032 4843 4502 15033 4842 4501 15034 4792 4451 15035 4840 4499 15036 4842 4501 15037 4843 4502 15038 4843 4502 15039 4792 4451 15040 4791 4450 15041 4722 4381 15042 4726 4385 15043 4844 4503 15044 4722 4381 15045 4844 4503 15046 4845 4504 15047 4846 4505 15048 4845 4504 15049 4847 4506 15050 4722 4381 15051 4845 4504 15052 4846 4505 15053 4848 4507 15054 4849 4508 15055 4850 4509 15056 4846 4505 15057 4847 4506 15058 4851 4510 15059 4852 4511 15060 4853 4512 15061 4854 4513 15062 4852 4511 15063 4854 4513 15064 4855 4514 15065 4856 4515 15066 4850 4509 15067 4857 4516 15068 4858 4517 15069 4859 4517 15070 4860 4517 15071 4861 4518 15072 4848 4507 15073 4850 4509 15074 4856 4515 15075 4861 4518 15076 4850 4509 15077 4862 4519 15078 4857 4516 15079 4863 4520 15080 4862 4519 15081 4856 4515 15082 4857 4516 15083 4811 4470 15084 4864 4521 15085 4808 4467 15086 4865 4522 15087 4863 4520 15088 4866 4523 15089 4865 4522 15090 4862 4519 15091 4863 4520 15092 4867 4524 15093 4868 4524 15094 4869 4524 15095 4865 4522 15096 4866 4523 15097 4870 4525 15098 4871 4526 15099 4872 4527 15100 4873 4528 15101 4874 4529 15102 4873 4528 15103 4875 4530 15104 4874 4529 15105 4871 4526 15106 4873 4528 15107 4874 4529 15108 4875 4530 15109 4876 4531 15110 4877 4532 15111 4876 4531 15112 4878 4533 15113 4874 4529 15114 4876 4531 15115 4877 4532 15116 4879 4534 15117 4880 4535 15118 4828 4487 15119 4881 4536 15120 4878 4533 15121 4882 4537 15122 4829 4488 15123 4879 4534 15124 4828 4487 15125 4877 4532 15126 4878 4533 15127 4881 4536 15128 4883 4538 15129 4884 4539 15130 4880 4535 15131 4885 4540 15132 4882 4537 15133 4886 4541 15134 4879 4534 15135 4883 4538 15136 4880 4535 15137 4881 4536 15138 4882 4537 15139 4885 4540 15140 4887 4542 15141 4886 4541 15142 4888 4543 15143 4885 4540 15144 4886 4541 15145 4887 4542 15146 4887 4542 15147 4888 4543 15148 4889 4544 15149 4890 4545 15150 4889 4544 15151 4830 4489 15152 4887 4542 15153 4889 4544 15154 4890 4545 15155 4890 4545 15156 4830 4489 15157 4819 4478 15158 4891 4546 15159 4772 4431 15160 4769 4428 15161 4891 4546 15162 4892 4547 15163 4772 4431 15164 4893 4548 15165 4769 4428 15166 4775 4434 15167 4893 4548 15168 4891 4546 15169 4769 4428 15170 4712 4371 15171 4775 4434 15172 4701 4360 15173 4712 4371 15174 4893 4548 15175 4775 4434 15176 4894 4549 15177 4892 4547 15178 4891 4546 15179 4894 4549 15180 4895 4550 15181 4892 4547 15182 4896 4551 15183 4891 4546 15184 4893 4548 15185 4896 4551 15186 4894 4549 15187 4891 4546 15188 4897 4552 15189 4893 4548 15190 4712 4371 15191 4897 4552 15192 4896 4551 15193 4893 4548 15194 4716 4375 15195 4897 4552 15196 4712 4371 15197 4678 4337 15198 4895 4550 15199 4894 4549 15200 4678 4337 15201 4680 4339 15202 4895 4550 15203 4676 4335 15204 4894 4549 15205 4896 4551 15206 4676 4335 15207 4678 4337 15208 4894 4549 15209 4674 4333 15210 4896 4551 15211 4897 4552 15212 4674 4333 15213 4676 4335 15214 4896 4551 15215 4671 4330 15216 4897 4552 15217 4716 4375 15218 4671 4330 15219 4674 4333 15220 4897 4552 15221 4673 4332 15222 4671 4330 15223 4716 4375 15224 4898 4553 15225 4899 4554 15226 4900 4555 15227 4901 4556 15228 4902 4557 15229 4903 4558 15230 4904 4559 15231 4898 4553 15232 4900 4555 15233 4905 4560 15234 4906 4561 15235 4907 4562 15236 4908 4563 15237 4905 4560 15238 4907 4562 15239 4898 4553 15240 4909 4564 15241 4899 4554 15242 4910 4565 15243 4903 4558 15244 4911 4566 15245 4910 4565 15246 4901 4556 15247 4903 4558 15248 4912 4567 15249 4913 4568 15250 4909 4564 15251 4914 4569 15252 4911 4566 15253 4915 4570 15254 4898 4553 15255 4912 4567 15256 4909 4564 15257 4910 4565 15258 4911 4566 15259 4914 4569 15260 4916 4571 15261 4851 4510 15262 4913 4568 15263 4917 4572 15264 4915 4570 15265 4853 4512 15266 4912 4567 15267 4916 4571 15268 4913 4568 15269 4914 4569 15270 4915 4570 15271 4917 4572 15272 4916 4571 15273 4846 4505 15274 4851 4510 15275 4917 4572 15276 4853 4512 15277 4852 4511 15278 4724 4383 15279 4846 4505 15280 4916 4571 15281 4724 4383 15282 4722 4381 15283 4846 4505 15284 4720 4379 15285 4916 4571 15286 4912 4567 15287 4720 4379 15288 4724 4383 15289 4916 4571 15290 4718 4377 15291 4912 4567 15292 4898 4553 15293 4718 4377 15294 4720 4379 15295 4912 4567 15296 4718 4377 15297 4898 4553 15298 4904 4559 15299 4718 4377 15300 4904 4559 15301 4690 4349 15302 4918 4573 15303 4686 4345 15304 4906 4561 15305 4905 4560 15306 4918 4573 15307 4906 4561 15308 4918 4573 15309 4693 4352 15310 4686 4345 15311 4694 4353 15312 4696 4355 15313 4919 4574 15314 4920 4575 15315 4921 4575 15316 4922 4575 15317 4923 4576 15318 4924 4577 15319 4905 4560 15320 4908 4563 15321 4923 4576 15322 4905 4560 15323 4925 4578 15324 4926 4578 15325 4859 4578 15326 4927 4579 15327 4928 4580 15328 4924 4577 15329 4929 4581 15330 4927 4579 15331 4924 4577 15332 4930 4582 15333 4929 4581 15334 4924 4577 15335 4931 4583 15336 4930 4582 15337 4924 4577 15338 4923 4576 15339 4931 4583 15340 4924 4577 15341 4932 4584 15342 4933 4585 15343 4928 4580 15344 4934 4586 15345 4932 4584 15346 4928 4580 15347 4935 4587 15348 4936 4587 15349 4926 4587 15350 4937 4588 15351 4934 4586 15352 4928 4580 15353 4927 4579 15354 4937 4588 15355 4928 4580 15356 4938 4589 15357 4939 4590 15358 4933 4585 15359 4940 4591 15360 4938 4589 15361 4933 4585 15362 4932 4584 15363 4940 4591 15364 4933 4585 15365 4941 4592 15366 4942 4593 15367 4939 4590 15368 4943 4594 15369 4944 4595 15370 4945 4596 15371 4938 4589 15372 4941 4592 15373 4939 4590 15374 4943 4594 15375 4946 4597 15376 4944 4595 15377 4941 4592 15378 4947 4598 15379 4942 4593 15380 4943 4594 15381 4945 4596 15382 4948 4599 15383 4949 4600 15384 4950 4601 15385 4951 4602 15386 4952 4603 15387 4953 4604 15388 4954 4605 15389 4955 4606 15390 4950 4601 15391 4949 4600 15392 4956 4607 15393 4957 4608 15394 4958 4609 15395 4956 4607 15396 4959 4610 15397 4957 4608 15398 4960 4611 15399 4961 4612 15400 4962 4613 15401 4963 4614 15402 4958 4609 15403 4964 4615 15404 4963 4614 15405 4956 4607 15406 4958 4609 15407 4965 4616 15408 4964 4615 15409 4966 4617 15410 4963 4614 15411 4964 4615 15412 4965 4616 15413 4967 4618 15414 4968 4619 15415 4969 4620 15416 4967 4618 15417 4970 4621 15418 4968 4619 15419 4971 4622 15420 4972 4622 15421 4973 4622 15422 4974 4623 15423 4969 4620 15424 4975 4624 15425 4967 4618 15426 4969 4620 15427 4974 4623 15428 4976 4625 15429 4977 4626 15430 4978 4627 15431 4976 4625 15432 4979 4628 15433 4977 4626 15434 4976 4625 15435 4978 4627 15436 4980 4629 15437 4981 4630 15438 4980 4629 15439 4982 4631 15440 4981 4630 15441 4976 4625 15442 4980 4629 15443 4981 4630 15444 4982 4631 15445 4983 4632 15446 4984 4633 15447 4983 4632 15448 4985 4634 15449 4981 4630 15450 4983 4632 15451 4984 4633 15452 4986 4635 15453 4987 4636 15454 4901 4556 15455 4973 4637 15456 4936 4637 15457 4935 4637 15458 4910 4565 15459 4986 4635 15460 4901 4556 15461 4952 4603 15462 4988 4638 15463 4953 4604 15464 4952 4603 15465 4989 4639 15466 4988 4638 15467 4990 4640 15468 4991 4641 15469 4992 4642 15470 4993 4643 15471 4994 4644 15472 4995 4644 15473 4996 4645 15474 4990 4640 15475 4992 4642 15476 4997 4646 15477 4996 4645 15478 4992 4642 15479 4998 4647 15480 4997 4646 15481 4992 4642 15482 4999 4648 15483 4998 4647 15484 4992 4642 15485 5000 4649 15486 4999 4648 15487 4992 4642 15488 5001 4650 15489 5000 4649 15490 4992 4642 15491 5002 4651 15492 5001 4650 15493 4992 4642 15494 5003 4652 15495 5002 4651 15496 4992 4642 15497 5004 4653 15498 5005 4654 15499 5006 4655 15500 5007 4656 15501 5008 4657 15502 5009 4658 15503 5010 4659 15504 5007 4656 15505 5009 4658 15506 5011 4660 15507 5012 4661 15508 5005 4654 15509 5013 4662 15510 5011 4660 15511 5005 4654 15512 5004 4653 15513 5013 4662 15514 5005 4654 15515 5004 4653 15516 5006 4655 15517 5014 4663 15518 5015 4664 15519 5016 4665 15520 5017 4666 15521 5018 4667 15522 5019 4668 15523 5020 4669 15524 5021 4670 15525 5018 4667 15526 5020 4669 15527 5022 4671 15528 5017 4666 15529 5023 4672 15530 5024 4673 15531 5015 4664 15532 5017 4666 15533 5022 4671 15534 5024 4673 15535 5017 4666 15536 5025 4674 15537 5023 4672 15538 5026 4675 15539 5022 4671 15540 5023 4672 15541 5025 4674 15542 5027 4676 15543 5026 4675 15544 5028 4677 15545 5025 4674 15546 5026 4675 15547 5027 4676 15548 5029 4678 15549 5028 4677 15550 5030 4679 15551 5027 4676 15552 5028 4677 15553 5029 4678 15554 5029 4678 15555 5030 4679 15556 5031 4680 15557 5032 4681 15558 5033 4682 15559 4989 4639 15560 5034 4683 15561 5029 4678 15562 5031 4680 15563 4952 4603 15564 5035 4684 15565 4989 4639 15566 5032 4681 15567 4989 4639 15568 5035 4684 15569 4993 4643 15570 5036 4685 15571 5037 4686 15572 5038 4687 15573 5039 4688 15574 5040 4689 15575 5041 4690 15576 5039 4688 15577 5038 4687 15578 5042 4691 15579 5043 4692 15580 5036 4685 15581 5044 4693 15582 5040 4689 15583 5045 4694 15584 5046 4695 15585 5042 4691 15586 5036 4685 15587 4993 4643 15588 5046 4695 15589 5036 4685 15590 5038 4687 15591 5040 4689 15592 5044 4693 15593 5047 4696 15594 5048 4697 15595 5043 4692 15596 5049 4698 15597 5045 4694 15598 5050 4699 15599 5042 4691 15600 5047 4696 15601 5043 4692 15602 5044 4693 15603 5045 4694 15604 5049 4698 15605 5049 4698 15606 5050 4699 15607 5051 4700 15608 5052 4701 15609 5053 4702 15610 5054 4703 15611 5052 4701 15612 5055 4704 15613 5053 4702 15614 5056 4705 15615 5054 4703 15616 5057 4706 15617 5056 4705 15618 5052 4701 15619 5054 4703 15620 5058 4707 15621 5057 4706 15622 5008 4657 15623 5058 4707 15624 5056 4705 15625 5057 4706 15626 5007 4656 15627 5058 4707 15628 5008 4657 15629 5051 4700 15630 5059 4708 15631 5060 4709 15632 5049 4698 15633 5060 4709 15634 5061 4710 15635 5049 4698 15636 5051 4700 15637 5060 4709 15638 5044 4693 15639 5061 4710 15640 5062 4711 15641 5044 4693 15642 5049 4698 15643 5061 4710 15644 5038 4687 15645 5062 4711 15646 5063 4712 15647 5038 4687 15648 5044 4693 15649 5062 4711 15650 5041 4690 15651 5038 4687 15652 5063 4712 15653 5064 4713 15654 5055 4704 15655 5052 4701 15656 5065 4714 15657 5052 4701 15658 5056 4705 15659 5065 4714 15660 5064 4713 15661 5052 4701 15662 5066 4715 15663 5056 4705 15664 5058 4707 15665 5066 4715 15666 5065 4714 15667 5056 4705 15668 5067 4716 15669 5058 4707 15670 5007 4656 15671 5067 4716 15672 5066 4715 15673 5058 4707 15674 5010 4659 15675 5068 4717 15676 5007 4656 15677 5069 4718 15678 5007 4656 15679 5068 4717 15680 5069 4718 15681 5067 4716 15682 5007 4656 15683 5070 4719 15684 5071 4720 15685 5012 4661 15686 5069 4718 15687 5068 4717 15688 5072 4721 15689 5073 4722 15690 5074 4723 15691 5071 4720 15692 5070 4719 15693 5073 4722 15694 5071 4720 15695 5011 4660 15696 5070 4719 15697 5012 4661 15698 5075 4724 15699 5069 4718 15700 5072 4721 15701 5076 4725 15702 5077 4726 15703 5074 4723 15704 5073 4722 15705 5076 4725 15706 5074 4723 15707 5078 4727 15708 5064 4713 15709 5065 4714 15710 5078 4727 15711 5079 4728 15712 5064 4713 15713 5080 4729 15714 5065 4714 15715 5066 4715 15716 5080 4729 15717 5078 4727 15718 5065 4714 15719 5081 4730 15720 5066 4715 15721 5067 4716 15722 5081 4730 15723 5080 4729 15724 5066 4715 15725 5082 4731 15726 5067 4716 15727 5069 4718 15728 5083 4732 15729 5081 4730 15730 5067 4716 15731 5082 4731 15732 5083 4732 15733 5067 4716 15734 5084 4733 15735 5069 4718 15736 5075 4724 15737 5084 4733 15738 5082 4731 15739 5069 4718 15740 5084 4733 15741 5075 4724 15742 5085 4734 15743 5086 4735 15744 5087 4736 15745 5077 4726 15746 5088 4737 15747 5086 4735 15748 5077 4726 15749 5076 4725 15750 5088 4737 15751 5077 4726 15752 5089 4738 15753 5090 4739 15754 5091 4740 15755 5092 4741 15756 5093 4742 15757 5094 4743 15758 5095 4744 15759 5093 4742 15760 5092 4741 15761 5089 4738 15762 5091 4740 15763 5096 4745 15764 5097 4746 15765 5098 4747 15766 5099 4748 15767 5097 4746 15768 5099 4748 15769 5100 4749 15770 5101 4750 15771 5100 4749 15772 5102 4751 15773 5101 4750 15774 5097 4746 15775 5100 4749 15776 5103 4752 15777 5102 4751 15778 5104 4753 15779 5103 4752 15780 5101 4750 15781 5102 4751 15782 5103 4752 15783 5104 4753 15784 5105 4754 15785 5089 4738 15786 5105 4754 15787 5090 4739 15788 5089 4738 15789 5103 4752 15790 5105 4754 15791 5106 4755 15792 5094 4743 15793 5107 4756 15794 5106 4755 15795 5092 4741 15796 5094 4743 15797 5108 4757 15798 5107 4756 15799 5109 4758 15800 5108 4757 15801 5106 4755 15802 5107 4756 15803 5110 4759 15804 5109 4758 15805 5111 4760 15806 5110 4759 15807 5108 4757 15808 5109 4758 15809 5112 4761 15810 5111 4760 15811 5113 4762 15812 5112 4761 15813 5110 4759 15814 5111 4760 15815 5112 4761 15816 5113 4762 15817 5114 4763 15818 5115 4764 15819 5114 4763 15820 5116 4765 15821 5115 4764 15822 5112 4761 15823 5114 4763 15824 5018 4667 15825 5116 4765 15826 5019 4668 15827 5018 4667 15828 5115 4764 15829 5116 4765 15830 5117 4766 15831 5118 4767 15832 5119 4768 15833 5120 4769 15834 5119 4768 15835 5118 4767 15836 5121 4770 15837 5117 4766 15838 5119 4768 15839 5122 4771 15840 5123 4772 15841 5118 4767 15842 5124 4773 15843 5118 4767 15844 5123 4772 15845 5117 4766 15846 5122 4771 15847 5118 4767 15848 5124 4773 15849 5120 4769 15850 5118 4767 15851 5125 4774 15852 5126 4775 15853 5123 4772 15854 5127 4776 15855 5123 4772 15856 5126 4775 15857 5122 4771 15858 5125 4774 15859 5123 4772 15860 5127 4776 15861 5124 4773 15862 5123 4772 15863 5128 4777 15864 5129 4778 15865 5126 4775 15866 5130 4779 15867 5126 4775 15868 5129 4778 15869 5125 4774 15870 5128 4777 15871 5126 4775 15872 5131 4780 15873 5127 4776 15874 5126 4775 15875 5130 4779 15876 5131 4780 15877 5126 4775 15878 5132 4781 15879 5133 4782 15880 5129 4778 15881 5134 4783 15882 5129 4778 15883 5133 4782 15884 5128 4777 15885 5132 4781 15886 5129 4778 15887 5134 4783 15888 5130 4779 15889 5129 4778 15890 5135 4784 15891 5136 4785 15892 5133 4782 15893 5137 4786 15894 5133 4782 15895 5136 4785 15896 5132 4781 15897 5135 4784 15898 5133 4782 15899 5137 4786 15900 5134 4783 15901 5133 4782 15902 5138 4787 15903 5139 4788 15904 5136 4785 15905 5140 4789 15906 5136 4785 15907 5139 4788 15908 5135 4784 15909 5138 4787 15910 5136 4785 15911 5141 4790 15912 5137 4786 15913 5136 4785 15914 5140 4789 15915 5141 4790 15916 5136 4785 15917 5142 4791 15918 5139 4788 15919 5143 4792 15920 5142 4791 15921 5140 4789 15922 5139 4788 15923 5144 4793 15924 5145 4794 15925 5143 4792 15926 5146 4795 15927 5143 4792 15928 5145 4794 15929 5147 4796 15930 5142 4791 15931 5143 4792 15932 5146 4795 15933 5147 4796 15934 5143 4792 15935 5148 4797 15936 5149 4798 15937 5145 4794 15938 5150 4799 15939 5145 4794 15940 5149 4798 15941 5151 4800 15942 5148 4797 15943 5145 4794 15944 5144 4793 15945 5151 4800 15946 5145 4794 15947 5152 4801 15948 5146 4795 15949 5145 4794 15950 5150 4799 15951 5152 4801 15952 5145 4794 15953 5095 4744 15954 5092 4741 15955 5149 4798 15956 5153 4802 15957 5149 4798 15958 5092 4741 15959 5148 4797 15960 5095 4744 15961 5149 4798 15962 5153 4802 15963 5150 4799 15964 5149 4798 15965 5154 4803 15966 5092 4741 15967 5106 4755 15968 5155 4804 15969 5153 4802 15970 5092 4741 15971 5154 4803 15972 5155 4804 15973 5092 4741 15974 5156 4805 15975 5106 4755 15976 5108 4757 15977 5156 4805 15978 5154 4803 15979 5106 4755 15980 5157 4806 15981 5108 4757 15982 5110 4759 15983 5157 4806 15984 5156 4805 15985 5108 4757 15986 5158 4807 15987 5110 4759 15988 5112 4761 15989 5158 4807 15990 5157 4806 15991 5110 4759 15992 5159 4808 15993 5112 4761 15994 5115 4764 15995 5160 4809 15996 5158 4807 15997 5112 4761 15998 5159 4808 15999 5160 4809 16000 5112 4761 16001 5161 4810 16002 5115 4764 16003 5018 4667 16004 5161 4810 16005 5159 4808 16006 5115 4764 16007 5162 4811 16008 5018 4667 16009 5021 4670 16010 5162 4811 16011 5161 4810 16012 5018 4667 16013 5163 4812 16014 5162 4811 16015 5021 4670 16016 5089 4738 16017 5096 4745 16018 5164 4813 16019 5089 4738 16020 5164 4813 16021 5165 4814 16022 5166 4815 16023 5167 4816 16024 5168 4817 16025 5169 4818 16026 5168 4817 16027 5170 4819 16028 5169 4818 16029 5166 4815 16030 5168 4817 16031 5171 4820 16032 5170 4819 16033 5172 4821 16034 5171 4820 16035 5169 4818 16036 5170 4819 16037 5171 4820 16038 5172 4821 16039 5173 4822 16040 5174 4823 16041 5173 4822 16042 5175 4824 16043 5174 4823 16044 5171 4820 16045 5173 4822 16046 5174 4823 16047 5175 4824 16048 5176 4825 16049 5174 4823 16050 5176 4825 16051 5177 4826 16052 5178 4827 16053 5177 4826 16054 5179 4828 16055 5178 4827 16056 5174 4823 16057 5177 4826 16058 5178 4827 16059 5179 4828 16060 5180 4829 16061 5178 4827 16062 5180 4829 16063 5181 4830 16064 5178 4827 16065 5181 4830 16066 5182 4831 16067 5183 4832 16068 5182 4831 16069 5184 4833 16070 5183 4832 16071 5178 4827 16072 5182 4831 16073 5183 4832 16074 5184 4833 16075 5185 4834 16076 5183 4832 16077 5185 4834 16078 5186 4835 16079 5183 4832 16080 5186 4835 16081 5187 4836 16082 5183 4832 16083 5187 4836 16084 5188 4837 16085 5189 4838 16086 5188 4837 16087 5190 4839 16088 5189 4838 16089 5183 4832 16090 5188 4837 16091 5189 4838 16092 5190 4839 16093 5191 4840 16094 5189 4838 16095 5191 4840 16096 5192 4841 16097 5189 4838 16098 5192 4841 16099 5193 4842 16100 5194 4843 16101 5193 4842 16102 5195 4844 16103 5194 4843 16104 5189 4838 16105 5193 4842 16106 5194 4843 16107 5195 4844 16108 5196 4845 16109 5194 4843 16110 5196 4845 16111 5197 4846 16112 5194 4843 16113 5197 4846 16114 5198 4847 16115 5199 4848 16116 5194 4843 16117 5198 4847 16118 5200 4849 16119 5201 4850 16120 5202 4851 16121 5203 4852 16122 5202 4851 16123 5204 4853 16124 5203 4852 16125 5200 4849 16126 5202 4851 16127 5205 4854 16128 5204 4853 16129 5206 4855 16130 5205 4854 16131 5203 4852 16132 5204 4853 16133 5207 4856 16134 5206 4855 16135 5208 4857 16136 5207 4856 16137 5205 4854 16138 5206 4855 16139 5209 4858 16140 5208 4857 16141 5210 4859 16142 5209 4858 16143 5207 4856 16144 5208 4857 16145 5211 4860 16146 5212 4861 16147 5194 4843 16148 5213 4862 16149 5210 4859 16150 5214 4863 16151 5215 4864 16152 5211 4860 16153 5194 4843 16154 5216 4865 16155 5215 4864 16156 5194 4843 16157 5217 4866 16158 5216 4865 16159 5194 4843 16160 5199 4848 16161 5217 4866 16162 5194 4843 16163 5213 4862 16164 5209 4858 16165 5210 4859 16166 4955 4606 16167 5218 4867 16168 5219 4868 16169 5220 4869 16170 5213 4862 16171 5214 4863 16172 4962 4613 16173 5221 4870 16174 5222 4871 16175 4960 4611 16176 4962 4613 16177 5222 4871 16178 4955 4606 16179 4949 4600 16180 5218 4867 16181 5034 4683 16182 5223 4872 16183 5029 4678 16184 5224 4873 16185 5200 4849 16186 5203 4852 16187 5225 4874 16188 5203 4852 16189 5205 4854 16190 5225 4874 16191 5224 4873 16192 5203 4852 16193 5226 4875 16194 5205 4854 16195 5207 4856 16196 5226 4875 16197 5225 4874 16198 5205 4854 16199 5227 4876 16200 5207 4856 16201 5209 4858 16202 5227 4876 16203 5226 4875 16204 5207 4856 16205 5228 4877 16206 5209 4858 16207 5213 4862 16208 5228 4877 16209 5227 4876 16210 5209 4858 16211 5228 4877 16212 5213 4862 16213 5220 4869 16214 5229 4878 16215 5228 4877 16216 5220 4869 16217 4962 4613 16218 5230 4879 16219 5221 4870 16220 5231 4880 16221 5224 4873 16222 5225 4874 16223 5232 4881 16224 5225 4874 16225 5226 4875 16226 5232 4881 16227 5231 4880 16228 5225 4874 16229 5233 4882 16230 5226 4875 16231 5227 4876 16232 5233 4882 16233 5232 4881 16234 5226 4875 16235 5234 4883 16236 5227 4876 16237 5228 4877 16238 5234 4883 16239 5233 4882 16240 5227 4876 16241 5234 4883 16242 5228 4877 16243 5229 4878 16244 5235 4884 16245 5234 4883 16246 5229 4878 16247 5236 4885 16248 5237 4886 16249 5230 4879 16250 5236 4885 16251 5230 4879 16252 4962 4613 16253 5238 4887 16254 5231 4880 16255 5232 4881 16256 5239 4888 16257 5232 4881 16258 5233 4882 16259 5239 4888 16260 5238 4887 16261 5232 4881 16262 5240 4889 16263 5233 4882 16264 5234 4883 16265 5240 4889 16266 5239 4888 16267 5233 4882 16268 5241 4890 16269 5234 4883 16270 5235 4884 16271 5241 4890 16272 5240 4889 16273 5234 4883 16274 5242 4891 16275 5241 4890 16276 5235 4884 16277 5243 4892 16278 5244 4893 16279 5237 4886 16280 5243 4892 16281 5237 4886 16282 5236 4885 16283 5245 4894 16284 5238 4887 16285 5239 4888 16286 5246 4895 16287 5239 4888 16288 5240 4889 16289 5246 4895 16290 5245 4894 16291 5239 4888 16292 5247 4896 16293 5240 4889 16294 5241 4890 16295 5248 4897 16296 5246 4895 16297 5240 4889 16298 5247 4896 16299 5248 4897 16300 5240 4889 16301 5249 4898 16302 5241 4890 16303 5242 4891 16304 5249 4898 16305 5247 4896 16306 5241 4890 16307 5250 4899 16308 5249 4898 16309 5242 4891 16310 5251 4900 16311 5252 4901 16312 5244 4893 16313 5251 4900 16314 5244 4893 16315 5253 4902 16316 5254 4903 16317 5253 4902 16318 5244 4893 16319 5254 4903 16320 5244 4893 16321 5243 4892 16322 5255 4904 16323 5256 4905 16324 5257 4906 16325 5258 4907 16326 5257 4906 16327 5259 4908 16328 5258 4907 16329 5255 4904 16330 5257 4906 16331 5258 4907 16332 5259 4908 16333 5260 4909 16334 5261 4910 16335 5260 4909 16336 5262 4911 16337 5261 4910 16338 5258 4907 16339 5260 4909 16340 5263 4912 16341 5261 4910 16342 5262 4911 16343 5258 4907 16344 5264 4913 16345 5255 4904 16346 5265 4914 16347 5266 4915 16348 5264 4913 16349 5258 4907 16350 5265 4914 16351 5264 4913 16352 5267 4916 16353 5268 4917 16354 5266 4915 16355 5265 4914 16356 5267 4916 16357 5266 4915 16358 5267 4916 16359 5269 4918 16360 5268 4917 16361 5270 4919 16362 5269 4918 16363 5267 4916 16364 5270 4919 16365 5271 4920 16366 5269 4918 16367 5272 4921 16368 5267 4916 16369 5265 4914 16370 5272 4921 16371 5270 4919 16372 5267 4916 16373 5261 4910 16374 5265 4914 16375 5258 4907 16376 5261 4910 16377 5272 4921 16378 5265 4914 16379 5273 4922 16380 5271 4920 16381 5270 4919 16382 5274 4923 16383 5275 4924 16384 5271 4920 16385 5276 4925 16386 5274 4923 16387 5271 4920 16388 5277 4926 16389 5276 4925 16390 5271 4920 16391 5273 4922 16392 5277 4926 16393 5271 4920 16394 5278 4927 16395 5270 4919 16396 5272 4921 16397 5278 4927 16398 5273 4922 16399 5270 4919 16400 5279 4928 16401 5272 4921 16402 5261 4910 16403 5279 4928 16404 5278 4927 16405 5272 4921 16406 5280 4929 16407 5279 4928 16408 5261 4910 16409 5281 4930 16410 5280 4929 16411 5261 4910 16412 5282 4931 16413 5281 4930 16414 5261 4910 16415 5283 4932 16416 5282 4931 16417 5261 4910 16418 5284 4933 16419 5283 4932 16420 5261 4910 16421 5263 4912 16422 5284 4933 16423 5261 4910 16424 5285 4934 16425 5286 4935 16426 5287 4936 16427 5288 4937 16428 5289 4937 16429 5290 4937 16430 5285 4934 16431 5291 4938 16432 5286 4935 16433 5292 4939 16434 5287 4936 16435 5293 4940 16436 5292 4939 16437 5285 4934 16438 5287 4936 16439 5294 4941 16440 5293 4940 16441 5295 4942 16442 5294 4941 16443 5292 4939 16444 5293 4940 16445 5296 4943 16446 5295 4942 16447 5297 4944 16448 5298 4945 16449 5299 4946 16450 5295 4942 16451 5294 4941 16452 5295 4942 16453 5299 4946 16454 5298 4945 16455 5295 4942 16456 5296 4943 16457 5300 4947 16458 5301 4948 16459 5302 4949 16460 5303 4950 16461 5304 4951 16462 5305 4952 16463 5300 4947 16464 5306 4953 16465 5301 4948 16466 5307 4954 16467 5302 4949 16468 5308 4955 16469 5300 4947 16470 5302 4949 16471 5307 4954 16472 5307 4954 16473 5308 4955 16474 5309 4956 16475 5310 4957 16476 5309 4956 16477 5311 4958 16478 5307 4954 16479 5309 4956 16480 5310 4957 16481 5312 4959 16482 5313 4959 16483 5314 4959 16484 5315 4960 16485 5316 4961 16486 5317 4962 16487 5318 4963 16488 5316 4961 16489 5315 4960 16490 5315 4960 16491 5317 4962 16492 5319 4964 16493 5285 4934 16494 5319 4964 16495 5291 4938 16496 5285 4934 16497 5315 4960 16498 5319 4964 16499 5320 4965 16500 5321 4965 16501 5322 4965 16502 5323 4966 16503 5315 4960 16504 5324 4967 16505 5325 4968 16506 5315 4960 16507 5323 4966 16508 5326 4969 16509 5315 4960 16510 5325 4968 16511 5318 4963 16512 5315 4960 16513 5326 4969 16514 5327 4970 16515 5328 4971 16516 5329 4972 16517 5330 4973 16518 5331 4973 16519 5332 4973 16520 5333 4974 16521 5334 4975 16522 5328 4971 16523 4865 4522 16524 5335 4976 16525 5336 4977 16526 5333 4974 16527 5337 4978 16528 5334 4975 16529 5333 4974 16530 5328 4971 16531 5327 4970 16532 5338 4979 16533 5339 4979 16534 5340 4979 16535 4865 4522 16536 5341 4980 16537 5342 4981 16538 4865 4522 16539 5343 4982 16540 5341 4980 16541 4865 4522 16542 5342 4981 16543 5344 4983 16544 4865 4522 16545 5344 4983 16546 5345 4984 16547 4865 4522 16548 5345 4984 16549 5346 4985 16550 4865 4522 16551 5346 4985 16552 5335 4976 16553 4865 4522 16554 4870 4525 16555 5347 4986 16556 4865 4522 16557 5347 4986 16558 5348 4987 16559 4865 4522 16560 5348 4987 16561 5349 4988 16562 4865 4522 16563 5349 4988 16564 5343 4982 16565 5350 4989 16566 4766 4425 16567 4768 4427 16568 5351 4990 16569 5350 4989 16570 4768 4427 16571 5352 4991 16572 4764 4423 16573 4766 4425 16574 5350 4989 16575 5352 4991 16576 4766 4425 16577 5353 4992 16578 4761 4420 16579 4764 4423 16580 5352 4991 16581 5353 4992 16582 4764 4423 16583 5354 4993 16584 4759 4418 16585 4761 4420 16586 5353 4992 16587 5354 4993 16588 4761 4420 16589 5355 4994 16590 4757 4416 16591 4759 4418 16592 5354 4993 16593 5355 4994 16594 4759 4418 16595 5356 4995 16596 4755 4414 16597 4757 4416 16598 5355 4994 16599 5356 4995 16600 4757 4416 16601 5357 4996 16602 4750 4409 16603 4755 4414 16604 5356 4995 16605 5357 4996 16606 4755 4414 16607 5358 4997 16608 4802 4461 16609 4750 4409 16610 5357 4996 16611 5358 4997 16612 4750 4409 16613 5359 4998 16614 4800 4459 16615 4802 4461 16616 5358 4997 16617 5359 4998 16618 4802 4461 16619 5360 4999 16620 4798 4457 16621 4800 4459 16622 5359 4998 16623 5360 4999 16624 4800 4459 16625 5361 5000 16626 4796 4455 16627 4798 4457 16628 5362 5001 16629 5361 5000 16630 4798 4457 16631 5360 4999 16632 5362 5001 16633 4798 4457 16634 5363 5002 16635 4793 4452 16636 4796 4455 16637 5361 5000 16638 5363 5002 16639 4796 4455 16640 5364 5003 16641 4787 4446 16642 4793 4452 16643 5363 5002 16644 5364 5003 16645 4793 4452 16646 5365 5004 16647 4791 4450 16648 4787 4446 16649 5364 5003 16650 5365 5004 16651 4787 4446 16652 5366 5005 16653 4843 4502 16654 4791 4450 16655 5365 5004 16656 5366 5005 16657 4791 4450 16658 5367 5006 16659 4840 4499 16660 4843 4502 16661 5366 5005 16662 5367 5006 16663 4843 4502 16664 5368 5007 16665 4838 4497 16666 4840 4499 16667 5367 5006 16668 5368 5007 16669 4840 4499 16670 5369 5008 16671 4835 4494 16672 4838 4497 16673 5368 5007 16674 5369 5008 16675 4838 4497 16676 5370 5009 16677 4833 4492 16678 4835 4494 16679 5369 5008 16680 5370 5009 16681 4835 4494 16682 5371 5010 16683 4831 4490 16684 4833 4492 16685 5372 5011 16686 5371 5010 16687 4833 4492 16688 5370 5009 16689 5372 5011 16690 4833 4492 16691 5373 5012 16692 4819 4478 16693 4831 4490 16694 5371 5010 16695 5373 5012 16696 4831 4490 16697 5374 5013 16698 4890 4545 16699 4819 4478 16700 5373 5012 16701 5374 5013 16702 4819 4478 16703 5375 5014 16704 4887 4542 16705 4890 4545 16706 5376 5015 16707 5375 5014 16708 4890 4545 16709 5374 5013 16710 5376 5015 16711 4890 4545 16712 5377 5016 16713 4885 4540 16714 4887 4542 16715 5375 5014 16716 5377 5016 16717 4887 4542 16718 5378 5017 16719 4881 4536 16720 4885 4540 16721 5377 5016 16722 5378 5017 16723 4885 4540 16724 5379 5018 16725 4877 4532 16726 4881 4536 16727 5378 5017 16728 5379 5018 16729 4881 4536 16730 5380 5019 16731 4874 4529 16732 4877 4532 16733 5379 5018 16734 5380 5019 16735 4877 4532 16736 5380 5019 16737 5381 5020 16738 4874 4529 16739 5382 5021 16740 5383 5022 16741 5384 5023 16742 5382 5021 16743 5384 5023 16744 5385 5024 16745 5382 5021 16746 5385 5024 16747 5386 5025 16748 5382 5021 16749 5386 5025 16750 5387 5026 16751 5382 5021 16752 5387 5026 16753 5388 5027 16754 5382 5021 16755 5388 5027 16756 5389 5028 16757 5390 5029 16758 5389 5028 16759 5391 5030 16760 5390 5029 16761 5382 5021 16762 5389 5028 16763 5390 5029 16764 5391 5030 16765 5392 5031 16766 5390 5029 16767 5392 5031 16768 5393 5032 16769 5390 5029 16770 5393 5032 16771 5394 5033 16772 5390 5029 16773 5394 5033 16774 5395 5034 16775 4935 492 16776 4926 492 16777 4925 492 16778 5396 5035 16779 4855 4514 16780 5397 5036 16781 4852 4511 16782 4855 4514 16783 5396 5035 16784 5398 5037 16785 5399 5038 16786 5400 5039 16787 5401 5040 16788 5402 5041 16789 5403 5042 16790 5404 5043 16791 5400 5039 16792 5405 5044 16793 5398 5037 16794 5400 5039 16795 5406 5045 16796 5404 5043 16797 5406 5045 16798 5400 5039 16799 5407 492 16800 5408 492 16801 4971 492 16802 5333 4974 16803 5405 5044 16804 5337 4978 16805 5333 4974 16806 5404 5043 16807 5405 5044 16808 4910 4565 16809 5409 5046 16810 4986 4635 16811 4981 4630 16812 4984 4633 16813 5410 5047 16814 4917 4572 16815 5411 5048 16816 5409 5046 16817 5412 5049 16818 5410 5047 16819 5413 5050 16820 4914 4569 16821 4917 4572 16822 5409 5046 16823 4910 4565 16824 4914 4569 16825 5409 5046 16826 4981 4630 16827 5410 5047 16828 5412 5049 16829 4852 4511 16830 5396 5035 16831 5411 5048 16832 5414 5051 16833 5413 5050 16834 5402 5041 16835 4917 4572 16836 4852 4511 16837 5411 5048 16838 5415 5052 16839 5413 5050 16840 5414 5051 16841 5412 5049 16842 5413 5050 16843 5415 5052 16844 5414 5051 16845 5402 5041 16846 5401 5040 16847 4976 4625 16848 5416 5053 16849 4979 4628 16850 4967 4618 16851 4974 4623 16852 5417 5054 16853 5418 5055 16854 5419 5056 16855 5416 5053 16856 5420 5057 16857 5417 5054 16858 5421 5058 16859 5422 5059 16860 5418 5055 16861 5416 5053 16862 4976 4625 16863 5422 5059 16864 5416 5053 16865 4967 4618 16866 5417 5054 16867 5420 5057 16868 5423 5060 16869 5424 5061 16870 5419 5056 16871 5425 5062 16872 5421 5058 16873 5426 5063 16874 5418 5055 16875 5423 5060 16876 5419 5056 16877 5427 5064 16878 5421 5058 16879 5425 5062 16880 5420 5057 16881 5421 5058 16882 5427 5064 16883 5428 5065 16884 5429 5066 16885 5424 5061 16886 5425 5062 16887 5426 5063 16888 5430 5067 16889 5423 5060 16890 5428 5065 16891 5424 5061 16892 5407 5068 16893 5431 5068 16894 5408 5068 16895 5432 5069 16896 5433 5070 16897 5434 5071 16898 5425 5062 16899 5430 5067 16900 5435 5072 16901 4971 5073 16902 5408 5073 16903 4972 5073 16904 5414 5051 16905 5423 5060 16906 5418 5055 16907 5436 5074 16908 5428 5065 16909 5423 5060 16910 5401 5040 16911 5436 5074 16912 5423 5060 16913 4973 492 16914 4972 492 16915 4936 492 16916 5414 5051 16917 5401 5040 16918 5423 5060 16919 5415 5052 16920 5418 5055 16921 5422 5059 16922 5415 5052 16923 5414 5051 16924 5418 5055 16925 5412 5049 16926 5422 5059 16927 4976 4625 16928 5412 5049 16929 5415 5052 16930 5422 5059 16931 4981 4630 16932 5412 5049 16933 4976 4625 16934 5404 5043 16935 5434 5071 16936 5406 5045 16937 5404 5043 16938 5432 5069 16939 5434 5071 16940 4967 4618 16941 5437 5075 16942 4970 4621 16943 4963 4614 16944 4965 4616 16945 5438 5076 16946 5420 5057 16947 5439 5077 16948 5437 5075 16949 5440 5078 16950 5438 5076 16951 5441 5079 16952 4967 4618 16953 5420 5057 16954 5437 5075 16955 4963 4614 16956 5438 5076 16957 5440 5078 16958 5425 5062 16959 5305 4952 16960 5439 5077 16961 5442 5080 16962 5441 5079 16963 5306 4953 16964 5427 5064 16965 5425 5062 16966 5439 5077 16967 5420 5057 16968 5427 5064 16969 5439 5077 16970 5440 5078 16971 5441 5079 16972 5442 5080 16973 5435 5072 16974 5303 4950 16975 5305 4952 16976 5425 5062 16977 5435 5072 16978 5305 4952 16979 5442 5080 16980 5306 4953 16981 5300 4947 16982 4956 4607 16983 5443 5081 16984 4959 4610 16985 5444 5082 16986 5445 5083 16987 5443 5081 16988 5446 5084 16989 5444 5082 16990 5443 5081 16991 4956 4607 16992 5446 5084 16993 5443 5081 16994 5307 4954 16995 5310 4957 16996 5445 5083 16997 5444 5082 16998 5307 4954 16999 5445 5083 17000 5300 4947 17001 5307 4954 17002 5444 5082 17003 5442 5080 17004 5444 5082 17005 5446 5084 17006 5442 5080 17007 5300 4947 17008 5444 5082 17009 5440 5078 17010 5446 5084 17011 4956 4607 17012 5440 5078 17013 5442 5080 17014 5446 5084 17015 4963 4614 17016 5440 5078 17017 4956 4607 17018 5333 4974 17019 5327 4970 17020 5447 5085 17021 5404 5043 17022 5447 5085 17023 5432 5069 17024 5333 4974 17025 5447 5085 17026 5404 5043 17027 5448 492 17028 5449 492 17029 5450 492 17030 5451 492 17031 5449 492 17032 5448 492 17033 5452 5086 17034 5449 5086 17035 5451 5086 17036 5453 492 17037 5450 492 17038 5454 492 17039 5455 5087 17040 5450 5087 17041 5453 5087 17042 5448 5088 17043 5450 5088 17044 5455 5088 17045 5456 492 17046 5454 492 17047 5457 492 17048 5453 492 17049 5454 492 17050 5456 492 17051 5458 5089 17052 5457 5089 17053 5459 5089 17054 5456 5090 17055 5457 5090 17056 5458 5090 17057 5460 492 17058 5459 492 17059 5461 492 17060 5458 5091 17061 5459 5091 17062 5460 5091 17063 5462 492 17064 5461 492 17065 5463 492 17066 5460 492 17067 5461 492 17068 5462 492 17069 5462 492 17070 5463 492 17071 5464 492 17072 5465 492 17073 5464 492 17074 5466 492 17075 5462 5092 17076 5464 5092 17077 5465 5092 17078 5467 492 17079 5466 492 17080 5468 492 17081 5465 5093 17082 5466 5093 17083 5467 5093 17084 5469 492 17085 5451 492 17086 5470 492 17087 5452 5094 17088 5451 5094 17089 5469 5094 17090 5471 492 17091 5470 492 17092 5472 492 17093 5469 492 17094 5470 492 17095 5471 492 17096 5473 5095 17097 5472 5095 17098 5474 5095 17099 5471 5096 17100 5472 5096 17101 5473 5096 17102 5475 492 17103 5474 492 17104 5476 492 17105 5473 5097 17106 5474 5097 17107 5475 5097 17108 5477 492 17109 5476 492 17110 5478 492 17111 5475 492 17112 5476 492 17113 5477 492 17114 5477 492 17115 5478 492 17116 5479 492 17117 5480 492 17118 5479 492 17119 5481 492 17120 5477 5098 17121 5479 5098 17122 5480 5098 17123 5482 492 17124 5481 492 17125 5483 492 17126 5480 5099 17127 5481 5099 17128 5482 5099 17129 5502 5100 17130 5503 5100 17131 5504 5100 17132 5505 5101 17133 5506 5101 17134 5507 5101 17135 5547 5102 17136 5548 5102 17137 5549 5102 17138 6002 5103 17139 6003 5103 17140 6004 5103 17141 6005 5104 17142 6006 5104 17143 6007 5104 17144 6008 5105 17145 6009 5105 17146 6010 5105 17147 6011 5106 17148 6012 5106 17149 6013 5106 17150 6275 5107 17151 6276 5107 17152 6277 5107 17153 6300 5108 17154 6301 5108 17155 6302 5108 17156 6303 5109 17157 6304 5109 17158 6305 5109 17159 6306 5110 17160 6303 5110 17161 6305 5110 17162 6319 5111 17163 6320 5111 17164 6321 5111 17165 6322 5112 17166 6323 5112 17167 6324 5112 17168 6325 5113 17169 6326 5113 17170 6327 5113 17171 6328 5114 17172 6329 5114 17173 6330 5114 17174 6338 5115 17175 6339 5115 17176 6340 5115 17177

+
+ + + + +

4365 5116 17178 4366 5117 17179 4367 5118 17180 4365 5116 17181 4368 5119 17182 4366 5117 17183 4372 5120 17184 4373 5120 17185 4374 5120 17186 4375 5121 17187 4376 5121 17188 4377 5121 17189 4378 5122 17190 4379 5122 17191 4380 5122 17192 4381 5123 17193 4382 5124 17194 4383 5125 17195 4384 5126 17196 4381 5123 17197 4383 5125 17198 4385 5121 17199 4386 5121 17200 4387 5121 17201 4388 5127 17202 4389 5127 17203 4390 5127 17204 4391 5128 17205 4388 5128 17206 4390 5128 17207 4392 5129 17208 4393 5129 17209 4394 5129 17210 4395 5121 17211 4385 5121 17212 4387 5121 17213 4396 5130 17214 4397 5130 17215 4398 5130 17216 4392 5131 17217 4394 5131 17218 4399 5131 17219 4400 5121 17220 4401 5121 17221 4402 5121 17222 4396 5132 17223 4398 5132 17224 4403 5132 17225 4404 5133 17226 4405 5133 17227 4406 5133 17228 4400 5134 17229 4402 5134 17230 4407 5134 17231 4414 5135 17232 4415 5136 17233 4416 5135 17234 4414 5135 17235 4417 5136 17236 4415 5136 17237 4418 5137 17238 4419 5137 17239 4420 5137 17240 4421 5138 17241 4422 5138 17242 4423 5138 17243 4427 5139 17244 4428 5139 17245 4429 5139 17246 4430 5121 17247 4431 5121 17248 4432 5121 17249 4433 5121 17250 4430 5121 17251 4432 5121 17252 4438 5140 17253 4439 5140 17254 4440 5140 17255 4460 5141 17256 4461 5142 17257 4462 5143 17258 4460 5141 17259 4463 5144 17260 4461 5142 17261 4464 5145 17262 4462 5143 17263 4465 5146 17264 4464 5145 17265 4460 5141 17266 4462 5143 17267 4464 5145 17268 4465 5146 17269 4466 5147 17270 4467 5122 17271 4468 5122 17272 4469 5122 17273 4464 5145 17274 4466 5147 17275 4470 5148 17276 4471 5149 17277 4472 5149 17278 4473 5149 17279 4467 5150 17280 4469 5150 17281 4474 5150 17282 4471 5151 17283 4473 5151 17284 4475 5151 17285 4476 5121 17286 4477 5121 17287 4478 5121 17288 4479 5152 17289 4480 5152 17290 4481 5152 17291 4482 5153 17292 4479 5153 17293 4481 5153 17294 4539 5154 17295 4540 5154 17296 4541 5154 17297 4542 5155 17298 4543 5155 17299 4544 5155 17300 4545 5156 17301 4542 5156 17302 4544 5156 17303 4546 5157 17304 4547 5157 17305 4542 5157 17306 4548 5158 17307 4542 5158 17308 4545 5158 17309 4548 5159 17310 4549 5159 17311 4542 5159 17312 4546 5160 17313 4542 5160 17314 4549 5160 17315 4550 5161 17316 4551 5161 17317 4547 5161 17318 4552 5162 17319 4550 5162 17320 4547 5162 17321 4553 5163 17322 4552 5163 17323 4547 5163 17324 4546 5164 17325 4553 5164 17326 4547 5164 17327 4554 5165 17328 4555 5165 17329 4556 5165 17330 4548 5166 17331 4545 5166 17332 4555 5166 17333 4554 5167 17334 4548 5167 17335 4555 5167 17336 4557 5168 17337 4556 5168 17338 4558 5168 17339 4559 5169 17340 4554 5169 17341 4556 5169 17342 4560 5170 17343 4559 5170 17344 4556 5170 17345 4561 5171 17346 4560 5171 17347 4556 5171 17348 4557 5172 17349 4561 5172 17350 4556 5172 17351 4562 5173 17352 4558 5173 17353 4563 5173 17354 4564 5174 17355 4558 5174 17356 4562 5174 17357 4565 5175 17358 4557 5175 17359 4558 5175 17360 4566 5176 17361 4565 5176 17362 4558 5176 17363 4567 5177 17364 4566 5177 17365 4558 5177 17366 4568 5178 17367 4567 5178 17368 4558 5178 17369 4564 5179 17370 4568 5179 17371 4558 5179 17372 4569 5180 17373 4563 5180 17374 4570 5180 17375 4562 5181 17376 4563 5181 17377 4569 5181 17378 4571 5182 17379 4570 5182 17380 4572 5182 17381 4569 5183 17382 4570 5183 17383 4571 5183 17384 4573 5184 17385 4572 5184 17386 4574 5184 17387 4571 5185 17388 4572 5185 17389 4573 5185 17390 4564 5186 17391 4562 5186 17392 4551 5186 17393 4575 5187 17394 4564 5187 17395 4551 5187 17396 4576 5188 17397 4575 5188 17398 4551 5188 17399 4577 5189 17400 4576 5189 17401 4551 5189 17402 4550 5190 17403 4577 5190 17404 4551 5190 17405 4578 5191 17406 4579 5191 17407 4580 5191 17408 4581 5192 17409 4582 5192 17410 4583 5192 17411 4581 5193 17412 4583 5193 17413 4584 5193 17414 4585 5122 17415 4586 5122 17416 4587 5122 17417 4588 5194 17418 4578 5194 17419 4580 5194 17420 4589 5195 17421 4590 5196 17422 4591 5197 17423 4592 5122 17424 4585 5122 17425 4587 5122 17426 4593 5198 17427 4591 5197 17428 4594 5199 17429 4589 5195 17430 4591 5197 17431 4593 5198 17432 4595 5200 17433 4594 5199 17434 4596 5201 17435 4593 5198 17436 4594 5199 17437 4595 5200 17438 4597 5202 17439 4596 5201 17440 4598 5203 17441 4595 5200 17442 4596 5201 17443 4597 5202 17444 4599 5204 17445 4598 5203 17446 4600 5205 17447 4597 5202 17448 4598 5203 17449 4599 5204 17450 4601 5206 17451 4600 5205 17452 4602 5207 17453 4599 5204 17454 4600 5205 17455 4601 5206 17456 4603 5208 17457 4602 5207 17458 4604 5209 17459 4601 5206 17460 4602 5207 17461 4603 5208 17462 4605 5210 17463 4604 5209 17464 4606 5211 17465 4603 5208 17466 4604 5209 17467 4605 5210 17468 4607 5212 17469 4606 5211 17470 4608 5213 17471 4605 5210 17472 4606 5211 17473 4607 5212 17474 4609 5214 17475 4608 5213 17476 4610 5215 17477 4607 5212 17478 4608 5213 17479 4609 5214 17480 4611 5216 17481 4610 5215 17482 4612 5217 17483 4609 5214 17484 4610 5215 17485 4611 5216 17486 4613 5218 17487 4612 5217 17488 4614 5219 17489 4611 5216 17490 4612 5217 17491 4613 5218 17492 4615 5220 17493 4614 5219 17494 4616 5221 17495 4613 5218 17496 4614 5219 17497 4615 5220 17498 4617 5221 17499 4616 5221 17500 4618 5222 17501 4615 5220 17502 4616 5221 17503 4617 5221 17504 4619 5223 17505 4618 5222 17506 4620 5224 17507 4617 5221 17508 4618 5222 17509 4619 5223 17510 4621 5225 17511 4620 5224 17512 4622 5226 17513 4619 5223 17514 4620 5224 17515 4621 5225 17516 4621 5225 17517 4622 5226 17518 4623 5226 17519 5484 5227 17520 5485 5227 17521 5486 5227 17522 5487 5228 17523 5488 5228 17524 5489 5228 17525 5490 5229 17526 5491 5229 17527 5492 5229 17528 5493 5230 17529 5494 5230 17530 5495 5230 17531 5487 5231 17532 5489 5231 17533 5496 5231 17534 5497 5122 17535 5498 5122 17536 5499 5122 17537 5493 5232 17538 5495 5232 17539 5500 5232 17540 5497 5233 17541 5499 5233 17542 5501 5233 17543 5508 5234 17544 5509 5235 17545 5510 5236 17546 5508 5234 17547 5511 5237 17548 5509 5235 17549 5512 5238 17550 5513 5238 17551 5514 5238 17552 5515 5239 17553 5512 5239 17554 5514 5239 17555 5516 5240 17556 5517 5240 17557 5518 5240 17558 5519 5241 17559 5516 5241 17560 5518 5241 17561 5520 5242 17562 5519 5242 17563 5518 5242 17564 5521 5243 17565 5520 5243 17566 5518 5243 17567 5522 5244 17568 5523 5244 17569 5524 5244 17570 5525 5245 17571 5526 5245 17572 5523 5245 17573 5522 5246 17574 5525 5246 17575 5523 5246 17576 5522 5247 17577 5527 5247 17578 5525 5247 17579 5528 5248 17580 5529 5248 17581 5527 5248 17582 5530 5249 17583 5528 5249 17584 5527 5249 17585 5522 5250 17586 5530 5250 17587 5527 5250 17588 5530 5251 17589 5531 5251 17590 5528 5251 17591 5532 5252 17592 5533 5253 17593 5534 5252 17594 5535 5254 17595 5536 5255 17596 5533 5253 17597 5532 5252 17598 5535 5254 17599 5533 5253 17600 5537 5256 17601 5538 5256 17602 5539 5256 17603 5540 5257 17604 5541 5257 17605 5542 5257 17606 5543 5258 17607 5544 5259 17608 5545 5260 17609 5543 5258 17610 5546 5261 17611 5544 5259 17612 6278 5133 17613 6279 5133 17614 6280 5133 17615 6281 5262 17616 6282 5262 17617 6283 5262 17618 6284 5263 17619 6285 5263 17620 6286 5263 17621 6287 5264 17622 6288 5264 17623 6289 5264 17624 6290 5265 17625 6291 5265 17626 6292 5265 17627 6293 5266 17628 6294 5266 17629 6295 5266 17630 6296 5267 17631 6293 5267 17632 6295 5267 17633 6297 5268 17634 6298 5268 17635 6299 5268 17636 6307 5227 17637 6308 5227 17638 6309 5227 17639 6310 5256 17640 6311 5256 17641 6312 5256 17642 6313 5269 17643 6314 5269 17644 6315 5269 17645 6316 5270 17646 6317 5270 17647 6318 5270 17648 6331 5122 17649 6332 5122 17650 6333 5122 17651 6334 5271 17652 6335 5272 17653 6336 5273 17654 6334 5271 17655 6337 5274 17656 6335 5272 17657 6341 5121 17658 6342 5121 17659 6343 5121 17660 6344 5275 17661 6345 5275 17662 6346 5275 17663

+
+ + + + +

5550 5276 17664 5551 5277 17665 5552 5278 17666 5553 5279 17667 5554 5280 17668 5555 5281 17669 5556 5282 17670 5550 5276 17671 5552 5278 17672 5557 5283 17673 5556 5282 17674 5552 5278 17675 5558 5284 17676 5559 5284 17677 5560 5284 17678 5558 5285 17679 5560 5285 17680 5561 5285 17681 5550 5276 17682 5562 5286 17683 5551 5277 17684 5563 5287 17685 5555 5281 17686 5564 5288 17687 5563 5287 17688 5553 5279 17689 5555 5281 17690 5550 5276 17691 5565 5289 17692 5562 5286 17693 5566 5290 17694 5564 5288 17695 5567 5291 17696 5566 5290 17697 5563 5287 17698 5564 5288 17699 5550 5276 17700 5568 5292 17701 5565 5289 17702 5569 5293 17703 5567 5291 17704 5570 5294 17705 5569 5293 17706 5566 5290 17707 5567 5291 17708 5550 5276 17709 5571 5295 17710 5568 5292 17711 5572 5296 17712 5570 5294 17713 5573 5297 17714 5572 5296 17715 5569 5293 17716 5570 5294 17717 5574 5298 17718 5575 5298 17719 5576 5298 17720 5577 5299 17721 5572 5296 17722 5573 5297 17723 5578 5300 17724 5550 5276 17725 5556 5282 17726 5579 5301 17727 5550 5276 17728 5578 5300 17729 5574 5302 17730 5576 5302 17731 5580 5302 17732 5557 5283 17733 5581 5303 17734 5556 5282 17735 5582 5304 17736 5556 5282 17737 5581 5303 17738 5583 5305 17739 5578 5300 17740 5556 5282 17741 5584 5306 17742 5583 5305 17743 5556 5282 17744 5585 5307 17745 5584 5306 17746 5556 5282 17747 5582 5304 17748 5585 5307 17749 5556 5282 17750 5586 5308 17751 5587 5309 17752 5581 5303 17753 5588 5310 17754 5581 5303 17755 5587 5309 17756 5557 5283 17757 5586 5308 17758 5581 5303 17759 5589 5311 17760 5582 5304 17761 5581 5303 17762 5590 5312 17763 5589 5311 17764 5581 5303 17765 5588 5310 17766 5590 5312 17767 5581 5303 17768 5591 5313 17769 5592 5314 17770 5587 5309 17771 5593 5315 17772 5587 5309 17773 5592 5314 17774 5594 5316 17775 5591 5313 17776 5587 5309 17777 5595 5317 17778 5594 5316 17779 5587 5309 17780 5596 5318 17781 5595 5317 17782 5587 5309 17783 5586 5308 17784 5596 5318 17785 5587 5309 17786 5597 5319 17787 5588 5310 17788 5587 5309 17789 5598 5320 17790 5597 5319 17791 5587 5309 17792 5593 5315 17793 5598 5320 17794 5587 5309 17795 5599 5321 17796 5600 5322 17797 5592 5314 17798 5601 5323 17799 5592 5314 17800 5600 5322 17801 5602 5324 17802 5599 5321 17803 5592 5314 17804 5603 5325 17805 5602 5324 17806 5592 5314 17807 5604 5326 17808 5603 5325 17809 5592 5314 17810 5605 5327 17811 5604 5326 17812 5592 5314 17813 5591 5313 17814 5605 5327 17815 5592 5314 17816 5606 5328 17817 5593 5315 17818 5592 5314 17819 5601 5323 17820 5606 5328 17821 5592 5314 17822 5607 5329 17823 5608 5330 17824 5600 5322 17825 5609 5331 17826 5600 5322 17827 5608 5330 17828 5599 5321 17829 5607 5329 17830 5600 5322 17831 5610 5332 17832 5601 5323 17833 5600 5322 17834 5609 5331 17835 5610 5332 17836 5600 5322 17837 5611 5333 17838 5612 5334 17839 5608 5330 17840 5613 5335 17841 5608 5330 17842 5612 5334 17843 5607 5329 17844 5611 5333 17845 5608 5330 17846 5614 5336 17847 5609 5331 17848 5608 5330 17849 5615 5337 17850 5614 5336 17851 5608 5330 17852 5613 5335 17853 5615 5337 17854 5608 5330 17855 5616 5338 17856 5617 5339 17857 5612 5334 17858 5618 5340 17859 5612 5334 17860 5617 5339 17861 5619 5341 17862 5616 5338 17863 5612 5334 17864 5620 5342 17865 5619 5341 17866 5612 5334 17867 5621 5343 17868 5620 5342 17869 5612 5334 17870 5622 5344 17871 5621 5343 17872 5612 5334 17873 5623 5345 17874 5622 5344 17875 5612 5334 17876 5611 5333 17877 5623 5345 17878 5612 5334 17879 5624 5346 17880 5613 5335 17881 5612 5334 17882 5625 5347 17883 5624 5346 17884 5612 5334 17885 5618 5340 17886 5625 5347 17887 5612 5334 17888 5626 5348 17889 5627 5348 17890 5628 5348 17891 5629 5349 17892 5618 5340 17893 5617 5339 17894 5630 5350 17895 5629 5349 17896 5617 5339 17897 5631 5351 17898 5630 5350 17899 5617 5339 17900 5626 5352 17901 5632 5352 17902 5627 5352 17903 5633 5353 17904 5634 5354 17905 5635 5355 17906 5626 5356 17907 5628 5356 17908 5636 5356 17909 5637 5357 17910 5635 5355 17911 5638 5358 17912 5633 5353 17913 5635 5355 17914 5637 5357 17915 5639 5359 17916 5638 5358 17917 5640 5360 17918 5641 5361 17919 5638 5358 17920 5639 5359 17921 5637 5357 17922 5638 5358 17923 5641 5361 17924 5642 5362 17925 5640 5360 17926 5643 5363 17927 5639 5359 17928 5640 5360 17929 5642 5362 17930 5642 5362 17931 5643 5363 17932 5644 5364 17933 5645 5365 17934 5646 5365 17935 5647 5365 17936 5642 5362 17937 5644 5364 17938 5648 5366 17939 5649 5367 17940 5647 5367 17941 5650 5367 17942 5645 5368 17943 5647 5368 17944 5649 5368 17945 5651 5369 17946 5650 5369 17947 5652 5369 17948 5649 5370 17949 5650 5370 17950 5651 5370 17951 5653 5371 17952 5654 5372 17953 5655 5373 17954 5656 5374 17955 5655 5373 17956 5657 5375 17957 5653 5371 17958 5655 5373 17959 5656 5374 17960 5656 5374 17961 5657 5375 17962 5658 5376 17963 5656 5374 17964 5658 5376 17965 5659 5377 17966 5660 5378 17967 5659 5377 17968 5661 5379 17969 5656 5374 17970 5659 5377 17971 5660 5378 17972 5660 5378 17973 5661 5379 17974 5662 5380 17975 5663 5381 17976 5662 5380 17977 5664 5382 17978 5660 5378 17979 5662 5380 17980 5663 5381 17981 5663 5381 17982 5664 5382 17983 5665 5383 17984 5666 5384 17985 5667 5384 17986 5668 5384 17987 5663 5381 17988 5665 5383 17989 5669 5385 17990 5558 5386 17991 5668 5386 17992 5559 5386 17993 5558 5387 17994 5666 5387 17995 5668 5387 17996 5579 5301 17997 5578 5300 17998 5670 5388 17999 5671 5389 18000 5672 5390 18001 5673 5391 18002 5574 5392 18003 5580 5392 18004 5674 5392 18005 5675 5393 18006 5574 5393 18007 5674 5393 18008 5676 5394 18009 5677 5394 18010 5678 5394 18011 5679 5395 18012 5676 5395 18013 5678 5395 18014 5671 5389 18015 5680 5396 18016 5672 5390 18017 5671 5389 18018 5673 5391 18019 5681 5397 18020 5682 5398 18021 5681 5397 18022 5683 5399 18023 5682 5398 18024 5671 5389 18025 5681 5397 18026 5682 5398 18027 5683 5399 18028 5684 5400 18029 5685 5401 18030 5684 5400 18031 5686 5402 18032 5687 5403 18033 5684 5400 18034 5685 5401 18035 5682 5398 18036 5684 5400 18037 5687 5403 18038 5687 5403 18039 5685 5401 18040 5688 5404 18041 5689 5405 18042 5688 5404 18043 5690 5406 18044 5687 5403 18045 5688 5404 18046 5689 5405 18047 5691 5407 18048 5690 5406 18049 5692 5408 18050 5689 5405 18051 5690 5406 18052 5691 5407 18053 5693 5409 18054 5692 5408 18055 5694 5410 18056 5691 5407 18057 5692 5408 18058 5693 5409 18059 5695 5411 18060 5694 5410 18061 5696 5412 18062 5693 5409 18063 5694 5410 18064 5695 5411 18065 5695 5411 18066 5696 5412 18067 5697 5413 18068 5695 5411 18069 5697 5413 18070 5698 5414 18071 5699 5415 18072 5698 5414 18073 5700 5416 18074 5701 5417 18075 5695 5411 18076 5698 5414 18077 5702 5418 18078 5701 5417 18079 5698 5414 18080 5703 5419 18081 5702 5418 18082 5698 5414 18083 5704 5420 18084 5703 5419 18085 5698 5414 18086 5705 5421 18087 5704 5420 18088 5698 5414 18089 5706 5422 18090 5705 5421 18091 5698 5414 18092 5707 5423 18093 5706 5422 18094 5698 5414 18095 5708 5424 18096 5707 5423 18097 5698 5414 18098 5709 5425 18099 5708 5424 18100 5698 5414 18101 5710 5426 18102 5709 5425 18103 5698 5414 18104 5711 5427 18105 5710 5426 18106 5698 5414 18107 5712 5428 18108 5711 5427 18109 5698 5414 18110 5713 5429 18111 5712 5428 18112 5698 5414 18113 5714 5430 18114 5713 5429 18115 5698 5414 18116 5715 5431 18117 5714 5430 18118 5698 5414 18119 5699 5415 18120 5715 5431 18121 5698 5414 18122 5716 5432 18123 5700 5416 18124 5717 5433 18125 5716 5432 18126 5699 5415 18127 5700 5416 18128 5716 5432 18129 5717 5433 18130 5718 5434 18131 5719 5435 18132 5718 5434 18133 5720 5436 18134 5719 5435 18135 5716 5432 18136 5718 5434 18137 5721 5437 18138 5720 5436 18139 5722 5438 18140 5721 5437 18141 5719 5435 18142 5720 5436 18143 5721 5437 18144 5722 5438 18145 5723 5439 18146 5724 5440 18147 5723 5439 18148 5725 5441 18149 5724 5440 18150 5721 5437 18151 5723 5439 18152 5726 5442 18153 5725 5441 18154 5727 5443 18155 5726 5442 18156 5724 5440 18157 5725 5441 18158 5726 5442 18159 5727 5443 18160 5728 5444 18161 5729 5445 18162 5728 5444 18163 5730 5446 18164 5726 5442 18165 5728 5444 18166 5729 5445 18167 5631 5351 18168 5731 5447 18169 5630 5350 18170 5732 5448 18171 5730 5446 18172 5733 5449 18173 5734 5450 18174 5730 5446 18175 5732 5448 18176 5735 5451 18177 5730 5446 18178 5734 5450 18179 5729 5445 18180 5730 5446 18181 5735 5451 18182 5626 5452 18183 5736 5452 18184 5632 5452 18185 5737 5453 18186 5738 5453 18187 5739 5453 18188 5740 5454 18189 5741 5454 18190 5742 5454 18191 5743 5455 18192 5742 5455 18193 5744 5455 18194 5743 5456 18195 5740 5456 18196 5742 5456 18197 5745 5457 18198 5746 5457 18199 5741 5457 18200 5747 5458 18201 5748 5458 18202 5746 5458 18203 5745 5459 18204 5747 5459 18205 5746 5459 18206 5740 5460 18207 5745 5460 18208 5741 5460 18209 5749 5461 18210 5744 5461 18211 5750 5461 18212 5749 5462 18213 5743 5462 18214 5744 5462 18215 5751 5463 18216 5750 5463 18217 5752 5463 18218 5751 5464 18219 5749 5464 18220 5750 5464 18221 5753 5465 18222 5752 5465 18223 5754 5465 18224 5753 5466 18225 5751 5466 18226 5752 5466 18227 5755 5467 18228 5754 5467 18229 5756 5467 18230 5755 5468 18231 5753 5468 18232 5754 5468 18233 5757 5469 18234 5756 5469 18235 5758 5469 18236 5757 5470 18237 5755 5470 18238 5756 5470 18239 5759 5471 18240 5757 5471 18241 5758 5471 18242 5760 5472 18243 5759 5472 18244 5758 5472 18245 5747 5473 18246 5761 5473 18247 5748 5473 18248 5760 5474 18249 5762 5474 18250 5759 5474 18251 5737 5475 18252 5739 5475 18253 5763 5475 18254 5764 5476 18255 5765 5476 18256 5762 5476 18257 5766 5477 18258 5767 5478 18259 5768 5479 18260 5760 5480 18261 5764 5480 18262 5762 5480 18263 5769 5481 18264 5770 5481 18265 5765 5481 18266 5771 5482 18267 5768 5479 18268 5772 5483 18269 5764 5484 18270 5769 5484 18271 5765 5484 18272 5773 5485 18273 5766 5477 18274 5768 5479 18275 5771 5482 18276 5773 5485 18277 5768 5479 18278 5769 5486 18279 5774 5486 18280 5770 5486 18281 5775 5487 18282 5772 5483 18283 5776 5488 18284 5775 5487 18285 5771 5482 18286 5772 5483 18287 5777 5489 18288 5778 5489 18289 5774 5489 18290 5779 5490 18291 5776 5488 18292 5780 5491 18293 5769 5492 18294 5777 5492 18295 5774 5492 18296 5779 5490 18297 5775 5487 18298 5776 5488 18299 5781 5493 18300 5782 5493 18301 5778 5493 18302 5783 5494 18303 5780 5491 18304 5784 5495 18305 5777 5496 18306 5781 5496 18307 5778 5496 18308 5783 5494 18309 5779 5490 18310 5780 5491 18311 5785 5497 18312 5786 5497 18313 5782 5497 18314 5787 5498 18315 5784 5495 18316 5788 5499 18317 5789 5500 18318 5785 5500 18319 5782 5500 18320 5781 5501 18321 5789 5501 18322 5782 5501 18323 5787 5498 18324 5783 5494 18325 5784 5495 18326 5790 5502 18327 5791 5502 18328 5786 5502 18329 5792 5503 18330 5788 5499 18331 5793 5504 18332 5785 5505 18333 5790 5505 18334 5786 5505 18335 5792 5503 18336 5787 5498 18337 5788 5499 18338 5794 5506 18339 5795 5506 18340 5791 5506 18341 5796 5507 18342 5793 5504 18343 5797 5508 18344 5790 5509 18345 5794 5509 18346 5791 5509 18347 5796 5507 18348 5792 5503 18349 5793 5504 18350 5798 5510 18351 5799 5510 18352 5795 5510 18353 5796 5507 18354 5797 5508 18355 5800 5511 18356 5794 5512 18357 5798 5512 18358 5795 5512 18359 5801 5513 18360 5802 5513 18361 5799 5513 18362 5803 5514 18363 5800 5511 18364 5804 5515 18365 5798 5516 18366 5801 5516 18367 5799 5516 18368 5803 5514 18369 5796 5507 18370 5800 5511 18371 5805 5517 18372 5806 5517 18373 5802 5517 18374 5807 5518 18375 5804 5515 18376 5808 5519 18377 5801 5520 18378 5805 5520 18379 5802 5520 18380 5807 5518 18381 5803 5514 18382 5804 5515 18383 5809 5521 18384 5810 5521 18385 5806 5521 18386 5811 5522 18387 5808 5519 18388 5812 5523 18389 5805 5524 18390 5809 5524 18391 5806 5524 18392 5811 5522 18393 5807 5518 18394 5808 5519 18395 5813 5525 18396 5814 5525 18397 5810 5525 18398 5815 5526 18399 5812 5523 18400 5816 5527 18401 5809 5528 18402 5813 5528 18403 5810 5528 18404 5815 5526 18405 5811 5522 18406 5812 5523 18407 5817 5529 18408 5818 5529 18409 5814 5529 18410 5819 5530 18411 5816 5527 18412 5820 5531 18413 5813 5532 18414 5817 5532 18415 5814 5532 18416 5819 5530 18417 5815 5526 18418 5816 5527 18419 5821 5533 18420 5822 5533 18421 5818 5533 18422 5823 5534 18423 5820 5531 18424 5824 5535 18425 5817 5536 18426 5821 5536 18427 5818 5536 18428 5825 5537 18429 5819 5530 18430 5820 5531 18431 5823 5534 18432 5825 5537 18433 5820 5531 18434 5826 5538 18435 5827 5538 18436 5822 5538 18437 5823 5534 18438 5824 5535 18439 5828 5539 18440 5829 5540 18441 5826 5540 18442 5822 5540 18443 5821 5541 18444 5829 5541 18445 5822 5541 18446 5830 5542 18447 5831 5542 18448 5827 5542 18449 5832 5543 18450 5828 5539 18451 5833 5544 18452 5826 5545 18453 5830 5545 18454 5827 5545 18455 5832 5543 18456 5823 5534 18457 5828 5539 18458 5834 5546 18459 5835 5546 18460 5831 5546 18461 5836 5547 18462 5833 5544 18463 5837 5548 18464 5830 5549 18465 5834 5549 18466 5831 5549 18467 5836 5547 18468 5832 5543 18469 5833 5544 18470 5838 5550 18471 5837 5548 18472 5839 5551 18473 5838 5550 18474 5836 5547 18475 5837 5548 18476 5840 5552 18477 5839 5551 18478 5841 5553 18479 5840 5552 18480 5838 5550 18481 5839 5551 18482 5842 5554 18483 5841 5553 18484 5843 5555 18485 5842 5554 18486 5840 5552 18487 5841 5553 18488 5844 5556 18489 5843 5555 18490 5845 5557 18491 5844 5556 18492 5842 5554 18493 5843 5555 18494 5846 5558 18495 5845 5557 18496 5847 5559 18497 5846 5558 18498 5844 5556 18499 5845 5557 18500 5848 5560 18501 5847 5559 18502 5849 5561 18503 5848 5560 18504 5846 5558 18505 5847 5559 18506 5850 5562 18507 5849 5561 18508 5851 5563 18509 5850 5562 18510 5848 5560 18511 5849 5561 18512 5852 5564 18513 5851 5563 18514 5853 5565 18515 5852 5564 18516 5850 5562 18517 5851 5563 18518 5854 5566 18519 5853 5565 18520 5855 5567 18521 5854 5566 18522 5852 5564 18523 5853 5565 18524 5856 5568 18525 5855 5567 18526 5857 5569 18527 5856 5568 18528 5854 5566 18529 5855 5567 18530 5858 5570 18531 5857 5569 18532 5859 5571 18533 5858 5570 18534 5856 5568 18535 5857 5569 18536 5860 5572 18537 5859 5571 18538 5861 5573 18539 5860 5572 18540 5858 5570 18541 5859 5571 18542 5862 5574 18543 5861 5573 18544 5863 5575 18545 5862 5574 18546 5860 5572 18547 5861 5573 18548 5864 5576 18549 5863 5575 18550 5865 5577 18551 5864 5576 18552 5862 5574 18553 5863 5575 18554 5864 5576 18555 5865 5577 18556 5866 5578 18557 5867 5579 18558 5866 5578 18559 5868 5580 18560 5867 5579 18561 5864 5576 18562 5866 5578 18563 5869 5581 18564 5868 5580 18565 5870 5582 18566 5869 5581 18567 5867 5579 18568 5868 5580 18569 5871 5583 18570 5870 5582 18571 5872 5584 18572 5871 5583 18573 5869 5581 18574 5870 5582 18575 5873 5585 18576 5872 5584 18577 5874 5586 18578 5873 5585 18579 5871 5583 18580 5872 5584 18581 5875 5587 18582 5874 5586 18583 5876 5588 18584 5875 5587 18585 5873 5585 18586 5874 5586 18587 5875 5587 18588 5876 5588 18589 5877 5589 18590 5671 5389 18591 5878 5590 18592 5680 5396 18593 5729 5445 18594 5735 5451 18595 5879 5591 18596 5729 5445 18597 5879 5591 18598 5880 5592 18599 5881 5593 18600 5880 5592 18601 5882 5594 18602 5881 5593 18603 5729 5445 18604 5880 5592 18605 5881 5593 18606 5882 5594 18607 5883 5595 18608 5884 5596 18609 5883 5595 18610 5885 5597 18611 5884 5596 18612 5881 5593 18613 5883 5595 18614 5886 5598 18615 5885 5597 18616 5887 5599 18617 5886 5598 18618 5884 5596 18619 5885 5597 18620 5886 5598 18621 5887 5599 18622 5888 5600 18623 5886 5598 18624 5888 5600 18625 5889 5601 18626 5890 5602 18627 5889 5601 18628 5891 5603 18629 5890 5602 18630 5886 5598 18631 5889 5601 18632 5890 5602 18633 5891 5603 18634 5892 5604 18635 5893 5605 18636 5892 5604 18637 5894 5606 18638 5893 5605 18639 5890 5602 18640 5892 5604 18641 5893 5605 18642 5894 5606 18643 5895 5607 18644 5893 5605 18645 5895 5607 18646 5896 5608 18647 5897 5609 18648 5896 5608 18649 5898 5610 18650 5897 5609 18651 5893 5605 18652 5896 5608 18653 5897 5609 18654 5898 5610 18655 5899 5611 18656 5900 5612 18657 5899 5611 18658 5901 5613 18659 5900 5612 18660 5897 5609 18661 5899 5611 18662 5902 5614 18663 5901 5613 18664 5903 5615 18665 5902 5614 18666 5900 5612 18667 5901 5613 18668 5904 5616 18669 5903 5615 18670 5905 5617 18671 5904 5616 18672 5902 5614 18673 5903 5615 18674 5904 5616 18675 5905 5617 18676 5906 5618 18677 5907 5619 18678 5906 5618 18679 5908 5620 18680 5907 5619 18681 5904 5616 18682 5906 5618 18683 5907 5619 18684 5908 5620 18685 5909 5621 18686 5907 5619 18687 5909 5621 18688 5910 5622 18689 5911 5623 18690 5910 5622 18691 5912 5624 18692 5911 5623 18693 5907 5619 18694 5910 5622 18695 5911 5623 18696 5912 5624 18697 5913 5625 18698 5914 5626 18699 5913 5625 18700 5915 5627 18701 5914 5626 18702 5911 5623 18703 5913 5625 18704 5914 5626 18705 5915 5627 18706 5916 5628 18707 5914 5626 18708 5916 5628 18709 5917 5629 18710 5918 5630 18711 5917 5629 18712 5919 5631 18713 5918 5630 18714 5914 5626 18715 5917 5629 18716 5920 5632 18717 5919 5631 18718 5921 5633 18719 5920 5632 18720 5918 5630 18721 5919 5631 18722 5920 5632 18723 5921 5633 18724 5922 5634 18725 5923 5635 18726 5922 5634 18727 5924 5636 18728 5923 5635 18729 5920 5632 18730 5922 5634 18731 5923 5635 18732 5924 5636 18733 5925 5637 18734 5671 5389 18735 5925 5637 18736 5926 5638 18737 5671 5389 18738 5923 5635 18739 5925 5637 18740 5671 5389 18741 5926 5638 18742 5878 5590 18743 5726 5442 18744 5729 5445 18745 5881 5593 18746 5927 5639 18747 5881 5593 18748 5884 5596 18749 5726 5442 18750 5881 5593 18751 5927 5639 18752 5928 5640 18753 5884 5596 18754 5886 5598 18755 5927 5639 18756 5884 5596 18757 5928 5640 18758 5929 5641 18759 5886 5598 18760 5890 5602 18761 5928 5640 18762 5886 5598 18763 5929 5641 18764 5930 5642 18765 5890 5602 18766 5893 5605 18767 5929 5641 18768 5890 5602 18769 5930 5642 18770 5931 5643 18771 5893 5605 18772 5897 5609 18773 5930 5642 18774 5893 5605 18775 5931 5643 18776 5932 5644 18777 5897 5609 18778 5900 5612 18779 5931 5643 18780 5897 5609 18781 5932 5644 18782 5933 5645 18783 5900 5612 18784 5902 5614 18785 5932 5644 18786 5900 5612 18787 5933 5645 18788 5934 5646 18789 5902 5614 18790 5904 5616 18791 5933 5645 18792 5902 5614 18793 5934 5646 18794 5935 5647 18795 5904 5616 18796 5907 5619 18797 5934 5646 18798 5904 5616 18799 5935 5647 18800 5936 5648 18801 5907 5619 18802 5911 5623 18803 5935 5647 18804 5907 5619 18805 5936 5648 18806 5937 5649 18807 5911 5623 18808 5914 5626 18809 5936 5648 18810 5911 5623 18811 5937 5649 18812 5938 5650 18813 5914 5626 18814 5918 5630 18815 5937 5649 18816 5914 5626 18817 5938 5650 18818 5939 5651 18819 5918 5630 18820 5920 5632 18821 5938 5650 18822 5918 5630 18823 5939 5651 18824 5940 5652 18825 5920 5632 18826 5923 5635 18827 5939 5651 18828 5920 5632 18829 5940 5652 18830 5941 5653 18831 5923 5635 18832 5671 5389 18833 5940 5652 18834 5923 5635 18835 5941 5653 18836 5941 5653 18837 5671 5389 18838 5682 5398 18839 5693 5409 18840 5695 5411 18841 5701 5417 18842 5942 5654 18843 5701 5417 18844 5702 5418 18845 5942 5654 18846 5693 5409 18847 5701 5417 18848 5943 5655 18849 5702 5418 18850 5703 5419 18851 5943 5655 18852 5942 5654 18853 5702 5418 18854 5944 5656 18855 5703 5419 18856 5704 5420 18857 5944 5656 18858 5943 5655 18859 5703 5419 18860 5945 5657 18861 5704 5420 18862 5705 5421 18863 5945 5657 18864 5944 5656 18865 5704 5420 18866 5946 5658 18867 5705 5421 18868 5706 5422 18869 5946 5658 18870 5945 5657 18871 5705 5421 18872 5947 5659 18873 5706 5422 18874 5707 5423 18875 5947 5659 18876 5946 5658 18877 5706 5422 18878 5948 5660 18879 5707 5423 18880 5708 5424 18881 5948 5660 18882 5947 5659 18883 5707 5423 18884 5949 5661 18885 5708 5424 18886 5709 5425 18887 5949 5661 18888 5948 5660 18889 5708 5424 18890 5950 5662 18891 5709 5425 18892 5710 5426 18893 5950 5662 18894 5949 5661 18895 5709 5425 18896 5951 5663 18897 5710 5426 18898 5711 5427 18899 5951 5663 18900 5950 5662 18901 5710 5426 18902 5952 5664 18903 5711 5427 18904 5712 5428 18905 5952 5664 18906 5951 5663 18907 5711 5427 18908 5953 5665 18909 5712 5428 18910 5713 5429 18911 5953 5665 18912 5952 5664 18913 5712 5428 18914 5954 5666 18915 5713 5429 18916 5714 5430 18917 5954 5666 18918 5953 5665 18919 5713 5429 18920 5955 5667 18921 5714 5430 18922 5715 5431 18923 5955 5667 18924 5954 5666 18925 5714 5430 18926 5956 5668 18927 5715 5431 18928 5699 5415 18929 5956 5668 18930 5955 5667 18931 5715 5431 18932 5716 5432 18933 5956 5668 18934 5699 5415 18935 5691 5407 18936 5693 5409 18937 5942 5654 18938 5957 5669 18939 5942 5654 18940 5943 5655 18941 5957 5669 18942 5691 5407 18943 5942 5654 18944 5958 5670 18945 5943 5655 18946 5944 5656 18947 5958 5670 18948 5957 5669 18949 5943 5655 18950 5959 5671 18951 5944 5656 18952 5945 5657 18953 5959 5671 18954 5958 5670 18955 5944 5656 18956 5960 5672 18957 5945 5657 18958 5946 5658 18959 5960 5672 18960 5959 5671 18961 5945 5657 18962 5961 5673 18963 5946 5658 18964 5947 5659 18965 5961 5673 18966 5960 5672 18967 5946 5658 18968 5962 5674 18969 5947 5659 18970 5948 5660 18971 5962 5674 18972 5961 5673 18973 5947 5659 18974 5963 5675 18975 5948 5660 18976 5949 5661 18977 5963 5675 18978 5962 5674 18979 5948 5660 18980 5964 5676 18981 5949 5661 18982 5950 5662 18983 5964 5676 18984 5963 5675 18985 5949 5661 18986 5965 5677 18987 5950 5662 18988 5951 5663 18989 5965 5677 18990 5964 5676 18991 5950 5662 18992 5966 5678 18993 5951 5663 18994 5952 5664 18995 5966 5678 18996 5965 5677 18997 5951 5663 18998 5967 5679 18999 5952 5664 19000 5953 5665 19001 5967 5679 19002 5966 5678 19003 5952 5664 19004 5968 5680 19005 5953 5665 19006 5954 5666 19007 5968 5680 19008 5967 5679 19009 5953 5665 19010 5969 5681 19011 5954 5666 19012 5955 5667 19013 5969 5681 19014 5968 5680 19015 5954 5666 19016 5970 5682 19017 5955 5667 19018 5956 5668 19019 5970 5682 19020 5969 5681 19021 5955 5667 19022 5971 5683 19023 5956 5668 19024 5716 5432 19025 5971 5683 19026 5970 5682 19027 5956 5668 19028 5719 5435 19029 5971 5683 19030 5716 5432 19031 5972 5684 19032 5691 5407 19033 5957 5669 19034 5972 5684 19035 5689 5405 19036 5691 5407 19037 5973 5685 19038 5957 5669 19039 5958 5670 19040 5973 5685 19041 5972 5684 19042 5957 5669 19043 5974 5686 19044 5958 5670 19045 5959 5671 19046 5974 5686 19047 5973 5685 19048 5958 5670 19049 5975 5687 19050 5959 5671 19051 5960 5672 19052 5975 5687 19053 5974 5686 19054 5959 5671 19055 5976 5688 19056 5960 5672 19057 5961 5673 19058 5976 5688 19059 5975 5687 19060 5960 5672 19061 5977 5689 19062 5961 5673 19063 5962 5674 19064 5977 5689 19065 5976 5688 19066 5961 5673 19067 5978 5690 19068 5962 5674 19069 5963 5675 19070 5978 5690 19071 5977 5689 19072 5962 5674 19073 5979 5691 19074 5963 5675 19075 5964 5676 19076 5979 5691 19077 5978 5690 19078 5963 5675 19079 5980 5692 19080 5964 5676 19081 5965 5677 19082 5980 5692 19083 5979 5691 19084 5964 5676 19085 5981 5693 19086 5965 5677 19087 5966 5678 19088 5981 5693 19089 5980 5692 19090 5965 5677 19091 5982 5694 19092 5966 5678 19093 5967 5679 19094 5982 5694 19095 5981 5693 19096 5966 5678 19097 5983 5695 19098 5967 5679 19099 5968 5680 19100 5983 5695 19101 5982 5694 19102 5967 5679 19103 5984 5696 19104 5968 5680 19105 5969 5681 19106 5984 5696 19107 5983 5695 19108 5968 5680 19109 5985 5697 19110 5969 5681 19111 5970 5682 19112 5985 5697 19113 5984 5696 19114 5969 5681 19115 5986 5698 19116 5970 5682 19117 5971 5683 19118 5986 5698 19119 5985 5697 19120 5970 5682 19121 5721 5437 19122 5971 5683 19123 5719 5435 19124 5721 5437 19125 5986 5698 19126 5971 5683 19127 5987 5699 19128 5689 5405 19129 5972 5684 19130 5987 5699 19131 5687 5403 19132 5689 5405 19133 5988 5700 19134 5972 5684 19135 5973 5685 19136 5988 5700 19137 5987 5699 19138 5972 5684 19139 5989 5701 19140 5973 5685 19141 5974 5686 19142 5989 5701 19143 5988 5700 19144 5973 5685 19145 5990 5702 19146 5974 5686 19147 5975 5687 19148 5990 5702 19149 5989 5701 19150 5974 5686 19151 5991 5703 19152 5975 5687 19153 5976 5688 19154 5991 5703 19155 5990 5702 19156 5975 5687 19157 5992 5704 19158 5976 5688 19159 5977 5689 19160 5992 5704 19161 5991 5703 19162 5976 5688 19163 5993 5705 19164 5977 5689 19165 5978 5690 19166 5993 5705 19167 5992 5704 19168 5977 5689 19169 5994 5706 19170 5978 5690 19171 5979 5691 19172 5994 5706 19173 5993 5705 19174 5978 5690 19175 5995 5707 19176 5979 5691 19177 5980 5692 19178 5995 5707 19179 5994 5706 19180 5979 5691 19181 5996 5708 19182 5980 5692 19183 5981 5693 19184 5996 5708 19185 5995 5707 19186 5980 5692 19187 5997 5709 19188 5981 5693 19189 5982 5694 19190 5997 5709 19191 5996 5708 19192 5981 5693 19193 5998 5710 19194 5982 5694 19195 5983 5695 19196 5998 5710 19197 5997 5709 19198 5982 5694 19199 5999 5711 19200 5983 5695 19201 5984 5696 19202 5999 5711 19203 5998 5710 19204 5983 5695 19205 6000 5712 19206 5984 5696 19207 5985 5697 19208 6000 5712 19209 5999 5711 19210 5984 5696 19211 6001 5713 19212 5985 5697 19213 5986 5698 19214 6001 5713 19215 6000 5712 19216 5985 5697 19217 5724 5440 19218 5986 5698 19219 5721 5437 19220 5724 5440 19221 6001 5713 19222 5986 5698 19223 5682 5398 19224 5687 5403 19225 5987 5699 19226 5941 5653 19227 5987 5699 19228 5988 5700 19229 5941 5653 19230 5682 5398 19231 5987 5699 19232 5940 5652 19233 5988 5700 19234 5989 5701 19235 5940 5652 19236 5941 5653 19237 5988 5700 19238 5939 5651 19239 5989 5701 19240 5990 5702 19241 5939 5651 19242 5940 5652 19243 5989 5701 19244 5938 5650 19245 5990 5702 19246 5991 5703 19247 5938 5650 19248 5939 5651 19249 5990 5702 19250 5937 5649 19251 5991 5703 19252 5992 5704 19253 5937 5649 19254 5938 5650 19255 5991 5703 19256 5936 5648 19257 5992 5704 19258 5993 5705 19259 5936 5648 19260 5937 5649 19261 5992 5704 19262 5935 5647 19263 5993 5705 19264 5994 5706 19265 5935 5647 19266 5936 5648 19267 5993 5705 19268 5934 5646 19269 5994 5706 19270 5995 5707 19271 5934 5646 19272 5935 5647 19273 5994 5706 19274 5933 5645 19275 5995 5707 19276 5996 5708 19277 5933 5645 19278 5934 5646 19279 5995 5707 19280 5932 5644 19281 5996 5708 19282 5997 5709 19283 5932 5644 19284 5933 5645 19285 5996 5708 19286 5931 5643 19287 5997 5709 19288 5998 5710 19289 5931 5643 19290 5932 5644 19291 5997 5709 19292 5930 5642 19293 5998 5710 19294 5999 5711 19295 5930 5642 19296 5931 5643 19297 5998 5710 19298 5929 5641 19299 5999 5711 19300 6000 5712 19301 5929 5641 19302 5930 5642 19303 5999 5711 19304 5928 5640 19305 6000 5712 19306 6001 5713 19307 5928 5640 19308 5929 5641 19309 6000 5712 19310 5927 5639 19311 6001 5713 19312 5724 5440 19313 5927 5639 19314 5928 5640 19315 6001 5713 19316 5726 5442 19317 5927 5639 19318 5724 5440 19319 6014 5714 19320 6015 5715 19321 6016 5716 19322 6017 5717 19323 6018 5718 19324 6019 5719 19325 6020 5720 19326 6014 5714 19327 6016 5716 19328 6021 5721 19329 6022 5721 19330 6023 5721 19331 6021 5722 19332 6023 5722 19333 6024 5722 19334 6014 5714 19335 6025 5723 19336 6015 5715 19337 6026 5724 19338 6019 5719 19339 6027 5725 19340 6028 5726 19341 6017 5717 19342 6019 5719 19343 6026 5724 19344 6028 5726 19345 6019 5719 19346 6014 5714 19347 6029 5727 19348 6025 5723 19349 6030 5728 19350 6027 5725 19351 6031 5729 19352 6030 5728 19353 6026 5724 19354 6027 5725 19355 6014 5714 19356 6032 5730 19357 6029 5727 19358 6033 5731 19359 6031 5729 19360 6034 5732 19361 6033 5731 19362 6030 5728 19363 6031 5729 19364 6014 5714 19365 6035 5733 19366 6032 5730 19367 6036 5734 19368 6034 5732 19369 6037 5735 19370 6036 5734 19371 6033 5731 19372 6034 5732 19373 6038 5736 19374 6039 5736 19375 6040 5736 19376 6041 5737 19377 6036 5734 19378 6037 5735 19379 6020 5720 19380 6042 5738 19381 6014 5714 19382 6043 5739 19383 6014 5714 19384 6042 5738 19385 6038 5740 19386 6040 5740 19387 6044 5740 19388 6045 5741 19389 6046 5742 19390 6042 5738 19391 6047 5743 19392 6042 5738 19393 6046 5742 19394 6020 5720 19395 6045 5741 19396 6042 5738 19397 6048 5744 19398 6043 5739 19399 6042 5738 19400 6047 5743 19401 6048 5744 19402 6042 5738 19403 6049 5745 19404 6050 5746 19405 6046 5742 19406 6051 5747 19407 6046 5742 19408 6050 5746 19409 6045 5741 19410 6049 5745 19411 6046 5742 19412 6051 5747 19413 6047 5743 19414 6046 5742 19415 6052 5748 19416 6053 5749 19417 6050 5746 19418 6054 5750 19419 6050 5746 19420 6053 5749 19421 6049 5745 19422 6052 5748 19423 6050 5746 19424 6054 5750 19425 6051 5747 19426 6050 5746 19427 6055 5751 19428 6056 5752 19429 6053 5749 19430 6057 5753 19431 6053 5749 19432 6056 5752 19433 6052 5748 19434 6055 5751 19435 6053 5749 19436 6058 5754 19437 6054 5750 19438 6053 5749 19439 6057 5753 19440 6058 5754 19441 6053 5749 19442 6059 5755 19443 6060 5756 19444 6056 5752 19445 6061 5757 19446 6056 5752 19447 6060 5756 19448 6055 5751 19449 6059 5755 19450 6056 5752 19451 6061 5757 19452 6057 5753 19453 6056 5752 19454 6062 5758 19455 6063 5759 19456 6060 5756 19457 6064 5760 19458 6060 5756 19459 6063 5759 19460 6065 5761 19461 6062 5758 19462 6060 5756 19463 6066 5762 19464 6065 5761 19465 6060 5756 19466 6067 5763 19467 6066 5762 19468 6060 5756 19469 6068 5764 19470 6067 5763 19471 6060 5756 19472 6069 5765 19473 6068 5764 19474 6060 5756 19475 6059 5755 19476 6069 5765 19477 6060 5756 19478 6070 5766 19479 6061 5757 19480 6060 5756 19481 6064 5760 19482 6070 5766 19483 6060 5756 19484 6062 5758 19485 6071 5767 19486 6063 5759 19487 6072 5768 19488 6073 5768 19489 6074 5768 19490 6072 5769 19491 6075 5769 19492 6073 5769 19493 6076 5770 19494 6077 5771 19495 6078 5772 19496 6072 5773 19497 6074 5773 19498 6079 5773 19499 6080 5774 19500 6078 5772 19501 6081 5775 19502 6082 5776 19503 6078 5772 19504 6080 5774 19505 6076 5770 19506 6078 5772 19507 6082 5776 19508 6083 5777 19509 6081 5775 19510 6084 5778 19511 6080 5774 19512 6081 5775 19513 6083 5777 19514 6085 5779 19515 6084 5778 19516 6086 5780 19517 6083 5777 19518 6084 5778 19519 6085 5779 19520 6087 5781 19521 6086 5780 19522 6088 5782 19523 6085 5779 19524 6086 5780 19525 6087 5781 19526 6089 5783 19527 6090 5783 19528 6091 5783 19529 6087 5781 19530 6088 5782 19531 6092 5784 19532 6093 5785 19533 6069 5765 19534 6059 5755 19535 6089 5786 19536 6091 5786 19537 6094 5786 19538 6093 5785 19539 6059 5755 19540 6055 5751 19541 6095 5787 19542 6055 5751 19543 6052 5748 19544 6095 5787 19545 6093 5785 19546 6055 5751 19547 6096 5788 19548 6052 5748 19549 6049 5745 19550 6097 5789 19551 6095 5787 19552 6052 5748 19553 6098 5790 19554 6097 5789 19555 6052 5748 19556 6096 5788 19557 6098 5790 19558 6052 5748 19559 6099 5791 19560 6049 5745 19561 6045 5741 19562 6100 5792 19563 6096 5788 19564 6049 5745 19565 6101 5793 19566 6100 5792 19567 6049 5745 19568 6099 5791 19569 6101 5793 19570 6049 5745 19571 6102 5794 19572 6045 5741 19573 6020 5720 19574 6102 5794 19575 6099 5791 19576 6045 5741 19577 6021 5795 19578 6103 5795 19579 6022 5795 19580 6038 5796 19581 6044 5796 19582 6104 5796 19583 6105 5797 19584 6048 5744 19585 6047 5743 19586 6038 5798 19587 6104 5798 19588 6106 5798 19589 6107 5799 19590 6047 5743 19591 6051 5747 19592 6108 5800 19593 6105 5797 19594 6047 5743 19595 6109 5801 19596 6108 5800 19597 6047 5743 19598 6110 5802 19599 6109 5801 19600 6047 5743 19601 6111 5803 19602 6110 5802 19603 6047 5743 19604 6112 5804 19605 6111 5803 19606 6047 5743 19607 6107 5799 19608 6112 5804 19609 6047 5743 19610 6113 5805 19611 6051 5747 19612 6054 5750 19613 6113 5805 19614 6107 5799 19615 6051 5747 19616 6114 5806 19617 6054 5750 19618 6058 5754 19619 6114 5806 19620 6113 5805 19621 6054 5750 19622 6115 5807 19623 6058 5754 19624 6057 5753 19625 6116 5808 19626 6114 5806 19627 6058 5754 19628 6115 5807 19629 6116 5808 19630 6058 5754 19631 6117 5809 19632 6057 5753 19633 6061 5757 19634 6117 5809 19635 6115 5807 19636 6057 5753 19637 6118 5810 19638 6061 5757 19639 6070 5766 19640 6118 5810 19641 6117 5809 19642 6061 5757 19643 6072 5811 19644 6119 5811 19645 6075 5811 19646 6120 5812 19647 6118 5810 19648 6070 5766 19649 6121 5813 19650 6120 5812 19651 6070 5766 19652 6122 5814 19653 6121 5813 19654 6070 5766 19655 6123 5815 19656 6122 5814 19657 6070 5766 19658 6124 5816 19659 6123 5816 19660 6070 5816 19661 6072 5817 19662 6125 5817 19663 6119 5817 19664 6126 5818 19665 6127 5819 19666 6128 5820 19667 6129 5821 19668 6038 5821 19669 6106 5821 19670 6130 5822 19671 6128 5820 19672 6131 5823 19673 6132 5824 19674 6128 5820 19675 6130 5822 19676 6126 5818 19677 6128 5820 19678 6132 5824 19679 6133 5825 19680 6131 5823 19681 6134 5826 19682 6130 5822 19683 6131 5823 19684 6133 5825 19685 6135 5827 19686 6134 5826 19687 6136 5828 19688 6133 5825 19689 6134 5826 19690 6135 5827 19691 6135 5827 19692 6136 5828 19693 6137 5829 19694 6138 5830 19695 6112 5804 19696 6107 5799 19697 6139 5831 19698 6137 5829 19699 6140 5832 19700 6135 5827 19701 6137 5829 19702 6139 5831 19703 6141 5833 19704 6107 5799 19705 6113 5805 19706 6142 5834 19707 6138 5830 19708 6107 5799 19709 6143 5835 19710 6142 5834 19711 6107 5799 19712 6144 5836 19713 6143 5835 19714 6107 5799 19715 6141 5833 19716 6144 5836 19717 6107 5799 19718 6145 5837 19719 6113 5805 19720 6114 5806 19721 6146 5838 19722 6141 5833 19723 6113 5805 19724 6147 5839 19725 6146 5838 19726 6113 5805 19727 6145 5837 19728 6147 5839 19729 6113 5805 19730 6148 5840 19731 6114 5806 19732 6116 5808 19733 6149 5841 19734 6145 5837 19735 6114 5806 19736 6148 5840 19737 6149 5841 19738 6114 5806 19739 6150 5842 19740 6116 5808 19741 6115 5807 19742 6151 5843 19743 6148 5840 19744 6116 5808 19745 6152 5844 19746 6151 5843 19747 6116 5808 19748 6150 5842 19749 6152 5844 19750 6116 5808 19751 6153 5845 19752 6115 5807 19753 6117 5809 19754 6154 5846 19755 6150 5842 19756 6115 5807 19757 6153 5845 19758 6154 5846 19759 6115 5807 19760 6155 5847 19761 6117 5809 19762 6118 5810 19763 6156 5848 19764 6153 5845 19765 6117 5809 19766 6157 5849 19767 6156 5848 19768 6117 5809 19769 6155 5847 19770 6157 5849 19771 6117 5809 19772 6158 5850 19773 6159 5851 19774 6160 5852 19775 6161 5853 19776 6155 5847 19777 6118 5810 19778 6162 5854 19779 6161 5853 19780 6118 5810 19781 6163 5855 19782 6162 5854 19783 6118 5810 19784 6158 5850 19785 6164 5856 19786 6159 5851 19787 6165 5857 19788 6160 5852 19789 6166 5858 19790 6158 5850 19791 6160 5852 19792 6165 5857 19793 6167 5859 19794 6166 5858 19795 6168 5860 19796 6165 5857 19797 6166 5858 19798 6167 5859 19799 6169 5861 19800 6168 5860 19801 6170 5862 19802 6167 5859 19803 6168 5860 19804 6169 5861 19805 6171 5863 19806 6170 5862 19807 6172 5864 19808 6169 5861 19809 6170 5862 19810 6171 5863 19811 6171 5863 19812 6172 5864 19813 6173 5865 19814 6139 5831 19815 6140 5832 19816 6174 5866 19817 6175 5867 19818 6174 5866 19819 6176 5868 19820 6139 5831 19821 6174 5866 19822 6175 5867 19823 6175 5867 19824 6176 5868 19825 6177 5869 19826 6178 5870 19827 6177 5869 19828 6179 5871 19829 6175 5867 19830 6177 5869 19831 6178 5870 19832 6178 5870 19833 6179 5871 19834 6180 5872 19835 6181 5873 19836 6180 5872 19837 6182 5874 19838 6178 5870 19839 6180 5872 19840 6181 5873 19841 6183 5875 19842 6182 5874 19843 6184 5876 19844 6181 5873 19845 6182 5874 19846 6183 5875 19847 6185 5877 19848 6184 5876 19849 6186 5878 19850 6183 5875 19851 6184 5876 19852 6185 5877 19853 6187 5879 19854 6186 5878 19855 6188 5880 19856 6185 5877 19857 6186 5878 19858 6187 5879 19859 6189 5881 19860 6188 5880 19861 6190 5882 19862 6187 5879 19863 6188 5880 19864 6189 5881 19865 6191 5883 19866 6190 5882 19867 6192 5884 19868 6193 5885 19869 6190 5882 19870 6191 5883 19871 6189 5881 19872 6190 5882 19873 6193 5885 19874 6194 5886 19875 6192 5884 19876 6195 5887 19877 6191 5883 19878 6192 5884 19879 6194 5886 19880 6196 5888 19881 6195 5887 19882 6197 5889 19883 6194 5886 19884 6195 5887 19885 6196 5888 19886 6198 5890 19887 6197 5889 19888 6199 5891 19889 6196 5888 19890 6197 5889 19891 6198 5890 19892 6200 5892 19893 6199 5891 19894 6201 5893 19895 6198 5890 19896 6199 5891 19897 6200 5892 19898 6200 5892 19899 6201 5893 19900 6202 5894 19901 6203 5895 19902 6202 5894 19903 6204 5896 19904 6200 5892 19905 6202 5894 19906 6203 5895 19907 6203 5895 19908 6204 5896 19909 6205 5897 19910 6206 5898 19911 6205 5897 19912 6207 5899 19913 6203 5895 19914 6205 5897 19915 6206 5898 19916 6206 5898 19917 6207 5899 19918 6164 5856 19919 6206 5898 19920 6164 5856 19921 6158 5850 19922 6208 5900 19923 6094 5900 19924 6209 5900 19925 6089 5901 19926 6094 5901 19927 6208 5901 19928 6210 5902 19929 6211 5903 19930 6212 5904 19931 6208 5905 19932 6209 5905 19933 6213 5905 19934 6214 5906 19935 6212 5904 19936 6215 5907 19937 6210 5902 19938 6212 5904 19939 6214 5906 19940 6216 5908 19941 6215 5907 19942 6217 5909 19943 6214 5906 19944 6215 5907 19945 6216 5908 19946 6218 5910 19947 6217 5909 19948 6219 5911 19949 6216 5908 19950 6217 5909 19951 6218 5910 19952 6220 5912 19953 6219 5911 19954 6221 5913 19955 6218 5910 19956 6219 5911 19957 6220 5912 19958 6220 5912 19959 6221 5913 19960 6222 5914 19961 6223 5915 19962 6224 5915 19963 6103 5915 19964 6220 5912 19965 6222 5914 19966 6225 5916 19967 6021 5917 19968 6223 5917 19969 6103 5917 19970 6226 5918 19971 6227 5918 19972 6228 5918 19973 6229 5919 19974 6230 5919 19975 6227 5919 19976 6226 5920 19977 6229 5920 19978 6227 5920 19979 6231 5921 19980 6228 5921 19981 6232 5921 19982 6231 5922 19983 6226 5922 19984 6228 5922 19985 6233 5923 19986 6232 5923 19987 6234 5923 19988 6233 5924 19989 6231 5924 19990 6232 5924 19991 6235 5925 19992 6234 5925 19993 6236 5925 19994 6235 5926 19995 6233 5926 19996 6234 5926 19997 6237 5927 19998 6236 5927 19999 6238 5927 20000 6237 5928 20001 6235 5928 20002 6236 5928 20003 6239 5929 20004 6238 5929 20005 6240 5929 20006 6239 5930 20007 6237 5930 20008 6238 5930 20009 6241 5931 20010 6239 5931 20011 6240 5931 20012 6242 5932 20013 6241 5932 20014 6240 5932 20015 6243 5933 20016 6244 5933 20017 6230 5933 20018 6245 5934 20019 6246 5934 20020 6244 5934 20021 6243 5935 20022 6245 5935 20023 6244 5935 20024 6229 5936 20025 6243 5936 20026 6230 5936 20027 6247 5937 20028 6248 5937 20029 6246 5937 20030 6245 5938 20031 6247 5938 20032 6246 5938 20033 6242 5939 20034 6249 5939 20035 6241 5939 20036 6250 5940 20037 6251 5940 20038 6249 5940 20039 6242 5941 20040 6250 5941 20041 6249 5941 20042 6252 5942 20043 6253 5942 20044 6251 5942 20045 6250 5943 20046 6252 5943 20047 6251 5943 20048 6254 5944 20049 6255 5944 20050 6253 5944 20051 6252 5945 20052 6254 5945 20053 6253 5945 20054 6256 5946 20055 6257 5946 20056 6255 5946 20057 6254 5947 20058 6256 5947 20059 6255 5947 20060 6258 5948 20061 6259 5948 20062 6257 5948 20063 6256 5949 20064 6258 5949 20065 6257 5949 20066 6260 5950 20067 6261 5950 20068 6259 5950 20069 6258 5951 20070 6260 5951 20071 6259 5951 20072 6262 5952 20073 6263 5952 20074 6261 5952 20075 6260 5953 20076 6262 5953 20077 6261 5953 20078 6264 5954 20079 6265 5954 20080 6263 5954 20081 6262 5955 20082 6264 5955 20083 6263 5955 20084 6266 5956 20085 6267 5956 20086 6265 5956 20087 6264 5957 20088 6266 5957 20089 6265 5957 20090 6268 5958 20091 6269 5958 20092 6267 5958 20093 6266 5959 20094 6268 5959 20095 6267 5959 20096 6270 5960 20097 6271 5960 20098 6269 5960 20099 6268 5961 20100 6270 5961 20101 6269 5961 20102 6272 5962 20103 6273 5962 20104 6271 5962 20105 6270 5963 20106 6272 5963 20107 6271 5963 20108 6272 5964 20109 6274 5964 20110 6273 5964 20111

+
+
+
+
+ + + + + 7.54969e-11 -3.25837e-10 -9.99987e-4 0 0 9.99987e-4 -3.25837e-10 -0.2604 9.99987e-4 0 7.54969e-11 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl new file mode 100644 index 0000000000000000000000000000000000000000..5a3d19b65d0abf6b8ea391d05abf26586a20216b GIT binary patch literal 4284 zcmb7{Z-^CD7{*UUf1o5&SHcQz1yYF;t|fMNX8I>veJWYML^nn6P5Z0us-^3CFVTn4 zqM{F5yDBB6SOonO3U=;*6>d;1Mj&R^mp(`l3+)#TZ9C67^UORm>k`d}yU))1{@&-D zGv~Z>@ABt2Zs^_As8=5A-SBkf?xz~h)Em7E7cW}6ta4M|<~5aDZ#Mty>ap3A6Wf!< zi`Rt!=RUbP9)0A^uw(bz0rfTe?hFsj>x>T%e;1zazR2eNV~J-|LL=03ghnL}sTDzK z7B%Wx9poOK$%rh%EO?NHHfHp6GupkRZv^DY+H=86e{YRzy9R^yu^quJ!vlfpulL_* z=dtqVW>kCl(8zl|qg~8G1oV&ZSK~bku5cQaPTg?UdK|GHU!@*pf?4YAXQ7{x6^nMG z^&WY4E3vg)Ryy{W^FWSjGOa`-93klGM&${NB+bhFv=Zy%Z_%S%mz6xRcG1fA?E1C{ zSzJ+$3M*~3o0ESYU`S{Lt3Vn#s*PEldMKe;>W%xxY+txHoVl$pvO7G$ZpRMS-46Z0 z>Yd@z&+oUpq(o#9(9F_G$oKme3X$>q2E$`pj^ji*zw~rv-ctz~Rlx&(r>f`NiE2d` zj{Vt5k1~NQ^>!Y~#T~1bq(uDd@9Vs=MwJJ)U=;Y)zPjwbC>1M|15@Z+(iLh*7a$X*ZZk%uNZ6 zs0Zq@lJ~gM5|fk7Lc?5%(KMRme2@Cg)FUve1Gfh;^5(#9ONZ-WCn`no30 zF8=~q4;^?tIPvkAJ9l!rgwW2Qb*a-npH(vE_?c#O$-!FJ2P2nP)tyAzMTLMz=Qn#k z!3uz2&!9$E(@Mx|Me|?X%Fd9D7g;(FRsvznqeH*7PtI((GbmZvPDIZ635{@6>{qOW z9AkQ{$1m0cnh{G#$0>U#L3f>pR)RKW|JoVt?w1GLE&-9QkDCW|{>(vqm=iH0@KDW4 zw!_&T0t%OXYVnG6mq7C!PVIN%@R?>Z@#^}n%ht`R zmIV2M90p%M5otLXji z_|8re>QSaSLfkjzf-iT4v%0q=S_^B%-Hsg9IiV4(G_%Uyo|tVtK+s+Nw30E^f$KlR zs7Op#mz6;07u@;ov+u!7BZK$zY`cTqs2C}~IeA|RuNlESL>K&WYPylApU>X={eom- zG{86gtS&Tv;~-15F(fnsKW0I5gx=#F>oH#PDAPs4bN-VNU1?nf&Gns{M0q5 + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T13:56:30 + 2019-01-15T13:56:30 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 77.5 642.6032 38.3792 50.47308 648.7558 42.62536 47.32196 643.5922 47.79023 35.42542 717.9 35.42658 47.32196 643.5922 47.79023 50.47308 648.7558 42.62536 77.5 639.1355 41.03991 47.32196 639.7785 50.22485 40.74011 643.5922 53.51185 47.32196 639.7785 50.22485 47.32196 643.5922 47.79023 32.20323 717.9 38.37903 40.74011 643.5922 53.51185 77.5 648.7792 32.20318 53.95177 653.757 36.08637 38.37838 717.9 32.20416 53.95177 653.757 36.08637 77.5 645.8261 35.42605 77.5 651.4399 28.73553 57.02378 657.8309 28.98574 45.52315 703.7416 27.85435 57.02378 657.8309 28.98574 41.03964 717.9 28.736 62.10222 659.8765 22.19279 59.41202 660.857 21.75381 48.57522 701.4026 23.37947 59.41202 660.857 21.75381 64.18595 656.2126 27.95369 62.00942 659.3376 23.41485 62.01773 658.7743 24.55237 62.11816 658.2664 25.47139 62.29016 657.8128 26.21096 62.55842 657.3568 26.87471 62.98109 656.881 27.46733 63.5478 656.4749 27.85109 45.74649 703.0996 27.77269 46.11853 702.5121 27.41659 46.58361 702.0513 26.83254 47.04394 701.7499 26.16085 47.50069 701.5541 25.41783 48.0111 701.4323 24.50188 62.75878 662.3268 15 61.0937 662.9323 14.49737 51.62331 702.0537 15 61.0937 662.9323 14.49737 62.46256 661.2213 18.63271 49.12485 701.4769 22.15966 50.49533 701.7933 18.61869 77.5 659.7387 8.700512 62.08981 664.1434 7.241837 49.33865 717.9 8.700526 62.08981 664.1434 7.241837 77.5 658.7927 12.96738 48.39268 717.9 12.96714 77.5 660.5 0 62.4189 664.541 0 49.90924 717.9 4.36768 62.4189 664.541 0 77.5 660.3093 4.367365 77.5 660.3093 -4.367365 62.4189 664.541 0 77.5 660.5 0 62.08983 664.1434 -7.241657 50.1 717.9 0 62.4189 664.541 0 62.08983 664.1434 -7.241657 50.1 717.9 0 77.5 655.4 0 77.5 660.5 0 77.5 660.3093 4.367365 77.5 654.6337 -8.269279 77.5 660.3093 -4.367365 77.5 654.6337 8.269279 77.5 659.7387 8.700512 77.5 658.7927 12.96738 68.53802 660.713 15 77.5 657.4785 17.13538 77.5 652.361 16.25649 77.5 657.4785 17.13538 65.66886 661.5147 15 67.89778 658.3236 21.85793 77.5 655.806 21.17293 77.5 655.806 21.17293 68.248 659.6306 18.46381 66.65319 656.5966 25.99156 77.5 653.7881 25.04945 77.5 648.6594 23.68981 77.5 653.7881 25.04945 67.05226 656.9118 25.1994 67.40803 657.3107 24.2416 67.70322 657.799 23.09259 77.5 651.4399 28.73553 64.84607 656.104 27.79201 65.52745 656.1467 27.3674 66.15838 656.3327 26.71948 77.5 643.6553 30.31632 77.5 648.7792 32.20318 77.5 645.8261 35.42605 77.5 637.5187 35.91052 77.5 642.6032 38.3792 77.5 630.4588 40.28202 77.5 639.1355 41.03991 77.5 635.4495 43.38809 77.5 622.7155 43.28194 77.5 635.4495 43.38809 47.32196 635.7871 52.35577 77.5 631.5729 45.40601 77.5 614.5524 44.808 77.5 631.5729 45.40601 77.5 589.2271 45.40601 77.5 627.5354 47.07843 47.32196 631.6422 54.1701 77.5 627.5354 47.07843 77.5 606.2476 44.808 77.5 593.2647 47.07843 77.5 623.3674 48.39265 47.32196 627.3689 55.65689 77.5 623.3674 48.39265 77.5 597.4326 48.39265 77.5 619.1005 49.33868 47.32196 622.9929 56.80713 77.5 619.1005 49.33868 77.5 601.6995 49.33868 77.5 614.7671 49.90929 47.32196 618.5408 57.61387 77.5 614.7671 49.90929 77.5 606.0329 49.90929 77.5 610.4 50.1 47.32196 614.0395 58.07224 77.5 610.4 50.1 47.32196 609.5162 58.17947 77.5 606.0329 49.90929 47.32196 600.5129 57.34001 77.5 601.6995 49.33868 47.32196 604.9982 57.93489 47.32196 596.0874 56.39839 77.5 597.4326 48.39265 47.32196 591.7484 55.11576 77.5 593.2647 47.07843 47.32196 587.5222 53.49986 77.5 589.2271 45.40601 47.32196 583.4343 51.56045 77.5 585.3505 43.38809 77.5 585.3505 43.38809 47.32196 579.5095 49.30928 77.5 581.6645 41.03991 77.5 598.0845 43.28194 77.5 581.6645 41.03991 47.32196 575.7714 46.75994 77.5 578.1968 38.3792 77.5 590.3413 40.28202 77.5 578.1968 38.3792 47.32196 572.2428 43.92787 77.5 574.9739 35.42605 77.5 583.2813 35.91052 77.5 574.9739 35.42605 47.32196 565.8976 37.48558 77.5 572.0208 32.20318 77.5 572.0208 32.20318 47.32196 568.9449 40.83017 47.32196 563.1195 33.91432 77.5 569.3601 28.73553 77.5 577.1447 30.31632 77.5 569.3601 28.73553 66.19887 564.5501 26.83977 77.5 567.0119 25.04945 77.5 567.0119 25.04945 47.32196 560.6272 30.138 64.23735 564.7014 28.1134 65.58666 564.7421 27.48444 64.90456 564.7985 27.92973 67.70588 563.0955 23.28385 77.5 564.994 21.17293 77.5 572.1406 23.68981 77.5 564.994 21.17293 67.41276 563.5829 24.41915 67.06282 563.9783 25.359 66.67414 564.2894 26.13252 68.26243 561.2156 18.57536 77.5 563.3216 17.13538 77.5 563.3216 17.13538 67.89778 562.5765 22.07587 68.56295 560.0941 15 77.5 562.0073 12.96738 77.5 568.439 16.25649 77.5 562.0073 12.96738 47.32196 553.7907 13.45434 77.5 561.0614 8.700512 77.5 561.0614 8.700512 62.78372 558.4802 15 65.6938 559.2923 15 47.32196 552.9165 9.015016 77.5 560.4907 4.367365 77.5 566.1663 8.269279 77.5 560.4907 4.367365 47.32196 552.2138 0 77.5 560.3 0 77.5 560.3 0 47.32196 552.3897 4.521177 47.32196 552.3897 -4.521177 77.5 560.3 0 47.32196 552.2138 0 77.5 560.4907 -4.367365 77.5 565.4 0 77.5 560.4907 -4.367365 38.81157 546.2232 0 47.32196 552.2138 0 47.32196 552.3897 4.521177 38.81157 546.8605 -9.02228 47.32196 552.3897 -4.521177 47.32196 552.2138 0 38.81157 546.2232 0 38.81157 546.8605 9.022282 47.32196 552.9165 9.015016 47.32196 553.7907 13.45434 47.32196 555.0073 17.81232 38.81157 548.76 17.86536 47.32196 555.0073 17.81232 62.47706 559.6246 18.74613 47.32196 556.5588 22.06258 47.32196 556.5588 22.06258 62.00885 561.5697 23.63809 47.32196 558.4359 26.17944 38.81157 551.8837 26.35358 47.32196 558.4359 26.17944 62.10222 561.0236 22.4144 63.02909 564.0618 27.68252 47.32196 560.6272 30.138 62.58525 563.5802 27.09823 62.30113 563.11 26.42594 62.12216 562.6474 25.68174 62.01863 562.1338 24.7637 38.81157 556.1698 34.31834 47.32196 563.1195 33.91432 63.60374 564.4553 28.03661 47.32196 565.8976 37.48558 38.81157 561.533 41.60146 47.32196 568.9449 40.83017 38.81157 567.8669 48.05825 47.32196 572.2428 43.92787 47.32196 575.7714 46.75994 38.81157 575.0455 53.56048 47.32196 579.5095 49.30928 47.32196 583.4343 51.56045 38.81157 582.9265 57.99885 47.32196 587.5222 53.49986 47.32196 591.7484 55.11576 38.81157 591.3531 61.2852 47.32196 596.0874 56.39839 47.32196 600.5129 57.34001 38.81157 600.158 63.35427 47.32196 604.9982 57.93489 38.81157 609.1664 64.16495 47.32196 609.5162 58.17947 47.32196 614.0395 58.07224 38.81157 618.1992 63.70113 47.32196 618.5408 57.61387 47.32196 622.9929 56.80713 38.81157 627.0772 61.97204 47.32196 627.3689 55.65689 47.32196 631.6422 54.1701 38.81157 635.6239 59.01202 47.32196 635.7871 52.35577 38.8449 643.5922 54.90309 62.10222 659.8765 15 62.75878 662.3268 15 62.46256 661.2213 18.63271 62.10222 659.8765 15 65.66886 661.5147 15 62.75878 662.3268 15 62.10222 659.8765 22.19279 62.10222 659.8765 15 62.10222 659.8765 22.19279 62.00942 659.3376 23.41485 62.01773 658.7743 24.55237 62.02574 658.7081 15 62.11816 658.2664 25.47139 62.29016 657.8128 26.21096 62.40221 657.5997 15 62.55842 657.3568 26.87471 62.98109 656.881 27.46733 63.174 656.7199 15 63.5478 656.4749 27.85109 64.18595 656.2126 27.95369 64.22358 656.2023 15 64.84607 656.104 27.79201 65.3913 656.1257 15 65.52745 656.1467 27.3674 66.15838 656.3327 26.71948 66.49959 656.5018 15 66.65319 656.5966 25.99156 67.05226 656.9118 25.1994 67.37981 657.2734 15 67.40803 657.3107 24.2416 67.70322 657.799 23.09259 67.89778 658.3236 21.85793 68.53802 660.713 15 67.89778 658.3236 21.85793 68.248 659.6306 18.46381 67.89778 658.3236 15 67.89778 658.3236 15 68.53802 660.713 15 62.02574 658.7081 15 67.89778 658.3236 15 67.89778 562.5765 15 68.56295 560.0941 15 68.26243 561.2156 18.57536 65.6938 559.2923 15 68.56295 560.0941 15 62.10222 561.0236 15 62.78372 558.4802 15 67.89778 562.5765 15 67.89778 562.5765 22.07587 67.89778 562.5765 15 67.89778 562.5765 22.07587 67.70588 563.0955 23.28385 67.41276 563.5829 24.41915 67.37981 563.6266 15 67.06282 563.9783 25.359 66.67414 564.2894 26.13252 66.49959 564.3983 15 66.19887 564.5501 26.83977 65.58666 564.7421 27.48444 65.3913 564.7742 15 64.90456 564.7985 27.92973 64.23735 564.7014 28.1134 64.22358 564.6976 15 63.60374 564.4553 28.03661 63.174 564.1801 15 63.02909 564.0618 27.68252 62.58525 563.5802 27.09823 62.40221 563.3004 15 62.30113 563.11 26.42594 62.12216 562.6474 25.68174 62.02574 562.192 15 62.01863 562.1338 24.7637 62.00885 561.5697 23.63809 62.10222 561.0236 22.4144 62.78372 558.4802 15 62.10222 561.0236 22.4144 62.47706 559.6246 18.74613 62.10222 561.0236 15 62.10222 561.0236 15 77.5 658.7927 -12.96738 61.09375 662.9324 -14.49705 49.33865 717.9 -8.700526 61.09375 662.9324 -14.49705 77.5 659.7387 -8.700512 49.90924 717.9 -4.36768 77.5 657.4785 -17.13538 59.41212 660.8571 -21.75345 48.39268 717.9 -12.96714 59.41212 660.8571 -21.75345 77.5 653.7881 -25.04945 57.02376 657.8309 -28.98578 45.40624 717.9 -21.17249 57.02376 657.8309 -28.98578 77.5 655.806 -21.17293 47.07857 717.9 -17.13495 77.5 651.4399 -28.73553 53.95239 653.7579 -36.08512 43.38824 717.9 -25.04928 53.95239 653.7579 -36.08512 77.5 645.8261 -35.42605 50.47417 648.7575 -42.62348 41.03964 717.9 -28.736 50.47417 648.7575 -42.62348 77.5 648.7792 -32.20318 77.5 639.1355 -41.03991 47.32196 643.5922 -47.79023 35.42542 717.9 -35.42658 47.32196 643.5922 -47.79023 77.5 642.6032 -38.3792 38.37838 717.9 -32.20416 77.5 635.4495 -43.38809 47.32196 639.7785 -50.22485 40.7393 643.5922 -53.51247 47.32196 643.5922 -47.79023 47.32196 639.7785 -50.22485 32.20323 717.9 -38.37903 40.7393 643.5922 -53.51247 47.32196 635.7871 -52.35577 38.84489 643.5922 -54.90309 47.32196 635.7871 -52.35577 77.5 631.5729 -45.40601 47.32196 631.6422 -54.1701 38.81157 635.6239 -59.01203 47.32196 631.6422 -54.1701 77.5 627.5354 -47.07843 47.32196 627.3689 -55.65689 47.32196 627.3689 -55.65689 77.5 623.3674 -48.39265 47.32196 622.9929 -56.80713 38.81157 627.0772 -61.97205 47.32196 622.9929 -56.80713 77.5 619.1005 -49.33868 47.32196 618.5408 -57.61387 47.32196 618.5408 -57.61387 77.5 614.7671 -49.90929 47.32196 614.0395 -58.07224 38.81157 618.1992 -63.70114 47.32196 614.0395 -58.07224 77.5 610.4 -50.1 47.32196 609.5162 -58.17947 47.32196 609.5162 -58.17947 77.5 606.0329 -49.90929 47.32196 604.9982 -57.93489 38.81157 609.1663 -64.16495 47.32196 604.9982 -57.93489 77.5 601.6995 -49.33868 47.32196 600.5129 -57.34001 38.81157 600.158 -63.35426 47.32196 600.5129 -57.34001 47.32196 596.0874 -56.39839 47.32196 596.0874 -56.39839 77.5 597.4326 -48.39265 47.32196 591.7484 -55.11576 38.81157 591.353 -61.2852 47.32196 591.7484 -55.11576 77.5 593.2647 -47.07843 47.32196 587.5222 -53.49986 47.32196 587.5222 -53.49986 77.5 589.2271 -45.40601 47.32196 583.4343 -51.56045 38.81157 582.9265 -57.99884 47.32196 583.4343 -51.56045 77.5 585.3505 -43.38809 47.32196 579.5095 -49.30928 47.32196 579.5095 -49.30928 77.5 581.6645 -41.03991 47.32196 575.7714 -46.75994 38.81157 575.0455 -53.56047 47.32196 575.7714 -46.75994 77.5 578.1968 -38.3792 47.32196 572.2428 -43.92787 47.32196 572.2428 -43.92787 77.5 574.9739 -35.42605 47.32196 568.9449 -40.83017 38.81157 567.8669 -48.05824 47.32196 568.9449 -40.83017 77.5 572.0208 -32.20318 47.32196 565.8976 -37.48558 38.81157 561.533 -41.60145 47.32196 565.8976 -37.48558 47.32196 563.1195 -33.91432 47.32196 563.1195 -33.91432 77.5 569.3601 -28.73553 47.32196 560.6272 -30.138 38.81157 556.1698 -34.31834 47.32196 560.6272 -30.138 77.5 567.0119 -25.04945 47.32196 558.4359 -26.17944 47.32196 558.4359 -26.17944 77.5 564.994 -21.17293 47.32196 556.5588 -22.06258 38.81157 551.8837 -26.35357 47.32196 556.5588 -22.06258 77.5 563.3216 -17.13538 47.32196 555.0073 -17.81232 47.32196 555.0073 -17.81232 77.5 562.0073 -12.96738 47.32196 553.7907 -13.45434 38.81157 548.76 -17.86535 47.32196 553.7907 -13.45434 77.5 561.0614 -8.700512 47.32196 552.9165 -9.015016 47.32196 552.9165 -9.015016 77.5 566.1663 -8.269279 77.5 561.0614 -8.700512 77.5 562.0073 -12.96738 77.5 568.439 -16.25649 77.5 563.3216 -17.13538 77.5 564.994 -21.17293 77.5 572.1406 -23.68981 77.5 567.0119 -25.04945 77.5 569.3601 -28.73553 77.5 577.1447 -30.31632 77.5 572.0208 -32.20318 77.5 574.9739 -35.42605 77.5 583.2813 -35.91052 77.5 578.1968 -38.3792 77.5 590.3413 -40.28202 77.5 581.6645 -41.03991 77.5 598.0845 -43.28194 77.5 585.3505 -43.38809 77.5 606.2476 -44.808 77.5 589.2271 -45.40601 77.5 631.5729 -45.40601 77.5 593.2647 -47.07843 77.5 614.5524 -44.808 77.5 627.5354 -47.07843 77.5 597.4326 -48.39265 77.5 623.3674 -48.39265 77.5 601.6995 -49.33868 77.5 619.1005 -49.33868 77.5 606.0329 -49.90929 77.5 614.7671 -49.90929 77.5 610.4 -50.1 77.5 635.4495 -43.38809 77.5 622.7155 -43.28194 77.5 639.1355 -41.03991 77.5 630.4588 -40.28202 77.5 642.6032 -38.3792 77.5 637.5187 -35.91052 77.5 645.8261 -35.42605 77.5 648.7792 -32.20318 77.5 643.6553 -30.31632 77.5 651.4399 -28.73553 77.5 653.7881 -25.04945 77.5 648.6594 -23.68981 77.5 655.806 -21.17293 77.5 657.4785 -17.13538 77.5 652.361 -16.25649 77.5 658.7927 -12.96738 77.5 659.7387 -8.700512 110 655.4 0 77.5 655.4 0 77.5 654.6337 8.269279 110 654.6336 -8.269443 77.5 654.6337 -8.269279 77.5 655.4 0 110 655.4 0 110 654.6336 8.269443 77.5 652.361 16.25649 110 652.361 16.25633 77.5 648.6594 23.68981 110 648.6597 23.68929 77.5 643.6553 30.31632 110 643.6558 30.31576 77.5 637.5187 35.91052 110 637.5191 35.91038 77.5 630.4588 40.28202 110 630.4579 40.28251 77.5 622.7155 43.28194 110 622.7141 43.2823 77.5 614.5524 44.808 110 614.5518 44.80796 77.5 606.2476 44.808 110 606.2483 44.80796 77.5 598.0845 43.28194 110 598.0859 43.2823 77.5 590.3413 40.28202 110 590.3421 40.28251 77.5 583.2813 35.91052 110 583.281 35.91038 77.5 577.1447 30.31632 110 577.1442 30.31576 77.5 572.1406 23.68981 110 572.1403 23.68929 77.5 568.439 16.25649 110 568.439 16.25633 77.5 566.1663 8.269279 110 566.1664 8.269443 77.5 565.4 0 110 565.4 0 77.5 565.4 0 77.5 566.1663 -8.269279 110 565.4 0 110 566.1664 -8.269443 77.5 568.439 -16.25649 110 568.439 -16.25633 77.5 572.1406 -23.68981 110 572.1403 -23.68929 77.5 577.1447 -30.31632 110 577.1442 -30.31576 77.5 583.2813 -35.91052 110 583.281 -35.91038 77.5 590.3413 -40.28202 110 590.3421 -40.28251 77.5 598.0845 -43.28194 110 598.0859 -43.2823 77.5 606.2476 -44.808 110 606.2483 -44.80796 77.5 614.5524 -44.808 110 614.5518 -44.80796 77.5 622.7155 -43.28194 110 622.7141 -43.2823 77.5 630.4588 -40.28202 110 630.4579 -40.28251 77.5 637.5187 -35.91052 110 637.5191 -35.91038 77.5 643.6553 -30.31632 110 643.6558 -30.31576 77.5 648.6594 -23.68981 110 648.6597 -23.68929 77.5 652.361 -16.25649 110 652.361 -16.25633 -12.01715 643.2918 66.32284 -2.000701 643.5922 67.22554 -11.12075 643.5922 66.32952 -4.365938 717.9 49.9093 -11.12075 643.5922 66.32952 -2.000701 643.5922 67.22554 -20.79582 641.5518 64.45455 -12.01715 643.2918 66.32284 -11.12075 643.5922 66.32952 -12.9663 717.9 48.39302 -20.79582 641.5518 64.45455 -8.698943 717.9 49.33895 -1.503472 636.2645 70.38302 -1.502664 643.5922 67.23851 -1.502664 643.5922 67.23851 -12.02569 633.3775 70.37342 7.146612 643.5922 66.87452 0 717.9 50.09988 7.146612 643.5922 66.87452 -1.503472 628.6304 72.73509 9.048579 634.6543 70.39072 9.051564 643.5922 66.64341 -12.02569 622.9602 72.95633 -1.50404 620.7918 74.26136 9.048579 625.2584 72.95446 -4.358844 619.9525 74.26136 -1.494158 620.793 57.9 -1.50404 620.7918 74.26136 -4.358844 619.9525 74.26136 0.001194 620.9 74.26136 0.001194 620.9 74.26136 -6.880674 618.3314 74.26136 -4.361477 619.9512 57.9 -6.880674 618.3314 74.26136 -8.838978 616.0677 74.26136 -8.832825 616.0772 57.9 -8.838978 616.0677 74.26136 -6.875587 618.3356 57.9 -12.02569 612.2788 74.00576 -10.07555 613.3552 74.26136 -10.07455 613.3586 57.9 -10.07555 613.3552 74.26136 -10.5 610.4 74.26136 -10.5 610.4 74.26136 -12.02569 601.5579 73.49967 -10.07569 607.4453 74.26136 -10.5 610.4 57.9 -10.5 610.4 74.26136 -10.07569 607.4453 74.26136 -10.5 610.4 57.9 -8.839447 604.733 74.26136 -10.07455 607.4414 57.9 -8.839447 604.733 74.26136 -6.880616 602.4686 74.26136 -8.832825 604.7229 57.9 -6.880616 602.4686 74.26136 -4.358481 600.8474 74.26136 -6.875587 602.4644 57.9 -4.358481 600.8474 74.26136 -12.02569 591.0229 71.44866 -1.50405 600.0083 74.26136 -4.361477 600.8488 57.9 -1.50405 600.0083 74.26136 -1.503472 589.5205 72.01934 0.001203954 599.9 74.26136 -1.494158 600.007 57.9 0.001203954 599.9 74.26136 -12.02569 580.8952 67.89588 -1.503472 579.4576 68.30305 9.048579 585.3692 70.11833 9.048579 595.1387 72.87124 -12.02569 571.3876 62.91597 -1.503472 570.028 63.18892 9.048579 576.0648 66.06224 -12.02569 562.7001 56.61362 -1.503472 561.4246 56.78161 9.048579 567.3986 60.77832 -12.02569 555.0152 49.12131 -1.503472 553.8236 49.21224 9.048579 559.5316 54.36479 -12.02569 548.4944 40.59651 -1.503472 547.3804 40.63573 9.048579 552.6101 46.94086 -12.02569 543.2748 31.21841 -1.503472 542.2269 31.22758 9.048579 546.7626 38.6445 -12.02569 539.4661 21.18412 -1.503472 538.4686 21.18036 9.048579 542.0978 29.6299 -12.02569 537.1484 10.70456 -1.503472 536.1824 10.69966 9.048579 538.7025 20.06462 -1.609086 535.4172 0 -1.503472 535.4151 0 9.048579 536.6397 10.12641 -12.02569 536.3704 0 -12.02569 537.1484 -10.70458 -1.503472 535.4151 0 -1.609086 535.4172 0 8.933217 535.9339 0 -1.503472 536.2016 -10.83232 8.933217 535.9339 0 -12.02569 536.3704 0 -22.30924 538.7949 0 -22.30924 539.5208 -10.16992 -22.30924 538.7949 0 -18.22507 539.2112 15 -22.30924 539.1934 7.543758 -18.56588 541.286 22.43991 -19.2432 544.8673 30.98637 -19.03967 544.1703 29.59924 -19.11506 544.5068 30.29371 -22.30924 551.7663 41.10218 -22.30847 546.6681 32.64316 -21.79627 546.6771 33.00472 -19.45848 545.278 31.7094 -19.7769 545.6984 32.36631 -20.14481 546.0416 32.82046 -20.60956 546.3424 33.11888 -21.1875 546.5719 33.1973 -22.30924 557.9962 48.7969 -22.30924 565.2279 55.55876 -22.30924 573.3231 61.25849 -22.30924 582.1272 65.78712 -22.30924 601.1782 71.00885 -22.30924 591.4718 69.05809 -22.30924 611.0609 71.60211 -22.30924 620.931 70.82653 -22.30924 630.5997 68.69696 -20.52479 640.4414 65.5839 -22.30034 639.8469 65.27307 -20.52479 640.4414 65.5839 4.365938 717.9 49.9093 9.051564 643.5922 66.64341 16.16083 643.5922 65.28479 8.698943 717.9 49.33895 16.16083 643.5922 65.28479 19.42106 633.9975 68.49073 19.4319 643.5922 64.38694 8.839296 616.0672 74.26136 9.102138 615.6346 74.26136 19.42106 623.839 71.18438 6.889374 618.3238 74.26136 4.377737 619.9439 74.26136 1.506638 620.7913 74.26136 10.07455 613.3586 57.9 9.102138 615.6346 74.26136 8.839296 616.0672 74.26136 19.42106 613.3977 72.37981 10.07566 613.3549 74.26136 10.07566 613.3549 74.26136 8.832825 616.0772 57.9 6.889374 618.3238 74.26136 6.875587 618.3356 57.9 4.377737 619.9439 74.26136 4.361477 619.9512 57.9 1.506638 620.7913 74.26136 1.494158 620.793 57.9 12.9663 717.9 48.39302 19.4319 643.5922 64.38694 29.40812 634.3891 64.68914 24.89033 643.5922 62.47997 17.13559 717.9 47.07846 24.89033 643.5922 62.47997 29.40812 624.5779 67.52149 29.40812 614.456 68.87461 9.102197 605.1655 74.26136 19.42106 602.8932 72.05186 29.40812 604.2453 68.71887 10.07558 607.4449 74.26136 10.5 610.4 74.26136 19.42106 592.5468 70.20745 29.40812 594.1694 67.05767 19.42106 582.5761 66.88536 29.40812 584.4491 63.9274 19.42106 573.191 62.15553 29.40812 575.2973 59.39665 19.42106 564.589 56.11752 29.40812 566.9145 53.56467 19.42106 556.9512 48.8984 19.42106 550.4384 40.65012 29.40812 559.4844 46.55923 19.40964 545.1973 31.57325 19.58107 545.4585 32.00284 29.40812 553.1697 38.53379 20.42887 546.2397 33.03202 19.96192 545.8854 32.62488 19.28491 544.96 31.15608 19.83661 545.7622 15 19.40964 545.1973 31.57325 19.28491 544.96 31.15608 19.58107 545.4585 32.00284 19.08872 544.4082 30.09496 19.20601 544.7763 15 19.08872 544.4082 30.09496 19.00259 543.8085 28.80062 19.00259 543.8085 28.80062 19.04578 543.1619 27.22683 19.00063 543.6239 15 19.04578 543.1619 27.22683 19.25207 542.4803 25.32335 19.25207 542.4803 25.32335 19.43515 542.0624 24.02561 20.42178 539.81 15 19.25207 542.4803 25.32335 19.43515 542.0624 24.02561 19.25207 542.4803 15 19.25207 542.4803 15 19.42106 539.7901 16.1883 19.91175 540.9743 20.21381 19.91175 540.9743 20.21381 19.42106 538.4176 8.145814 20.42178 539.81 15 19.29859 537.9254 0 19.42106 537.9581 0 29.40812 542.1618 10.1839 9.048579 535.9479 0 9.048579 536.7319 -10.77635 19.42106 537.9581 0 19.29859 537.9254 0 29.28174 541.3524 0 19.42106 538.7318 -10.55842 29.28174 541.3524 0 9.048579 535.9479 0 8.839051 604.7324 74.26136 1.506723 600.0087 74.26136 4.377624 600.8561 74.26136 6.889151 602.476 74.26136 10.07455 607.4414 57.9 9.102197 605.1655 74.26136 10.07558 607.4449 74.26136 8.832825 604.7229 57.9 8.839051 604.7324 74.26136 10.5 610.4 74.26136 10.5 610.4 57.9 10.5 610.4 74.26136 10.5 610.4 57.9 29.42342 643.5922 60.47758 21.17391 717.9 45.40562 29.42342 643.5922 60.47758 33.14047 643.5922 58.52336 33.14047 643.5922 58.52336 23.41555 546.3291 31.17099 29.40812 548.1088 29.66418 22.84083 546.5638 32.06598 22.22432 546.6756 32.71517 21.59967 546.6572 33.09516 20.97253 546.5026 33.20058 25.53974 543.0801 20.99402 29.40812 544.4125 20.1447 24.74793 544.8877 26.84546 24.38055 545.5097 28.63266 23.93071 545.9802 30.04009 26.13549 541.72 15 29.40812 541.4061 0 23.29965 540.7069 15 29.40812 541.4061 0 38.68494 546.1468 0 29.40812 542.1618 -10.1839 38.68494 546.1468 0 26.13549 541.72 15 20.42178 539.81 15 23.29965 540.7069 15 19.25207 542.4803 15 24.74793 544.8877 15 26.13549 541.72 15 25.53974 543.0801 20.99402 24.74793 544.8877 15 24.74793 544.8877 26.84546 24.74793 544.8877 15 24.74793 544.8877 26.84546 24.38055 545.5097 28.63266 24.07783 545.8479 15 23.93071 545.9802 30.04009 23.41555 546.3291 31.17099 23.0915 546.4783 15 22.84083 546.5638 32.06598 22.22432 546.6756 32.71517 21.93924 546.6833 15 21.59967 546.6572 33.09516 20.97253 546.5026 33.20058 20.79635 546.4318 15 20.42887 546.2397 33.03202 19.96192 545.8854 32.62488 25.05051 717.9 43.38747 38.8449 643.5922 54.90309 28.73621 717.9 41.03935 -74.2573 620.9288 0 -74.74909 616.5299 0 -75 610.4 0 -74.2573 620.8216 -1.498403 -75 610.4 0 -74.74909 616.5299 0 -74.2573 620.8216 1.498403 -74.2573 620.5023 2.966303 -74.2573 619.9773 4.373817 -74.2573 619.2574 5.692294 -74.2573 618.3571 6.894891 -74.2573 617.2949 7.957128 -74.2573 616.0923 8.857382 -74.2573 614.7738 9.577324 -74.2573 613.3663 10.1023 -74.2573 611.8984 10.42162 -74.2573 610.4 10.52879 -74.2573 608.9016 10.42162 -74.2573 607.4337 10.1023 -74.2573 606.0262 9.577324 -74.2573 604.7077 8.857382 -74.2573 603.5051 7.957128 -74.2573 602.4429 6.894891 -74.2573 601.5426 5.692294 -74.2573 600.8227 4.373817 -74.2573 600.2977 2.966303 -74.2573 599.9784 1.498403 -74.2573 599.8712 0 -74.2573 599.9784 -1.498403 -74.2573 599.8712 0 -74.2573 620.5023 -2.966303 -74.2573 619.9773 -4.373817 -74.2573 619.2574 -5.692294 -74.2573 618.3571 -6.894891 -74.2573 617.2949 -7.957128 -74.2573 616.0923 -8.857382 -74.2573 614.7738 -9.577324 -74.2573 613.3663 -10.1023 -74.2573 611.8984 -10.42162 -74.2573 610.4 -10.52879 -74.2573 608.9016 -10.42162 -74.2573 607.4337 -10.1023 -74.2573 606.0262 -9.577324 -74.2573 604.7077 -8.857382 -74.2573 603.5051 -7.957128 -74.2573 602.4429 -6.894891 -74.2573 601.5426 -5.692294 -74.2573 600.8227 -4.373817 -74.2573 600.2977 -2.966303 -74.2573 620.9288 0 -73.99801 622.6187 0 -73.98886 622.6217 -1.131711 -73.99801 622.6187 0 -73.96193 622.6306 2.246201 -73.98903 622.6216 1.120714 -73.85391 622.6665 4.48723 -73.91674 622.6456 3.370743 -73.66977 622.7275 6.767397 -73.77298 622.6932 5.605648 -73.36798 622.8276 9.364587 -72.92195 622.9755 12.21661 -72.2576 623.1959 15.4953 -72.04092 621.0845 17.91503 -72.0606 623.2612 16.33581 -72.04092 618.6578 19.155 -72.04092 616.0903 20.06805 -73.46936 611.9009 15 -73.42343 613.4 15 -73.48471 610.4 15 -73.42343 607.4 15 -73.46936 608.8992 15 -72.04092 604.4735 19.99957 -72.068 607.4 20.54919 -72.04092 601.6928 18.95498 -72.04092 599.0888 17.52602 -72.04092 596.714 15.74165 -72.04092 594.6168 13.63806 -72.04092 592.8397 11.25792 -72.04092 591.4187 8.649483 -72.04092 590.3825 5.865647 -72.04092 589.7523 2.962865 -72.04092 589.5408 0 -72.04092 589.5408 0 -68.39488 579.9673 4.581541 -68.39488 579.6243 0 -72.04092 589.7727 -3.101565 -68.39488 579.6243 0 -70.23377 630.6911 0 -73.99801 622.6187 0 -73.98903 622.6216 1.120714 -70.06282 630.7318 -4.760512 -73.98886 622.6217 -1.131711 -73.96193 622.6306 2.246201 -73.91674 622.6456 3.370743 -73.85391 622.6665 4.48723 -70.06282 630.7318 4.760514 -73.77298 622.6932 5.605648 -73.66977 622.7275 6.767397 -73.36798 622.8276 9.364587 -69.54856 630.854 9.512948 -72.92195 622.9755 12.21661 -72.2576 623.1959 15.4953 -68.69244 631.0565 14.22278 -72.0606 623.2612 16.33581 -71.26155 623.5264 19.35178 -71.26155 623.5264 19.35178 -69.82097 624.0044 23.76871 -68.39488 620.7763 28.97368 -68.40866 624.4733 27.33496 -72.26541 613.4 19.84262 -72.06803 613.4 20.54914 -68.39488 616.8218 30.0982 -73.42343 613.4 15 -72.06803 613.4 20.54914 -72.26541 613.4 19.84262 -70.25 613.4 26.09478 -70.25 613.4 26.09478 -70.25 613.4 15 -73.42343 613.4 15 -73.46936 611.9009 15 -70.25 613.4 15 -67.47837 611.5477 15 -73.48471 610.4 15 -69.10161 613.1715 15 -68.12844 612.5209 15 -67.25014 610.4 15 -73.46936 608.8992 15 -68.12844 608.2791 15 -73.42343 607.4 15 -67.47837 609.2523 15 -72.26533 607.4 19.84291 -70.25 607.4 15 -73.42343 607.4 15 -72.26533 607.4 19.84291 -69.10161 607.6286 15 -70.25 607.4 15 -72.068 607.4 20.54919 -68.39488 603.5045 29.9932 -69.6644 607.4577 27.62632 -70.25 607.4 26.09478 -70.25 607.4 26.09478 -68.39488 599.1163 28.63246 -68.39488 594.9795 26.6336 -68.39488 591.1864 24.04119 -68.39488 587.8215 20.91299 -68.39488 584.9598 17.31871 -68.39488 582.6651 13.33848 -68.39488 580.9885 9.060976 -63.39152 570.7169 5.636383 -63.39152 570.3187 0 -68.39488 579.9531 -4.486048 -63.39152 570.3187 0 -70.25 607.4 15 -70.25 607.4 26.09478 -69.6644 607.4577 27.62632 -69.15261 607.6079 28.89844 -69.15261 607.6079 28.89844 -68.72097 607.8189 29.92946 -69.10161 607.6286 15 -68.72097 607.8189 29.92946 -68.39242 608.0443 30.69081 -68.39242 608.0443 30.69081 -63.39152 604.0189 39.57014 -63.39152 609.6468 40.07427 -68.34957 608.0787 30.78881 -68.34957 608.0787 30.78881 -63.39152 598.5178 38.2796 -63.39152 593.2529 36.22831 -63.39152 588.3287 33.45702 -63.39152 583.8432 30.02082 -63.39152 579.8854 25.98799 -63.39152 576.5341 21.43868 -63.39152 573.8558 16.46331 -63.39152 571.9039 11.16075 -57.13015 562.0743 5.076511 -57.13015 561.8084 0 -63.39152 570.7169 -5.63583 -57.13015 561.8084 0 -68.00145 608.4141 31.57286 -68.12844 608.2791 15 -68.00145 608.4141 31.57286 -67.66099 608.8844 32.32186 -67.66099 608.8844 32.32186 -67.3945 609.4802 32.89564 -67.47837 609.2523 15 -67.3945 609.4802 32.89564 -67.26568 610.0937 33.1698 -67.26568 610.0937 33.1698 -63.39152 615.2897 39.78197 -67.26165 610.664 33.17856 -67.25014 610.4 15 -67.26165 610.664 33.17856 -67.37651 611.262 32.93401 -67.37651 611.262 32.93401 -67.62919 611.8599 32.39083 -67.47837 611.5477 15 -67.62919 611.8599 32.39083 -67.97679 612.3577 31.62765 -67.97679 612.3577 31.62765 -68.33828 612.712 30.81453 -68.12844 612.5209 15 -68.33828 612.712 30.81453 -68.39253 612.7558 30.69057 -68.39253 612.7558 30.69057 -68.71479 612.9774 29.94398 -68.71479 612.9774 29.94398 -63.39152 620.8354 38.69906 -69.14739 613.19 28.91108 -69.6615 613.3417 27.63368 -67.82604 624.6667 28.6547 -65.47879 625.4463 33.33375 -63.42197 626.1297 36.81345 -65.97993 631.6911 23.38922 -68.40866 624.4733 27.33496 -67.82604 624.6667 28.6547 -69.82097 624.0044 23.76871 -64.12982 632.1183 27.82041 -65.47879 625.4463 33.33375 -61.95378 632.6161 32.12916 -63.42197 626.1297 36.81345 -62.76384 626.3484 37.83317 -62.76384 626.3484 37.83317 -57.13015 621.4311 47.32294 -59.10451 627.5651 42.86042 -57.26454 628.1773 45.05265 -57.13015 614.3345 48.43207 -57.13015 607.1518 48.48294 -57.13015 600.0402 47.47441 -57.13015 593.1549 45.42853 -57.13015 586.6464 42.39 -57.13015 580.657 38.42522 -57.13015 575.3175 33.62082 -57.13514 570.762 28.09628 -59.24118 569.2998 20.64593 -57.3353 570.6715 27.55557 -57.80462 570.3815 26.11795 -60.34629 568.4676 15 -57.13015 562.8691 10.09746 -58.62241 566.0896 15 -57.13713 564.1914 15 -49.73501 554.8876 8.35443 -49.73501 554.2624 0 -57.13015 562.2779 -6.738749 -49.73501 554.2624 0 -59.46541 633.1798 36.28043 -59.10451 627.5651 42.86042 -56.68139 633.8043 40.24372 -57.26454 628.1773 45.05265 -53.80528 629.3286 48.70009 -53.60992 634.4871 44.00482 -53.80528 629.3286 48.70009 -49.73501 622.7445 54.76351 -49.83775 630.65 52.26025 -49.73501 614.4571 55.99079 -49.73501 606.0794 55.97106 -49.73501 597.7978 54.70478 -49.73501 589.7969 52.22013 -49.73501 582.255 48.57246 -49.73501 575.3398 43.84301 -56.79975 570.8765 28.92544 -55.61899 570.9607 31.24211 -54.99074 570.8101 32.15046 -49.73501 569.2055 38.1371 -56.22544 570.9765 30.15783 -56.74977 570.8898 15 -57.13514 570.762 28.09628 -57.3353 570.6715 27.55557 -56.79975 570.8765 28.92544 -57.80462 570.3815 26.11795 -60.34629 568.4676 15 -57.80462 570.3815 26.11795 -59.24118 569.2998 20.64593 -57.80462 570.3815 15 -57.80462 570.3815 15 -53.02935 567.5669 15 -60.34629 568.4676 15 -58.62241 566.0896 15 -53.60358 569.7896 15 -57.80462 570.3815 15 -53.09548 568.7354 15 -54.19538 565.5885 15 -57.13713 564.1914 15 -53.41547 566.4619 15 -56.72421 563.6842 15 -56.72421 563.6842 15 -49.73501 556.749 16.52279 -41.35287 548.4362 8.685245 -41.35287 547.8305 0 -49.73501 554.8875 -8.354279 -41.35287 547.8305 0 -49.73501 559.8054 24.32316 -55.63002 564.5082 20.5971 -54.19538 565.5885 15 -56.72421 563.6842 15 -55.63002 564.5082 20.5971 -54.19538 565.5885 26.07275 -54.19538 565.5885 26.07275 -49.73501 563.9886 31.58182 -53.78998 565.9562 27.50262 -54.19538 565.5885 15 -54.19538 565.5885 26.07275 -53.78998 565.9562 27.50262 -53.45192 566.4016 28.84482 -53.45192 566.4016 28.84482 -53.22024 566.8568 29.94317 -53.41547 566.4619 15 -53.22024 566.8568 29.94317 -53.07683 567.3104 30.84073 -53.07683 567.3104 30.84073 -53.00473 567.8165 31.65664 -53.02935 567.5669 15 -53.00473 567.8165 31.65664 -53.0339 568.4348 32.42361 -53.0339 568.4348 32.42361 -53.20914 569.0855 32.96821 -53.09548 568.7354 15 -53.20914 569.0855 32.96821 -53.50529 569.6513 33.19223 -53.50529 569.6513 33.19223 -53.89653 570.124 33.13631 -53.60358 569.7896 15 -53.89653 570.124 33.13631 -54.39794 570.5214 32.79579 -54.39794 570.5214 32.79579 -54.47632 570.5692 15 -54.99074 570.8101 32.15046 -55.58104 570.9555 15 -55.61899 570.9607 31.24211 -56.22544 570.9765 30.15783 -50.26397 635.2245 47.54362 -49.83775 630.65 52.26025 -41.35287 625.2471 60.78244 -46.71368 631.6912 54.67649 -46.65792 636.0131 50.84039 -46.71368 631.6912 54.67649 -41.35287 616.6661 62.25492 -41.35287 607.9639 62.52204 -41.35287 599.3088 61.57861 -41.35287 590.8685 59.44291 -41.35287 582.8063 56.15629 -41.35287 575.2785 51.78238 -41.35287 568.4306 46.40586 -41.35287 562.3953 40.13085 -41.35287 557.2894 33.07883 -41.35287 553.212 25.38634 -41.35287 550.2417 17.20233 -32.15007 543.3086 9.492854 -32.15007 542.6403 0 -41.35287 548.4362 -8.685099 -32.15007 542.6403 0 -41.33376 633.4856 58.16851 -42.81807 636.8469 53.86824 -41.33376 633.4856 58.16851 -32.15007 627.5878 65.54351 -38.48593 634.4362 59.7168 -38.7592 637.7229 56.61368 -38.48593 634.4362 59.7168 -32.15007 618.236 67.30506 -32.15007 608.7296 67.73908 -32.15007 599.2561 66.83702 -32.15007 590.0024 64.61663 -32.15007 581.151 61.12175 -32.15007 572.8765 56.42129 -32.15007 565.3422 50.60798 -32.15007 558.6966 43.79647 -32.15007 553.0708 36.12111 -32.15007 548.5758 27.7333 -32.15007 545.3002 18.79847 -32.15007 543.3085 -9.492728 -32.14546 636.554 62.51109 -34.50469 638.6359 59.05865 -32.14546 636.554 62.51109 -29.73155 637.361 63.35725 -30.07635 639.5817 61.18894 -29.73155 637.361 63.35725 -24.44622 545.4207 28.37372 -22.42555 546.6537 32.53459 -23.04883 546.4947 31.77834 -23.60556 546.2182 30.7973 -24.06015 545.8648 29.68694 -24.77742 542.0843 18.54829 -24.77209 544.831 26.6842 -24.97357 544.0814 24.55922 -24.96033 543.1977 22.04169 -24.62635 541.1646 15 -22.30891 540.3835 15 -25.49728 640.5556 62.99166 -22.30034 639.8469 65.27307 -21.31669 546.6051 15 -22.30847 546.6681 32.64316 -22.42555 546.6537 32.53459 -21.79627 546.6771 33.00472 -22.48626 546.6442 15 -23.04883 546.4947 31.77834 -23.58184 546.2329 15 -23.60556 546.2182 30.7973 -24.06015 545.8648 29.68694 -24.4368 545.4337 15 -24.44622 545.4207 28.37372 -24.77209 544.831 26.6842 -24.92097 544.368 15 -24.97357 544.0814 24.55922 -24.96033 543.1977 22.04169 -24.62635 541.1646 15 -24.96033 543.1977 22.04169 -24.77742 542.0843 18.54829 -24.96033 543.1977 15 -24.96033 543.1977 15 -19.03967 544.1703 15 -24.62635 541.1646 15 -22.30891 540.3835 15 -24.96033 543.1977 15 -21.44661 540.1146 15 -21.44661 540.1146 15 -18.22507 539.2112 15 -19.03967 544.1703 15 -18.22507 539.2112 15 -18.56588 541.286 22.43991 -19.03967 544.1703 29.59924 -19.03967 544.1703 15 -19.03967 544.1703 29.59924 -19.11506 544.5068 30.29371 -19.2432 544.8673 30.98637 -19.45133 545.2664 15 -19.45848 545.278 31.7094 -19.7769 545.6984 32.36631 -20.14481 546.0416 32.82046 -20.25098 546.1213 15 -20.60956 546.3424 33.11888 -21.1875 546.5719 33.1973 1.494158 600.007 57.9 1.506723 600.0087 74.26136 4.361477 600.8488 57.9 4.377624 600.8561 74.26136 6.875587 602.4644 57.9 6.889151 602.476 74.26136 -67.50106 631.3365 18.85424 -69.10161 613.1715 15 -69.14739 613.19 28.91108 -69.6615 613.3417 27.63368 -70.25 613.4 26.09478 -70.25 613.4 15 38.84489 643.5922 -54.90309 33.14016 643.5922 -58.52354 28.73621 717.9 -41.03935 33.14016 643.5922 -58.52354 29.40812 634.3891 -64.68914 29.42344 643.5922 -60.47757 29.40812 624.5779 -67.52149 29.40812 614.456 -68.87461 29.40812 604.2453 -68.71887 29.40812 594.1694 -67.05767 29.40812 584.4491 -63.9274 29.40812 575.2973 -59.39665 29.40812 566.9145 -53.56467 29.40812 559.4844 -46.55923 29.40812 553.1697 -38.53379 29.40812 548.1088 -29.66418 29.40812 544.4125 -20.1447 25.05051 717.9 -43.38747 29.42344 643.5922 -60.47757 24.89029 643.5922 -62.47998 21.17391 717.9 -45.40562 24.89029 643.5922 -62.47998 19.42106 633.9244 -68.51589 19.43191 643.5922 -64.38694 19.42106 623.687 -71.21292 19.42106 613.1658 -72.38904 19.42106 602.5855 -72.01914 19.42106 592.1721 -70.11111 19.42106 582.1481 -66.70571 19.42106 572.7274 -61.87565 19.42106 564.1113 -55.72412 19.42106 556.4838 -48.38246 19.42106 550.0078 -40.0075 19.42106 544.8215 -30.77809 19.42106 541.036 -20.89135 17.13559 717.9 -47.07846 19.43191 643.5922 -64.38694 16.16067 643.5922 -65.28482 12.9663 717.9 -48.39302 16.16067 643.5922 -65.28482 9.048579 633.6422 -70.73137 9.051488 643.5922 -66.64342 9.048579 623.1596 -73.35064 9.048579 612.4083 -74.42507 9.048579 601.6148 -73.93201 9.048579 591.0062 -71.88187 9.048579 580.8061 -68.31781 9.048579 571.2293 -63.3149 9.048579 562.4774 -56.97851 9.048579 554.7349 -49.44209 9.048579 548.1647 -40.86436 9.048579 542.9053 -31.42598 9.048579 539.0675 -21.32574 8.698943 717.9 -49.33895 9.051488 643.5922 -66.64342 7.146537 643.5922 -66.87453 7.146537 643.5922 -66.87453 -1.503472 633.5443 -71.32377 -1.502658 643.5922 -67.23851 -1.503472 622.9981 -73.91906 -1.503472 612.1876 -74.96363 -1.503472 601.3397 -74.43554 -1.503472 590.6818 -72.3459 -1.503472 580.4375 -68.73854 -1.503472 570.8218 -63.68914 -1.503472 562.0364 -57.30361 -1.503472 554.2656 -49.71594 -1.503472 547.6725 -41.08529 -1.503472 542.3953 -31.59273 -1.503472 538.5447 -21.43739 4.365938 717.9 -49.9093 -1.502658 643.5922 -67.23851 -2.000693 643.5922 -67.22554 0 717.9 -50.09988 -2.000693 643.5922 -67.22554 -12.02569 622.9604 -72.95629 -12.02569 633.3778 -70.37334 -12.02569 612.279 -74.00576 -12.02569 601.5581 -73.49969 -12.02569 591.0231 -71.44871 -12.02569 580.8953 -67.89595 -12.02569 571.3878 -62.91604 -12.02569 562.7002 -56.6137 -12.02569 555.0153 -49.12139 -12.02569 548.4945 -40.59658 -12.02569 543.2749 -31.21846 -12.02569 539.4661 -21.18416 -12.01718 643.2918 -66.32284 -11.12075 643.5922 -66.32952 -4.365938 717.9 -49.9093 -11.12075 643.5922 -66.32952 -20.79552 641.5518 -64.45463 -11.12075 643.5922 -66.32952 -12.01718 643.2918 -66.32284 -8.698943 717.9 -49.33895 -20.79552 641.5518 -64.45463 -20.6169 640.4105 -65.56913 -20.6169 640.4105 -65.56913 -22.30924 630.3144 -68.7802 -22.30049 639.8469 -65.27305 -22.30924 620.3438 -70.91135 -22.30924 610.1716 -71.60479 -22.30924 600.004 -70.84648 -22.30924 590.0473 -68.65176 -22.30924 580.5031 -65.06517 -22.30924 571.5651 -60.15938 -22.30924 563.4145 -54.0339 -22.30924 556.2165 -46.8129 -22.30924 550.1171 -38.64277 -22.30924 545.2398 -29.68918 -22.30924 541.6837 -20.13366 -73.91513 622.6461 -3.404045 -73.96121 622.6309 -2.268409 -73.85105 622.6674 -4.531647 -73.66295 622.7297 -6.837187 -73.76853 622.6948 -5.660743 -73.35289 622.8326 -9.475621 -72.89551 622.9843 -12.36451 -72.05484 623.2632 -16.35969 -72.22494 623.2067 -15.63799 -72.04092 620.7395 -18.11631 -72.04092 617.9309 -19.45231 -72.04092 614.9548 -20.35584 -72.04092 611.8774 -20.80681 -72.04092 608.7672 -20.7952 -72.04092 605.6933 -20.32125 -72.04092 602.7241 -19.39551 -72.04092 599.9255 -18.03857 -72.04092 597.3598 -16.28058 -72.04092 595.0839 -14.16064 -72.04092 593.1486 -11.72587 -72.04092 591.5969 -9.030405 -72.04092 590.4631 -6.134174 -68.39488 580.9322 -8.876266 -68.39488 582.5408 -13.07687 -68.39488 584.7445 -16.99813 -68.39488 587.4963 -20.55628 -68.39488 590.7373 -23.6753 -68.39488 594.3984 -26.28858 -68.39488 598.4013 -28.34028 -68.39488 602.6605 -29.78659 -68.39488 607.085 -30.5966 -68.39488 611.5804 -30.753 -68.39488 616.0505 -30.25247 -68.39488 620.4 -29.10569 -68.41205 624.4721 -27.32707 -71.27449 623.522 -19.30701 -69.9265 623.9694 -23.47676 -68.69245 631.0565 -14.22268 -72.05484 623.2632 -16.35969 -72.22494 623.2067 -15.63799 -67.50109 631.3365 -18.85409 -71.27449 623.522 -19.30701 -72.89551 622.9843 -12.36451 -69.54857 630.854 -9.512896 -73.35289 622.8326 -9.475621 -73.66295 622.7297 -6.837187 -73.76853 622.6948 -5.660743 -73.85105 622.6674 -4.531647 -73.91513 622.6461 -3.404045 -73.96121 622.6309 -2.268409 -69.9265 623.9694 -23.47676 -63.39152 571.9036 -11.15968 -63.39152 573.8552 -16.46178 -63.39152 576.533 -21.4368 -63.39152 579.8836 -25.98587 -63.39152 583.8407 -30.0186 -63.39152 588.3255 -33.45487 -63.39152 593.2489 -36.2264 -63.39152 598.513 -38.27811 -63.39152 604.0134 -39.56925 -63.39152 609.6407 -40.07415 -63.39152 615.283 -39.78279 -63.39152 620.8284 -38.70095 -67.95505 624.6239 -28.36889 -65.62387 625.3981 -33.06912 -63.41157 626.1331 -36.82989 -65.97998 631.6911 -23.38911 -68.41205 624.4721 -27.32707 -64.12979 632.1184 -27.82045 -67.95505 624.6239 -28.36889 -65.62387 625.3981 -33.06912 -57.13015 563.6774 -13.34727 -57.13015 565.9799 -19.69784 -57.13015 569.1409 -25.66773 -57.13015 573.0993 -31.14157 -57.13015 577.7784 -36.01357 -57.13015 583.088 -40.18957 -57.13015 588.9255 -43.58889 -57.13015 595.178 -46.1458 -57.13015 601.7246 -47.81091 -57.13015 608.4389 -48.55203 -57.13015 615.1911 -48.35484 -57.13015 621.8507 -47.22315 -62.93724 626.2908 -37.56842 -59.32432 627.492 -42.58505 -57.27402 628.1741 -45.04188 -61.95365 632.6161 -32.12939 -63.41157 626.1331 -36.82989 -59.4652 633.1798 -36.28075 -62.93724 626.2908 -37.56842 -59.32432 627.492 -42.58505 -49.73501 556.749 -16.5225 -49.73501 559.8052 -24.32276 -49.73501 563.9883 -31.58132 -49.73501 569.205 -38.13655 -49.73501 575.3391 -43.84244 -49.73501 582.254 -48.57194 -49.73501 589.7958 -52.21969 -49.73501 597.7965 -54.70448 -49.73501 606.0778 -55.97095 -49.73501 614.4555 -55.9909 -49.73501 622.7427 -54.7639 -54.08446 629.2357 -48.42613 -56.68117 633.8044 -40.24401 -57.27402 628.1741 -45.04188 -53.60979 634.4871 -44.00498 -54.08446 629.2357 -48.42613 -49.83535 630.6508 -52.26224 -50.26371 635.2246 -47.54389 -49.83535 630.6508 -52.26224 -41.35287 550.2416 -17.20204 -41.35287 553.2118 -25.38594 -41.35287 557.2891 -33.07833 -41.35287 562.3948 -40.13028 -41.35287 568.4299 -46.40527 -41.35287 575.2776 -51.7818 -41.35287 582.8052 -56.15577 -41.35287 590.8673 -59.4425 -41.35287 599.3074 -61.57835 -41.35287 607.9623 -62.52198 -41.35287 616.6644 -62.2551 -41.35287 625.2452 -60.78289 -47.01904 631.5894 -54.45383 -46.65755 636.0131 -50.8407 -47.01904 631.5894 -54.45383 -41.33788 633.4843 -58.16613 -42.81766 636.847 -53.86854 -41.33788 633.4843 -58.16613 -32.15007 545.3001 -18.79822 -32.15007 548.5756 -27.73295 -32.15007 553.0705 -36.12068 -32.15007 558.6962 -43.79598 -32.15007 565.3416 -50.60747 -32.15007 572.8758 -56.4208 -32.15007 581.1501 -61.12131 -32.15007 590.0013 -64.61629 -32.15007 599.2548 -66.83679 -32.15007 608.7282 -67.73905 -32.15007 618.2344 -67.30523 -32.15007 627.5863 -65.54393 -38.73876 634.3518 -59.58708 -38.75888 637.7229 -56.61388 -38.73876 634.3518 -59.58708 -32.14459 636.5543 -62.51141 -34.50445 638.636 -59.05878 -32.14459 636.5543 -62.51141 -29.90929 637.3016 -63.29882 -30.07608 639.5818 -61.18906 -29.90929 637.3016 -63.29882 -25.49694 640.5557 -62.99178 -22.30049 639.8469 -65.27305 -17.13559 717.9 -47.07846 -25.49694 640.5557 -62.99178 -12.9663 717.9 -48.39302 -21.17391 717.9 -45.40562 -30.07608 639.5818 -61.18906 -25.05051 717.9 -43.38747 -34.50445 638.636 -59.05878 -38.75888 637.7229 -56.61388 -28.73621 717.9 -41.03935 -42.81766 636.847 -53.86854 -32.20323 717.9 -38.37903 -46.65755 636.0131 -50.8407 -35.42542 717.9 -35.42658 -50.26371 635.2246 -47.54389 -38.37838 717.9 -32.20416 -53.60979 634.4871 -44.00498 -56.68117 633.8044 -40.24401 -41.03964 717.9 -28.736 -59.4652 633.1798 -36.28075 -43.38824 717.9 -25.04928 -61.95365 632.6161 -32.12939 -45.40624 717.9 -21.17249 -64.12979 632.1184 -27.82045 -47.07857 717.9 -17.13495 -65.97998 631.6911 -23.38911 -67.50109 631.3365 -18.85409 -48.39268 717.9 -12.96714 -68.69245 631.0565 -14.22268 -49.33865 717.9 -8.700526 -69.54857 630.854 -9.512896 -49.90924 717.9 -4.36768 -70.06282 630.7318 -4.760512 -70.23377 630.6911 0 -50.1 717.9 0 -70.23377 630.6911 0 -70.06282 630.7318 4.760514 -50.1 717.9 0 -49.90924 717.9 4.36768 -69.54856 630.854 9.512948 -49.33865 717.9 8.700526 -68.69244 631.0565 14.22278 -62.34753 657.1444 15 -67.50106 631.3365 18.85424 -61.04067 656.8427 19.87928 -65.97993 631.6911 23.38922 -59.36985 656.4569 24.65391 -64.12982 632.1183 27.82041 -58.76423 656.3808 26.10779 -61.95378 632.6161 32.12916 -56.89267 656.9818 29.66942 -59.46541 633.1798 36.28043 -58.23399 656.4157 27.25105 -57.76486 656.5278 28.17288 -57.33029 656.7084 28.95481 -45.4854 703.6893 27.93901 -56.68139 633.8043 40.24372 -56.43425 657.408 30.32435 -56.04573 657.9724 30.76682 -55.79978 658.5941 30.91602 -47.01517 701.7388 26.21781 -46.56807 702.0243 26.87203 -46.10879 702.4635 27.45482 -45.72483 703.0423 27.83376 -41.03964 717.9 28.736 -53.60992 634.4871 44.00482 -38.37838 717.9 32.20416 -50.26397 635.2245 47.54362 -35.42542 717.9 35.42658 -46.65792 636.0131 50.84039 -32.20323 717.9 38.37903 -42.81807 636.8469 53.86824 -28.73621 717.9 41.03935 -38.7592 637.7229 56.61368 -34.50469 638.6359 59.05865 -25.05051 717.9 43.38747 -30.07635 639.5817 61.18894 -21.17391 717.9 45.40562 -25.49728 640.5556 62.99166 -17.13559 717.9 47.07846 -44.808 717.9 4.152421 -50.1 717.9 0 -49.90924 717.9 4.36768 -44.808 717.9 -4.152421 -49.90924 717.9 -4.36768 -49.33865 717.9 8.700526 -60.96049 662.9819 15 -48.39268 717.9 12.96714 -43.28194 717.9 12.31547 -48.39268 717.9 12.96714 -61.65057 660.0786 15 -50.21664 707.8983 15 -47.07857 717.9 17.13495 -47.07857 717.9 17.13495 -59.66622 662.6832 19.74302 -51.62068 702.0646 15 -50.91425 705.0014 15 -47.72515 707.3231 21.97631 -45.40624 717.9 21.17249 -40.28202 717.9 20.05874 -45.40624 717.9 21.17249 -49.08933 707.6381 18.527 -45.95701 706.1412 26.02611 -43.38824 717.9 25.04928 -43.38824 717.9 25.04928 -46.28607 706.5287 25.2499 -46.69724 706.8699 24.31086 -47.19492 707.1473 23.18525 -35.91052 717.9 27.11875 -41.03964 717.9 28.736 -45.40032 704.3557 27.78344 -45.46807 705.0355 27.36919 -45.67605 705.6571 26.73769 -38.37838 717.9 32.20416 -30.31632 717.9 33.25526 -35.42542 717.9 35.42658 -23.68981 717.9 38.25945 -32.20323 717.9 38.37903 -28.73621 717.9 41.03935 -16.25649 717.9 41.96096 -25.05051 717.9 43.38747 -8.269279 717.9 44.23367 -21.17391 717.9 45.40562 21.17391 717.9 45.40562 -17.13559 717.9 47.07846 0 717.9 45 17.13559 717.9 47.07846 -12.9663 717.9 48.39302 12.9663 717.9 48.39302 -8.698943 717.9 49.33895 8.698943 717.9 49.33895 -4.365938 717.9 49.9093 4.365938 717.9 49.9093 0 717.9 50.09988 25.05051 717.9 43.38747 16.25649 717.9 41.96096 28.73621 717.9 41.03935 8.269279 717.9 44.23367 32.20323 717.9 38.37903 23.68981 717.9 38.25945 35.42542 717.9 35.42658 30.31632 717.9 33.25526 38.37838 717.9 32.20416 41.03964 717.9 28.736 45.74522 705.6978 26.60056 43.38824 717.9 25.04928 35.91052 717.9 27.11875 43.38824 717.9 25.04928 45.53133 705.0938 27.23746 45.45003 704.4136 27.67633 47.25069 707.1499 23.07005 45.40624 717.9 21.17249 45.40624 717.9 21.17249 46.75381 706.8745 24.19959 46.34671 706.5392 25.13329 46.02232 706.1625 25.90043 49.11193 707.6317 18.47118 47.07857 717.9 17.13495 40.28202 717.9 20.05874 47.07857 717.9 17.13495 47.77515 707.3231 21.8674 50.21927 707.8874 15 48.39268 717.9 12.96714 43.28194 717.9 12.31547 49.33865 717.9 8.700526 50.91688 704.9905 15 49.90924 717.9 4.36768 44.808 717.9 4.152421 50.1 717.9 0 44.808 717.9 -4.152421 49.90924 717.9 -4.36768 -59.36985 656.4569 15 -62.34753 657.1444 15 -61.04067 656.8427 19.87928 -55.73621 659.8749 15 -61.65057 660.0786 15 -62.34753 657.1444 15 -55.77202 658.7052 15 -56.25259 657.6382 15 -57.10491 656.8361 15 -59.36985 656.4569 15 -59.36985 656.4569 24.65391 -59.36985 656.4569 15 -59.36985 656.4569 24.65391 -58.76423 656.3808 26.10779 -58.23399 656.4157 27.25105 -58.19949 656.4212 15 -57.76486 656.5278 28.17288 -57.33029 656.7084 28.95481 -57.10491 656.8361 15 -56.89267 656.9818 29.66942 -56.43425 657.408 30.32435 -56.25259 657.6382 15 -56.04573 657.9724 30.76682 -55.79978 658.5941 30.91602 -47.46367 701.5499 25.48898 -55.69826 659.2402 30.79105 -55.77202 658.7052 15 -55.69826 659.2402 30.79105 -55.74392 659.9196 30.38207 -55.73621 659.8749 15 -55.74392 659.9196 30.38207 -55.94521 660.5794 29.68608 -55.94521 660.5794 29.68608 -47.96909 701.4311 24.5846 -56.28447 661.1659 28.7414 -56.15069 660.9694 15 -56.28447 661.1659 28.7414 -48.53236 701.4029 23.46816 -56.73226 661.6489 27.59294 -56.73226 661.6489 27.59294 -57.30456 662.0383 26.16809 -56.9526 661.8221 15 -57.30456 662.0383 26.16809 -49.07485 701.4769 22.27017 -58.02014 662.3031 24.38332 -58.02014 662.3031 24.38332 -60.96049 662.9819 15 -58.02014 662.3031 24.38332 -59.66622 662.6832 19.74302 -50.47284 701.7996 18.67533 -58.02014 662.3031 15 -58.02014 662.3031 15 -58.02014 662.3031 15 -60.96049 662.9819 15 -56.9526 661.8221 15 -56.15069 660.9694 15 -49.07485 701.4769 15 -51.62068 702.0646 15 -50.47284 701.7996 18.67533 -45.44121 704.8948 15 -50.91425 705.0014 15 -51.62068 702.0646 15 -45.47702 703.7252 15 -45.95759 702.6582 15 -46.80992 701.8562 15 -49.07485 701.4769 15 -49.07485 701.4769 22.27017 -49.07485 701.4769 15 -49.07485 701.4769 22.27017 -48.53236 701.4029 23.46816 -47.96909 701.4311 24.5846 -47.90449 701.4412 15 -47.46367 701.5499 25.48898 -47.01517 701.7388 26.21781 -46.80992 701.8562 15 -46.56807 702.0243 26.87203 -46.10879 702.4635 27.45482 -45.95759 702.6582 15 -45.72483 703.0423 27.83376 -45.4854 703.6893 27.93901 -45.47702 703.7252 15 -45.40032 704.3557 27.78344 -45.44121 704.8948 15 -45.46807 705.0355 27.36919 -45.67605 705.6571 26.73769 -45.85569 705.9894 15 -45.95701 706.1412 26.02611 -46.28607 706.5287 25.2499 -46.6576 706.8421 15 -46.69724 706.8699 24.31086 -47.19492 707.1473 23.18525 -47.72515 707.3231 21.97631 -50.21664 707.8983 15 -47.72515 707.3231 21.97631 -49.08933 707.6381 18.527 -47.72515 707.3231 15 -47.72515 707.3231 15 -47.72515 707.3231 15 -50.21664 707.8983 15 -46.6576 706.8421 15 -45.85569 705.9894 15 47.77515 707.3231 15 50.21927 707.8874 15 49.11193 707.6317 18.47118 45.90569 705.9894 15 50.91688 704.9905 15 50.21927 707.8874 15 46.7076 706.8421 15 47.77515 707.3231 15 47.77515 707.3231 21.8674 47.77515 707.3231 15 47.77515 707.3231 21.8674 47.25069 707.1499 23.07005 46.75381 706.8745 24.19959 46.7076 706.8421 15 46.34671 706.5392 25.13329 46.02232 706.1625 25.90043 45.90569 705.9894 15 45.74522 705.6978 26.60056 45.53133 705.0938 27.23746 45.49121 704.8948 15 45.45003 704.4136 27.67633 45.52315 703.7416 27.85435 45.52702 703.7252 15 45.74649 703.0996 27.77269 46.00759 702.6582 15 46.11853 702.5121 27.41659 46.58361 702.0513 26.83254 46.85992 701.8562 15 47.04394 701.7499 26.16085 47.50069 701.5541 25.41783 47.95449 701.4412 15 48.0111 701.4323 24.50188 48.57522 701.4026 23.37947 49.12485 701.4769 22.15966 51.62331 702.0537 15 49.12485 701.4769 22.15966 50.49533 701.7933 18.61869 49.12485 701.4769 15 49.12485 701.4769 15 46.00759 702.6582 15 51.62331 702.0537 15 46.85992 701.8562 15 49.12485 701.4769 15 45.52702 703.7252 15 45.49121 704.8948 15 49.33865 717.9 -8.700526 43.28194 717.9 -12.31547 48.39268 717.9 -12.96714 47.07857 717.9 -17.13495 40.28202 717.9 -20.05874 45.40624 717.9 -21.17249 43.38824 717.9 -25.04928 35.91052 717.9 -27.11875 41.03964 717.9 -28.736 38.37838 717.9 -32.20416 30.31632 717.9 -33.25526 35.42542 717.9 -35.42658 23.68981 717.9 -38.25945 32.20323 717.9 -38.37903 28.73621 717.9 -41.03935 16.25649 717.9 -41.96096 25.05051 717.9 -43.38747 8.269279 717.9 -44.23367 21.17391 717.9 -45.40562 -21.17391 717.9 -45.40562 17.13559 717.9 -47.07846 0 717.9 -45 -17.13559 717.9 -47.07846 12.9663 717.9 -48.39302 -12.9663 717.9 -48.39302 8.698943 717.9 -49.33895 -8.698943 717.9 -49.33895 4.365938 717.9 -49.9093 -4.365938 717.9 -49.9093 0 717.9 -50.09988 -25.05051 717.9 -43.38747 -16.25649 717.9 -41.96096 -28.73621 717.9 -41.03935 -8.269279 717.9 -44.23367 -32.20323 717.9 -38.37903 -23.68981 717.9 -38.25945 -35.42542 717.9 -35.42658 -30.31632 717.9 -33.25526 -38.37838 717.9 -32.20416 -41.03964 717.9 -28.736 -35.91052 717.9 -27.11875 -43.38824 717.9 -25.04928 -45.40624 717.9 -21.17249 -40.28202 717.9 -20.05874 -47.07857 717.9 -17.13495 -48.39268 717.9 -12.96714 -43.28194 717.9 -12.31547 -49.33865 717.9 -8.700526 0 750.4 -45 0 717.9 -45 -8.269279 717.9 -44.23367 8.269443 750.4 -44.23362 8.269279 717.9 -44.23367 0 717.9 -45 0 750.4 -45 -8.269443 750.4 -44.23362 -16.25649 717.9 -41.96096 -16.25633 750.4 -41.96097 -23.68981 717.9 -38.25945 -23.68929 750.4 -38.25974 -30.31632 717.9 -33.25526 -30.31576 750.4 -33.25579 -35.91052 717.9 -27.11875 -35.91038 750.4 -27.11904 -40.28202 717.9 -20.05874 -40.28251 750.4 -20.05788 -43.28194 717.9 -12.31547 -43.2823 750.4 -12.3141 -44.808 717.9 -4.152421 -44.80796 750.4 -4.151734 -44.808 717.9 4.152421 -44.80796 750.4 4.151734 -43.28194 717.9 12.31547 -43.2823 750.4 12.3141 -40.28202 717.9 20.05874 -40.28251 750.4 20.05788 -35.91052 717.9 27.11875 -35.91038 750.4 27.11904 -30.31632 717.9 33.25526 -30.31576 750.4 33.25579 -23.68981 717.9 38.25945 -23.68929 750.4 38.25974 -16.25649 717.9 41.96096 -16.25633 750.4 41.96097 -8.269279 717.9 44.23367 -8.269443 750.4 44.23362 0 717.9 45 0 750.4 45 0 717.9 45 8.269279 717.9 44.23367 0 750.4 45 8.269443 750.4 44.23362 16.25649 717.9 41.96096 16.25633 750.4 41.96097 23.68981 717.9 38.25945 23.68929 750.4 38.25974 30.31632 717.9 33.25526 30.31576 750.4 33.25579 35.91052 717.9 27.11875 35.91038 750.4 27.11904 40.28202 717.9 20.05874 40.28251 750.4 20.05788 43.28194 717.9 12.31547 43.2823 750.4 12.3141 44.808 717.9 4.152421 44.80796 750.4 4.151734 44.808 717.9 -4.152421 44.80796 750.4 -4.151734 43.28194 717.9 -12.31547 43.2823 750.4 -12.3141 40.28202 717.9 -20.05874 40.28251 750.4 -20.05788 35.91052 717.9 -27.11875 35.91038 750.4 -27.11904 30.31632 717.9 -33.25526 30.31576 750.4 -33.25579 23.68981 717.9 -38.25945 23.68929 750.4 -38.25974 16.25649 717.9 -41.96096 16.25633 750.4 -41.96097 10.07455 613.3586 57.9 -10.07455 613.3586 57.9 -10.5 610.4 57.9 10.5 610.4 57.9 -10.07455 607.4414 57.9 8.832825 616.0772 57.9 -8.832825 616.0772 57.9 6.875587 618.3356 57.9 -6.875587 618.3356 57.9 4.361477 619.9512 57.9 -4.361477 619.9512 57.9 1.494158 620.793 57.9 -1.494158 620.793 57.9 10.07455 607.4414 57.9 -8.832825 604.7229 57.9 8.832825 604.7229 57.9 -6.875587 602.4644 57.9 6.875587 602.4644 57.9 -4.361477 600.8488 57.9 4.361477 600.8488 57.9 -1.494158 600.007 57.9 1.494158 600.007 57.9 -54.47632 570.5692 15 -56.74977 570.8898 15 -55.58104 570.9555 15 -24.92097 544.368 15 -19.45133 545.2664 15 -24.4368 545.4337 15 -20.25098 546.1213 15 -23.58184 546.2329 15 -21.31669 546.6051 15 -22.48626 546.6442 15 19.00063 543.6239 15 19.20601 544.7763 15 19.83661 545.7622 15 24.07783 545.8479 15 20.79635 546.4318 15 23.0915 546.4783 15 21.93924 546.6833 15 -58.19949 656.4212 15 -47.90449 701.4412 15 47.95449 701.4412 15 62.40221 657.5997 15 67.37981 657.2734 15 63.174 656.7199 15 66.49959 656.5018 15 64.22358 656.2023 15 65.3913 656.1257 15 62.02574 562.192 15 62.40221 563.3004 15 67.37981 563.6266 15 63.174 564.1801 15 66.49959 564.3983 15 64.22358 564.6976 15 65.3913 564.7742 15 8.269443 750.4 44.23362 8.269443 750.4 -44.23362 0 750.4 -45 0 750.4 45 -8.269443 750.4 -44.23362 16.25633 750.4 41.96097 16.25633 750.4 -41.96097 23.68929 750.4 38.25974 23.68929 750.4 -38.25974 30.31576 750.4 33.25579 30.31576 750.4 -33.25579 35.91038 750.4 27.11904 35.91038 750.4 -27.11904 40.28251 750.4 20.05788 40.28251 750.4 -20.05788 43.2823 750.4 12.3141 43.2823 750.4 -12.3141 44.80796 750.4 4.151734 44.80796 750.4 -4.151734 -8.269443 750.4 44.23362 -16.25633 750.4 -41.96097 -16.25633 750.4 41.96097 -23.68929 750.4 -38.25974 -23.68929 750.4 38.25974 -30.31576 750.4 -33.25579 -30.31576 750.4 33.25579 -35.91038 750.4 -27.11904 -35.91038 750.4 27.11904 -40.28251 750.4 -20.05788 -40.28251 750.4 20.05788 -43.2823 750.4 -12.3141 -43.2823 750.4 12.3141 -44.80796 750.4 -4.151734 -44.80796 750.4 4.151734 110 566.1664 -8.269443 110 654.6336 -8.269443 110 655.4 0 110 565.4 0 110 654.6336 8.269443 110 568.439 -16.25633 110 652.361 -16.25633 110 572.1403 -23.68929 110 648.6597 -23.68929 110 577.1442 -30.31576 110 643.6558 -30.31576 110 583.281 -35.91038 110 637.5191 -35.91038 110 590.3421 -40.28251 110 630.4579 -40.28251 110 598.0859 -43.2823 110 622.7141 -43.2823 110 606.2483 -44.80796 110 614.5518 -44.80796 110 566.1664 8.269443 110 652.361 16.25633 110 568.439 16.25633 110 648.6597 23.68929 110 572.1403 23.68929 110 643.6558 30.31576 110 577.1442 30.31576 110 637.5191 35.91038 110 583.281 35.91038 110 630.4579 40.28251 110 590.3421 40.28251 110 622.7141 43.2823 110 598.0859 43.2823 110 614.5518 44.80796 110 606.2483 44.80796 -7.408469 609.2319 57.9 -7.499978 610.4 57.9 -7.408469 611.5682 57.9 -7.408469 611.5682 62.05 -7.408469 611.5682 57.9 -7.499978 610.4 57.9 -4.715887 616.2319 57.9 -4.715887 616.2319 62.05 -4.715887 616.2319 57.9 -7.408469 611.5682 57.9 -7.408469 611.5682 62.05 -7.499978 610.4 62.05 -7.408469 609.2319 57.9 -4.715887 604.5682 57.9 -7.408469 609.2319 62.05 -7.408469 609.2319 57.9 -4.715887 604.5682 57.9 -7.408469 609.2319 62.05 -3.755648 616.8919 57.9 -3.755648 603.9081 57.9 -4.715887 604.5682 62.05 -4.715887 604.5682 57.9 -3.755648 603.9081 57.9 -4.715887 604.5682 62.05 -2.692582 617.4 57.9 -2.692582 603.4 57.9 -3.755648 603.9081 62.05 -2.692582 603.4 57.9 2.692582 617.4 57.9 2.692582 603.4 57.9 -2.692582 603.4 62.05 -2.692582 603.4 57.9 2.692582 603.4 57.9 -2.692582 603.4 62.05 3.755648 616.8919 57.9 3.755648 603.9081 57.9 2.692582 603.4 62.05 2.692582 603.4 57.9 3.755648 603.9081 57.9 2.692582 603.4 62.05 4.715887 616.2319 57.9 4.715887 604.5682 57.9 3.755648 603.9081 62.05 4.715887 604.5682 57.9 7.408469 611.5682 57.9 7.408469 609.2319 57.9 4.715887 604.5682 62.05 4.715887 604.5682 57.9 7.408469 609.2319 57.9 4.715887 604.5682 62.05 7.499978 610.4 57.9 7.408469 609.2319 62.05 7.408469 609.2319 57.9 7.499978 610.4 57.9 7.408469 609.2319 62.05 7.499978 610.4 62.05 7.408469 611.5682 57.9 7.408469 611.5682 62.05 7.408469 611.5682 57.9 4.715887 616.2319 57.9 7.408469 611.5682 62.05 4.715887 616.2319 62.05 4.715887 616.2319 57.9 3.755648 616.8919 57.9 4.715887 616.2319 62.05 3.755648 616.8919 62.05 2.692582 617.4 57.9 2.692582 617.4 62.05 2.692582 617.4 57.9 -2.692582 617.4 57.9 2.692582 617.4 62.05 -2.692582 617.4 62.05 -2.692582 617.4 57.9 -3.755648 616.8919 57.9 -2.692582 617.4 62.05 -3.755648 616.8919 62.05 -4.715887 616.2319 57.9 -4.715887 616.2319 62.05 4.715887 616.2319 62.05 5.405114 613.0018 62.05 6 610.4 62.05 6 610.4 65.4 6 610.4 62.05 5.405114 613.0018 62.05 7.408469 609.2319 62.05 5.405114 607.7983 62.05 5.406202 607.8007 65.4 5.405114 607.7983 62.05 6 610.4 62.05 6 610.4 65.4 3.755648 616.8919 62.05 3.738611 615.0924 62.05 5.406202 612.9993 65.4 3.738611 615.0924 62.05 2.692582 617.4 62.05 1.337587 616.2481 62.05 3.738526 615.0904 65.4 1.337587 616.2481 62.05 -2.692582 617.4 62.05 -1.337587 616.2481 62.05 1.331379 616.25 65.4 -1.337587 616.2481 62.05 -3.738611 615.0924 62.05 -1.331379 616.25 65.4 -3.738611 615.0924 62.05 -4.715887 616.2319 62.05 -5.405114 613.0018 62.05 -3.738526 615.0904 65.4 -5.405114 613.0018 62.05 -3.755648 616.8919 62.05 -7.408469 611.5682 62.05 -6 610.4 62.05 -5.406202 612.9993 65.4 -6 610.4 62.05 -4.715887 604.5682 62.05 -5.405114 607.7983 62.05 -6 610.4 65.4 -6 610.4 62.05 -5.405114 607.7983 62.05 -6 610.4 65.4 -3.755648 603.9081 62.05 -3.738611 605.7076 62.05 -5.406202 607.8007 65.4 -3.738611 605.7076 62.05 -2.692582 603.4 62.05 -1.337587 604.552 62.05 -3.738526 605.7096 65.4 -1.337587 604.552 62.05 2.692582 603.4 62.05 1.337587 604.552 62.05 -1.331379 604.5501 65.4 1.337587 604.552 62.05 3.738611 605.7076 62.05 1.331379 604.5501 65.4 3.738611 605.7076 62.05 4.715887 604.5682 62.05 3.738526 605.7096 65.4 3.755648 603.9081 62.05 -7.408469 609.2319 62.05 -7.499978 610.4 62.05 7.408469 611.5682 62.05 7.499978 610.4 62.05 4.198536 607.9738 65.4 5.406202 607.8007 65.4 6 610.4 65.4 4.85 610.4 65.4 5.406202 612.9993 65.4 2.426187 606.2015 65.4 3.738526 605.7096 65.4 -1.331379 604.5501 65.4 1.331379 604.5501 65.4 0 605.55 65.4 -3.738526 605.7096 65.4 -2.426187 606.2015 65.4 -5.406202 607.8007 65.4 -4.85 610.4 65.4 -6 610.4 65.4 -4.198536 607.9738 65.4 -4.198536 612.8262 65.4 -5.406202 612.9993 65.4 -2.426187 614.5985 65.4 -3.738526 615.0904 65.4 1.331379 616.25 65.4 -1.331379 616.25 65.4 0 615.25 65.4 3.738526 615.0904 65.4 2.426187 614.5985 65.4 4.198536 612.8262 65.4 4.85 610.4 68.9 4.85 610.4 65.4 4.198536 612.8262 65.4 4.198776 607.9758 68.9 4.198536 607.9738 65.4 4.85 610.4 65.4 4.85 610.4 68.9 4.198776 612.8242 68.9 2.426187 614.5985 65.4 2.425 614.6002 68.9 0 615.25 65.4 0 615.2484 68.9 -2.426187 614.5985 65.4 -2.425 614.6002 68.9 -4.198536 612.8262 65.4 -4.198776 612.8242 68.9 -4.85 610.4 65.4 -4.85 610.4 68.9 -4.85 610.4 65.4 -4.198536 607.9738 65.4 -4.85 610.4 68.9 -4.198776 607.9758 68.9 -2.426187 606.2015 65.4 -2.425 606.1998 68.9 0 605.55 65.4 0 605.5517 68.9 2.426187 606.2015 65.4 2.425 606.1998 68.9 -4.198776 607.9758 68.9 4.198776 607.9758 68.9 4.85 610.4 68.9 -4.85 610.4 68.9 4.198776 612.8242 68.9 -2.425 606.1998 68.9 2.425 606.1998 68.9 0 605.5517 68.9 -4.198776 612.8242 68.9 2.425 614.6002 68.9 -2.425 614.6002 68.9 0 615.2484 68.9 + + + + + + + + + + 0.2592886 0.6202661 0.7402969 0.2568491 0.6376974 0.7262029 0.2580071 0.553766 0.7916916 0.6889472 0.2250813 0.6889777 0.6672602 0.2240681 0.7103221 0.7348856 0.2248086 0.6398471 0.258862 0.5541941 0.7911129 0.2587718 0.4878485 0.8336913 0.5683053 0.331809 0.7529488 0.5777567 0.4029434 0.7098127 0.591038 0.4340463 0.6799103 0.6264 0.2253513 0.7462171 0.6080943 0.2243158 0.7615142 0.2560263 0.7389637 0.623204 0.2567284 0.7314255 0.6317495 0.7467472 0.2245002 0.6260737 0.8001272 0.2243176 0.5563077 0.2558428 0.6856454 0.6814947 0.2594788 0.7906443 0.5545741 0.2486693 0.8173919 0.519648 0.8180819 0.2251136 0.5292125 0.8619323 0.2234334 0.4551376 0.7978351 0.2248966 0.5593574 0.2431437 0.8827276 0.402086 0.2454688 0.8860744 0.3932141 0.8794459 0.2225472 0.4207704 0.9110987 0.2234027 0.3463963 0.2591071 0.8107094 0.5249896 0.1934573 0.889617 0.4137101 0.2236147 0.8710812 0.4372802 0.240765 0.8571589 0.4553142 0.2502921 0.8467389 0.4694542 0.2555985 0.8381189 0.4818985 0.2580419 0.8310748 0.4926753 0.2587419 0.8264908 0.4999657 0.2588263 0.8257411 0.5011594 0.8235102 0.2191612 0.5232585 0.835522 0.2215688 0.5028025 0.8431143 0.2228793 0.4893701 0.8508869 0.2238919 0.4752514 0.8590477 0.2246195 0.4599817 0.8681073 0.2249236 0.4424921 0.2473914 0.9267562 0.2827025 0.2476974 0.9337484 0.2583793 0.9360261 0.2245913 0.2709501 0.9466669 0.223185 0.2324017 0.2115877 0.9252729 0.3148027 0.8931161 0.2222719 0.391074 0.9147678 0.2249534 0.3355532 0.2589263 0.9509838 0.1690773 0.2555978 0.9578434 0.1311713 0.9593877 0.2257167 0.169196 0.9676408 0.2237055 0.1167358 0.2602699 0.9331021 0.2481537 0.9409297 0.2272135 0.2510489 0.2512611 0.966713 0.04831123 0.2582804 0.9639052 0.06463873 0.9706016 0.2253231 0.08462965 0.9730945 0.2235507 0.05578851 0.2546836 0.9637079 0.08002156 0.2592278 0.9622316 -0.08313357 0.2533394 0.9654731 -0.06067204 0.2585869 0.9650695 -0.0421161 0.2553241 0.9574806 -0.1343152 0.9738255 0.2230621 -0.04367244 0.9728136 0.224587 -0.05652058 0.9675721 0.2241615 -0.1164297 0.9734908 0.2247409 0.04251277 1 0 0 0.2591665 0.924204 0.2804992 0.2612136 0.9067855 0.3309193 0.2591685 0.9287583 0.2650281 0.2594754 0.8824969 0.3922649 0.2607851 0.8750111 0.4078563 1 -2.75777e-6 0 0.2591995 0.9032459 0.3419981 0.2617017 0.8408943 0.4737183 0.26103 0.8361627 0.4823851 0.2685695 0.8434609 0.4652356 0.2631943 0.8554119 0.4460935 0.2596259 0.8673219 0.424673 1 2.7621e-6 0 0.2623454 0.8093461 0.5254845 0.2593792 0.8275473 0.4978834 0.258866 0.8337305 0.4877314 1 -1.39751e-6 0 1 1.18679e-6 0 1 7.69563e-7 0 0.2594434 0.4830268 0.836286 1 1.00742e-6 0 1 -4.78363e-7 0 0.2583492 0.421599 0.8692008 0.2598751 0.4082007 0.8751212 1 -3.7584e-7 0 0.2580387 0.3527699 0.8994274 0.2601479 0.3303121 0.9073131 0.2578538 0.2818111 0.9241721 0.2602949 0.2499184 0.932624 0.2577999 0.2090905 0.943303 0.2603 0.1676431 0.9508627 0.2578864 0.135108 0.9566821 0.260145 0.08408015 0.9619019 0.2580384 0.06033611 0.9642489 0.2598673 -1.22075e-4 0.9656443 0.2583467 -0.01480185 0.9659389 0.2593811 -0.08438503 0.9620814 0.2588649 -0.1639498 0.9518978 0.2593193 -0.1675183 0.9511526 0.2588359 -0.08987993 0.9617305 0.2584356 -0.2374689 0.9363864 0.259782 -0.2498021 0.9327981 0.2580991 -0.3095847 0.9151733 0.2601181 -0.3301605 0.9073768 0.2578889 -0.3798138 0.8883889 0.2602714 -0.4080169 0.8750892 0.2578254 -0.4477459 0.8561832 0.2603012 -0.4827582 0.8361746 0.2578557 -0.5129648 0.818766 0.260178 -0.5538663 0.7909106 1 -1.00742e-6 0 0.2580086 -0.5750412 0.7763758 0.2599307 -0.6207574 0.7396596 1 -1.18678e-6 0 0.2582858 -0.6336137 0.7292615 0.2593571 -0.6831243 0.6826971 1 -7.69558e-7 0 0.2589864 -0.7386272 0.6223794 0.259229 -0.7397518 0.620941 1 -1.20418e-6 0 0.258867 -0.6883691 0.6775957 0.2584988 -0.7848657 0.5631733 0.2598064 -0.7909553 0.553977 1 1.51667e-6 0 0.2638717 -0.8269264 0.4965526 0.2609737 -0.8356286 0.48334 0.2581896 -0.8263899 0.5004178 0.2583122 -0.8076226 0.5301139 0.265123 -0.8209749 0.5056778 0.2620693 -0.8150182 0.5167835 0.2619431 -0.8641712 0.4296441 0.2613332 -0.8749764 0.4075797 0.2627691 -0.8551744 0.4467989 0.2599353 -0.8469795 0.4637451 0.2588963 -0.8393758 0.4779342 0.2586189 -0.902694 0.3438892 0.2614311 -0.906799 0.3307107 0.2590212 -0.8809225 0.3960855 0.2590754 -0.9240531 0.2810796 0.2614864 -0.9325677 0.2488821 0.257433 -0.940218 0.2229763 0.2599955 -0.9509567 0.1675825 0.2589239 -0.9285736 0.2659127 0.2591664 -0.9287507 0.2650565 0.2582252 -0.9544354 0.1495759 0.2593216 -0.9621481 0.08380568 0.2591999 -0.9650797 0.03790485 0.2585865 -0.9650683 0.04214656 0.2588896 -0.9630157 0.07467907 0.2585849 -0.9630786 -0.07492339 0.2591706 -0.9649314 -0.04168945 0.2586168 -0.9652503 -0.03753817 0.2596244 -0.9620478 -0.08401858 0.5414974 -0.8388434 0.05588012 0.5753216 -0.81731 0.0317707 0.573674 -0.8166697 0.0628395 0.5139487 -0.8494803 -0.1193313 0.5647298 -0.8233507 -0.05633866 0.5649065 -0.8239822 -0.04397785 0.528198 -0.8454769 -0.07858723 0.5125615 -0.8501593 0.1204572 0.5750409 -0.8079627 0.1285464 0.5734872 -0.7975594 0.1871135 0.2568165 -0.9200838 0.2957892 0.5133051 -0.8243889 0.2385393 0.5733394 -0.7788577 0.2542885 0.2606024 -0.9063251 0.3326579 0.2570598 -0.8941398 0.3666529 0.5730038 -0.7597832 0.3072399 0.2569724 -0.8707764 0.4191824 0.2575498 -0.8628024 0.4350177 0.51423 -0.7821642 0.3518335 0.5704615 -0.731022 0.3744072 0.2578278 -0.8842079 0.3894885 0.2569435 -0.8295804 0.4957584 0.5722419 -0.7040558 0.4205291 0.2515982 -0.834205 0.4907142 0.2550789 -0.8424807 0.4745115 0.2574585 -0.8506566 0.4583652 0.2587134 -0.8596109 0.4406093 0.5152887 -0.7244073 0.4579429 0.5664703 -0.6654142 0.4861433 0.2587576 -0.8236073 0.5046935 0.2587721 -0.8242924 0.5035664 0.5710804 -0.6316005 0.5243551 0.5154113 -0.6538473 0.5539268 0.5737008 -0.5837111 0.5745858 0.5142852 -0.5687627 0.6418876 0.5753836 -0.5354641 0.6182329 0.5735853 -0.4889544 0.6572089 0.5146829 -0.4725353 0.7154104 0.5740977 -0.4321221 0.6954728 0.5732064 -0.3826462 0.7245802 0.5151978 -0.3669346 0.7745516 0.5716344 -0.3181681 0.7563091 0.5725699 -0.2671036 0.7751255 0.5158922 -0.2541312 0.8180908 0.5680539 -0.1960553 0.7992979 0.5715298 -0.1449043 0.807686 0.5157816 -0.1379181 0.8455461 0.5736996 -0.07565701 0.8155642 0.5146785 -0.01632785 0.8572278 0.5755623 -0.01190245 0.8176714 0.5736402 0.04999053 0.8175806 0.5147614 0.1046186 0.8509265 0.5746713 0.1168264 0.8100028 0.5733605 0.1745992 0.8004829 0.5150121 0.2234008 0.8275595 0.5726383 0.2430577 0.7829486 0.5728193 0.2953976 0.7646034 0.5169423 0.3344346 0.7879875 0.5694831 0.3639687 0.7370319 0.5378398 0.3764238 0.7543431 0.9659232 -0.2588289 0 0 0 1 0.9659262 -0.2588176 0 0.9978095 -0.06613403 0.001617491 0.985498 -0.1696872 0 0.999761 0.01815855 0.01217693 0.9860548 0.1664177 0.00112915 0.9915136 0.129982 0.002349972 0.9406982 0.3391921 0.005981743 0.8785292 0.4776884 4.5779e-4 0.865904 0.5001997 0.003234922 0.7732822 0.634056 0.002777159 0.6335718 0.773684 3.05189e-5 0.6080594 0.7938892 0.001922667 0.4577878 0.8890543 0.003601253 0.2784584 0.9604434 0.003082394 0.2600526 0.9655913 0.002471983 0.08191388 0.9966394 -3.96751e-4 -0.1304991 0.9914391 0.004303157 -0.1238469 0.9923013 -3.05192e-4 -0.3233237 0.9462879 0.001037657 -0.4995344 0.8662807 0.004821956 -0.5009496 0.8654764 -4.57795e-4 -0.6397392 0.7685903 0.001617491 -0.7943247 0.6074858 0.003082394 -0.7647806 0.6442908 -2.44154e-4 -0.8683908 0.4958745 0.002472043 -0.9256017 0.3783098 0.0119633 -0.9658939 0.2589383 3.45389e-5 -0.9659271 0.2588142 0 -0.8968614 0.4423117 0 -0.9659249 -0.2588227 -9.96392e-6 -0.9659251 -0.2588217 0 -0.8971441 -0.4417358 0.001464903 -0.9379533 -0.3467617 0 -0.8550837 -0.5183361 0.01263487 -0.7674247 -0.641138 0.00125122 -0.7936514 -0.6083694 0.002075254 -0.6369376 -0.7708867 0.006653189 -0.5104371 -0.859915 5.49349e-4 -0.4997153 -0.8661853 0.002807676 -0.334733 -0.9423063 0.003570675 -0.1423698 -0.9898136 3.05187e-4 -0.1296143 -0.9915634 0.00149542 0.06894278 -0.9976107 0.004455745 0.2590439 -0.9658603 0.003204464 0.2575214 -0.9662699 0.002258419 0.4449415 -0.8955596 -3.66232e-4 0.6087629 -0.7933419 0.004059016 0.6188306 -0.7855246 -2.44151e-4 0.7643744 -0.6447712 0.001434326 0.865722 -0.5005055 0.004455685 0.8734769 -0.4868655 -3.66225e-4 0.9414383 -0.3371806 0.001861691 0.9916357 -0.1290359 0.002899289 0.985446 -0.1699886 -2.74668e-4 0.9999718 0.007110774 0.002441465 0.990429 0.1375485 0.01144456 0.9659956 0.2585586 1.41289e-4 0.9659251 0.2588219 0 0.997865 0.0653097 0 0.2559924 0.9344882 -0.247386 0.2553558 0.9304452 -0.2628026 0.9593877 0.2257167 -0.169196 0.9464312 0.2237363 -0.232831 0.2556926 0.9514158 -0.1715502 0.9708496 0.2244695 -0.08405017 0.2593536 0.9077073 -0.3298534 0.2548096 0.8832421 -0.393644 0.9410062 0.2252945 -0.2524874 0.9110581 0.223858 -0.3462094 0.2574315 0.8379417 -0.4812305 0.2546223 0.8180692 -0.5156843 0.8831122 0.2253559 -0.4114944 0.8618001 0.2237054 -0.4552544 0.257459 0.8747684 -0.4104816 0.9156413 0.2249276 -0.3331797 0.2591704 0.7908787 -0.5543841 0.2546511 0.733312 -0.6304018 0.8436709 0.2256279 -0.4871464 0.8004847 0.2240405 -0.5559049 0.258983 0.6835003 -0.6824626 0.2570953 0.6362682 -0.7273685 0.7979774 0.2251683 -0.559045 0.7348821 0.2246549 -0.639905 0.2588049 0.7397913 -0.6210707 0.2572174 0.5554223 -0.7907878 0.2588638 0.5539234 -0.7913017 0.6889472 0.2250813 -0.6889777 0.6672602 0.2240681 -0.7103221 0.2575231 0.6196364 -0.7414396 0.7464497 0.2249603 -0.6262634 0.2593826 0.4830578 -0.8362869 0.2588315 0.4878764 -0.8336564 0.5682922 0.3318014 -0.7529621 0.591038 0.4340463 -0.6799103 0.5808408 0.4047757 -0.7062441 0.6262833 0.2250481 -0.7464066 0.6077044 0.2249287 -0.7616447 0.2583492 0.421599 -0.8692008 0.5362932 0.3784144 -0.7544483 0.5736751 0.3594282 -0.7360084 0.2598751 0.4082007 -0.8751212 0.2580387 0.3527699 -0.8994274 0.5162904 0.3339697 -0.7886118 0.573127 0.295582 -0.7643015 0.2601479 0.3303121 -0.9073131 0.2578538 0.2818111 -0.9241721 0.5729653 0.2427182 -0.7828145 0.2602949 0.2499184 -0.932624 0.2577999 0.2090905 -0.943303 0.5154421 0.2227305 -0.8274725 0.5701919 0.1723119 -0.8032371 0.2603 0.1676431 -0.9508627 0.2578864 0.135108 -0.9566821 0.5721709 0.1197261 -0.8113485 0.260145 0.08408015 -0.9619019 0.2580384 0.06033611 -0.9642489 0.5162311 0.1040092 -0.8501104 0.5660731 0.04422253 -0.8231681 0.2598673 -1.22075e-4 -0.9656443 0.2583467 -0.01480185 -0.9659389 0.5709485 -0.006561517 -0.8209598 0.2594103 -0.0843541 -0.9620763 0.258772 -0.08984839 -0.9617506 0.516143 -0.01492393 -0.8563725 0.5736996 -0.07565701 -0.8155642 0.2593811 -0.1675798 -0.9511249 0.2588351 -0.1639808 -0.9519006 0.5147027 -0.1369997 -0.8463524 0.5753078 -0.1402944 -0.8058155 0.2584356 -0.2374689 -0.9363864 0.5735477 -0.1996262 -0.7944762 0.259782 -0.2498021 -0.9327981 0.2580991 -0.3095847 -0.9151733 0.5148893 -0.2548658 -0.8184942 0.5739217 -0.2654903 -0.7746799 0.2601181 -0.3301605 -0.9073768 0.2578889 -0.3798138 -0.8883889 0.5731793 -0.3190467 -0.754768 0.2602714 -0.4080169 -0.8750892 0.2578254 -0.4477459 -0.8561832 0.5152323 -0.3675173 -0.7742524 0.57138 -0.3847247 -0.724922 0.2603012 -0.4827582 -0.8361746 0.2578557 -0.5129648 -0.818766 0.5725098 -0.4313279 -0.6972724 0.260178 -0.5538663 -0.7909106 0.2580086 -0.5750412 -0.7763758 0.5157526 -0.4726588 -0.714558 0.5676844 -0.4953237 -0.6575629 0.2599307 -0.6207574 -0.7396596 0.2582858 -0.6336137 -0.7292615 0.5714368 -0.5338985 -0.6232275 0.2595333 -0.6830145 -0.6827399 0.2586802 -0.6883288 -0.6777081 0.5154195 -0.5674864 -0.6421075 0.5737008 -0.5837111 -0.5745858 0.2593851 -0.7397924 -0.6208274 0.258808 -0.7387319 -0.6223294 0.5140293 -0.6536226 -0.5554739 0.5755314 -0.6258881 -0.5263344 0.2584988 -0.7848657 -0.5631733 0.5736327 -0.6647925 -0.4785358 0.2597166 -0.7909607 -0.5540113 0.2581663 -0.8263518 -0.5004928 0.5139147 -0.7253831 -0.4579423 0.5745542 -0.7014224 -0.4217751 0.2600554 -0.8361999 -0.4828467 0.257919 -0.8628126 -0.4347786 0.5733302 -0.7304116 -0.3712028 0.2602649 -0.8750675 -0.4080678 0.2578263 -0.8940297 -0.3663831 0.513887 -0.7826111 -0.3513402 0.5724261 -0.760366 -0.3068748 0.260298 -0.9073045 -0.3302174 0.2578266 -0.9198197 -0.2957316 0.5727816 -0.7790598 -0.2549256 0.2602365 -0.932664 -0.2498294 0.2579783 -0.9399897 -0.2233086 0.5140372 -0.8241443 -0.2378067 0.5691503 -0.8013394 -0.1841826 0.2599955 -0.9509567 -0.1675825 0.2582252 -0.9544354 -0.1495759 0.5718775 -0.8095951 -0.1323332 1 2.75781e-6 0 1 -2.76207e-6 0 1 1.39751e-6 0 1 4.78359e-7 0 1 3.75843e-7 0 1 1.20418e-6 0 1 -1.51667e-6 0 0 0.9957351 0.09225815 0 0.9829716 0.1837578 0 0.9829726 -0.1837523 0 0.9829716 -0.1837578 0 0.9957351 -0.09225815 0 0.9829726 0.1837523 0 0.932469 0.3612501 0 0.8502163 0.5264335 0 0.7390073 0.6736975 0 0.7390224 0.6736809 0 0.6026336 0.798018 0 0.4457358 0.8951646 0 0.2736608 0.9618263 0 0.2736327 0.9618343 0 0.09225815 0.9957351 0 -0.09225815 0.9957351 0 -0.2736689 0.9618241 0 -0.2736327 0.9618343 0 -0.4457603 0.8951524 0 -0.4457358 0.8951646 0 -0.6026336 0.798018 0 -0.7390224 0.6736809 0 -0.8502027 0.5264555 0 -0.8502249 0.5264198 0 -0.932469 0.3612501 0 -0.9829716 0.1837578 0 -0.9829726 0.1837523 0 -0.9957324 0.09228843 0 -0.9957324 -0.09228843 0 -0.9957351 -0.09225815 0 -0.9829716 -0.1837578 0 -0.9957351 0.09225815 0 -0.932469 -0.3612501 0 -0.8502163 -0.5264335 0 -0.7390224 -0.6736809 0 -0.6026336 -0.798018 0 -0.602653 -0.7980033 0 -0.4457358 -0.8951646 0 -0.2736608 -0.9618263 0 -0.2736327 -0.9618343 0 -0.09225815 -0.9957351 0 0.09225815 -0.9957351 0 0.2736689 -0.9618241 0 0.2736327 -0.9618343 0 0.4457603 -0.8951524 0 0.4457237 -0.8951706 0 0.6026336 -0.798018 0 0.7390224 -0.6736809 0 0.8502027 -0.5264555 0 0.8502249 -0.5264198 0 0.932469 -0.3612501 -0.1392265 0.3636919 0.921056 -0.06439518 0.38689 0.9198747 -0.0943641 0.2602643 0.9609152 -0.08499634 0.2252938 0.9705764 -0.1675496 0.2235215 0.9601903 -0.05935937 0.2247416 0.9726088 -0.3141324 0.6428224 0.6986417 -0.2730519 0.793123 0.5444251 -0.2722911 0.8006066 0.5337479 -0.2518128 0.2250781 0.9412387 -0.2892318 0.2241036 0.930657 -0.1693508 0.2248957 0.9595531 -0.02313351 0.3474918 0.9373977 0.007416129 0.3943394 0.918935 0.00701934 0.2250478 0.9743225 -0.160319 0.3068128 0.9381704 0.09677618 0.3345509 0.9373955 4.57782e-4 0.2248015 0.9744045 0.07968509 0.2246504 0.9711759 -0.02084481 0.2436676 0.9696349 0.1236622 0.3230417 0.9382706 0.1291275 0.3703221 0.9198846 -0.169929 0.1758191 0.9696453 -0.0321061 0.2132982 0.9764595 0.1292499 0.2066167 0.9698474 -0.07989776 0.2183303 0.9725987 0.1443254 -0.9895254 0.003112912 0.1779239 -0.9840443 3.05187e-5 0.4155773 -0.9095579 3.0519e-5 -0.01699888 0.3194396 0.9474542 -1.22078e-4 -1 3.35714e-4 -0.1207012 0.1427967 0.9823648 0.4154027 -0.9096377 0 0.6551839 -0.7554696 -3.05191e-5 -0.1732249 0.1030926 0.9794719 0.8412073 -0.5407129 6.10389e-5 0.8416602 -0.5400077 -3.05193e-5 0.6547912 -0.75581 0 -0.1994758 0.02719289 0.9795254 -0.1636111 0.06262445 0.9845352 0.9594957 -0.2817234 3.05193e-5 0.9596126 -0.2813252 0 -0.2050275 -0.02917629 0.9783213 0.98984 -0.1421861 0 -0.1815899 -0.1292187 0.9748476 -0.2406444 -0.04571783 0.969536 0.9898222 0.14231 3.0519e-5 0.9898486 0.1421263 0 0.9596315 0.2812607 0 0.9898179 -0.1423399 0 -0.1463686 -0.08942031 0.9851803 0.9594874 0.2817516 6.1038e-5 0.8416829 0.5399723 -3.0519e-5 -0.1174987 -0.1562581 0.9807026 0.8412073 0.5407129 6.10389e-5 0.6551839 0.7554696 -6.10382e-5 -0.08719384 -0.2086914 0.9740868 0.6547912 0.75581 0 0.4155773 0.9095579 0 -0.1615374 -0.2592899 0.9521946 -0.04751896 -0.2141253 0.9756497 0.4154027 0.9096377 3.05196e-5 0.1779239 0.9840443 0 -0.02285903 -0.2798331 0.9597765 0.009613335 -0.2185746 0.975773 0.1442956 0.9895297 0.003143489 -1.22078e-4 1 3.35714e-4 -0.1606857 -0.3928484 0.9054559 -0.02246224 -0.412866 0.9105148 0.1206132 -0.3335176 0.9349966 0.1266839 -0.2101225 0.9694327 -0.1598317 -0.5199031 0.8391392 -0.02246224 -0.5384846 0.8423359 0.1203674 -0.4579091 0.8808127 -0.1590982 -0.6359961 0.7551137 -0.02243149 -0.6531073 0.7569331 0.1201548 -0.573795 0.8101371 -0.1584231 -0.7386773 0.6551778 -0.02230983 -0.7544144 0.6560192 0.1199402 -0.6789287 0.7243412 -0.1567775 -0.8251494 0.5427241 -0.02212631 -0.8403115 0.5416521 0.1197564 -0.7713364 0.625059 -0.1459729 -0.8961631 0.4190273 -0.02188223 -0.9090143 0.4161903 0.1195424 -0.8493095 0.5141819 -0.1421582 -0.9480776 0.2844996 -0.02151608 -0.9591289 0.2821506 0.1179571 -0.9119164 0.393058 -0.1504609 -0.9792472 0.135781 -0.0210278 -0.9895897 0.1423727 0.1175588 -0.9562491 0.267895 -0.05539125 -0.9958835 0.07174926 0.01431322 -0.9973812 0.07089489 0.117132 -0.9840251 0.13407 -0.1598297 -0.9845535 0.07147622 -0.1594293 -0.9768406 -0.1427052 -0.002471983 -0.9959498 -0.08987778 -0.03759938 -0.9916232 -0.1235714 0.08441483 -0.9940871 0.06830096 -0.02002066 -0.9893144 -0.1444174 0.1012917 -0.9873726 -0.1218003 -0.1594612 -0.9846311 -0.07123106 -0.2916719 -0.9549149 0.0553618 -0.2963757 -0.9454359 -0.1353238 -0.2956369 -0.9528927 -0.06778252 -0.2196173 -0.9587963 0.1802168 -0.294964 -0.9511178 0.09149527 -0.201214 -0.9285206 0.3120298 -0.1938568 -0.8733632 0.4468291 -0.2030134 -0.9022685 0.3803908 -0.2080522 -0.8857401 0.4149446 -0.2957914 -0.7815339 0.5492833 -0.3440113 -0.7946564 0.5001776 -0.5184373 -0.3902853 0.760855 -0.1670008 -0.87413 0.4560784 -0.1903775 -0.8609108 0.4717934 -0.2126567 -0.846049 0.4888541 -0.2406099 -0.823793 0.5132951 -0.2978408 -0.7671104 0.5681836 -0.2954813 -0.6983883 0.6518779 -0.2950969 -0.6018831 0.742061 -0.2946366 -0.4938992 0.8180788 -0.2940548 -0.3765183 0.878502 -0.2947529 -0.1232969 0.9475857 -0.2940847 -0.2526699 0.9217766 -0.2953939 0.008484244 0.955338 -0.2959443 0.1401134 0.9448731 -0.2953659 0.2674103 0.9171972 -0.2432658 0.3265517 0.9133377 -0.2880411 0.3244201 0.9009906 -0.3061699 0.6410279 0.7038062 0.08435505 0.224896 0.9707245 0.1497551 0.2246479 0.9628639 0.2293509 0.3387619 0.9124903 0.1692265 0.2255641 0.9594181 0.2208699 0.2244407 0.9491274 0.2571507 0.3148615 0.9136387 0.2692998 0.3629626 0.8920402 0.2043235 0.1332147 0.9697968 0.1981904 0.1128287 0.9736479 0.2589541 0.1790857 0.9491423 0.1350458 0.142706 0.980509 0.07440543 0.1759424 0.9815845 0.02771121 0.2372544 0.9710523 -0.9594957 -0.2817234 2.44154e-4 -0.8862138 -0.4631274 0.0117498 -0.8123896 -0.583038 0.009491443 0.2640221 0.04025489 0.9636762 0.1967264 0.06039738 0.9785965 -0.9629368 -0.2697273 0 -0.84123 -0.5406774 9.15575e-5 -0.6560337 -0.7547317 -9.15566e-5 -0.6548086 -0.7557949 1.22075e-4 -0.4168061 -0.9089955 -1.22078e-4 -0.4153659 -0.9096544 1.22077e-4 -0.1785363 -0.9839334 -6.1038e-5 -0.1443254 -0.9895254 0.003143429 0.2520572 0.2255666 0.9410563 0.2896854 0.2245885 0.9303991 0.3909854 0.317708 0.8638241 0.3335731 0.3717219 0.866344 0.3332099 0.2256293 0.9154576 0.3579242 0.2245572 0.9063467 0.3896043 0.1894613 0.9012841 0.3892999 0.05435425 0.919506 0.2062796 -0.1042538 0.9729235 0.2603564 -0.1007122 0.9602456 0.3890593 -0.08194416 0.917561 0.2525769 -0.09207642 0.9631859 0.2085674 -0.006866753 0.977984 0.2608518 -0.2384808 0.9354588 0.3888456 -0.216534 0.8954955 0.2613379 -0.3712078 0.8910148 0.3886664 -0.3463969 0.8537843 0.2617627 -0.4960582 0.8278929 0.3885034 -0.4687066 0.7933343 0.26222 -0.6105344 0.747321 0.3882662 -0.5809038 0.7154022 0.262314 -0.7118031 0.6515579 0.2590172 -0.7967672 0.5459597 0.3883855 -0.6798425 0.6220699 0.1752703 -0.8668604 0.4667264 0.07880139 -0.8632445 0.4985973 0.3919324 -0.7610058 0.5169712 0.2373824 -0.8280003 0.5080009 0.1639186 -0.8532255 0.4951131 0.1807026 -0.8802882 0.4386792 0.7210799 -0.6928496 0.001861631 0.8437609 -0.5367085 0.003418087 0.8909832 -0.4540065 0.005218803 0.766801 -0.6418849 3.05194e-5 0.185495 -0.8900281 0.4164634 0.931324 -0.3641856 0.00213629 0.9517918 -0.3067451 -6.10377e-5 0.1745076 -0.9088255 0.378924 0.9921736 -0.1248228 0.003326535 0.1442345 -0.917748 0.3700474 0.9997852 0.02069211 0.00125128 0.9954504 0.09528148 -6.10387e-5 0.1677332 -0.925554 0.3394339 0.9628286 0.2700363 0.006439566 0.1801836 -0.9355571 0.3037546 0.9159121 0.4013792 3.29276e-5 0.9159732 0.4012395 0 0.9766729 0.2147325 0 0.2310905 -0.9478006 0.2197068 0.05276817 -0.9597467 0.2758657 0.9160165 0.4011409 0 0.2597163 -0.9604317 0.1005905 0.2642005 -0.9509631 0.1608336 0.2229418 -0.9732534 0.05545312 0.295213 -0.9536665 0.05804765 0.3997145 -0.9081092 0.1247639 0.1520459 -0.9862234 0.06515818 0.1202161 -0.9822991 -0.143655 0.2739713 -0.9577549 -0.08743762 0.2386281 -0.9636683 -0.1200007 0.3568325 -0.9315732 0.06958413 0.2581624 -0.955802 -0.1406937 0.3716915 -0.9206987 -0.1189938 0.1371233 -0.9865372 -0.08911639 0.2082597 -0.1357778 0.9686033 0.02801674 -0.2340223 0.9718275 0.0755645 -0.1768563 0.9813317 0.1377028 -0.1450884 0.9797895 -0.9598174 0.2806207 0.001678526 -0.889391 0.4571473 2.13635e-4 -0.9629447 0.269699 0 -0.8405964 0.5416587 0.001892149 -0.8084523 0.5885618 -3.05191e-5 -0.9898443 0.1421562 0 -0.9898222 -0.14231 3.0519e-5 -0.9898486 -0.1421263 0 -0.9898222 0.14231 0 0.4102427 0.3754506 0.8311063 0.4118848 0.2254135 0.8829154 0.4240014 0.2249866 0.8772706 0.4543347 0.3729713 0.8089947 0.4879438 0.2250193 0.8433725 0.3614097 -0.8194131 0.4449105 0.409326 -0.8219175 0.3961111 0.361959 -0.8105928 0.4603532 0.3366907 -0.8070567 0.4850763 0.2995219 -0.7970567 0.5243923 0.1670954 -0.7360132 0.6560211 0.3734069 -0.880398 0.2923469 0.4145762 -0.8691023 0.2697919 0.3881106 -0.8573715 0.3380594 0.3607343 -0.8501061 0.3836541 0.3546965 -0.8403823 0.4098145 0.3708733 -0.9112521 0.1790885 0.4213518 -0.9044445 0.0666545 0.3041896 -0.9473919 0.09958571 0.4054233 -0.9101576 -0.08511936 0.4842197 -0.8727307 0.06222885 0.3904916 -0.9105976 -0.1353826 0.4978032 -0.8593063 -0.1174084 -0.9159785 -0.4012273 5.88884e-6 -0.9159752 -0.4012348 0 -0.8215076 -0.5701845 0.003875851 -0.8610377 -0.5085411 0 -0.743605 -0.6686188 -7.62985e-4 -0.6923637 -0.7215403 0.003479182 -0.58234 -0.8129442 0.001434385 -0.4108506 -0.9117026 -4.2727e-4 -0.3636361 -0.9315372 0.002685666 -0.2171111 -0.9761455 0.001678526 -0.02688694 -0.9996386 0 0.02044743 -0.9997889 0.002075254 0.1637355 -0.9865029 0.001648008 0.3342164 -0.9424957 0.00125128 0.4012617 -0.915962 0.001709043 0.4963623 -0.8681151 8.54534e-4 0.6402873 -0.7681311 0.002594053 0.4873313 0.2249879 0.843735 0.5498293 0.224833 0.8044488 0.5585654 0.2252328 0.798295 -0.9933839 0.1128886 0.02108842 -0.9985184 0 0.05441522 -0.992581 0.1192696 -0.02362197 -0.9985226 -0.001312315 -0.05432391 -0.981483 0.04767024 -0.1855235 -0.9936226 0.1116097 0.01605319 -0.9934651 0.1093202 0.03280824 -0.9931412 0.105839 0.04968452 -0.9925801 0.1012936 0.06726455 -0.9917972 0.09500473 0.08551341 -0.9906629 0.08682793 0.1051091 -0.989838 0.07614606 0.1200941 -0.9896863 0.05948245 0.1303182 -0.9896687 0.04034602 0.1375795 -0.9914494 0.02539199 0.1279978 -0.9924604 -9.15582e-5 0.1225659 -0.9924171 -0.01760941 0.1216487 -0.9906008 -0.04477202 0.1292499 -0.989651 -0.05960428 0.1305312 -0.9896488 -0.07757997 0.1207342 -0.989649 -0.09396886 0.1084655 -0.989649 -0.1084655 0.09396886 -0.9896488 -0.1207342 0.07757997 -0.989647 -0.1305612 0.05960404 -0.9896478 -0.1377028 0.04043799 -0.9896465 -0.1420669 0.02041733 -0.9895924 -0.1435328 0.0102545 -0.9896515 -0.1420371 -0.02038693 -0.9895924 -0.1435328 -0.0102545 -0.9934115 0.1098975 -0.03250229 -0.9931362 0.1058722 -0.04971629 -0.9925627 0.1013834 -0.06738549 -0.9917638 0.0951876 -0.08569628 -0.9904898 0.08713132 -0.1064803 -0.9897148 0.07730573 -0.1203686 -0.9897045 0.05945122 -0.1301946 -0.9897079 0.04031586 -0.1373059 -0.989709 0.02035629 -0.1416398 -0.9897077 0 -0.1431046 -0.989709 -0.02035629 -0.1416398 -0.9897038 -0.04031568 -0.1373359 -0.9897027 -0.05948162 -0.1301943 -0.9896982 -0.07742649 -0.1204277 -0.9896935 -0.09378421 -0.1082196 -0.9896863 -0.1082832 -0.09378641 -0.989677 -0.1205814 -0.07745772 -0.9896728 -0.130408 -0.05951219 -0.9896592 -0.1376391 -0.04037618 -0.9912601 0.1316288 -0.008789479 -0.9886268 0.1501221 0.008972525 -0.9883763 0.1512808 -0.01504564 -0.9884104 0.1516171 -0.007568597 -0.9881684 0.1502441 0.03082394 -0.9885436 0.150276 0.01409977 -0.9874235 0.145852 0.06100821 -0.9878714 0.148231 0.04623633 -0.9858554 0.1355654 0.09854584 -0.9869861 0.1406012 0.0780372 -0.983507 0.1204892 0.1348942 -0.9792661 0.09451758 0.1791775 -0.9740871 0.07202571 0.2143986 -0.9649232 0.1294926 0.2283746 -0.97079 0.1223826 0.2063718 -0.9610437 0.1059315 0.2552915 -0.9577579 0.08408075 0.2750098 -0.9852673 0.02035599 0.1698063 -0.9564622 0.2772947 0.09103786 -0.985446 -1.83112e-4 0.1699886 -0.3726685 -0.9261626 0.05780309 -0.9853184 -0.02014279 0.1695352 -0.9597715 -0.07977747 0.2692109 -0.9569387 -0.09027665 0.2758962 -0.9599369 -0.1170089 0.2546179 -0.9599226 -0.1520165 0.2354561 -0.9599006 -0.1839718 0.2115309 -0.9598761 -0.2122275 0.1832957 -0.9598429 -0.2362145 0.1513421 -0.9598017 -0.2554466 0.1163091 -0.9597622 -0.2695135 0.07886111 -0.9596874 -0.2782468 0.03973644 -0.9594345 -0.2812046 0.02023428 -0.9594283 -0.2811723 -0.02096658 -0.9108523 -0.4081668 0.06122195 -0.9104072 -0.412584 0.03054934 -0.9596562 -0.2780635 -0.04172015 -0.9103188 -0.4127991 -0.03027474 -0.9057583 0.423794 -7.62988e-4 -0.9045397 0.4263749 -0.003540098 -0.9058886 0.4233258 0.01269578 -0.9035151 0.4247024 -0.05734515 -0.9019107 0.4317891 -0.01074284 -0.904617 0.4254669 0.02542239 -0.9025066 0.429005 0.0379045 -0.9034808 0.4261045 0.04644972 -0.9030927 0.4256203 0.05719292 -0.9037479 0.4235984 0.06167811 -0.9013141 0.4259215 0.07889127 -0.8988697 0.4262253 0.1018106 -0.8965288 0.4277251 0.1152706 -0.8928422 0.4291624 0.1365739 -0.8880102 0.4305615 0.1614148 -0.8859344 0.4314157 0.1702957 -0.8828603 0.4316335 0.1850686 -0.9501952 0.139169 0.278857 -0.8750467 0.433861 0.2146111 -0.9348363 0.09088641 0.3432504 -0.9133778 0.130561 0.3856098 -0.9263961 0.140142 0.3495005 -0.9666019 0.05975645 0.2492192 -0.9500869 0.07260465 0.3034199 -0.908069 0.09427386 0.4080725 0 -0.9999999 5.54139e-4 0 -1 0 -0.9379794 0.1348646 0.3193842 0 1 0 0 1 -1.28277e-5 -0.908842 -0.0994327 0.4051166 -0.9339969 -0.1089826 0.3402539 0.5586585 -0.8089791 -0.1829031 -0.9111202 -0.1511005 0.3834432 -0.9111251 -0.2065245 0.3566493 -0.9111145 -0.2573363 0.321945 -0.9110816 -0.3024731 0.2800722 -0.9110388 -0.3408727 0.231979 -0.9109912 -0.371721 0.178658 -0.9109166 -0.3943429 0.1213456 -0.8449942 -0.5295138 0.07483386 -0.8442729 -0.5346899 0.03619527 -0.9108043 -0.4084641 -0.05993896 -0.8432775 -0.5361317 -0.03802698 -0.1947425 0.980854 8.85054e-4 -0.09799575 0.9951869 0 -0.2831848 0.9590256 0.008728384 -0.9196479 -0.06653058 0.3870676 -0.4189903 0.9079904 7.62966e-4 -0.9123519 -0.06296181 0.4045368 -0.3822253 0.9240674 0.001770079 -0.5553656 0.8315988 0.003540217 -0.8893117 -0.0825833 0.449783 -0.6284837 0.7777839 0.007782399 -0.844168 -0.08517974 0.5292683 -0.8415482 -0.01217728 0.5400448 -0.7778571 -0.4028913 0.4823038 -0.6821593 0.7312033 8.24011e-4 -0.8441973 -0.158823 0.5119631 -0.844233 -0.2292632 0.484468 -0.8442645 -0.2951554 0.4473262 -0.844289 -0.3551544 0.4012997 -0.8443369 -0.4080382 0.347275 -0.8473293 -0.4467981 0.2870616 -0.8523074 -0.4759762 0.2168383 -0.8484988 -0.5100088 0.1412129 -0.7586989 -0.6482207 0.06469994 -0.7576554 -0.6515727 0.03756839 -0.8438678 -0.5312552 -0.07520037 -0.7594999 -0.648929 -0.04529041 -0.8292348 -0.2707961 0.4889162 -0.7071649 0.7070428 0.002899289 -0.7919673 0.6105626 0.001068115 -0.861307 -0.1408146 0.4881818 -0.8927055 0.4506406 -3.35707e-4 -0.8708642 -0.06567722 0.4871163 -0.9239811 0.3824286 0.002716124 -0.9639047 0.2662457 0.001098632 -0.8697956 -0.01483225 0.4931893 -0.9957689 0.09189224 4.27264e-4 -0.842497 0.06808704 0.534381 -0.8663279 0.01205521 0.4993303 -0.999997 0 0.002441525 -0.9968952 -0.07873839 4.883e-4 -0.8752236 0.04754859 0.481376 -0.9681239 -0.2504695 0.001159667 -0.880535 0.08191305 0.4668495 -0.9238779 -0.3826805 0.002288937 -0.9009814 -0.4338579 0 -0.8832253 0.1211612 0.4530268 -0.802423 -0.596751 0.00238049 -0.8835315 0.1519247 0.4430475 -0.7075769 -0.7066308 0.002838194 -0.6877277 -0.7259687 -3.35715e-4 -0.8934761 0.08023458 0.4418855 -0.6204499 -0.784245 0.001312255 -0.9128268 0.05975639 0.4039511 -0.5540154 -0.8325033 0.002319455 -0.8452553 0.1351383 0.5169925 -0.9199912 0.06421166 0.3866435 -0.9275686 0.07892251 0.3652227 -0.9011973 0.1646198 0.4009289 -0.8709028 0.09332841 0.4825124 -0.8619163 0.1561349 0.4824131 -0.8505086 0.445458 0.2796472 -0.845665 0.4453406 0.294147 -0.8341225 0.4490302 0.3203304 -0.8609681 0.4380985 0.2584643 -0.8273082 0.4534203 0.3316191 -0.8135673 0.4549116 0.3621653 -0.7997944 0.4639577 0.3808836 -0.7914754 0.4653207 0.396287 -0.8289253 0.1776813 0.5303889 -0.7756747 0.4700254 0.4211948 -0.7603346 0.1441135 0.6333425 -0.7852614 0.1252816 0.6063573 -0.7698152 0.1782013 0.6128857 -0.7593778 0.05282866 0.6485017 -0.7593796 -0.04330676 0.6492051 -0.759372 -0.1385254 0.6357398 -0.7593914 -0.230729 0.6083493 -0.7594335 -0.3178548 0.5676524 -0.7594964 -0.3979986 0.5145507 -0.7643817 -0.4584886 0.4533309 -0.8040043 -0.4610267 0.3755418 -0.8150266 -0.5079076 0.2788578 -0.811563 -0.4517432 0.3705319 -0.8103842 -0.4753717 0.3424898 -0.8146561 -0.55579 0.1656291 -0.7607849 -0.6350759 0.1337355 -0.7897156 -0.610934 0.05575859 -0.7855723 -0.6010819 0.1468904 -0.6609591 -0.7422629 0.1103582 -0.6611884 -0.7481972 0.05505573 -0.7604108 -0.6432484 -0.08948159 -0.6599241 -0.7492853 -0.05542343 -0.7690511 0.4737177 0.4291293 -0.7466478 0.4791486 0.4614475 -0.7349529 0.4874762 0.4713928 -0.7179282 0.4902262 0.4942241 -0.7053664 0.1772571 0.6863222 -0.6974835 0.5006963 0.5126598 -0.6830503 0.5017662 0.5307289 -0.6622961 0.1646203 0.7309337 -0.6635757 0.1999608 0.7208904 -0.6629085 0.05408006 0.7467449 -0.6631869 -0.05765116 0.7462303 -0.6633714 -0.1680707 0.7291713 -0.6634494 -0.2746697 0.6959825 -0.6634327 -0.3751761 0.6473793 -0.6633683 -0.4673731 0.5843842 -0.7909184 -0.471377 0.3901945 -0.7566455 -0.4953965 0.4266965 -0.7326811 -0.4882506 0.47412 -0.6570242 -0.548863 0.516787 -0.7728328 -0.4863203 0.4077033 0.2510781 -0.9679647 0.002044737 0.3336979 -0.9426799 6.10386e-4 0.419061 -0.9079504 0.00375384 0.1921765 -0.9813604 -2.13631e-4 0.5037474 -0.8638111 0.008301138 0.6013387 -0.7989944 0 0.6015329 -0.7988481 0 0.4341037 -0.9008629 0 -0.7284022 -0.6574755 0.1927593 -0.6605671 -0.7174862 0.2210537 -0.5496477 -0.8274015 0.1153008 -0.5488809 -0.8338657 0.05829089 -0.6614169 -0.741805 -0.1106939 -0.5497152 -0.8332709 -0.0589329 -0.6549453 -0.6831452 0.3230473 -0.6974662 -0.6673128 0.2612179 -0.6015505 0.7988348 0 -0.6897028 -0.6388579 0.3408381 -0.6015471 0.7988374 0 -0.6479886 -0.6292497 0.4291337 -0.6762436 -0.6410551 0.3629644 -0.7454948 0.6665108 0.001068174 -0.6718111 0.7407226 0 -0.7967177 0.6042981 0.008056879 -0.685106 -0.6181763 0.3853416 -0.8802651 0.4744819 6.10384e-4 -0.6759641 -0.604153 0.4219855 -0.8612732 0.5081393 0.001739561 -0.9492083 0.3146225 0.004059016 -0.5779815 -0.6854413 0.4428404 -0.985781 0.1680353 1.52593e-4 -0.6296113 -0.6311984 0.4529662 -0.9902402 0.1393483 0.002533018 -0.9998818 -0.01528978 0.001678466 -0.6607698 -0.5920102 0.4614188 -0.9776033 -0.2104564 -2.44149e-4 -0.6804329 -0.5619562 0.4703365 -0.9681299 -0.2504405 0.002075254 -0.9152087 -0.402975 0.002044737 -0.6952788 -0.533041 0.4821357 -0.8279328 -0.5608262 0.001159727 -0.7146973 -0.4829349 0.5059463 -0.7987267 -0.6016926 0.001281797 -0.7146042 -0.6995278 0.001342833 -0.7614641 -0.2136677 0.6119791 -0.575398 -0.8178684 0.002929747 -0.50854 -0.8610358 0.00213629 -0.3961724 -0.9181762 -3.35713e-4 -0.1397454 -0.9901812 0.003540158 -0.1984984 -0.9801012 -1.52597e-4 0.001861631 -0.9999983 2.74675e-4 -0.6574766 0.5150126 0.5499877 -0.6419302 0.5175055 0.5657861 -0.5493078 0.1960833 0.8122883 -0.6223208 0.1995052 0.7569112 -0.6141098 0.5313109 0.5835905 -0.6019055 0.5310392 0.596412 -0.549923 0.0837748 0.8310034 -0.5494903 -0.03241091 0.8348713 -0.5491623 -0.1480791 0.8224922 -0.5489111 -0.2609662 0.7940991 -0.5487417 -0.3688289 0.7502319 -0.5486461 -0.4695399 0.6917513 -0.5486108 -0.5611236 0.6198118 -0.5486514 -0.6417668 0.5358331 -0.5487734 -0.709917 0.4414359 -0.5489802 -0.7642019 0.33855 -0.549308 -0.8035906 0.2291352 -0.4327574 -0.8929209 0.1241507 -0.4298973 -0.9008738 0.06012332 -0.5501153 -0.8271414 -0.1149367 -0.4264783 -0.902276 -0.0633583 -0.5435149 0.2453431 0.8027443 -0.5713906 0.5442281 0.6142708 -0.5525145 0.5498288 0.6264313 -0.427303 0.2271258 0.875115 -0.5036547 0.2400928 0.829872 -0.5222808 0.5650387 0.6387128 -0.5103482 0.5639405 0.6492427 -0.4286376 0.104283 0.8974379 -0.4287942 -0.02246206 0.903123 -0.4289801 -0.1487513 0.8909821 -0.4291546 -0.2721052 0.8612695 -0.4293155 -0.3900371 0.8145916 -0.4294962 -0.5002701 0.7518396 -0.4296562 -0.6006276 0.6742715 -0.4297981 -0.6891174 0.5834304 -0.429986 -0.7639888 0.4810752 -0.4351723 -0.8211173 0.3693121 -0.4394201 -0.8631226 0.2488561 -0.427363 -0.8951946 -0.1264418 -0.4200645 0.2823929 0.8624384 -0.4780235 0.5748612 0.6640996 -0.4550444 0.5858201 0.6706336 -0.3773959 0.2822381 0.8819943 -0.4244629 0.6008952 0.6773155 -0.4140513 0.5980503 0.6862197 -0.3908604 -0.8430036 0.3695579 -0.409568 -0.7400608 0.5334455 -0.3924738 -0.7851001 0.4791476 -0.3814655 -0.8145093 0.4371029 -0.3772199 -0.8309824 0.4088685 -0.3888489 -0.8923594 0.2291098 -0.4400581 -0.821397 0.3628442 -0.4071897 -0.8528643 0.3268321 -0.3857342 -0.8769738 0.2865768 -0.3604881 -0.9232243 0.133062 -0.3207586 -0.9372805 0.1364521 -0.3793613 0.5985242 0.7055877 -0.3517072 0.626078 0.6959371 -0.2275778 -0.9737595 0.00100708 0.04342848 -0.9990388 0.005981683 0.1413321 -0.9899352 0.007324457 -0.1063908 -0.9943239 0.001129209 0.1612601 -0.9869099 0.002014219 0.2857235 -0.958312 -2.13636e-4 0.5271642 -0.8497558 0.00363177 0.472738 -0.8812031 -9.15567e-5 0.6341249 -0.7732307 2.44152e-4 0.8121083 -0.5834912 0.004272639 0.7714411 -0.6363008 -6.1039e-5 0.8878447 -0.4601435 3.05196e-5 0.9740056 -0.2265101 0.002533018 0.9744521 -0.2245918 -0.001342833 0.9999834 -0.002563536 0.005157649 0.9867671 0.1621443 -2.04058e-5 0.9867741 0.1621017 0 0.9994353 -0.03360134 0 -0.2800095 -0.9482784 0.1495418 -0.9867758 -0.1620911 8.16201e-7 -0.9867753 -0.1620945 0 -0.936916 -0.3495391 0.003326594 -0.975813 -0.2186073 0 -0.9464322 -0.3228936 0.002411007 -0.8962872 -0.4434741 4.27268e-4 -0.8491957 -0.528073 0.00238049 -0.8154333 -0.5788511 3.05189e-5 -0.7060005 -0.7081979 0.004364192 -0.5858735 -0.8104019 0.00112915 -0.5830348 -0.8124461 0.001312315 -0.437039 -0.8994396 0.002319455 -0.2789142 -0.9603143 0.001831114 -0.1442956 0.9895297 0.003143489 -0.1785363 0.9839334 -6.1038e-5 -0.4153659 0.9096544 1.22077e-4 -0.4167945 0.9090008 -1.22075e-4 -0.6548236 0.7557817 1.22077e-4 -0.6560012 0.7547599 -9.15563e-5 -0.8701474 0.4378663 0.22609 -0.3817957 -0.9242447 0.001953184 -0.4209481 -0.9070848 -1.52595e-4 -0.262376 -0.9649648 0.001342833 -0.1224119 -0.9924492 0.007751822 -0.1951417 -0.9807751 0 0.5500165 0.225445 -0.8041496 0.4543399 0.3729451 -0.809004 0.558751 0.2248677 -0.798268 0.4880328 0.2249571 -0.8433376 0.3909778 0.3177629 -0.8638073 0.4102475 0.3754244 -0.831116 0.3896707 0.1895555 -0.9012355 0.3894861 0.05444622 -0.9194217 0.389304 -0.08179163 -0.9174708 0.3892063 -0.2163172 -0.8953912 0.3891482 -0.3461164 -0.8536786 0.3891259 -0.468355 -0.7932369 0.3891568 -0.5803323 -0.715382 0.3892425 -0.6795721 -0.6218296 0.3893929 -0.763923 -0.5145822 0.3896068 -0.8314623 -0.3960769 0.3898836 -0.8807554 -0.2688137 0.4874228 0.2250184 -0.843674 0.4239738 0.2248966 -0.8773071 0.3335769 0.3716956 -0.8663539 0.4118227 0.225535 -0.8829133 0.3579242 0.2245572 -0.9063467 0.2583411 0.3114743 -0.9144636 0.2812635 0.3737362 -0.8838621 0.2576451 0.1770128 -0.9498872 0.2576735 0.03668403 -0.9655355 0.2577046 -0.1044369 -0.9605631 0.2577338 -0.2433287 -0.9350746 0.2577975 -0.3770063 -0.8896104 0.257826 -0.5026509 -0.8251471 0.2578855 -0.6175213 -0.7430765 0.2579507 -0.7192223 -0.6451209 0.2580112 -0.8055604 -0.5333881 0.258072 -0.874686 -0.4102723 0.2581293 -0.9251212 -0.2784245 0.3332099 0.2256293 -0.9154576 0.2896574 0.2245905 -0.9304074 0.2048155 0.3716955 -0.9054795 0.2520572 0.2255666 -0.9410563 0.2208699 0.2244407 -0.9491274 0.1197879 0.3083052 -0.9437154 0.1468266 0.3734298 -0.9159651 0.1194519 0.1698696 -0.9782001 0.1195126 0.0264905 -0.9924793 0.1195738 -0.117407 -0.9858589 0.1196351 -0.258833 -0.9584848 0.119695 -0.3948226 -0.9109272 0.1197857 -0.5225102 -0.8441769 0.1198508 -0.6391741 -0.7596659 0.1199406 -0.7423808 -0.6591548 0.1200001 -0.8299606 -0.5447618 0.1200609 -0.9000598 -0.4189007 0.1201549 -0.9511981 -0.2842271 0.1691372 0.2254452 -0.9594619 0.1495756 0.224928 -0.9628263 0.07199454 0.372394 -0.9252781 0.07983833 0.2249574 -0.9710922 -0.01971548 0.3076662 -0.9512901 0.009888231 0.374412 -0.9272098 -0.02017325 0.1677646 -0.9856207 -0.02014231 0.02362143 -0.999518 -0.02014267 -0.1209477 -0.9924546 -0.02011179 -0.2630409 -0.9645751 -0.02011215 -0.3996183 -0.9164609 -0.02008122 -0.5278194 -0.8491194 -0.02005094 -0.6449269 -0.7639814 -0.02005106 -0.7485139 -0.662816 -0.02002072 -0.8364146 -0.5477316 -0.02002072 -0.9067618 -0.4211677 -0.01998996 -0.9580864 -0.285781 0.08438384 0.2247083 -0.9707655 0.007355093 0.2246216 -0.9744184 -0.05951219 0.3745915 -0.9252782 5.49342e-4 0.2247725 -0.9744111 -0.05966466 0.2242538 -0.9727026 -0.1572951 0.1679768 -0.9731609 -0.1567739 0.305369 -0.93924 -0.1574179 0.02545297 -0.9872041 -0.1575406 -0.1175298 -0.9804936 -0.1576906 -0.2580974 -0.953163 -0.1578462 -0.3932421 -0.9057844 -0.1580263 -0.5201013 -0.8393584 -0.158214 -0.6360303 -0.7552707 -0.1584247 -0.7385627 -0.6553066 -0.1586363 -0.8255622 -0.5415549 -0.158883 -0.8951894 -0.4164041 -0.1591269 -0.9459722 -0.282516 -0.1395336 0.3636969 -0.9210076 -0.09439492 0.2603566 -0.9608872 -0.08502548 0.2253512 -0.9705604 -0.1679775 0.2241021 -0.9599802 -0.3132169 0.6422731 -0.6995574 -0.2722933 0.8006436 -0.5336912 -0.2730842 0.7930673 -0.5444899 -0.170205 0.2237355 -0.9596733 -0.2889524 0.2245271 -0.9306417 -0.2439414 0.3259165 -0.9133843 -0.3075123 0.6397148 -0.7044156 -0.2958893 0.2637215 -0.9180962 -0.288983 0.3227673 -0.9012826 -0.2968578 0.1322386 -0.9457211 -0.2968323 -0.003418147 -0.9549236 -0.2968312 -0.1390156 -0.9447571 -0.2967958 -0.2718008 -0.9154434 -0.2967681 -0.3990682 -0.8675674 -0.2967372 -0.5182449 -0.8021031 -0.296706 -0.6269219 -0.7203712 -0.296646 -0.7229068 -0.6240248 -0.2965828 -0.8042039 -0.5150677 -0.2965238 -0.8692151 -0.3956499 -0.296463 -0.9166119 -0.2682023 -0.988037 0.1472564 -0.04580968 -0.9884701 0.1478936 -0.03247189 -0.9874086 0.1456972 -0.06161761 -0.9858236 0.1349243 -0.09973597 -0.9869828 0.1401125 -0.07895249 -0.9834176 0.1191466 -0.1367256 -0.9790541 0.09232038 -0.1814668 -0.9713333 0.1196351 -0.2054244 -0.9741925 0.0484029 -0.2204682 -0.9631741 0.1246694 -0.2382299 -0.9598431 0.1012305 -0.2616367 -0.9598088 0.06128323 -0.2738823 -0.9597992 0.01986801 -0.2799834 -0.9597816 -0.02197343 -0.2798867 -0.9597705 -0.063358 -0.2735443 -0.9597594 -0.1033371 -0.26112 -0.9597397 -0.1410601 -0.2429029 -0.9597302 -0.1756367 -0.2192483 -0.9597222 -0.2063065 -0.1907114 -0.9597103 -0.2324045 -0.1579374 -0.9596914 -0.2533663 -0.1216475 -0.9596849 -0.2686629 -0.0826162 -0.9109094 -0.3951028 -0.1189032 -0.9109618 -0.3734305 -0.1752096 -0.9110198 -0.3437954 -0.2277015 -0.9110619 -0.306841 -0.275345 -0.9110973 -0.2633829 -0.3170666 -0.9111307 -0.2143083 -0.3520125 -0.9111582 -0.1606544 -0.3794484 -0.9111816 -0.1036127 -0.398764 -0.9111853 -0.04437512 -0.4096 -0.9111925 0.0157786 -0.4116786 -0.911187 0.07562702 -0.4049924 -0.9131574 0.1262568 -0.3875601 -0.9279105 0.1372761 -0.3466084 -0.9507015 0.1444165 -0.274428 -0.9340667 0.0197153 -0.3565543 -0.8853381 0.432094 -0.1716718 -0.8821075 0.4327372 -0.1860778 -0.888113 0.4292851 -0.1642246 -0.87047 0.4374629 -0.2256287 -0.8750577 0.4348431 -0.2125689 -0.8936467 0.427367 -0.1369417 -0.8965208 0.428118 -0.1138657 -0.8988724 0.4258298 -0.1034284 -0.8994109 0.4304476 -0.07599365 -0.9019337 0.4269635 -0.0649448 -0.9045493 0.4235106 -0.04928797 -0.9045365 0.4248312 -0.03650128 -0.9036616 0.4275988 -0.02356046 -0.8616725 0.4378251 -0.256573 -0.8438217 -0.5154365 -0.1492993 -0.8437999 -0.4893478 -0.2203194 -0.8437869 -0.453511 -0.2869693 -0.8437808 -0.40866 -0.3478951 -0.8437669 -0.3556718 -0.4019391 -0.8437679 -0.2956102 -0.4479627 -0.8437835 -0.2296538 -0.4850656 -0.8437875 -0.1591562 -0.512535 -0.8437952 -0.08548426 -0.5298135 -0.843823 -0.01013231 -0.536526 -0.8438463 0.06540185 -0.5325845 -0.8452658 0.1350484 -0.5169989 -0.903237 0.163276 -0.3968676 -0.8728262 0.1061467 -0.4763478 -0.8622495 0.1566533 -0.4816488 -0.8505312 0.4453012 -0.2798278 -0.8458124 0.4458262 -0.2929854 -0.8274343 0.4533004 -0.3314681 -0.8351204 0.4494525 -0.3171223 -0.8148558 0.4542744 -0.3600625 -0.7606928 -0.6243023 -0.1777442 -0.7609446 -0.5933311 -0.2625294 -0.7611168 -0.5509926 -0.3422111 -0.761223 -0.4980514 -0.4153124 -0.7612754 -0.4355115 -0.4804055 -0.7612715 -0.3645521 -0.5362533 -0.7612072 -0.2865743 -0.5817549 -0.7610833 -0.203043 -0.6160568 -0.7609024 -0.1155758 -0.6384902 -0.7606663 -0.02581942 -0.6486295 -0.7603549 0.064426 -0.6463047 -0.7623115 0.1479576 -0.6300714 -0.8312793 0.1782926 -0.5264851 -0.7876552 0.1296736 -0.6023156 -0.7714049 0.1805214 -0.6102021 -0.7998116 0.4638583 -0.3809687 -0.7919584 0.4653965 -0.3952315 -0.7691805 0.4737527 -0.4288586 -0.7772315 0.469934 -0.4184177 -0.7484857 0.4783289 -0.4593154 -0.6618767 -0.7164761 -0.2204119 -0.6619758 -0.6755571 -0.3246703 -0.662058 -0.6196055 -0.4216259 -0.6620809 -0.5499233 -0.5091498 -0.662113 -0.4680112 -0.5852963 -0.6621276 -0.3757296 -0.6483937 -0.6621169 -0.2750707 -0.6970921 -0.6621145 -0.1682829 -0.7302639 -0.6620711 -0.05768018 -0.7472181 -0.6620136 0.05423188 -0.7475273 -0.6599567 0.1628223 -0.733448 -0.7164142 0.1974915 -0.6691396 -0.7347214 0.4877288 -0.4714925 -0.7189815 0.4899927 -0.4929226 -0.6973406 0.5008254 -0.512728 -0.6849406 0.5011239 -0.5288963 -0.6584447 0.2085965 -0.7231447 -0.6578359 0.5143968 -0.5501345 -0.6430817 0.5171877 -0.564768 -0.549308 -0.8035906 -0.2291352 -0.5489859 -0.7642099 -0.338523 -0.5487734 -0.709917 -0.4414359 -0.5486407 -0.6417848 -0.5358226 -0.5486108 -0.5611236 -0.6198118 -0.5486382 -0.4695637 -0.6917413 -0.5487356 -0.3688553 -0.7502235 -0.54892 -0.2610009 -0.7940815 -0.5491598 -0.1481089 -0.8224884 -0.5495043 -0.03241175 -0.8348621 -0.549923 0.0837748 -0.8310034 -0.5493782 0.1962087 -0.8122105 -0.624764 0.195996 -0.7558146 -0.6138373 0.5312212 -0.5839588 -0.6040645 0.5302388 -0.5949394 -0.5449797 0.2444885 -0.8020116 -0.5720184 0.5432389 -0.6145619 -0.5535879 0.5494373 -0.6258268 -0.4274573 -0.8686178 -0.2505658 -0.4275149 -0.8249377 -0.3697417 -0.4275783 -0.7649716 -0.4816589 -0.4276657 -0.6899478 -0.5840156 -0.4277207 -0.6013115 -0.6748923 -0.4277616 -0.5008253 -0.7524588 -0.4278208 -0.390465 -0.8151728 -0.4278561 -0.2724191 -0.8618162 -0.427906 -0.1489934 -0.8914581 -0.4279412 -0.02264529 -0.9035229 -0.4279671 0.1041306 -0.8977757 -0.4269016 0.2270929 -0.8753193 -0.5056465 0.2377466 -0.829336 -0.5219169 0.5648887 -0.639143 -0.5122376 0.5631439 -0.6484456 -0.4210076 0.2816585 -0.8622188 -0.4786395 0.5737388 -0.6646262 -0.4557475 0.5855163 -0.6704215 -0.3782854 0.2805324 -0.8821574 -0.4240266 0.6006688 -0.6777895 -0.4155239 0.597329 -0.6859578 -0.3798742 0.5972024 -0.7064312 -0.35198 0.6258609 -0.6959944 -0.3332077 0.2256583 -0.9154514 -0.3697451 0.2245938 -0.9015799 -0.25108 0.223857 -0.9417255 -0.4117946 0.2255669 -0.8829184 -0.4337698 0.2247436 -0.8725447 -0.4872105 0.2253547 -0.8437069 -0.4952363 0.2249576 -0.8391277 -0.5536866 0.2248989 -0.8017804 -0.5587363 0.2254111 -0.798125 -0.609255 0.2246824 -0.7604777 -0.6261743 0.2256022 -0.7463307 -0.6615305 0.2246201 -0.7154881 -0.688878 0.2255975 -0.688878 -0.7102469 0.2247141 -0.667123 -0.7464123 0.225355 -0.626166 -0.7552307 0.2249883 -0.6156353 -0.7961069 0.2249913 -0.5617765 -0.7980155 0.2253231 -0.5589283 -0.8331773 0.2247442 -0.5052778 -0.8437038 0.2255675 -0.4871172 -0.8660964 0.2246497 -0.4465528 -0.8829702 0.225595 -0.4116682 -0.8947383 0.2247451 -0.3859183 -0.9155508 0.2253856 -0.333119 -0.9189767 0.2249602 -0.3238438 -0.9388101 0.2249286 -0.2608501 -0.9410409 0.2253871 -0.2522749 -0.9544033 0.2247145 -0.1965145 -0.9594166 0.2255942 -0.1691957 -0.9655418 0.2246837 -0.1313249 -0.9706032 0.2252929 -0.08469086 -0.9721447 0.2250453 -0.06549322 -0.973729 0.2252583 -0.03332638 -0.9733996 0.2251988 0.04217708 -0.9738439 0.224806 0.03302198 -0.9721834 0.2248336 0.0656464 -0.9734908 0.2247409 -0.04251277 -0.9705404 0.2255062 0.08484327 -0.9655418 0.2246837 0.1313249 -0.9594125 0.2256309 0.1691698 -0.9545879 0.224196 0.1962096 -0.947617 0.22578 0.2259326 -0.9390591 0.2238238 0.260904 -0.9265846 0.2266029 0.3001534 -0.9190943 0.2239519 0.3242085 -0.9048498 0.2257851 0.3609266 -0.8947783 0.2241294 0.3861838 -0.890787 0.2235208 0.3956476 -0.8660654 0.2244665 0.4467052 -0.8623631 0.2224193 0.4548181 -0.8331773 0.2247442 0.5052778 -0.8834356 0.2225756 0.4123127 -0.8759683 0.2241041 0.4271498 -0.8694856 0.2248027 0.4398394 -0.8162754 0.22499 0.532047 -0.7961372 0.2249608 0.5617458 -0.8573141 0.2214776 0.4647154 -0.8525212 0.2227286 0.4728633 -0.8440361 0.22459 0.4869932 -0.850403 0.2246866 0.4757422 -0.8430871 0.2247113 0.4885785 -0.8366037 0.224899 0.4995145 -0.8320098 0.2249557 0.5071042 -0.8312656 0.2249563 0.5083229 -0.7974382 0.2263004 0.5593573 -0.7552269 0.2249261 0.6156628 -0.7463885 0.2254181 0.6261717 -0.710262 0.2247092 0.6671085 -0.688878 0.2255975 0.688878 -0.6615305 0.2246201 0.7154881 -0.6261743 0.2256022 0.7463307 -0.6092883 0.2246834 0.7604506 -0.5587133 0.2253226 0.7981662 -0.553679 0.2249569 0.8017694 -0.4952619 0.2250469 0.8390886 -0.4872638 0.2252901 0.8436934 -0.4337698 0.2247436 0.8725447 -0.4117946 0.2255669 0.8829184 -0.3697451 0.2245938 0.9015799 -0.3332077 0.2256583 0.9154514 0 1 -1.50389e-5 0 1 1.50389e-5 0 1 1.64769e-5 -0.9457005 0.2253543 0.2342354 -0.9409672 0.2271236 0.2509897 0 1 1.63326e-5 -0.950261 0.2257163 0.2146075 0 1 -1.11163e-5 -0.9321379 0.2251682 0.2835813 -0.9148411 0.2270011 0.3339707 0 1 -5.50934e-6 -0.9247225 0.2242528 0.3075694 -0.9667802 0.2143042 0.1393191 -0.9367473 0.2253211 0.2678339 -0.8890648 0.225692 0.39828 -0.8828865 0.22636 0.4114277 0 1 1.08258e-5 -0.9104314 0.2254486 0.3468252 0 1 -1.11336e-5 -0.8470622 0.2278873 0.4801596 -0.8436836 0.2269436 0.4865128 0 1 1.10405e-5 -0.8498927 0.2349046 0.4717015 -0.861643 0.2296249 0.4525967 -0.873503 0.225998 0.4311817 0 1 -1.07513e-5 -0.8143165 0.2287423 0.5334472 -0.8331739 0.2257199 0.5048484 -0.8396565 0.2250518 0.4942961 0 1 5.60048e-6 0 1 1.91327e-5 0 1 -2.11716e-5 0 1 -1.88474e-5 0 1 1.24108e-5 0 1 -4.78916e-5 0 1 6.22409e-5 0 1 -2.75705e-5 0 1 -9.9749e-5 0 1 -1.08383e-5 0 1 -1.99051e-5 0 1 1.14587e-4 0 1 -9.84151e-5 0 1 1.96088e-4 0 1 -3.3063e-5 0 1 3.25469e-5 0 1 2.91069e-5 0.8358281 0.2301754 0.4984083 0.8431195 0.2266345 0.4876335 0.829701 0.2315813 0.5079042 0.8232536 0.2283746 0.5197103 0.873227 0.2281035 0.4306316 0.8827561 0.2271513 0.4112712 0 1 9.83907e-6 0.8641453 0.2292587 0.4479883 0.8557884 0.2262997 0.4652039 0.848232 0.2251127 0.4794024 0.9110857 0.225017 0.3453842 0.9148631 0.2273653 0.3336624 0.8898761 0.2253531 0.3966568 0.9321758 0.2252005 0.283431 0 1 -4.98559e-6 0.9367473 0.2253211 0.2678339 0 1 1.51451e-5 0.2249661 0.9743666 8.18651e-6 0.2249865 0.974362 0 0.03082406 0.9995246 7.93491e-4 0.1246695 0.9921984 0 -0.06729519 0.9976783 0.01046812 -0.2086014 0.9780002 0.001129209 -0.1644086 0.9863909 0.001709043 -0.3695232 0.9292098 0.004669368 -0.5038691 0.86378 2.74671e-4 -0.5300627 0.8479539 0.002807736 -0.6537585 0.7567008 0.001922726 -0.7891567 0.614192 -1.83113e-4 -0.8144693 0.5802029 0.002075314 -0.8982068 0.4395662 0.002441525 -0.9647405 0.2631971 0.001800596 -0.8584105 0.2249867 0.4609909 -0.8537144 0.2249878 0.4696299 -0.9742033 0.2256589 0.002441525 -0.9973093 0.07330733 -3.96751e-4 -0.8549686 0.2249885 0.4673425 -0.9863 -0.1649225 0.003601193 -0.9916917 -0.1286385 -1.22077e-4 -0.8600385 0.2249284 0.457975 -0.941726 -0.3363808 1.22076e-4 -0.867367 0.2249904 0.4439076 -0.8670814 0.2249571 0.4444819 -0.8480687 -0.529875 0.003479182 -0.8449133 -0.5349032 -5.49339e-4 -0.8773659 0.224957 0.4238201 -0.8758403 0.2249571 0.4269638 -0.7136971 -0.7004517 0.001953244 -0.8863022 0.2248945 0.4048345 -0.5799345 -0.8146612 0.001831173 -0.5332349 -0.8459672 -3.96752e-4 -0.8921847 0.2254114 0.3914028 -0.9020193 0.2244977 0.3687304 -0.36382 -0.9314477 0.006347954 -0.2255848 -0.9742236 1.32027e-4 -0.9142122 0.2257834 0.3365082 -0.224932 -0.9743745 0 -0.4107885 -0.9117307 0 0.2249127 0.974379 -1.27119e-5 0.2249128 0.974379 0 0.03131282 0.9995084 0.001617491 0.1351976 0.9908186 0 -0.05215615 0.9985666 0.01202428 -0.2009966 0.9795913 0.001159667 -0.1645272 0.9863699 0.002319395 -0.3723309 0.9280806 0.006012201 -0.5090007 0.860766 4.88309e-4 -0.5301197 0.8479169 0.003173947 -0.6616594 0.7497992 0.002838253 -0.7958464 0.6054988 6.10382e-5 -0.8146322 0.579975 0.001892149 -0.9048362 0.4257442 0.003662288 -0.9699384 0.2433314 0.003082454 -0.9740896 0.2261492 0.002472043 -0.998993 0.04486358 -3.66233e-4 -0.9862865 -0.1649864 0.004303157 -0.9869661 -0.1609286 -3.05194e-4 -0.9337363 -0.3579602 0.001068115 -0.8483331 -0.5294414 0.004791438 -0.8466978 -0.532074 -4.27271e-4 -0.7450327 -0.6670259 0.001648008 -0.5794008 -0.815037 0.003051877 -0.6163149 -0.7874999 -2.44158e-4 -0.4645962 -0.8855192 0.00250256 -0.3450445 -0.9385113 0.01187175 -0.2253741 -0.9742724 0 -0.2249479 -0.9743709 0 0.2249512 -0.9743701 0 0.2249327 -0.9743744 0 0.4101155 -0.9120324 0.001525938 0.3136172 -0.9495496 0 0.4883074 -0.8725749 0.01300114 0.6134012 -0.7897704 0.001281797 0.5802925 -0.8144055 0.00213629 0.7475928 -0.6641234 0.006744682 0.8408728 -0.5412325 5.49351e-4 0.8482005 -0.5296675 0.002899348 0.9294065 -0.3690403 0.003570735 0.983883 -0.1788129 2.74674e-4 0.9864323 -0.1641612 0.001556456 0.9994747 0.03210622 0.004455804 0.9746868 0.223552 0.003234982 0.9746677 0.2236462 0.002319455 0.9110446 0.4123078 -3.96743e-4 0.8140954 0.5807163 0.004150569 0.807319 0.5901153 -2.44152e-4 0.6719381 0.740606 0.001434385 0.5304186 0.8477236 0.004577815 0.5179743 0.8553962 -3.66232e-4 0.3705322 0.9288179 0.001861631 0.1635222 0.9865351 0.002990841 0.2045367 0.978859 -2.74669e-4 0.02798551 0.9996052 0.002502501 -0.1022069 0.9946938 0.01174962 -0.224696 0.974429 1.23244e-4 -0.2249389 0.9743729 0 -0.03048866 0.9995352 0 0 1 -1.64769e-5 0 1 -1.63326e-5 0 1 1.11163e-5 0 1 5.50934e-6 0 1 -1.08258e-5 0 1 1.11336e-5 0 1 -1.10405e-5 0 1 1.07513e-5 0 1 -5.60048e-6 0 1 -1.91327e-5 0 1 2.11716e-5 0 1 1.88474e-5 0 1 -1.24108e-5 0 1 4.78916e-5 0 1 -6.22409e-5 0 1 2.75705e-5 0 1 9.9749e-5 0 1 1.08383e-5 0 1 1.99051e-5 0 1 -1.14587e-4 0 1 9.84151e-5 0 1 -1.96088e-4 0 1 3.3063e-5 0 1 -3.25469e-5 0 1 -2.91069e-5 0 1 -9.83907e-6 0 1 4.98559e-6 0 1 -1.51451e-5 -0.09225815 0 -0.9957351 -0.1837523 0 -0.9829726 0.1837578 0 -0.9829716 0.1837523 0 -0.9829726 0.09225815 0 -0.9957351 -0.1837578 0 -0.9829716 -0.3612501 0 -0.932469 -0.5264335 0 -0.8502163 -0.5264198 0 -0.8502249 -0.6736975 0 -0.7390073 -0.6736809 0 -0.7390224 -0.798018 0 -0.6026336 -0.8951646 0 -0.4457358 -0.9618263 0 -0.2736608 -0.9618343 0 -0.2736327 -0.9957351 0 -0.09225815 -0.9957351 0 0.09225815 -0.9618241 0 0.2736689 -0.9618343 0 0.2736327 -0.8951646 0 0.4457358 -0.798018 0 0.6026336 -0.6736975 0 0.7390073 -0.6736809 0 0.7390224 -0.5264335 0 0.8502163 -0.5264198 0 0.8502249 -0.3612501 0 0.932469 -0.1837523 0 0.9829726 -0.1837578 0 0.9829716 -0.09225815 0 0.9957351 0.09225815 0 0.9957351 0.1837523 0 0.9829726 0.1837578 0 0.9829716 0.3612501 0 0.932469 0.5264335 0 0.8502163 0.5264198 0 0.8502249 0.6736975 0 0.7390073 0.6736809 0 0.7390224 0.798018 0 0.6026336 0.8951646 0 0.4457358 0.9618263 0 0.2736608 0.9618343 0 0.2736327 0.9957351 0 0.09225815 0.9957351 0 -0.09225815 0.9618241 0 -0.2736689 0.9618343 0 -0.2736327 0.8951646 0 -0.4457358 0.798018 0 -0.6026336 0.6736975 0 -0.7390073 0.6736809 0 -0.7390224 0.5264335 0 -0.8502163 0.5264198 0 -0.8502249 0.3612501 0 -0.932469 0 0 -1 -0.9969457 0.07809907 0 -1 0 0 4.85135e-6 0 -1 -0.8660256 0.4999998 0 -0.8660262 0.4999986 0 -0.9969457 -0.07809907 0 -1.94345e-6 0 -1 -0.8660256 -0.4999998 0 4.89553e-6 0 -1 -0.56649 -0.8240687 0 -0.5003696 -0.8658119 0 -0.8660262 -0.4999986 0 3.07576e-6 0 -1 -0.4311996 -0.9022567 0 -8.84392e-6 0 -1 5.52745e-6 0 -1 0.4311996 -0.9022567 0 0.5003696 -0.8658119 0 -8.20203e-6 0 -1 -5.44965e-6 0 -1 0.56649 -0.8240687 0 0.8660256 -0.4999998 0 1.94347e-6 0 -1 0.9969457 -0.07809907 0 0.8660262 -0.4999986 0 0.9969457 0.07809907 0 0.8660256 0.4999998 0 0.5664343 0.8241069 0 0.5003696 0.8658119 0 0.8660262 0.4999986 0 0.4312363 0.902239 0 -0.4312363 0.902239 0 -0.5003696 0.8658119 0 -0.5664343 0.8241069 0 -2.37982e-4 0 1 0.9748669 0.2227883 -6.10379e-5 0.9748455 0.222882 0 0.9009045 0.4340175 6.1039e-5 0.9009518 -0.4339193 6.1038e-5 0.9008629 -0.4341037 6.10382e-5 0.9748603 -0.2228173 -6.10375e-5 0.9748883 -0.2226947 0 0.9009933 0.4338331 6.10388e-5 0.6234101 0.7818949 4.27265e-4 3.52232e-6 0 1 0.6235108 0.7818148 3.96752e-4 0.2227593 0.9748736 -3.05192e-5 -1.58801e-5 0 1 0.2223043 0.9749773 -1.22078e-4 -0.2226657 0.9748949 -1.22075e-4 -3.52232e-6 0 1 -0.2222397 0.9749922 -6.10381e-5 -0.6235108 0.7818148 3.96752e-4 -0.6235964 0.7817463 4.27267e-4 -0.9008629 0.4341037 6.10382e-5 -8.77316e-6 0 1 7.93985e-6 0 1 -0.9009518 0.4339193 6.1038e-5 -0.9748603 0.2228173 -6.10375e-5 2.78297e-6 0 1 2.38095e-4 0 1 -0.9748669 -0.2227883 -6.10379e-5 -0.9748455 -0.222882 0 -0.9009045 -0.4340175 6.1039e-5 2.27269e-6 0 1 -0.9748883 0.2226947 0 -1.00567e-5 0 1 -0.9009933 -0.4338331 6.10388e-5 -0.6234101 -0.7818949 3.96746e-4 -0.6235108 -0.7818148 3.96752e-4 -0.2227303 -0.9748802 -3.05194e-5 -0.2222977 -0.9749789 -9.15559e-5 0.2226657 -0.9748949 -1.22075e-4 0.2222107 -0.9749988 -3.05193e-5 0.6235108 -0.7818148 3.96752e-4 7.74162e-6 0 1 0.6235964 -0.7817463 4.27267e-4 -7.94018e-6 0 1 -2.78297e-6 0 1 -9.70233e-6 0 1 9.70271e-6 0 1 9.41354e-6 0 1 -1.00299e-5 0 1 1.55891e-6 0 1 -2.33779e-6 0 1 0.965775 0.2593813 3.0519e-5 0.9657903 0.2593244 0 0.8658328 0.5003336 1.83116e-4 0.8660789 -0.4999074 1.83116e-4 0.8659218 -0.5001795 9.15577e-5 0.9657827 -0.2593529 3.05193e-5 0.9657675 -0.2594098 0 0.8660107 0.5000254 6.10383e-5 0.5004154 0.8657855 -9.15562e-5 0.5001205 0.8659559 0 -2.1363e-4 1 1.83111e-4 -2.13636e-4 1 1.83117e-4 -0.5001205 0.8659559 0 -0.4998123 0.8661338 -9.15575e-5 -0.8659218 0.5001795 6.10384e-5 -0.8660789 0.4999074 1.83116e-4 -0.9657827 0.2593529 3.05193e-5 -0.965775 -0.2593813 3.0519e-5 -0.9657924 -0.2593168 0 -0.8658328 -0.5003336 1.83116e-4 -0.9657675 0.2594098 0 -0.8660107 -0.5000254 9.15574e-5 -0.5004154 -0.8657855 -9.15562e-5 -0.5001205 -0.8659559 3.05193e-5 2.13636e-4 -1 2.13636e-4 0.5000844 -0.8659768 0 0.4998123 -0.8661338 -9.15575e-5 + + + + + + + + + + 0.07212901 0.182382 0.114509 0.1885679 0.118756 0.197077 0.142846 0.172404 0.118756 0.197077 0.114509 0.1885679 0.07148396 0.186815 0.07212901 0.182382 0.118756 0.197077 0.11832 0.201286 0.07148396 0.186815 0.118756 0.197077 0.128935 0.205946 0.11832 0.201286 0.118756 0.197077 0.147325 0.176512 0.128935 0.205946 0.118756 0.197077 0.142846 0.172404 0.147325 0.176512 0.118756 0.197077 0.07326 0.172402 0.109813 0.178112 0.114509 0.1885679 0.1387439 0.167921 0.114509 0.1885679 0.109813 0.178112 0.07272195 0.177565 0.07326 0.172402 0.114509 0.1885679 0.07212901 0.182382 0.07272195 0.177565 0.114509 0.1885679 0.1387439 0.167921 0.142846 0.172404 0.114509 0.1885679 0.07374095 0.16693 0.105684 0.167026 0.109813 0.178112 0.127555 0.162633 0.109813 0.178112 0.105684 0.167026 0.07326 0.172402 0.07374095 0.16693 0.109813 0.178112 0.135048 0.163097 0.1387439 0.167921 0.109813 0.178112 0.127555 0.162633 0.135048 0.163097 0.109813 0.178112 0.09831696 0.1566269 0.102492 0.15593 0.105684 0.167026 0.123008 0.156397 0.105684 0.167026 0.102492 0.15593 0.09464997 0.165527 0.105684 0.167026 0.07374095 0.16693 0.09837996 0.158498 0.09831696 0.1566269 0.105684 0.167026 0.09828799 0.160245 0.09837996 0.158498 0.105684 0.167026 0.098064 0.16166 0.09828799 0.160245 0.105684 0.167026 0.097741 0.1628029 0.098064 0.16166 0.105684 0.167026 0.09727096 0.163833 0.097741 0.1628029 0.105684 0.167026 0.096565 0.164756 0.09727096 0.163833 0.105684 0.167026 0.09565097 0.165359 0.096565 0.164756 0.105684 0.167026 0.09464997 0.165527 0.09565097 0.165359 0.105684 0.167026 0.12718 0.162553 0.127555 0.162633 0.105684 0.167026 0.126598 0.162079 0.12718 0.162553 0.105684 0.167026 0.125896 0.161274 0.126598 0.162079 0.105684 0.167026 0.125214 0.160335 0.125896 0.161274 0.105684 0.167026 0.124548 0.159288 0.125214 0.160335 0.105684 0.167026 0.123812 0.157992 0.124548 0.159288 0.105684 0.167026 0.123008 0.156397 0.123812 0.157992 0.105684 0.167026 0.09767895 0.145699 0.100255 0.144929 0.102492 0.15593 0.118752 0.144461 0.102492 0.15593 0.100255 0.144929 0.09796595 0.151203 0.09767895 0.145699 0.102492 0.15593 0.09831696 0.1566269 0.09796595 0.151203 0.102492 0.15593 0.122236 0.154658 0.123008 0.156397 0.102492 0.15593 0.120324 0.149612 0.122236 0.154658 0.102492 0.15593 0.118752 0.144461 0.120324 0.149612 0.102492 0.15593 0.075217 0.1362529 0.098935 0.134012 0.100255 0.144929 0.123534 0.135246 0.100255 0.144929 0.098935 0.134012 0.075051 0.142702 0.075217 0.1362529 0.100255 0.144929 0.09767895 0.145699 0.075051 0.142702 0.100255 0.144929 0.123534 0.135246 0.124845 0.141176 0.100255 0.144929 0.118752 0.144461 0.100255 0.144929 0.124845 0.141176 0.07535099 0.123156 0.098499 0.123156 0.098935 0.134012 0.122743 0.129225 0.098935 0.134012 0.098499 0.123156 0.07531696 0.129725 0.07535099 0.123156 0.098935 0.134012 0.075217 0.1362529 0.07531696 0.129725 0.098935 0.134012 0.122743 0.129225 0.123534 0.135246 0.098935 0.134012 0.07531696 0.116587 0.098499 0.123156 0.07535099 0.123156 0.07531696 0.116587 0.098935 0.1123 0.098499 0.123156 0.122478 0.123156 0.098499 0.123156 0.098935 0.1123 0.122478 0.123156 0.122743 0.129225 0.098499 0.123156 0.07444995 0.123156 0.07535099 0.123156 0.07531696 0.129725 0.07431399 0.110612 0.07531696 0.116587 0.07535099 0.123156 0.07431399 0.110612 0.07535099 0.123156 0.07444995 0.123156 0.07431399 0.1357 0.07531696 0.129725 0.075217 0.1362529 0.07431399 0.1357 0.07444995 0.123156 0.07531696 0.129725 0.07431399 0.1357 0.075217 0.1362529 0.075051 0.142702 0.08878797 0.145734 0.07481896 0.149033 0.075051 0.142702 0.07390695 0.147896 0.075051 0.142702 0.07481896 0.149033 0.09320598 0.145717 0.075051 0.142702 0.09767895 0.145699 0.09320598 0.145717 0.08878797 0.145734 0.075051 0.142702 0.07390695 0.147896 0.07431399 0.1357 0.075051 0.142702 0.08937799 0.156171 0.07452297 0.155207 0.07481896 0.149033 0.07390695 0.147896 0.07481896 0.149033 0.07452297 0.155207 0.089055 0.150991 0.08937799 0.156171 0.07481896 0.149033 0.08878797 0.145734 0.089055 0.150991 0.07481896 0.149033 0.09098595 0.162519 0.07416296 0.161186 0.07452297 0.155207 0.07323896 0.159403 0.07452297 0.155207 0.07416296 0.161186 0.090433 0.1613 0.09098595 0.162519 0.07452297 0.155207 0.08995795 0.1598269 0.090433 0.1613 0.07452297 0.155207 0.08958899 0.1580629 0.08995795 0.1598269 0.07452297 0.155207 0.08937799 0.156171 0.08958899 0.1580629 0.07452297 0.155207 0.07323896 0.159403 0.07390695 0.147896 0.07452297 0.155207 0.09464997 0.165527 0.07374095 0.16693 0.07416296 0.161186 0.07323896 0.159403 0.07416296 0.161186 0.07374095 0.16693 0.09363698 0.165285 0.09464997 0.165527 0.07416296 0.161186 0.092615 0.164635 0.09363698 0.165285 0.07416296 0.161186 0.09169095 0.163639 0.092615 0.164635 0.07416296 0.161186 0.09098595 0.162519 0.09169095 0.163639 0.07416296 0.161186 0.07232296 0.169884 0.07374095 0.16693 0.07326 0.172402 0.07232296 0.169884 0.07323896 0.159403 0.07374095 0.16693 0.07232296 0.169884 0.07326 0.172402 0.07272195 0.177565 0.07118099 0.179015 0.07272195 0.177565 0.07212901 0.182382 0.07118099 0.179015 0.07232296 0.169884 0.07272195 0.177565 0.069839 0.186487 0.07212901 0.182382 0.07148396 0.186815 0.069839 0.186487 0.07118099 0.179015 0.07212901 0.182382 0.11832 0.201286 0.070791 0.19083 0.07148396 0.186815 0.06833398 0.1920199 0.07148396 0.186815 0.070791 0.19083 0.06833398 0.1920199 0.069839 0.186487 0.07148396 0.186815 0.117859 0.205093 0.07005298 0.194394 0.070791 0.19083 0.066706 0.195369 0.070791 0.19083 0.07005298 0.194394 0.11832 0.201286 0.117859 0.205093 0.070791 0.19083 0.066706 0.195369 0.06833398 0.1920199 0.070791 0.19083 0.06137496 0.19941 0.07005298 0.194394 0.06927496 0.197474 0.117373 0.208469 0.06927496 0.197474 0.07005298 0.194394 0.06500595 0.196339 0.07005298 0.194394 0.06137496 0.19941 0.117859 0.205093 0.117373 0.208469 0.07005298 0.194394 0.06500595 0.196339 0.066706 0.195369 0.07005298 0.194394 0.06225496 0.201681 0.06927496 0.197474 0.06846195 0.200042 0.116865 0.21139 0.06846195 0.200042 0.06927496 0.197474 0.06137496 0.19941 0.06927496 0.197474 0.06225496 0.201681 0.117373 0.208469 0.116865 0.21139 0.06927496 0.197474 0.063151 0.203312 0.06846195 0.200042 0.06761795 0.202069 0.116339 0.213829 0.06761795 0.202069 0.06846195 0.200042 0.06225496 0.201681 0.06846195 0.200042 0.063151 0.203312 0.116865 0.21139 0.116339 0.213829 0.06846195 0.200042 0.06405597 0.204304 0.06761795 0.202069 0.06674998 0.203529 0.115795 0.215764 0.06674998 0.203529 0.06761795 0.202069 0.063151 0.203312 0.06761795 0.202069 0.06405597 0.204304 0.116339 0.213829 0.115795 0.215764 0.06761795 0.202069 0.06496196 0.204664 0.06674998 0.203529 0.06586199 0.2044 0.115238 0.217173 0.06586199 0.2044 0.06674998 0.203529 0.06405597 0.204304 0.06674998 0.203529 0.06496196 0.204664 0.115795 0.215764 0.115238 0.217173 0.06674998 0.203529 0.114669 0.2180359 0.06496196 0.204664 0.06586199 0.2044 0.115238 0.217173 0.114669 0.2180359 0.06586199 0.2044 0.113512 0.21806 0.06405597 0.204304 0.06496196 0.204664 0.114093 0.218336 0.113512 0.21806 0.06496196 0.204664 0.114669 0.2180359 0.114093 0.218336 0.06496196 0.204664 0.112931 0.217195 0.063151 0.203312 0.06405597 0.204304 0.113512 0.21806 0.112931 0.217195 0.06405597 0.204304 0.112352 0.215735 0.06225496 0.201681 0.063151 0.203312 0.112931 0.217195 0.112352 0.215735 0.063151 0.203312 0.111781 0.213674 0.06137496 0.19941 0.06225496 0.201681 0.112352 0.215735 0.111781 0.213674 0.06225496 0.201681 0.11122 0.211014 0.0605179 0.196506 0.06137496 0.19941 0.06500595 0.196339 0.06137496 0.19941 0.0605179 0.196506 0.111781 0.213674 0.11122 0.211014 0.06137496 0.19941 0.110674 0.207759 0.05969399 0.19298 0.0605179 0.196506 0.06328999 0.194801 0.0605179 0.196506 0.05969399 0.19298 0.11122 0.211014 0.110674 0.207759 0.0605179 0.196506 0.06328999 0.194801 0.06500595 0.196339 0.0605179 0.196506 0.110148 0.20392 0.05890893 0.18885 0.05969399 0.19298 0.06161898 0.190708 0.05969399 0.19298 0.05890893 0.18885 0.110674 0.207759 0.110148 0.20392 0.05969399 0.19298 0.06161898 0.190708 0.06328999 0.194801 0.05969399 0.19298 0.109644 0.199511 0.05817097 0.184141 0.05890893 0.18885 0.06005698 0.18411 0.05890893 0.18885 0.05817097 0.184141 0.110148 0.20392 0.109644 0.199511 0.05890893 0.18885 0.06005698 0.18411 0.06161898 0.190708 0.05890893 0.18885 0.108723 0.1890709 0.05748796 0.1788859 0.05817097 0.184141 0.06005698 0.18411 0.05817097 0.184141 0.05748796 0.1788859 0.109168 0.194552 0.108723 0.1890709 0.05817097 0.184141 0.109644 0.199511 0.109168 0.194552 0.05817097 0.184141 0.108314 0.183098 0.05686599 0.173123 0.05748796 0.1788859 0.05866897 0.17517 0.05748796 0.1788859 0.05686599 0.173123 0.108723 0.1890709 0.108314 0.183098 0.05748796 0.1788859 0.05866897 0.17517 0.06005698 0.18411 0.05748796 0.1788859 0.07542598 0.170339 0.05631196 0.166899 0.05686599 0.173123 0.05866897 0.17517 0.05686599 0.173123 0.05631196 0.166899 0.108314 0.183098 0.1079429 0.176672 0.05686599 0.173123 0.07888495 0.172581 0.05686599 0.173123 0.1079429 0.176672 0.07653498 0.171461 0.07542598 0.170339 0.05686599 0.173123 0.07773798 0.172244 0.07653498 0.171461 0.05686599 0.173123 0.07888495 0.172581 0.07773798 0.172244 0.05686599 0.173123 0.072488 0.164187 0.05583298 0.160266 0.05631196 0.166899 0.05751496 0.164164 0.05631196 0.166899 0.05583298 0.160266 0.07310301 0.166151 0.072488 0.164187 0.05631196 0.166899 0.073798 0.167776 0.07310301 0.166151 0.05631196 0.166899 0.07454198 0.1691139 0.073798 0.167776 0.05631196 0.166899 0.07542598 0.170339 0.07454198 0.1691139 0.05631196 0.166899 0.05751496 0.164164 0.05866897 0.17517 0.05631196 0.166899 0.071114 0.156 0.05543392 0.153282 0.05583298 0.160266 0.05751496 0.164164 0.05583298 0.160266 0.05543392 0.153282 0.07204198 0.1620939 0.071114 0.156 0.05583298 0.160266 0.072488 0.164187 0.07204198 0.1620939 0.05583298 0.160266 0.07034498 0.149733 0.05511796 0.146009 0.05543392 0.153282 0.05664891 0.151485 0.05543392 0.153282 0.05511796 0.146009 0.071114 0.156 0.07034498 0.149733 0.05543392 0.153282 0.05664891 0.151485 0.05751496 0.164164 0.05543392 0.153282 0.106908 0.147358 0.05488991 0.138516 0.05511796 0.146009 0.05664891 0.151485 0.05511796 0.146009 0.05488991 0.138516 0.08020299 0.1498399 0.106908 0.147358 0.05511796 0.146009 0.07522898 0.1497859 0.05511796 0.146009 0.07034498 0.149733 0.07522898 0.1497859 0.08020299 0.1498399 0.05511796 0.146009 0.106774 0.1394 0.05475199 0.130874 0.05488991 0.138516 0.05611199 0.137626 0.05488991 0.138516 0.05475199 0.130874 0.106908 0.147358 0.106774 0.1394 0.05488991 0.138516 0.05611199 0.137626 0.05664891 0.151485 0.05488991 0.138516 0.106666 0.123156 0.05470591 0.123156 0.05475199 0.130874 0.05611199 0.137626 0.05475199 0.130874 0.05470591 0.123156 0.106693 0.1313109 0.106666 0.123156 0.05475199 0.130874 0.106774 0.1394 0.106693 0.1313109 0.05475199 0.130874 0.106693 0.115001 0.05470591 0.123156 0.106666 0.123156 0.05475199 0.115438 0.05470591 0.123156 0.106693 0.115001 0.05592989 0.123156 0.05470591 0.123156 0.05475199 0.115438 0.05592989 0.123156 0.05611199 0.137626 0.05470591 0.123156 0.121217 0.123156 0.106666 0.123156 0.106693 0.1313109 0.121299 0.106701 0.106693 0.115001 0.106666 0.123156 0.121299 0.106701 0.106666 0.123156 0.121217 0.123156 0.121299 0.139611 0.106693 0.1313109 0.106774 0.1394 0.121217 0.123156 0.106693 0.1313109 0.121299 0.139611 0.121299 0.139611 0.106774 0.1394 0.106908 0.147358 0.08020299 0.1498399 0.107094 0.1551229 0.106908 0.147358 0.121544 0.155619 0.106908 0.147358 0.107094 0.1551229 0.121299 0.139611 0.106908 0.147358 0.121544 0.155619 0.08097195 0.156435 0.10733 0.162634 0.107094 0.1551229 0.121544 0.155619 0.107094 0.1551229 0.10733 0.162634 0.08020299 0.1498399 0.08097195 0.156435 0.107094 0.1551229 0.08217698 0.16497 0.107614 0.169835 0.10733 0.162634 0.121942 0.170754 0.10733 0.162634 0.107614 0.169835 0.08190596 0.162845 0.08217698 0.16497 0.10733 0.162634 0.08097195 0.156435 0.08190596 0.162845 0.10733 0.162634 0.121544 0.155619 0.10733 0.162634 0.121942 0.170754 0.08087199 0.171891 0.1079429 0.176672 0.107614 0.169835 0.121942 0.170754 0.107614 0.169835 0.1079429 0.176672 0.08155596 0.170908 0.08087199 0.171891 0.107614 0.169835 0.081963 0.169766 0.08155596 0.170908 0.107614 0.169835 0.08218699 0.168494 0.081963 0.169766 0.107614 0.169835 0.08226895 0.1669149 0.08218699 0.168494 0.107614 0.169835 0.08217698 0.16497 0.08226895 0.1669149 0.107614 0.169835 0.122481 0.184634 0.1079429 0.176672 0.108314 0.183098 0.07994395 0.172474 0.07888495 0.172581 0.1079429 0.176672 0.08087199 0.171891 0.07994395 0.172474 0.1079429 0.176672 0.121942 0.170754 0.1079429 0.176672 0.122481 0.184634 0.122481 0.184634 0.108314 0.183098 0.108723 0.1890709 0.123145 0.196931 0.108723 0.1890709 0.109168 0.194552 0.122481 0.184634 0.108723 0.1890709 0.123145 0.196931 0.123912 0.2073889 0.109168 0.194552 0.109644 0.199511 0.123145 0.196931 0.109168 0.194552 0.123912 0.2073889 0.123912 0.2073889 0.109644 0.199511 0.110148 0.20392 0.124761 0.21582 0.110148 0.20392 0.110674 0.207759 0.123912 0.2073889 0.110148 0.20392 0.124761 0.21582 0.124761 0.21582 0.110674 0.207759 0.11122 0.211014 0.12567 0.222108 0.11122 0.211014 0.111781 0.213674 0.124761 0.21582 0.11122 0.211014 0.12567 0.222108 0.12567 0.222108 0.111781 0.213674 0.112352 0.215735 0.126614 0.226203 0.112352 0.215735 0.112931 0.217195 0.12567 0.222108 0.112352 0.215735 0.126614 0.226203 0.126614 0.226203 0.112931 0.217195 0.113512 0.21806 0.127573 0.228112 0.113512 0.21806 0.114093 0.218336 0.126614 0.226203 0.113512 0.21806 0.127573 0.228112 0.128526 0.227891 0.114093 0.218336 0.114669 0.2180359 0.127573 0.228112 0.114093 0.218336 0.128526 0.227891 0.128526 0.227891 0.114669 0.2180359 0.115238 0.217173 0.129453 0.225636 0.115238 0.217173 0.115795 0.215764 0.128526 0.227891 0.115238 0.217173 0.129453 0.225636 0.129453 0.225636 0.115795 0.215764 0.116339 0.213829 0.130338 0.221476 0.116339 0.213829 0.116865 0.21139 0.129453 0.225636 0.116339 0.213829 0.130338 0.221476 0.130338 0.221476 0.116865 0.21139 0.117373 0.208469 0.1311669 0.215561 0.117373 0.208469 0.117859 0.205093 0.130338 0.221476 0.117373 0.208469 0.1311669 0.215561 0.1311669 0.215561 0.117859 0.205093 0.11832 0.201286 0.1311669 0.215561 0.11832 0.201286 0.131869 0.208103 0.128935 0.205946 0.131869 0.208103 0.11832 0.201286 0.09831696 0.145784 0.09767895 0.145699 0.09796595 0.151203 0.09831696 0.145784 0.09320598 0.145717 0.09767895 0.145699 0.09831696 0.145784 0.09796595 0.151203 0.09831696 0.1566269 0.09831696 0.145784 0.09831696 0.1566269 0.09837996 0.158498 0.09831696 0.145784 0.09837996 0.158498 0.09828799 0.160245 0.098266 0.145824 0.09828799 0.160245 0.098064 0.16166 0.09831696 0.145784 0.09828799 0.160245 0.098266 0.145824 0.098266 0.145824 0.098064 0.16166 0.097741 0.1628029 0.09754198 0.14586 0.097741 0.1628029 0.09727096 0.163833 0.098266 0.145824 0.097741 0.1628029 0.09754198 0.14586 0.09754198 0.14586 0.09727096 0.163833 0.096565 0.164756 0.09625101 0.145888 0.096565 0.164756 0.09565097 0.165359 0.09754198 0.14586 0.096565 0.164756 0.09625101 0.145888 0.09625101 0.145888 0.09565097 0.165359 0.09464997 0.165527 0.09459096 0.145902 0.09464997 0.165527 0.09363698 0.165285 0.09625101 0.145888 0.09464997 0.165527 0.09459096 0.145902 0.092817 0.145901 0.09363698 0.165285 0.092615 0.164635 0.09459096 0.145902 0.09363698 0.165285 0.092817 0.145901 0.092817 0.145901 0.092615 0.164635 0.09169095 0.163639 0.09120297 0.145884 0.09169095 0.163639 0.09098595 0.162519 0.092817 0.145901 0.09169095 0.163639 0.09120297 0.145884 0.09120297 0.145884 0.09098595 0.162519 0.090433 0.1613 0.08999496 0.145855 0.090433 0.1613 0.08995795 0.1598269 0.09120297 0.145884 0.090433 0.1613 0.08999496 0.145855 0.08999496 0.145855 0.08995795 0.1598269 0.08958899 0.1580629 0.08999496 0.145855 0.08958899 0.1580629 0.08937799 0.156171 0.08878797 0.145734 0.08937799 0.156171 0.089055 0.150991 0.08937799 0.145817 0.08937799 0.156171 0.08878797 0.145734 0.08999496 0.145855 0.08937799 0.156171 0.08937799 0.145817 0.09831696 0.145784 0.08878797 0.145734 0.09320598 0.145717 0.098266 0.145824 0.08937799 0.145817 0.08878797 0.145734 0.09831696 0.145784 0.098266 0.145824 0.08878797 0.145734 0.07204198 0.149621 0.07034498 0.149733 0.071114 0.156 0.07522898 0.1497859 0.07034498 0.149733 0.08190596 0.149724 0.08190596 0.149724 0.08020299 0.1498399 0.07522898 0.1497859 0.07204198 0.149621 0.08190596 0.149724 0.07034498 0.149733 0.07204198 0.149621 0.071114 0.156 0.07204198 0.1620939 0.07204198 0.149621 0.07204198 0.1620939 0.072488 0.164187 0.07204198 0.149621 0.072488 0.164187 0.07310301 0.166151 0.07317 0.1495749 0.07310301 0.166151 0.073798 0.167776 0.07204198 0.149621 0.07310301 0.166151 0.07317 0.1495749 0.07317 0.1495749 0.073798 0.167776 0.07454198 0.1691139 0.07486897 0.149544 0.07454198 0.1691139 0.07542598 0.170339 0.07317 0.1495749 0.07454198 0.1691139 0.07486897 0.149544 0.07486897 0.149544 0.07542598 0.170339 0.07653498 0.171461 0.076882 0.149533 0.07653498 0.171461 0.07773798 0.172244 0.07486897 0.149544 0.07653498 0.171461 0.076882 0.149533 0.076882 0.149533 0.07773798 0.172244 0.07888495 0.172581 0.07890796 0.149543 0.07888495 0.172581 0.07994395 0.172474 0.076882 0.149533 0.07888495 0.172581 0.07890796 0.149543 0.08064198 0.149572 0.07994395 0.172474 0.08087199 0.171891 0.07890796 0.149543 0.07994395 0.172474 0.08064198 0.149572 0.08064198 0.149572 0.08087199 0.171891 0.08155596 0.170908 0.08182197 0.149617 0.08155596 0.170908 0.081963 0.169766 0.08064198 0.149572 0.08155596 0.170908 0.08182197 0.149617 0.08182197 0.149617 0.081963 0.169766 0.08218699 0.168494 0.08226799 0.14967 0.08218699 0.168494 0.08226895 0.1669149 0.08182197 0.149617 0.08218699 0.168494 0.08226799 0.14967 0.08226799 0.14967 0.08226895 0.1669149 0.08217698 0.16497 0.08226799 0.14967 0.08217698 0.16497 0.08190596 0.162845 0.08020299 0.1498399 0.08190596 0.162845 0.08097195 0.156435 0.08190596 0.149724 0.08190596 0.162845 0.08020299 0.1498399 0.08226799 0.14967 0.08190596 0.162845 0.08190596 0.149724 0.075051 0.10361 0.100255 0.101384 0.098935 0.1123 0.123534 0.111066 0.098935 0.1123 0.100255 0.101384 0.075217 0.110059 0.075051 0.10361 0.098935 0.1123 0.07531696 0.116587 0.075217 0.110059 0.098935 0.1123 0.122743 0.117087 0.122478 0.123156 0.098935 0.1123 0.123534 0.111066 0.122743 0.117087 0.098935 0.1123 0.07481896 0.09727895 0.102492 0.09038299 0.100255 0.101384 0.124845 0.105136 0.100255 0.101384 0.102492 0.09038299 0.075051 0.10361 0.07481896 0.09727895 0.100255 0.101384 0.124845 0.105136 0.123534 0.111066 0.100255 0.101384 0.07416296 0.08512598 0.105684 0.07928597 0.102492 0.09038299 0.128988 0.09373098 0.102492 0.09038299 0.105684 0.07928597 0.07452297 0.09110498 0.07416296 0.08512598 0.102492 0.09038299 0.07481896 0.09727895 0.07452297 0.09110498 0.102492 0.09038299 0.126668 0.09934395 0.124845 0.105136 0.102492 0.09038299 0.128988 0.09373098 0.126668 0.09934395 0.102492 0.09038299 0.07374095 0.079382 0.109812 0.06820195 0.105684 0.07928597 0.131788 0.08834099 0.105684 0.07928597 0.109812 0.06820195 0.07416296 0.08512598 0.07374095 0.079382 0.105684 0.07928597 0.131788 0.08834099 0.128988 0.09373098 0.105684 0.07928597 0.07272195 0.06874698 0.114507 0.05774688 0.109812 0.06820195 0.135048 0.08321499 0.109812 0.06820195 0.114507 0.05774688 0.07326 0.07390999 0.07272195 0.06874698 0.109812 0.06820195 0.07374095 0.079382 0.07326 0.07390999 0.109812 0.06820195 0.135048 0.08321499 0.131788 0.08834099 0.109812 0.06820195 0.07148396 0.05949693 0.118756 0.04923492 0.114507 0.05774688 0.142846 0.07390797 0.114507 0.05774688 0.118756 0.04923492 0.07212901 0.06392997 0.07148396 0.05949693 0.114507 0.05774688 0.07272195 0.06874698 0.07212901 0.06392997 0.114507 0.05774688 0.1387439 0.07839095 0.135048 0.08321499 0.114507 0.05774688 0.142846 0.07390797 0.1387439 0.07839095 0.114507 0.05774688 0.070791 0.05548197 0.11832 0.045026 0.118756 0.04923492 0.128937 0.04036498 0.118756 0.04923492 0.11832 0.045026 0.07148396 0.05949693 0.070791 0.05548197 0.118756 0.04923492 0.147325 0.06979995 0.118756 0.04923492 0.128937 0.04036498 0.147325 0.06979995 0.142846 0.07390797 0.118756 0.04923492 0.070791 0.05548197 0.117859 0.04121893 0.11832 0.045026 0.131869 0.03820896 0.11832 0.045026 0.117859 0.04121893 0.131869 0.03820896 0.128937 0.04036498 0.11832 0.045026 0.07005298 0.05191797 0.117373 0.03784292 0.117859 0.04121893 0.1311669 0.03075093 0.117859 0.04121893 0.117373 0.03784292 0.070791 0.05548197 0.07005298 0.05191797 0.117859 0.04121893 0.1311669 0.03075093 0.131869 0.03820896 0.117859 0.04121893 0.06927496 0.0488379 0.116865 0.034922 0.117373 0.03784292 0.1311669 0.03075093 0.117373 0.03784292 0.116865 0.034922 0.07005298 0.05191797 0.06927496 0.0488379 0.117373 0.03784292 0.06846195 0.04626995 0.116339 0.03248298 0.116865 0.034922 0.130338 0.024836 0.116865 0.034922 0.116339 0.03248298 0.06927496 0.0488379 0.06846195 0.04626995 0.116865 0.034922 0.130338 0.024836 0.1311669 0.03075093 0.116865 0.034922 0.06761795 0.04424291 0.115795 0.03054797 0.116339 0.03248298 0.130338 0.024836 0.116339 0.03248298 0.115795 0.03054797 0.06846195 0.04626995 0.06761795 0.04424291 0.116339 0.03248298 0.06674998 0.04278296 0.115238 0.02913898 0.115795 0.03054797 0.129453 0.02067589 0.115795 0.03054797 0.115238 0.02913898 0.06761795 0.04424291 0.06674998 0.04278296 0.115795 0.03054797 0.129453 0.02067589 0.130338 0.024836 0.115795 0.03054797 0.06586199 0.0419119 0.114669 0.0282759 0.115238 0.02913898 0.129453 0.02067589 0.115238 0.02913898 0.114669 0.0282759 0.06674998 0.04278296 0.06586199 0.0419119 0.115238 0.02913898 0.06496196 0.04164797 0.114093 0.02797597 0.114669 0.0282759 0.128526 0.01842099 0.114669 0.0282759 0.114093 0.02797597 0.06586199 0.0419119 0.06496196 0.04164797 0.114669 0.0282759 0.128526 0.01842099 0.129453 0.02067589 0.114669 0.0282759 0.06405597 0.04200798 0.113512 0.028252 0.114093 0.02797597 0.127573 0.01820099 0.114093 0.02797597 0.113512 0.028252 0.06496196 0.04164797 0.06405597 0.04200798 0.114093 0.02797597 0.127573 0.01820099 0.128526 0.01842099 0.114093 0.02797597 0.06405597 0.04200798 0.112931 0.02911692 0.113512 0.028252 0.127573 0.01820099 0.113512 0.028252 0.112931 0.02911692 0.063151 0.04299998 0.112352 0.030577 0.112931 0.02911692 0.126614 0.02010893 0.112931 0.02911692 0.112352 0.030577 0.06405597 0.04200798 0.063151 0.04299998 0.112931 0.02911692 0.126614 0.02010893 0.127573 0.01820099 0.112931 0.02911692 0.06225496 0.04463189 0.111781 0.03263795 0.112352 0.030577 0.126614 0.02010893 0.112352 0.030577 0.111781 0.03263795 0.063151 0.04299998 0.06225496 0.04463189 0.112352 0.030577 0.06137496 0.046902 0.11122 0.03529793 0.111781 0.03263795 0.12567 0.02420395 0.111781 0.03263795 0.11122 0.03529793 0.06225496 0.04463189 0.06137496 0.046902 0.111781 0.03263795 0.12567 0.02420395 0.126614 0.02010893 0.111781 0.03263795 0.0605179 0.04980593 0.110674 0.03855293 0.11122 0.03529793 0.12567 0.02420395 0.11122 0.03529793 0.110674 0.03855293 0.06137496 0.046902 0.0605179 0.04980593 0.11122 0.03529793 0.05969399 0.05333197 0.110148 0.04239189 0.110674 0.03855293 0.124761 0.03049188 0.110674 0.03855293 0.110148 0.04239189 0.0605179 0.04980593 0.05969399 0.05333197 0.110674 0.03855293 0.124761 0.03049188 0.12567 0.02420395 0.110674 0.03855293 0.05890893 0.05746191 0.109644 0.04680097 0.110148 0.04239189 0.124761 0.03049188 0.110148 0.04239189 0.109644 0.04680097 0.05969399 0.05333197 0.05890893 0.05746191 0.110148 0.04239189 0.05817097 0.06217098 0.109168 0.05175989 0.109644 0.04680097 0.123912 0.03892296 0.109644 0.04680097 0.109168 0.05175989 0.05890893 0.05746191 0.05817097 0.06217098 0.109644 0.04680097 0.123912 0.03892296 0.124761 0.03049188 0.109644 0.04680097 0.05748796 0.06742596 0.108723 0.05724096 0.109168 0.05175989 0.123145 0.04938089 0.109168 0.05175989 0.108723 0.05724096 0.05817097 0.06217098 0.05748796 0.06742596 0.109168 0.05175989 0.123145 0.04938089 0.123912 0.03892296 0.109168 0.05175989 0.05748796 0.06742596 0.108314 0.063214 0.108723 0.05724096 0.123145 0.04938089 0.108723 0.05724096 0.108314 0.063214 0.05686599 0.07318896 0.1079429 0.06963998 0.108314 0.063214 0.122481 0.06167799 0.108314 0.063214 0.1079429 0.06963998 0.05748796 0.06742596 0.05686599 0.07318896 0.108314 0.063214 0.122481 0.06167799 0.123145 0.04938089 0.108314 0.063214 0.05631196 0.07941299 0.107614 0.07647699 0.1079429 0.06963998 0.122481 0.06167799 0.1079429 0.06963998 0.107614 0.07647699 0.05686599 0.07318896 0.05631196 0.07941299 0.1079429 0.06963998 0.05583298 0.08604598 0.10733 0.083678 0.107614 0.07647699 0.121942 0.075558 0.107614 0.07647699 0.10733 0.083678 0.05631196 0.07941299 0.05583298 0.08604598 0.107614 0.07647699 0.121942 0.075558 0.122481 0.06167799 0.107614 0.07647699 0.05543392 0.09303098 0.107094 0.09118896 0.10733 0.083678 0.121942 0.075558 0.10733 0.083678 0.107094 0.09118896 0.05583298 0.08604598 0.05543392 0.09303098 0.10733 0.083678 0.05511796 0.100303 0.106908 0.09895396 0.107094 0.09118896 0.121544 0.09069299 0.107094 0.09118896 0.106908 0.09895396 0.05543392 0.09303098 0.05511796 0.100303 0.107094 0.09118896 0.121544 0.09069299 0.121942 0.075558 0.107094 0.09118896 0.05488991 0.107796 0.106774 0.106912 0.106908 0.09895396 0.121544 0.09069299 0.106908 0.09895396 0.106774 0.106912 0.05511796 0.100303 0.05488991 0.107796 0.106908 0.09895396 0.05475199 0.115438 0.106693 0.115001 0.106774 0.106912 0.121299 0.106701 0.106774 0.106912 0.106693 0.115001 0.05488991 0.107796 0.05475199 0.115438 0.106774 0.106912 0.121299 0.106701 0.121544 0.09069299 0.106774 0.106912 0.05611199 0.108686 0.05475199 0.115438 0.05488991 0.107796 0.05611199 0.108686 0.05592989 0.123156 0.05475199 0.115438 0.05611199 0.108686 0.05488991 0.107796 0.05511796 0.100303 0.05664891 0.09482699 0.05511796 0.100303 0.05543392 0.09303098 0.05664891 0.09482699 0.05611199 0.108686 0.05511796 0.100303 0.05664891 0.09482699 0.05543392 0.09303098 0.05583298 0.08604598 0.05751496 0.08214795 0.05583298 0.08604598 0.05631196 0.07941299 0.05751496 0.08214795 0.05664891 0.09482699 0.05583298 0.08604598 0.05751496 0.08214795 0.05631196 0.07941299 0.05686599 0.07318896 0.05866897 0.07114195 0.05686599 0.07318896 0.05748796 0.06742596 0.05866897 0.07114195 0.05751496 0.08214795 0.05686599 0.07318896 0.05866897 0.07114195 0.05748796 0.06742596 0.05817097 0.06217098 0.06005698 0.06220191 0.05817097 0.06217098 0.05890893 0.05746191 0.06005698 0.06220191 0.05866897 0.07114195 0.05817097 0.06217098 0.06161898 0.05560398 0.05890893 0.05746191 0.05969399 0.05333197 0.06161898 0.05560398 0.06005698 0.06220191 0.05890893 0.05746191 0.06328999 0.05151093 0.05969399 0.05333197 0.0605179 0.04980593 0.06328999 0.05151093 0.06161898 0.05560398 0.05969399 0.05333197 0.06500595 0.04997295 0.0605179 0.04980593 0.06137496 0.046902 0.06500595 0.04997295 0.06328999 0.05151093 0.0605179 0.04980593 0.07005298 0.05191797 0.06137496 0.046902 0.06225496 0.04463189 0.066706 0.05094289 0.06137496 0.046902 0.07005298 0.05191797 0.066706 0.05094289 0.06500595 0.04997295 0.06137496 0.046902 0.06927496 0.0488379 0.06225496 0.04463189 0.063151 0.04299998 0.07005298 0.05191797 0.06225496 0.04463189 0.06927496 0.0488379 0.06846195 0.04626995 0.063151 0.04299998 0.06405597 0.04200798 0.06927496 0.0488379 0.063151 0.04299998 0.06846195 0.04626995 0.06761795 0.04424291 0.06405597 0.04200798 0.06496196 0.04164797 0.06846195 0.04626995 0.06405597 0.04200798 0.06761795 0.04424291 0.06674998 0.04278296 0.06496196 0.04164797 0.06586199 0.0419119 0.06761795 0.04424291 0.06496196 0.04164797 0.06674998 0.04278296 0.066706 0.05094289 0.07005298 0.05191797 0.070791 0.05548197 0.06833398 0.05429196 0.070791 0.05548197 0.07148396 0.05949693 0.06833398 0.05429196 0.066706 0.05094289 0.070791 0.05548197 0.069839 0.059825 0.07148396 0.05949693 0.07212901 0.06392997 0.069839 0.059825 0.06833398 0.05429196 0.07148396 0.05949693 0.07118099 0.06729698 0.07212901 0.06392997 0.07272195 0.06874698 0.07118099 0.06729698 0.069839 0.059825 0.07212901 0.06392997 0.07118099 0.06729698 0.07272195 0.06874698 0.07326 0.07390999 0.07232296 0.07642799 0.07326 0.07390999 0.07374095 0.079382 0.07232296 0.07642799 0.07118099 0.06729698 0.07326 0.07390999 0.07232296 0.07642799 0.07374095 0.079382 0.07416296 0.08512598 0.07323896 0.08690899 0.07416296 0.08512598 0.07452297 0.09110498 0.07323896 0.08690899 0.07232296 0.07642799 0.07416296 0.08512598 0.07323896 0.08690899 0.07452297 0.09110498 0.07481896 0.09727895 0.07390695 0.09841597 0.07481896 0.09727895 0.075051 0.10361 0.07390695 0.09841597 0.07323896 0.08690899 0.07481896 0.09727895 0.07390695 0.09841597 0.075051 0.10361 0.075217 0.110059 0.07431399 0.110612 0.075217 0.110059 0.07531696 0.116587 0.07431399 0.110612 0.07390695 0.09841597 0.075217 0.110059 0.02586597 0.123156 0.07444995 0.123156 0.07431399 0.1357 0.02567398 0.1106989 0.07431399 0.110612 0.07444995 0.123156 0.02567398 0.1106989 0.07444995 0.123156 0.02586597 0.123156 0.02567398 0.135613 0.07431399 0.1357 0.07390695 0.147896 0.02567398 0.135613 0.02586597 0.123156 0.07431399 0.1357 0.02510493 0.147723 0.07390695 0.147896 0.07323896 0.159403 0.02567398 0.135613 0.07390695 0.147896 0.02510493 0.147723 0.02416998 0.159147 0.07323896 0.159403 0.07232296 0.169884 0.02510493 0.147723 0.07323896 0.159403 0.02416998 0.159147 0.02288889 0.169549 0.07232296 0.169884 0.07118099 0.179015 0.02416998 0.159147 0.07232296 0.169884 0.02288889 0.169549 0.02129089 0.178607 0.07118099 0.179015 0.069839 0.186487 0.02288889 0.169549 0.07118099 0.179015 0.02129089 0.178607 0.01941496 0.186016 0.069839 0.186487 0.06833398 0.1920199 0.02129089 0.178607 0.069839 0.186487 0.01941496 0.186016 0.01730996 0.191496 0.06833398 0.1920199 0.066706 0.195369 0.01941496 0.186016 0.06833398 0.1920199 0.01730996 0.191496 0.01503592 0.194804 0.066706 0.195369 0.06500595 0.196339 0.01730996 0.191496 0.066706 0.195369 0.01503592 0.194804 0.01266098 0.195751 0.06500595 0.196339 0.06328999 0.194801 0.01503592 0.194804 0.06500595 0.196339 0.01266098 0.195751 0.01026499 0.1942099 0.06328999 0.194801 0.06161898 0.190708 0.01266098 0.195751 0.06328999 0.194801 0.01026499 0.1942099 0.007931947 0.190137 0.06161898 0.190708 0.06005698 0.18411 0.01026499 0.1942099 0.06161898 0.190708 0.007931947 0.190137 0.005752921 0.183582 0.06005698 0.18411 0.05866897 0.17517 0.007931947 0.190137 0.06005698 0.18411 0.005752921 0.183582 0.003816962 0.174709 0.05866897 0.17517 0.05751496 0.164164 0.005752921 0.183582 0.05866897 0.17517 0.003816962 0.174709 0.002208948 0.163794 0.05751496 0.164164 0.05664891 0.151485 0.003816962 0.174709 0.05751496 0.164164 0.002208948 0.163794 0.001001954 0.151226 0.05664891 0.151485 0.05611199 0.137626 0.002208948 0.163794 0.05664891 0.151485 0.001001954 0.151226 2.54e-4 0.137493 0.05611199 0.137626 0.05592989 0.123156 0.001001954 0.151226 0.05611199 0.137626 2.54e-4 0.137493 0 0.123156 0.05592989 0.123156 0.05611199 0.108686 2.54e-4 0.137493 0.05592989 0.123156 0 0.123156 2.54e-4 0.108819 0.05611199 0.108686 0.05664891 0.09482699 0 0.123156 0.05611199 0.108686 2.54e-4 0.108819 0.001001954 0.09508597 0.05664891 0.09482699 0.05751496 0.08214795 2.54e-4 0.108819 0.05664891 0.09482699 0.001001954 0.09508597 0.002208948 0.08251798 0.05751496 0.08214795 0.05866897 0.07114195 0.001001954 0.09508597 0.05751496 0.08214795 0.002208948 0.08251798 0.003816962 0.071603 0.05866897 0.07114195 0.06005698 0.06220191 0.002208948 0.08251798 0.05866897 0.07114195 0.003816962 0.071603 0.005752921 0.06272995 0.06005698 0.06220191 0.06161898 0.05560398 0.003816962 0.071603 0.06005698 0.06220191 0.005752921 0.06272995 0.007931947 0.05617499 0.06161898 0.05560398 0.06328999 0.05151093 0.005752921 0.06272995 0.06161898 0.05560398 0.007931947 0.05617499 0.01026499 0.05210191 0.06328999 0.05151093 0.06500595 0.04997295 0.007931947 0.05617499 0.06328999 0.05151093 0.01026499 0.05210191 0.01266098 0.05056095 0.06500595 0.04997295 0.066706 0.05094289 0.01026499 0.05210191 0.06500595 0.04997295 0.01266098 0.05056095 0.01503592 0.05150789 0.066706 0.05094289 0.06833398 0.05429196 0.01266098 0.05056095 0.066706 0.05094289 0.01503592 0.05150789 0.01730996 0.05481588 0.06833398 0.05429196 0.069839 0.059825 0.01503592 0.05150789 0.06833398 0.05429196 0.01730996 0.05481588 0.01941496 0.06029593 0.069839 0.059825 0.07118099 0.06729698 0.01730996 0.05481588 0.069839 0.059825 0.01941496 0.06029593 0.02129089 0.06770497 0.07118099 0.06729698 0.07232296 0.07642799 0.01941496 0.06029593 0.07118099 0.06729698 0.02129089 0.06770497 0.02288889 0.07676297 0.07232296 0.07642799 0.07323896 0.08690899 0.02129089 0.06770497 0.07232296 0.07642799 0.02288889 0.07676297 0.02416998 0.08716499 0.07323896 0.08690899 0.07390695 0.09841597 0.02288889 0.07676297 0.07323896 0.08690899 0.02416998 0.08716499 0.02510493 0.098589 0.07390695 0.09841597 0.07431399 0.110612 0.02416998 0.08716499 0.07390695 0.09841597 0.02510493 0.098589 0.02510493 0.098589 0.07431399 0.110612 0.02567398 0.1106989 0.210831 0.225874 0.195261 0.227232 0.20943 0.22584 0.198234 0.192564 0.20943 0.22584 0.195261 0.227232 0.224556 0.2232339 0.210831 0.225874 0.20943 0.22584 0.210212 0.190452 0.224556 0.2232339 0.20943 0.22584 0.204269 0.19177 0.210212 0.190452 0.20943 0.22584 0.198234 0.192564 0.204269 0.19177 0.20943 0.22584 0.194515 0.233327 0.194487 0.227252 0.195261 0.227232 0.198234 0.192564 0.195261 0.227232 0.194487 0.227252 0.211136 0.2337909 0.194515 0.233327 0.195261 0.227232 0.210831 0.225874 0.211136 0.2337909 0.195261 0.227232 0.181048 0.226686 0.194487 0.227252 0.194515 0.233327 0.192152 0.19283 0.194487 0.227252 0.181048 0.226686 0.192152 0.19283 0.198234 0.192564 0.194487 0.227252 0.211136 0.2337909 0.194544 0.238348 0.194515 0.233327 0.177896 0.233605 0.194515 0.233327 0.194544 0.238348 0.178089 0.226327 0.181048 0.226686 0.194515 0.233327 0.177896 0.233605 0.178089 0.226327 0.194515 0.233327 0.211454 0.2397159 0.194575 0.242214 0.194544 0.238348 0.177681 0.239298 0.194544 0.238348 0.194575 0.242214 0.211136 0.2337909 0.211454 0.2397159 0.194544 0.238348 0.177681 0.239298 0.177896 0.233605 0.194544 0.238348 0.211454 0.2397159 0.199183 0.242371 0.194575 0.242214 0.194559 0.2161549 0.194575 0.242214 0.199183 0.242371 0.1921499 0.242193 0.177681 0.239298 0.194575 0.242214 0.194559 0.2161549 0.1921499 0.242193 0.194575 0.242214 0.211454 0.2397159 0.20328 0.242676 0.199183 0.242371 0.199187 0.216278 0.199183 0.242371 0.20328 0.242676 0.194559 0.2161549 0.199183 0.242371 0.199187 0.216278 0.211454 0.2397159 0.206499 0.243106 0.20328 0.242676 0.206488 0.216853 0.20328 0.242676 0.206499 0.243106 0.203271 0.216516 0.20328 0.242676 0.206488 0.216853 0.199187 0.216278 0.20328 0.242676 0.203271 0.216516 0.211791 0.243419 0.208578 0.243627 0.206499 0.243106 0.208576 0.217263 0.206499 0.243106 0.208578 0.243627 0.211454 0.2397159 0.211791 0.243419 0.206499 0.243106 0.206488 0.216853 0.206499 0.243106 0.208576 0.217263 0.211791 0.243419 0.209352 0.244203 0.208578 0.243627 0.208576 0.217263 0.208578 0.243627 0.209352 0.244203 0.21214 0.2447119 0.208738 0.244788 0.209352 0.244203 0.209352 0.217715 0.209352 0.244203 0.208738 0.244788 0.211791 0.243419 0.21214 0.2447119 0.209352 0.244203 0.208576 0.217263 0.209352 0.244203 0.209352 0.217715 0.21214 0.2447119 0.206768 0.245332 0.208738 0.244788 0.208736 0.218174 0.208738 0.244788 0.206768 0.245332 0.208736 0.218174 0.209352 0.217715 0.208738 0.244788 0.21214 0.2447119 0.203572 0.245791 0.206768 0.245332 0.206758 0.218601 0.206768 0.245332 0.203572 0.245791 0.208736 0.218174 0.206768 0.245332 0.206758 0.218601 0.21214 0.2447119 0.199406 0.246124 0.203572 0.245791 0.203564 0.218961 0.203572 0.245791 0.199406 0.246124 0.206758 0.218601 0.203572 0.245791 0.203564 0.218961 0.2124969 0.243437 0.1946589 0.246297 0.199406 0.246124 0.199411 0.2192209 0.199406 0.246124 0.1946589 0.246297 0.21214 0.2447119 0.2124969 0.243437 0.199406 0.246124 0.203564 0.218961 0.199406 0.246124 0.199411 0.2192209 0.2124969 0.243437 0.194702 0.244719 0.1946589 0.246297 0.1921499 0.2463189 0.1946589 0.246297 0.194702 0.244719 0.194642 0.219357 0.1946589 0.246297 0.1921499 0.2463189 0.199411 0.2192209 0.1946589 0.246297 0.194642 0.219357 0.212851 0.239485 0.194747 0.2404879 0.194702 0.244719 0.176695 0.242359 0.194702 0.244719 0.194747 0.2404879 0.2124969 0.243437 0.212851 0.239485 0.194702 0.244719 0.176949 0.24498 0.194702 0.244719 0.176695 0.242359 0.1921499 0.2463189 0.194702 0.244719 0.176949 0.24498 0.213196 0.232801 0.19479 0.233557 0.194747 0.2404879 0.176446 0.237322 0.194747 0.2404879 0.19479 0.233557 0.212851 0.239485 0.213196 0.232801 0.194747 0.2404879 0.176695 0.242359 0.194747 0.2404879 0.176446 0.237322 0.21352 0.223407 0.19483 0.223951 0.19479 0.233557 0.1762059 0.229853 0.19479 0.233557 0.19483 0.223951 0.213196 0.232801 0.21352 0.223407 0.19479 0.233557 0.176446 0.237322 0.19479 0.233557 0.1762059 0.229853 0.213816 0.21141 0.194867 0.211782 0.19483 0.223951 0.1759819 0.220001 0.19483 0.223951 0.194867 0.211782 0.21352 0.223407 0.213816 0.21141 0.19483 0.223951 0.1762059 0.229853 0.19483 0.223951 0.1759819 0.220001 0.214074 0.197018 0.194899 0.197257 0.194867 0.211782 0.175779 0.207885 0.194867 0.211782 0.194899 0.197257 0.213816 0.21141 0.214074 0.197018 0.194867 0.211782 0.1759819 0.220001 0.194867 0.211782 0.175779 0.207885 0.214284 0.180542 0.194925 0.180684 0.194899 0.197257 0.175604 0.193708 0.194899 0.197257 0.194925 0.180684 0.214074 0.197018 0.214284 0.180542 0.194899 0.197257 0.175779 0.207885 0.194899 0.197257 0.175604 0.193708 0.21444 0.162395 0.194944 0.16247 0.194925 0.180684 0.175462 0.177752 0.194925 0.180684 0.194944 0.16247 0.214284 0.180542 0.21444 0.162395 0.194925 0.180684 0.175604 0.193708 0.194925 0.180684 0.175462 0.177752 0.214536 0.143077 0.194956 0.143109 0.194944 0.16247 0.175357 0.16038 0.194944 0.16247 0.194956 0.143109 0.21444 0.162395 0.214536 0.143077 0.194944 0.16247 0.175462 0.177752 0.194944 0.16247 0.175357 0.16038 0.195157 0.123156 0.1949599 0.123156 0.194956 0.143109 0.175292 0.142021 0.194956 0.143109 0.1949599 0.123156 0.214569 0.123156 0.195157 0.123156 0.194956 0.143109 0.214536 0.143077 0.214569 0.123156 0.194956 0.143109 0.175357 0.16038 0.194956 0.143109 0.175292 0.142021 0.214536 0.103235 0.1949599 0.123156 0.195157 0.123156 0.175485 0.123156 0.175292 0.142021 0.1949599 0.123156 0.194956 0.102957 0.175485 0.123156 0.1949599 0.123156 0.214536 0.103235 0.194956 0.102957 0.1949599 0.123156 0.214536 0.103235 0.195157 0.123156 0.214569 0.123156 0.233534 0.123156 0.214569 0.123156 0.214536 0.143077 0.233479 0.104324 0.214569 0.123156 0.233534 0.123156 0.233479 0.104324 0.214536 0.103235 0.214569 0.123156 0.225939 0.150951 0.214536 0.143077 0.21444 0.162395 0.2335039 0.137134 0.233534 0.123156 0.214536 0.143077 0.225939 0.150951 0.2335039 0.137134 0.214536 0.143077 0.226438 0.164565 0.21444 0.162395 0.214284 0.180542 0.226438 0.164565 0.225939 0.150951 0.21444 0.162395 0.227455 0.179929 0.214284 0.180542 0.214074 0.197018 0.227126 0.1774629 0.226438 0.164565 0.214284 0.180542 0.227243 0.1787 0.227126 0.1774629 0.214284 0.180542 0.227455 0.179929 0.227243 0.1787 0.214284 0.180542 0.232563 0.19745 0.214074 0.197018 0.213816 0.21141 0.232938 0.182749 0.214074 0.197018 0.232563 0.19745 0.232002 0.183408 0.214074 0.197018 0.232938 0.182749 0.227822 0.181206 0.227455 0.179929 0.214074 0.197018 0.2283779 0.1823599 0.227822 0.181206 0.214074 0.197018 0.229028 0.183149 0.2283779 0.1823599 0.214074 0.197018 0.229857 0.183658 0.229028 0.183149 0.214074 0.197018 0.230897 0.183773 0.229857 0.183658 0.214074 0.197018 0.232002 0.183408 0.230897 0.183773 0.214074 0.197018 0.232112 0.210315 0.213816 0.21141 0.21352 0.223407 0.232563 0.19745 0.213816 0.21141 0.232112 0.210315 0.2316009 0.22106 0.21352 0.223407 0.213196 0.232801 0.232112 0.210315 0.21352 0.223407 0.2316009 0.22106 0.231045 0.22952 0.213196 0.232801 0.212851 0.239485 0.2316009 0.22106 0.213196 0.232801 0.231045 0.22952 0.230457 0.235608 0.212851 0.239485 0.2124969 0.243437 0.231045 0.22952 0.212851 0.239485 0.230457 0.235608 0.2292439 0.240647 0.2124969 0.243437 0.21214 0.2447119 0.229852 0.239304 0.2124969 0.243437 0.2292439 0.240647 0.230457 0.235608 0.2124969 0.243437 0.229852 0.239304 0.228645 0.239724 0.21214 0.2447119 0.211791 0.243419 0.2292439 0.240647 0.21214 0.2447119 0.228645 0.239724 0.228065 0.236658 0.211791 0.243419 0.211454 0.2397159 0.228645 0.239724 0.211791 0.243419 0.228065 0.236658 0.227515 0.2316 0.211454 0.2397159 0.211136 0.2337909 0.228065 0.236658 0.211454 0.2397159 0.227515 0.2316 0.224189 0.225153 0.211136 0.2337909 0.210831 0.225874 0.227515 0.2316 0.211136 0.2337909 0.2269909 0.224757 0.224189 0.225153 0.2269909 0.224757 0.211136 0.2337909 0.224556 0.2232339 0.224189 0.225153 0.210831 0.225874 0.186071 0.192564 0.181048 0.226686 0.178089 0.226327 0.186071 0.192564 0.192152 0.19283 0.181048 0.226686 0.167047 0.2242169 0.178089 0.226327 0.177896 0.233605 0.180036 0.19177 0.178089 0.226327 0.167047 0.2242169 0.180036 0.19177 0.186071 0.192564 0.178089 0.226327 0.161529 0.230719 0.177896 0.233605 0.177681 0.239298 0.1619679 0.222822 0.167047 0.2242169 0.177896 0.233605 0.161529 0.230719 0.1619679 0.222822 0.177896 0.233605 0.177805 0.243106 0.177368 0.243189 0.177681 0.239298 0.161031 0.236717 0.177681 0.239298 0.177368 0.243189 0.181011 0.242677 0.177805 0.243106 0.177681 0.239298 0.185091 0.242372 0.181011 0.242677 0.177681 0.239298 0.189725 0.242214 0.185091 0.242372 0.177681 0.239298 0.1921499 0.242193 0.189725 0.242214 0.177681 0.239298 0.161031 0.236717 0.161529 0.230719 0.177681 0.239298 0.175728 0.217263 0.177368 0.243189 0.177805 0.243106 0.160501 0.240553 0.161031 0.236717 0.177368 0.243189 0.175727 0.243628 0.160501 0.240553 0.177368 0.243189 0.175728 0.217263 0.175727 0.243628 0.177368 0.243189 0.177816 0.216853 0.177805 0.243106 0.181011 0.242677 0.175728 0.217263 0.177805 0.243106 0.177816 0.216853 0.181033 0.216516 0.181011 0.242677 0.185091 0.242372 0.177816 0.216853 0.181011 0.242677 0.181033 0.216516 0.185117 0.216278 0.185091 0.242372 0.189725 0.242214 0.181033 0.216516 0.185091 0.242372 0.185117 0.216278 0.189745 0.2161549 0.189725 0.242214 0.1921499 0.242193 0.185117 0.216278 0.189725 0.242214 0.189745 0.2161549 0.189745 0.2161549 0.1921499 0.242193 0.194559 0.2161549 0.174093 0.190452 0.167047 0.2242169 0.1619679 0.222822 0.174093 0.190452 0.180036 0.19177 0.167047 0.2242169 0.145829 0.224667 0.1619679 0.222822 0.161529 0.230719 0.145829 0.224667 0.153497 0.219861 0.1619679 0.222822 0.168288 0.1886219 0.1619679 0.222822 0.153497 0.219861 0.168288 0.1886219 0.174093 0.190452 0.1619679 0.222822 0.145102 0.230727 0.161529 0.230719 0.161031 0.236717 0.145102 0.230727 0.145829 0.224667 0.161529 0.230719 0.1443279 0.234654 0.161031 0.236717 0.160501 0.240553 0.1443279 0.234654 0.145102 0.230727 0.161031 0.236717 0.177112 0.245244 0.15995 0.242041 0.160501 0.240553 0.143521 0.236264 0.160501 0.240553 0.15995 0.242041 0.175567 0.244788 0.177112 0.245244 0.160501 0.240553 0.174952 0.244203 0.175567 0.244788 0.160501 0.240553 0.175727 0.243628 0.174952 0.244203 0.160501 0.240553 0.143521 0.236264 0.1443279 0.234654 0.160501 0.240553 0.176949 0.24498 0.159388 0.241028 0.15995 0.242041 0.142698 0.235404 0.15995 0.242041 0.159388 0.241028 0.177112 0.245244 0.176949 0.24498 0.15995 0.242041 0.142698 0.235404 0.143521 0.236264 0.15995 0.242041 0.176695 0.242359 0.158828 0.237402 0.159388 0.241028 0.1418769 0.231967 0.159388 0.241028 0.158828 0.237402 0.176949 0.24498 0.176695 0.242359 0.159388 0.241028 0.1418769 0.231967 0.142698 0.235404 0.159388 0.241028 0.176446 0.237322 0.1582829 0.23111 0.158828 0.237402 0.1410779 0.225903 0.158828 0.237402 0.1582829 0.23111 0.176695 0.242359 0.176446 0.237322 0.158828 0.237402 0.1410779 0.225903 0.1418769 0.231967 0.158828 0.237402 0.1762059 0.229853 0.1577669 0.222168 0.1582829 0.23111 0.140325 0.217235 0.1582829 0.23111 0.1577669 0.222168 0.176446 0.237322 0.1762059 0.229853 0.1582829 0.23111 0.140325 0.217235 0.1410779 0.225903 0.1582829 0.23111 0.1759819 0.220001 0.157296 0.210675 0.1577669 0.222168 0.140325 0.217235 0.1577669 0.222168 0.157296 0.210675 0.1762059 0.229853 0.1759819 0.220001 0.1577669 0.222168 0.175779 0.207885 0.156884 0.1968269 0.157296 0.210675 0.139638 0.2060689 0.157296 0.210675 0.156884 0.1968269 0.1759819 0.220001 0.175779 0.207885 0.157296 0.210675 0.139638 0.2060689 0.140325 0.217235 0.157296 0.210675 0.175604 0.193708 0.156566 0.180966 0.156884 0.1968269 0.156269 0.1817229 0.156884 0.1968269 0.156566 0.180966 0.175779 0.207885 0.175604 0.193708 0.156884 0.1968269 0.139039 0.192606 0.139638 0.2060689 0.156884 0.1968269 0.15477 0.183512 0.139039 0.192606 0.156884 0.1968269 0.1556 0.18281 0.15477 0.183512 0.156884 0.1968269 0.156269 0.1817229 0.1556 0.18281 0.156884 0.1968269 0.175462 0.177752 0.156779 0.18023 0.156566 0.180966 0.155822 0.150615 0.156566 0.180966 0.156779 0.18023 0.175604 0.193708 0.175462 0.177752 0.156566 0.180966 0.155822 0.150615 0.156269 0.1817229 0.156566 0.180966 0.175462 0.177752 0.157103 0.178346 0.156779 0.18023 0.156912 0.1506659 0.156779 0.18023 0.157103 0.178346 0.155822 0.150615 0.156779 0.18023 0.156912 0.1506659 0.175462 0.177752 0.157223 0.176035 0.157103 0.178346 0.156912 0.1506659 0.157103 0.178346 0.157223 0.176035 0.175357 0.16038 0.157102 0.17321 0.157223 0.176035 0.1572149 0.150725 0.157223 0.176035 0.157102 0.17321 0.175462 0.177752 0.175357 0.16038 0.157223 0.176035 0.156912 0.1506659 0.157223 0.176035 0.1572149 0.150725 0.175357 0.16038 0.156678 0.1697739 0.157102 0.17321 0.1572149 0.150725 0.157102 0.17321 0.156678 0.1697739 0.175357 0.16038 0.156313 0.167421 0.156678 0.1697739 0.154339 0.1509169 0.156678 0.1697739 0.156313 0.167421 0.156678 0.150782 0.156678 0.1697739 0.154339 0.1509169 0.1572149 0.150725 0.156678 0.1697739 0.156678 0.150782 0.175357 0.16038 0.156189 0.153118 0.156313 0.167421 0.155362 0.160479 0.156313 0.167421 0.156189 0.153118 0.154339 0.1509169 0.156313 0.167421 0.155362 0.160479 0.175292 0.142021 0.1560969 0.138274 0.156189 0.153118 0.154339 0.1509169 0.156189 0.153118 0.1560969 0.138274 0.175357 0.16038 0.175292 0.142021 0.156189 0.153118 0.154339 0.1509169 0.155362 0.160479 0.156189 0.153118 0.156292 0.123156 0.156066 0.123156 0.1560969 0.138274 0.1379629 0.14191 0.1560969 0.138274 0.156066 0.123156 0.17527 0.123156 0.156292 0.123156 0.1560969 0.138274 0.175292 0.142021 0.17527 0.123156 0.1560969 0.138274 0.154339 0.1509169 0.1560969 0.138274 0.1379629 0.14191 0.1752949 0.103084 0.156066 0.123156 0.156292 0.123156 0.138115 0.123156 0.1379629 0.14191 0.156066 0.123156 0.156118 0.103573 0.138115 0.123156 0.156066 0.123156 0.1752949 0.103084 0.156118 0.103573 0.156066 0.123156 0.1752949 0.103084 0.156292 0.123156 0.17527 0.123156 0.175485 0.123156 0.17527 0.123156 0.175292 0.142021 0.194956 0.102957 0.17527 0.123156 0.175485 0.123156 0.194956 0.102957 0.1752949 0.103084 0.17527 0.123156 0.177537 0.245332 0.176949 0.24498 0.177112 0.245244 0.1896409 0.246297 0.1921499 0.2463189 0.176949 0.24498 0.184867 0.246122 0.1896409 0.246297 0.176949 0.24498 0.180718 0.24579 0.184867 0.246122 0.176949 0.24498 0.177537 0.245332 0.180718 0.24579 0.176949 0.24498 0.175568 0.218174 0.177112 0.245244 0.175567 0.244788 0.177547 0.218601 0.177537 0.245332 0.177112 0.245244 0.177547 0.218601 0.177112 0.245244 0.175568 0.218174 0.175568 0.218174 0.175567 0.244788 0.174952 0.244203 0.174952 0.217715 0.174952 0.244203 0.175727 0.243628 0.175568 0.218174 0.174952 0.244203 0.174952 0.217715 0.174952 0.217715 0.175727 0.243628 0.175728 0.217263 0.145829 0.224667 0.146466 0.2167519 0.153497 0.219861 0.162666 0.1862919 0.153497 0.219861 0.146466 0.2167519 0.162666 0.1862919 0.168288 0.1886219 0.153497 0.219861 0.1311669 0.215561 0.146466 0.2167519 0.145829 0.224667 0.1311669 0.215561 0.140705 0.21372 0.146466 0.2167519 0.162666 0.1862919 0.146466 0.2167519 0.140705 0.21372 0.130338 0.221476 0.145829 0.224667 0.145102 0.230727 0.130338 0.221476 0.1311669 0.215561 0.145829 0.224667 0.129453 0.225636 0.145102 0.230727 0.1443279 0.234654 0.129453 0.225636 0.130338 0.221476 0.145102 0.230727 0.128526 0.227891 0.1443279 0.234654 0.143521 0.236264 0.128526 0.227891 0.129453 0.225636 0.1443279 0.234654 0.127573 0.228112 0.143521 0.236264 0.142698 0.235404 0.127573 0.228112 0.128526 0.227891 0.143521 0.236264 0.126614 0.226203 0.142698 0.235404 0.1418769 0.231967 0.126614 0.226203 0.127573 0.228112 0.142698 0.235404 0.12567 0.222108 0.1418769 0.231967 0.1410779 0.225903 0.12567 0.222108 0.126614 0.226203 0.1418769 0.231967 0.124761 0.21582 0.1410779 0.225903 0.140325 0.217235 0.124761 0.21582 0.12567 0.222108 0.1410779 0.225903 0.123912 0.2073889 0.140325 0.217235 0.139638 0.2060689 0.123912 0.2073889 0.124761 0.21582 0.140325 0.217235 0.123145 0.196931 0.139638 0.2060689 0.139039 0.192606 0.123145 0.196931 0.123912 0.2073889 0.139638 0.2060689 0.1493189 0.180097 0.13855 0.177147 0.139039 0.192606 0.122481 0.184634 0.139039 0.192606 0.13855 0.177147 0.150387 0.181706 0.1493189 0.180097 0.139039 0.192606 0.151521 0.182879 0.150387 0.181706 0.139039 0.192606 0.15266 0.183576 0.151521 0.182879 0.139039 0.192606 0.153795 0.183788 0.15266 0.183576 0.139039 0.192606 0.15477 0.183512 0.153795 0.183788 0.139039 0.192606 0.122481 0.184634 0.123145 0.196931 0.139039 0.192606 0.145159 0.161751 0.138187 0.160088 0.13855 0.177147 0.121942 0.170754 0.13855 0.177147 0.138187 0.160088 0.1467649 0.172333 0.145159 0.161751 0.13855 0.177147 0.147489 0.175544 0.1467649 0.172333 0.13855 0.177147 0.148349 0.178068 0.147489 0.175544 0.13855 0.177147 0.1493189 0.180097 0.148349 0.178068 0.13855 0.177147 0.121942 0.170754 0.122481 0.184634 0.13855 0.177147 0.143944 0.150806 0.1379629 0.14191 0.138187 0.160088 0.121544 0.155619 0.138187 0.160088 0.1379629 0.14191 0.145159 0.161751 0.143944 0.150806 0.138187 0.160088 0.121544 0.155619 0.121942 0.170754 0.138187 0.160088 0.138115 0.123156 0.137887 0.123156 0.1379629 0.14191 0.121299 0.139611 0.1379629 0.14191 0.137887 0.123156 0.149088 0.150865 0.154339 0.1509169 0.1379629 0.14191 0.143944 0.150806 0.149088 0.150865 0.1379629 0.14191 0.121299 0.139611 0.121544 0.155619 0.1379629 0.14191 0.156118 0.103573 0.137887 0.123156 0.138115 0.123156 0.121438 0.123156 0.121299 0.139611 0.137887 0.123156 0.1379629 0.104402 0.121438 0.123156 0.137887 0.123156 0.156118 0.103573 0.1379629 0.104402 0.137887 0.123156 0.143944 0.150806 0.154339 0.1509169 0.149088 0.150865 0.156678 0.150782 0.154339 0.1509169 0.143944 0.150806 0.1467649 0.150649 0.143944 0.150806 0.145159 0.161751 0.1467649 0.150649 0.156678 0.150782 0.143944 0.150806 0.1467649 0.150649 0.145159 0.161751 0.1467649 0.172333 0.1467649 0.150649 0.1467649 0.172333 0.147489 0.175544 0.14807 0.1506029 0.147489 0.175544 0.148349 0.178068 0.1467649 0.150649 0.147489 0.175544 0.14807 0.1506029 0.14807 0.1506029 0.148349 0.178068 0.1493189 0.180097 0.149922 0.150573 0.1493189 0.180097 0.150387 0.181706 0.14807 0.1506029 0.1493189 0.180097 0.149922 0.150573 0.149922 0.150573 0.150387 0.181706 0.151521 0.182879 0.152042 0.150565 0.151521 0.182879 0.15266 0.183576 0.149922 0.150573 0.151521 0.182879 0.152042 0.150565 0.152042 0.150565 0.15266 0.183576 0.153795 0.183788 0.154112 0.15058 0.153795 0.183788 0.15477 0.183512 0.152042 0.150565 0.153795 0.183788 0.154112 0.15058 0.154112 0.15058 0.15477 0.183512 0.1556 0.18281 0.155822 0.150615 0.1556 0.18281 0.156269 0.1817229 0.154112 0.15058 0.1556 0.18281 0.155822 0.150615 0.1311669 0.215561 0.131869 0.208103 0.140705 0.21372 0.157272 0.183483 0.140705 0.21372 0.131869 0.208103 0.157272 0.183483 0.162666 0.1862919 0.140705 0.21372 0.152145 0.180214 0.131869 0.208103 0.128935 0.205946 0.152145 0.180214 0.157272 0.183483 0.131869 0.208103 0.121438 0.123156 0.121217 0.123156 0.121299 0.139611 0.1379629 0.104402 0.121217 0.123156 0.121438 0.123156 0.1379629 0.104402 0.121299 0.106701 0.121217 0.123156 0.147325 0.176512 0.152145 0.180214 0.128935 0.205946 0.311178 0.123156 0.312805 0.123156 0.31441 0.123156 0.311198 0.12076 0.31441 0.123156 0.312805 0.123156 0.311198 0.125553 0.311178 0.123156 0.31441 0.123156 0.311259 0.127903 0.311198 0.125553 0.31441 0.123156 0.311358 0.130161 0.311259 0.127903 0.31441 0.123156 0.311496 0.132283 0.311358 0.130161 0.31441 0.123156 0.311668 0.134226 0.311496 0.132283 0.31441 0.123156 0.311872 0.135953 0.311668 0.134226 0.31441 0.123156 0.312103 0.137428 0.311872 0.135953 0.31441 0.123156 0.312358 0.138621 0.312103 0.137428 0.31441 0.123156 0.312631 0.139505 0.312358 0.138621 0.31441 0.123156 0.312917 0.140062 0.312631 0.139505 0.31441 0.123156 0.313211 0.140277 0.312917 0.140062 0.31441 0.123156 0.313506 0.140144 0.313211 0.140277 0.31441 0.123156 0.313796 0.139663 0.313506 0.140144 0.31441 0.123156 0.314076 0.138841 0.313796 0.139663 0.31441 0.123156 0.314339 0.137693 0.314076 0.138841 0.31441 0.123156 0.31458 0.136241 0.314339 0.137693 0.31441 0.123156 0.314794 0.134514 0.31458 0.136241 0.31441 0.123156 0.314976 0.132547 0.314794 0.134514 0.31441 0.123156 0.315121 0.130381 0.314976 0.132547 0.31441 0.123156 0.315228 0.12806 0.315121 0.130381 0.31441 0.123156 0.315293 0.125635 0.315228 0.12806 0.31441 0.123156 0.315314 0.123156 0.315293 0.125635 0.31441 0.123156 0.315293 0.120678 0.315314 0.123156 0.31441 0.123156 0.311259 0.118409 0.31441 0.123156 0.311198 0.12076 0.311358 0.116151 0.31441 0.123156 0.311259 0.118409 0.311496 0.11403 0.31441 0.123156 0.311358 0.116151 0.311668 0.1120859 0.31441 0.123156 0.311496 0.11403 0.311872 0.110359 0.31441 0.123156 0.311668 0.1120859 0.312103 0.108884 0.31441 0.123156 0.311872 0.110359 0.312358 0.107691 0.31441 0.123156 0.312103 0.108884 0.312631 0.106807 0.31441 0.123156 0.312358 0.107691 0.312917 0.10625 0.31441 0.123156 0.312631 0.106807 0.313211 0.106035 0.31441 0.123156 0.312917 0.10625 0.313506 0.106168 0.31441 0.123156 0.313211 0.106035 0.313796 0.106649 0.31441 0.123156 0.313506 0.106168 0.314076 0.107471 0.31441 0.123156 0.313796 0.106649 0.314339 0.108619 0.31441 0.123156 0.314076 0.107471 0.31458 0.110071 0.31441 0.123156 0.314339 0.108619 0.314794 0.111798 0.31441 0.123156 0.31458 0.110071 0.314976 0.113765 0.31441 0.123156 0.314794 0.111798 0.315121 0.115931 0.31441 0.123156 0.314976 0.113765 0.315228 0.118252 0.31441 0.123156 0.315121 0.115931 0.315293 0.120678 0.31441 0.123156 0.315228 0.118252 0.311198 0.12076 0.312805 0.123156 0.311178 0.123156 0.310447 0.123156 0.311178 0.123156 0.311198 0.125553 0.310432 0.121351 0.311178 0.123156 0.310447 0.123156 0.310432 0.121351 0.311198 0.12076 0.311178 0.123156 0.310388 0.126738 0.311198 0.125553 0.311259 0.127903 0.310432 0.124943 0.310447 0.123156 0.311198 0.125553 0.310388 0.126738 0.310432 0.124943 0.311198 0.125553 0.31021 0.130312 0.311259 0.127903 0.311358 0.130161 0.310313 0.128532 0.310388 0.126738 0.311259 0.127903 0.31021 0.130312 0.310313 0.128532 0.311259 0.127903 0.309907 0.133948 0.311358 0.130161 0.311496 0.132283 0.310077 0.1320959 0.31021 0.130312 0.311358 0.130161 0.309907 0.133948 0.310077 0.1320959 0.311358 0.130161 0.30941 0.138087 0.311496 0.132283 0.311668 0.134226 0.30941 0.138087 0.309907 0.133948 0.311496 0.132283 0.308676 0.1426309 0.311668 0.134226 0.311872 0.135953 0.308676 0.1426309 0.30941 0.138087 0.311668 0.134226 0.307584 0.14785 0.311872 0.135953 0.312103 0.137428 0.307584 0.14785 0.308676 0.1426309 0.311872 0.135953 0.307628 0.151801 0.312103 0.137428 0.312358 0.138621 0.30726 0.149187 0.307584 0.14785 0.312103 0.137428 0.307628 0.151801 0.30726 0.149187 0.312103 0.137428 0.308077 0.153901 0.312358 0.138621 0.312631 0.139505 0.308077 0.153901 0.307628 0.151801 0.312358 0.138621 0.308556 0.155498 0.312631 0.139505 0.312917 0.140062 0.308556 0.155498 0.308077 0.153901 0.312631 0.139505 0.311648 0.14749 0.312917 0.140062 0.313211 0.140277 0.311284 0.147432 0.308556 0.155498 0.312917 0.140062 0.311648 0.14749 0.311284 0.147432 0.312917 0.140062 0.311963 0.147549 0.313211 0.140277 0.313506 0.140144 0.311963 0.147549 0.311648 0.14749 0.313211 0.140277 0.31245 0.147668 0.313506 0.140144 0.313796 0.139663 0.312231 0.147608 0.311963 0.147549 0.313506 0.140144 0.31245 0.147668 0.312231 0.147608 0.313506 0.140144 0.310772 0.155998 0.313796 0.139663 0.314076 0.138841 0.31025 0.1567389 0.31245 0.147668 0.313796 0.139663 0.310772 0.155998 0.31025 0.1567389 0.313796 0.139663 0.311315 0.154425 0.314076 0.138841 0.314339 0.137693 0.311315 0.154425 0.310772 0.155998 0.314076 0.138841 0.311828 0.152193 0.314339 0.137693 0.31458 0.136241 0.311828 0.152193 0.311315 0.154425 0.314339 0.137693 0.3123 0.14934 0.31458 0.136241 0.314794 0.134514 0.3123 0.14934 0.311828 0.152193 0.31458 0.136241 0.31272 0.145921 0.314794 0.134514 0.314976 0.132547 0.31272 0.145921 0.3123 0.14934 0.314794 0.134514 0.313078 0.142005 0.314976 0.132547 0.315121 0.130381 0.313078 0.142005 0.31272 0.145921 0.314976 0.132547 0.313365 0.137673 0.315121 0.130381 0.315228 0.12806 0.313365 0.137673 0.313078 0.142005 0.315121 0.130381 0.313576 0.133018 0.315228 0.12806 0.315293 0.125635 0.313576 0.133018 0.313365 0.137673 0.315228 0.12806 0.313704 0.128143 0.315293 0.125635 0.315314 0.123156 0.313704 0.128143 0.313576 0.133018 0.315293 0.125635 0.313704 0.128143 0.315314 0.123156 0.313748 0.123156 0.315293 0.120678 0.313748 0.123156 0.315314 0.123156 0.309539 0.1310009 0.313704 0.128143 0.313748 0.123156 0.309539 0.1310009 0.313748 0.123156 0.309608 0.123156 0.3137 0.117936 0.309608 0.123156 0.313748 0.123156 0.3137 0.117936 0.313748 0.123156 0.315293 0.120678 0.303055 0.123156 0.310447 0.123156 0.310432 0.124943 0.30278 0.115655 0.310432 0.121351 0.310447 0.123156 0.303055 0.123156 0.30278 0.115655 0.310447 0.123156 0.303055 0.123156 0.310432 0.124943 0.310388 0.126738 0.303055 0.123156 0.310388 0.126738 0.310313 0.128532 0.303055 0.123156 0.310313 0.128532 0.31021 0.130312 0.30278 0.130657 0.31021 0.130312 0.310077 0.1320959 0.30278 0.130657 0.303055 0.123156 0.31021 0.130312 0.30278 0.130657 0.310077 0.1320959 0.309907 0.133948 0.30278 0.130657 0.309907 0.133948 0.30941 0.138087 0.301954 0.138144 0.30941 0.138087 0.308676 0.1426309 0.301954 0.138144 0.30278 0.130657 0.30941 0.138087 0.301954 0.138144 0.308676 0.1426309 0.307584 0.14785 0.300578 0.1455579 0.307584 0.14785 0.30726 0.149187 0.300578 0.1455579 0.301954 0.138144 0.307584 0.14785 0.305946 0.153982 0.30726 0.149187 0.307628 0.151801 0.300578 0.1455579 0.30726 0.149187 0.305946 0.153982 0.30358 0.160992 0.307628 0.151801 0.308077 0.153901 0.305946 0.153982 0.307628 0.151801 0.30358 0.160992 0.301886 0.169515 0.308077 0.153901 0.308556 0.155498 0.301263 0.1666409 0.308077 0.153901 0.301886 0.169515 0.30358 0.160992 0.308077 0.153901 0.301263 0.1666409 0.309423 0.1552709 0.309105 0.156415 0.308556 0.155498 0.302584 0.171616 0.308556 0.155498 0.309105 0.156415 0.311284 0.147432 0.309423 0.1552709 0.308556 0.155498 0.301886 0.169515 0.308556 0.155498 0.302584 0.171616 0.311284 0.147432 0.309105 0.156415 0.309423 0.1552709 0.306181 0.165396 0.309105 0.156415 0.311284 0.147432 0.306181 0.165396 0.302584 0.171616 0.309105 0.156415 0.306181 0.147446 0.311284 0.147432 0.311648 0.14749 0.306181 0.147446 0.306181 0.165396 0.311284 0.147432 0.302048 0.147531 0.311648 0.14749 0.311963 0.147549 0.304374 0.14746 0.306181 0.147446 0.311648 0.14749 0.302923 0.14749 0.304374 0.14746 0.311648 0.14749 0.302048 0.147531 0.302923 0.14749 0.311648 0.14749 0.301883 0.147577 0.311963 0.147549 0.312231 0.147608 0.301883 0.147577 0.302048 0.147531 0.311963 0.147549 0.303689 0.147658 0.312231 0.147608 0.31245 0.147668 0.302459 0.147622 0.301883 0.147577 0.312231 0.147608 0.303689 0.147658 0.302459 0.147622 0.312231 0.147608 0.31025 0.1567389 0.31057 0.155584 0.31245 0.147668 0.307297 0.147683 0.31245 0.147668 0.31057 0.155584 0.305389 0.147679 0.303689 0.147658 0.31245 0.147668 0.307297 0.147683 0.305389 0.147679 0.31245 0.147668 0.307297 0.147683 0.31057 0.155584 0.31025 0.1567389 0.305 0.172498 0.31025 0.1567389 0.310772 0.155998 0.306335 0.168308 0.307297 0.165807 0.31025 0.1567389 0.307297 0.147683 0.31025 0.1567389 0.307297 0.165807 0.305 0.172498 0.306335 0.168308 0.31025 0.1567389 0.30582 0.170603 0.310772 0.155998 0.311315 0.154425 0.30582 0.170603 0.305 0.172498 0.310772 0.155998 0.306603 0.167598 0.311315 0.154425 0.311828 0.152193 0.306603 0.167598 0.30582 0.170603 0.311315 0.154425 0.307331 0.163531 0.311828 0.152193 0.3123 0.14934 0.307331 0.163531 0.306603 0.167598 0.311828 0.152193 0.307984 0.15848 0.3123 0.14934 0.31272 0.145921 0.307984 0.15848 0.307331 0.163531 0.3123 0.14934 0.308546 0.152554 0.31272 0.145921 0.313078 0.142005 0.308546 0.152554 0.307984 0.15848 0.31272 0.145921 0.309 0.145888 0.313078 0.142005 0.313365 0.137673 0.309 0.145888 0.308546 0.152554 0.313078 0.142005 0.309334 0.138644 0.313365 0.137673 0.313576 0.133018 0.309334 0.138644 0.309 0.145888 0.313365 0.137673 0.309539 0.1310009 0.313576 0.133018 0.313704 0.128143 0.309539 0.1310009 0.309334 0.138644 0.313576 0.133018 0.302772 0.132971 0.309539 0.1310009 0.309608 0.123156 0.302772 0.132971 0.309608 0.123156 0.302849 0.123156 0.309542 0.115474 0.302849 0.123156 0.309608 0.123156 0.309542 0.115474 0.309608 0.123156 0.3137 0.117936 0.307297 0.147683 0.307297 0.165807 0.306335 0.168308 0.305 0.172498 0.305476 0.170377 0.306335 0.168308 0.307297 0.147683 0.306335 0.168308 0.305476 0.170377 0.305 0.172498 0.304736 0.172046 0.305476 0.170377 0.305389 0.147679 0.305476 0.170377 0.304736 0.172046 0.307297 0.147683 0.305476 0.170377 0.305389 0.147679 0.305 0.172498 0.304161 0.173272 0.304736 0.172046 0.305389 0.147679 0.304736 0.172046 0.304161 0.173272 0.296719 0.1882179 0.304161 0.173272 0.305 0.172498 0.295761 0.188444 0.304085 0.17343 0.304161 0.173272 0.305389 0.147679 0.304161 0.173272 0.304085 0.17343 0.296719 0.1882179 0.295761 0.188444 0.304161 0.173272 0.297673 0.186672 0.305 0.172498 0.30582 0.170603 0.297673 0.186672 0.296719 0.1882179 0.305 0.172498 0.298602 0.183803 0.30582 0.170603 0.306603 0.167598 0.298602 0.183803 0.297673 0.186672 0.30582 0.170603 0.299487 0.179637 0.306603 0.167598 0.307331 0.163531 0.299487 0.179637 0.298602 0.183803 0.306603 0.167598 0.300305 0.17423 0.307331 0.163531 0.307984 0.15848 0.300305 0.17423 0.299487 0.179637 0.307331 0.163531 0.301037 0.167677 0.307984 0.15848 0.308546 0.152554 0.301037 0.167677 0.300305 0.17423 0.307984 0.15848 0.301665 0.160102 0.308546 0.152554 0.309 0.145888 0.301665 0.160102 0.301037 0.167677 0.308546 0.152554 0.302172 0.151664 0.309 0.145888 0.309334 0.138644 0.302172 0.151664 0.301665 0.160102 0.309 0.145888 0.302545 0.14255 0.309334 0.138644 0.309539 0.1310009 0.302545 0.14255 0.302172 0.151664 0.309334 0.138644 0.302772 0.132971 0.302545 0.14255 0.309539 0.1310009 0.293446 0.1321409 0.302772 0.132971 0.302849 0.123156 0.293446 0.1321409 0.302849 0.123156 0.293494 0.123156 0.302772 0.113342 0.293494 0.123156 0.302849 0.123156 0.302772 0.113342 0.302849 0.123156 0.309542 0.115474 0.295761 0.188444 0.303459 0.174683 0.304085 0.17343 0.303689 0.147658 0.304085 0.17343 0.303459 0.174683 0.305389 0.147679 0.304085 0.17343 0.303689 0.147658 0.295761 0.188444 0.302821 0.175866 0.303459 0.174683 0.303689 0.147658 0.303459 0.174683 0.302821 0.175866 0.295761 0.188444 0.302282 0.176751 0.302821 0.175866 0.302459 0.147622 0.302821 0.175866 0.302282 0.176751 0.303689 0.147658 0.302821 0.175866 0.302459 0.147622 0.295761 0.188444 0.301963 0.177144 0.302282 0.176751 0.302459 0.147622 0.302282 0.176751 0.301963 0.177144 0.294817 0.1873829 0.301855 0.177109 0.301963 0.177144 0.301883 0.147577 0.301963 0.177144 0.301855 0.177109 0.295761 0.188444 0.294817 0.1873829 0.301963 0.177144 0.302459 0.147622 0.301963 0.177144 0.301883 0.147577 0.294817 0.1873829 0.301934 0.176659 0.301855 0.177109 0.301883 0.147577 0.301855 0.177109 0.301934 0.176659 0.294817 0.1873829 0.302236 0.175725 0.301934 0.176659 0.302048 0.147531 0.301934 0.176659 0.302236 0.175725 0.301883 0.147577 0.301934 0.176659 0.302048 0.147531 0.294817 0.1873829 0.302708 0.174445 0.302236 0.175725 0.302048 0.147531 0.302236 0.175725 0.302708 0.174445 0.294817 0.1873829 0.303227 0.173097 0.302708 0.174445 0.302923 0.14749 0.302708 0.174445 0.303227 0.173097 0.302048 0.147531 0.302708 0.174445 0.302923 0.14749 0.294817 0.1873829 0.303307 0.172892 0.303227 0.173097 0.302923 0.14749 0.303227 0.173097 0.303307 0.172892 0.294817 0.1873829 0.302584 0.171616 0.303307 0.172892 0.303786 0.1716639 0.303307 0.172892 0.302584 0.171616 0.302923 0.14749 0.303307 0.172892 0.303786 0.1716639 0.293906 0.185088 0.301886 0.169515 0.302584 0.171616 0.294817 0.1873829 0.293906 0.185088 0.302584 0.171616 0.304444 0.169973 0.303786 0.1716639 0.302584 0.171616 0.305245 0.167893 0.304444 0.169973 0.302584 0.171616 0.306181 0.165396 0.305245 0.167893 0.302584 0.171616 0.300308 0.1687279 0.301263 0.1666409 0.301886 0.169515 0.296463 0.176113 0.300308 0.1687279 0.301886 0.169515 0.2931 0.181585 0.296463 0.176113 0.301886 0.169515 0.293906 0.185088 0.2931 0.181585 0.301886 0.169515 0.296224 0.159965 0.301263 0.1666409 0.300308 0.1687279 0.296224 0.159965 0.30358 0.160992 0.301263 0.1666409 0.293258 0.1669149 0.300308 0.1687279 0.296463 0.176113 0.293258 0.1669149 0.296224 0.159965 0.300308 0.1687279 0.289774 0.173659 0.296463 0.176113 0.2931 0.181585 0.289774 0.173659 0.293258 0.1669149 0.296463 0.176113 0.292025 0.1831859 0.2931 0.181585 0.293906 0.185088 0.289774 0.173659 0.2931 0.181585 0.292025 0.1831859 0.283828 0.198843 0.293906 0.185088 0.294817 0.1873829 0.286056 0.191047 0.292025 0.1831859 0.293906 0.185088 0.283061 0.194458 0.286056 0.191047 0.293906 0.185088 0.283828 0.198843 0.283061 0.194458 0.293906 0.185088 0.284881 0.201493 0.294817 0.1873829 0.295761 0.188444 0.284881 0.201493 0.283828 0.198843 0.294817 0.1873829 0.285971 0.202491 0.295761 0.188444 0.296719 0.1882179 0.285971 0.202491 0.284881 0.201493 0.295761 0.188444 0.287077 0.201756 0.296719 0.1882179 0.297673 0.186672 0.287077 0.201756 0.285971 0.202491 0.296719 0.1882179 0.288172 0.199244 0.297673 0.186672 0.298602 0.183803 0.288172 0.199244 0.287077 0.201756 0.297673 0.186672 0.28923 0.19495 0.298602 0.183803 0.299487 0.179637 0.28923 0.19495 0.288172 0.199244 0.298602 0.183803 0.290225 0.1889179 0.299487 0.179637 0.300305 0.17423 0.290225 0.1889179 0.28923 0.19495 0.299487 0.179637 0.29113 0.181243 0.300305 0.17423 0.301037 0.167677 0.29113 0.181243 0.290225 0.1889179 0.300305 0.17423 0.291923 0.172098 0.301037 0.167677 0.301665 0.160102 0.291923 0.172098 0.29113 0.181243 0.301037 0.167677 0.295839 0.159211 0.301665 0.160102 0.302172 0.151664 0.292286 0.171163 0.291923 0.172098 0.301665 0.160102 0.293151 0.168682 0.292286 0.171163 0.301665 0.160102 0.295839 0.159211 0.293151 0.168682 0.301665 0.160102 0.297912 0.149389 0.302172 0.151664 0.302545 0.14255 0.297912 0.149389 0.295839 0.159211 0.302172 0.151664 0.293304 0.1410019 0.302545 0.14255 0.302772 0.132971 0.295341 0.149507 0.297912 0.149389 0.302545 0.14255 0.293081 0.149601 0.295341 0.149507 0.302545 0.14255 0.293304 0.1410019 0.293081 0.149601 0.302545 0.14255 0.293446 0.1321409 0.293304 0.1410019 0.302772 0.132971 0.281544 0.138151 0.293446 0.1321409 0.293494 0.123156 0.281544 0.138151 0.293494 0.123156 0.281644 0.123156 0.29341 0.111233 0.281644 0.123156 0.293494 0.123156 0.29341 0.111233 0.293494 0.123156 0.302772 0.113342 0.285793 0.180142 0.292025 0.1831859 0.286056 0.191047 0.285793 0.180142 0.289774 0.173659 0.292025 0.1831859 0.281345 0.186315 0.286056 0.191047 0.283061 0.194458 0.281345 0.186315 0.285793 0.180142 0.286056 0.191047 0.277441 0.200107 0.283061 0.194458 0.283828 0.198843 0.276445 0.192155 0.283061 0.194458 0.277441 0.200107 0.276445 0.192155 0.281345 0.186315 0.283061 0.194458 0.271847 0.210592 0.283828 0.198843 0.284881 0.201493 0.271014 0.205579 0.277441 0.200107 0.283828 0.198843 0.271847 0.210592 0.271014 0.205579 0.283828 0.198843 0.272917 0.213733 0.284881 0.201493 0.285971 0.202491 0.272917 0.213733 0.271847 0.210592 0.284881 0.201493 0.274029 0.214937 0.285971 0.202491 0.287077 0.201756 0.274029 0.214937 0.272917 0.213733 0.285971 0.202491 0.275158 0.2141 0.287077 0.201756 0.288172 0.199244 0.275158 0.2141 0.274029 0.214937 0.287077 0.201756 0.276279 0.211154 0.288172 0.199244 0.28923 0.19495 0.276279 0.211154 0.275158 0.2141 0.288172 0.199244 0.277363 0.206084 0.28923 0.19495 0.290225 0.1889179 0.277363 0.206084 0.276279 0.211154 0.28923 0.19495 0.278382 0.198931 0.290225 0.1889179 0.29113 0.181243 0.278382 0.198931 0.277363 0.206084 0.290225 0.1889179 0.291321 0.173533 0.29113 0.181243 0.291923 0.172098 0.289259 0.177563 0.288194 0.179162 0.29113 0.181243 0.279307 0.189803 0.29113 0.181243 0.288194 0.179162 0.290308 0.175671 0.289259 0.177563 0.29113 0.181243 0.291321 0.173533 0.290308 0.175671 0.29113 0.181243 0.279307 0.189803 0.278382 0.198931 0.29113 0.181243 0.291232 0.149296 0.291923 0.172098 0.292286 0.171163 0.291232 0.149296 0.291321 0.173533 0.291923 0.172098 0.291232 0.149296 0.292286 0.171163 0.293151 0.168682 0.297912 0.149389 0.293151 0.168682 0.295839 0.159211 0.293151 0.149314 0.293151 0.168682 0.297912 0.149389 0.291232 0.149296 0.293151 0.168682 0.293151 0.149314 0.285314 0.149464 0.297912 0.149389 0.295341 0.149507 0.285952 0.14936 0.293151 0.149314 0.297912 0.149389 0.285239 0.14941 0.285952 0.14936 0.297912 0.149389 0.285314 0.149464 0.285239 0.14941 0.297912 0.149389 0.287682 0.14955 0.295341 0.149507 0.293081 0.149601 0.286171 0.149513 0.285314 0.149464 0.295341 0.149507 0.287682 0.14955 0.286171 0.149513 0.295341 0.149507 0.292446 0.149627 0.293081 0.149601 0.293304 0.1410019 0.287682 0.14955 0.293081 0.149601 0.292446 0.149627 0.281544 0.138151 0.293304 0.1410019 0.293446 0.1321409 0.281247 0.152707 0.292446 0.149627 0.293304 0.1410019 0.281544 0.138151 0.281247 0.152707 0.293304 0.1410019 0.267411 0.1389459 0.281544 0.138151 0.281644 0.123156 0.267411 0.1389459 0.281644 0.123156 0.267494 0.123156 0.281544 0.108161 0.267494 0.123156 0.281644 0.123156 0.281544 0.108161 0.281644 0.123156 0.29341 0.111233 0.280763 0.166408 0.290381 0.159451 0.292446 0.149627 0.287682 0.14955 0.292446 0.149627 0.290381 0.159451 0.281247 0.152707 0.280763 0.166408 0.292446 0.149627 0.280763 0.166408 0.287682 0.169012 0.290381 0.159451 0.287682 0.14955 0.290381 0.159451 0.287682 0.169012 0.280109 0.178879 0.28691 0.171495 0.287682 0.169012 0.287682 0.14955 0.287682 0.169012 0.28691 0.171495 0.280763 0.166408 0.280109 0.178879 0.287682 0.169012 0.280109 0.178879 0.286245 0.1738139 0.28691 0.171495 0.287682 0.14955 0.28691 0.171495 0.286245 0.1738139 0.280109 0.178879 0.285764 0.1756989 0.286245 0.1738139 0.286171 0.149513 0.286245 0.1738139 0.285764 0.1756989 0.287682 0.14955 0.286245 0.1738139 0.286171 0.149513 0.279307 0.189803 0.285439 0.17723 0.285764 0.1756989 0.286171 0.149513 0.285764 0.1756989 0.285439 0.17723 0.280109 0.178879 0.279307 0.189803 0.285764 0.1756989 0.279307 0.189803 0.285231 0.178609 0.285439 0.17723 0.285314 0.149464 0.285439 0.17723 0.285231 0.178609 0.286171 0.149513 0.285439 0.17723 0.285314 0.149464 0.279307 0.189803 0.285181 0.179889 0.285231 0.178609 0.285314 0.149464 0.285231 0.178609 0.285181 0.179889 0.279307 0.189803 0.28538 0.180773 0.285181 0.179889 0.285239 0.14941 0.285181 0.179889 0.28538 0.180773 0.285314 0.149464 0.285181 0.179889 0.285239 0.14941 0.279307 0.189803 0.285804 0.181103 0.28538 0.180773 0.285239 0.14941 0.28538 0.180773 0.285804 0.181103 0.279307 0.189803 0.286407 0.1809549 0.285804 0.181103 0.285952 0.14936 0.285804 0.181103 0.286407 0.1809549 0.285239 0.14941 0.285804 0.181103 0.285952 0.14936 0.279307 0.189803 0.287213 0.1803179 0.286407 0.1809549 0.285952 0.14936 0.286407 0.1809549 0.287213 0.1803179 0.279307 0.189803 0.288194 0.179162 0.287213 0.1803179 0.287341 0.149321 0.287213 0.1803179 0.288194 0.179162 0.285952 0.14936 0.287213 0.1803179 0.287341 0.149321 0.289194 0.149298 0.288194 0.179162 0.289259 0.177563 0.287341 0.149321 0.288194 0.179162 0.289194 0.149298 0.289194 0.149298 0.289259 0.177563 0.290308 0.175671 0.291232 0.149296 0.290308 0.175671 0.291321 0.173533 0.289194 0.149298 0.290308 0.175671 0.291232 0.149296 0.271116 0.19763 0.277441 0.200107 0.271014 0.205579 0.271116 0.19763 0.276445 0.192155 0.277441 0.200107 0.258194 0.219855 0.271014 0.205579 0.271847 0.210592 0.258194 0.219855 0.265968 0.209263 0.271014 0.205579 0.265381 0.20271 0.271014 0.205579 0.265968 0.209263 0.265381 0.20271 0.271116 0.19763 0.271014 0.205579 0.259111 0.223545 0.271847 0.210592 0.272917 0.213733 0.259111 0.223545 0.258194 0.219855 0.271847 0.210592 0.260066 0.2254 0.272917 0.213733 0.274029 0.214937 0.260066 0.2254 0.259111 0.223545 0.272917 0.213733 0.261044 0.225305 0.274029 0.214937 0.275158 0.2141 0.261044 0.225305 0.260066 0.2254 0.274029 0.214937 0.262025 0.223178 0.275158 0.2141 0.276279 0.211154 0.262025 0.223178 0.261044 0.225305 0.275158 0.2141 0.262988 0.218975 0.276279 0.211154 0.277363 0.206084 0.262988 0.218975 0.262025 0.223178 0.276279 0.211154 0.263912 0.212697 0.277363 0.206084 0.278382 0.198931 0.263912 0.212697 0.262988 0.218975 0.277363 0.206084 0.264773 0.2044 0.278382 0.198931 0.279307 0.189803 0.264773 0.2044 0.263912 0.212697 0.278382 0.198931 0.26555 0.1942009 0.279307 0.189803 0.280109 0.178879 0.26555 0.1942009 0.264773 0.2044 0.279307 0.189803 0.26622 0.182281 0.280109 0.178879 0.280763 0.166408 0.26622 0.182281 0.26555 0.1942009 0.280109 0.178879 0.266764 0.1688849 0.280763 0.166408 0.281247 0.152707 0.266764 0.1688849 0.26622 0.182281 0.280763 0.166408 0.267165 0.154321 0.281247 0.152707 0.281544 0.138151 0.267165 0.154321 0.266764 0.1688849 0.281247 0.152707 0.267411 0.1389459 0.267165 0.154321 0.281544 0.138151 0.251258 0.140596 0.267411 0.1389459 0.267494 0.123156 0.251258 0.140596 0.267494 0.123156 0.25133 0.123156 0.267411 0.107366 0.25133 0.123156 0.267494 0.123156 0.267411 0.107366 0.267494 0.123156 0.281544 0.108161 0.258194 0.219855 0.257308 0.214529 0.265968 0.209263 0.259286 0.207352 0.265968 0.209263 0.257308 0.214529 0.259286 0.207352 0.265381 0.20271 0.265968 0.209263 0.243335 0.227081 0.257308 0.214529 0.258194 0.219855 0.243335 0.227081 0.25274 0.216834 0.257308 0.214529 0.252855 0.211536 0.257308 0.214529 0.25274 0.216834 0.252855 0.211536 0.259286 0.207352 0.257308 0.214529 0.244108 0.23145 0.258194 0.219855 0.259111 0.223545 0.244108 0.23145 0.243335 0.227081 0.258194 0.219855 0.244918 0.2338269 0.259111 0.223545 0.260066 0.2254 0.244918 0.2338269 0.244108 0.23145 0.259111 0.223545 0.245751 0.234072 0.260066 0.2254 0.261044 0.225305 0.245751 0.234072 0.244918 0.2338269 0.260066 0.2254 0.24659 0.23208 0.261044 0.225305 0.262025 0.223178 0.24659 0.23208 0.245751 0.234072 0.261044 0.225305 0.247417 0.227786 0.262025 0.223178 0.262988 0.218975 0.247417 0.227786 0.24659 0.23208 0.262025 0.223178 0.248214 0.221174 0.262988 0.218975 0.263912 0.212697 0.248214 0.221174 0.247417 0.227786 0.262988 0.218975 0.248959 0.212292 0.263912 0.212697 0.264773 0.2044 0.248959 0.212292 0.248214 0.221174 0.263912 0.212697 0.249634 0.201258 0.264773 0.2044 0.26555 0.1942009 0.249634 0.201258 0.248959 0.212292 0.264773 0.2044 0.250217 0.188264 0.26555 0.1942009 0.26622 0.182281 0.250217 0.188264 0.249634 0.201258 0.26555 0.1942009 0.250692 0.173582 0.26622 0.182281 0.266764 0.1688849 0.250692 0.173582 0.250217 0.188264 0.26622 0.182281 0.251042 0.1575559 0.266764 0.1688849 0.267165 0.154321 0.251042 0.1575559 0.250692 0.173582 0.266764 0.1688849 0.251258 0.140596 0.267165 0.154321 0.267411 0.1389459 0.251258 0.140596 0.251042 0.1575559 0.267165 0.154321 0.2335039 0.137134 0.251258 0.140596 0.25133 0.123156 0.2335039 0.137134 0.25133 0.123156 0.233534 0.123156 0.251258 0.105716 0.233534 0.123156 0.25133 0.123156 0.251258 0.105716 0.25133 0.123156 0.267411 0.107366 0.243335 0.227081 0.242608 0.220921 0.25274 0.216834 0.246128 0.215236 0.25274 0.216834 0.242608 0.220921 0.246128 0.215236 0.252855 0.211536 0.25274 0.216834 0.227515 0.2316 0.242608 0.220921 0.243335 0.227081 0.227515 0.2316 0.238766 0.222129 0.242608 0.220921 0.239143 0.2184309 0.242608 0.220921 0.238766 0.222129 0.239143 0.2184309 0.246128 0.215236 0.242608 0.220921 0.228065 0.236658 0.243335 0.227081 0.244108 0.23145 0.228065 0.236658 0.227515 0.2316 0.243335 0.227081 0.228645 0.239724 0.244108 0.23145 0.244918 0.2338269 0.228645 0.239724 0.228065 0.236658 0.244108 0.23145 0.2292439 0.240647 0.244918 0.2338269 0.245751 0.234072 0.2292439 0.240647 0.228645 0.239724 0.244918 0.2338269 0.229852 0.239304 0.245751 0.234072 0.24659 0.23208 0.229852 0.239304 0.2292439 0.240647 0.245751 0.234072 0.230457 0.235608 0.24659 0.23208 0.247417 0.227786 0.230457 0.235608 0.229852 0.239304 0.24659 0.23208 0.231045 0.22952 0.247417 0.227786 0.248214 0.221174 0.231045 0.22952 0.230457 0.235608 0.247417 0.227786 0.2316009 0.22106 0.248214 0.221174 0.248959 0.212292 0.2316009 0.22106 0.231045 0.22952 0.248214 0.221174 0.232112 0.210315 0.248959 0.212292 0.249634 0.201258 0.232112 0.210315 0.2316009 0.22106 0.248959 0.212292 0.232563 0.19745 0.249634 0.201258 0.250217 0.188264 0.232563 0.19745 0.232112 0.210315 0.249634 0.201258 0.232938 0.182749 0.250217 0.188264 0.250692 0.173582 0.232938 0.182749 0.232563 0.19745 0.250217 0.188264 0.236943 0.175079 0.250692 0.173582 0.251042 0.1575559 0.233152 0.182552 0.232938 0.182749 0.250692 0.173582 0.2343029 0.181189 0.233152 0.182552 0.250692 0.173582 0.235342 0.179427 0.2343029 0.181189 0.250692 0.173582 0.236201 0.177435 0.235342 0.179427 0.250692 0.173582 0.236943 0.175079 0.236201 0.177435 0.250692 0.173582 0.237828 0.157324 0.251042 0.1575559 0.251258 0.140596 0.237588 0.172044 0.236943 0.175079 0.251042 0.1575559 0.23802 0.168217 0.237588 0.172044 0.251042 0.1575559 0.238071 0.163669 0.23802 0.168217 0.251042 0.1575559 0.237828 0.157324 0.238071 0.163669 0.251042 0.1575559 0.237627 0.150838 0.237828 0.157324 0.251258 0.140596 0.233412 0.150883 0.237627 0.150838 0.251258 0.140596 0.2335039 0.137134 0.233412 0.150883 0.251258 0.140596 0.233479 0.104324 0.233534 0.123156 0.251258 0.105716 0.227515 0.2316 0.2269909 0.224757 0.238766 0.222129 0.231936 0.221103 0.238766 0.222129 0.2269909 0.224757 0.231936 0.221103 0.239143 0.2184309 0.238766 0.222129 0.224556 0.2232339 0.2269909 0.224757 0.224189 0.225153 0.224556 0.2232339 0.231936 0.221103 0.2269909 0.224757 0.231131 0.15057 0.232938 0.182749 0.233152 0.182552 0.231131 0.15057 0.232002 0.183408 0.232938 0.182749 0.233264 0.150566 0.233152 0.182552 0.2343029 0.181189 0.231131 0.15057 0.233152 0.182552 0.233264 0.150566 0.235297 0.150584 0.2343029 0.181189 0.235342 0.179427 0.233264 0.150566 0.2343029 0.181189 0.235297 0.150584 0.235297 0.150584 0.235342 0.179427 0.236201 0.177435 0.236925 0.150623 0.236201 0.177435 0.236943 0.175079 0.235297 0.150584 0.236201 0.177435 0.236925 0.150623 0.236925 0.150623 0.236943 0.175079 0.237588 0.172044 0.2379 0.1506749 0.237588 0.172044 0.23802 0.168217 0.236925 0.150623 0.237588 0.172044 0.2379 0.1506749 0.2379 0.1506749 0.23802 0.168217 0.238071 0.163669 0.237627 0.150838 0.238071 0.163669 0.237828 0.157324 0.238071 0.150734 0.238071 0.163669 0.237627 0.150838 0.2379 0.1506749 0.238071 0.163669 0.238071 0.150734 0.227126 0.1506969 0.237627 0.150838 0.233412 0.150883 0.227126 0.1506969 0.238071 0.150734 0.237627 0.150838 0.231839 0.1508989 0.233412 0.150883 0.2335039 0.137134 0.227126 0.1506969 0.233412 0.150883 0.231839 0.1508989 0.225939 0.150951 0.231839 0.1508989 0.2335039 0.137134 0.227126 0.1506969 0.231839 0.1508989 0.225939 0.150951 0.227126 0.1506969 0.225939 0.150951 0.226438 0.164565 0.227126 0.1506969 0.226438 0.164565 0.227126 0.1774629 0.227126 0.1506969 0.227126 0.1774629 0.227243 0.1787 0.227126 0.1506969 0.227243 0.1787 0.227455 0.179929 0.22781 0.150641 0.227455 0.179929 0.227822 0.181206 0.227126 0.1506969 0.227455 0.179929 0.22781 0.150641 0.22781 0.150641 0.227822 0.181206 0.2283779 0.1823599 0.22781 0.150641 0.2283779 0.1823599 0.229028 0.183149 0.2292169 0.150597 0.229028 0.183149 0.229857 0.183658 0.22781 0.150641 0.229028 0.183149 0.2292169 0.150597 0.2292169 0.150597 0.229857 0.183658 0.230897 0.183773 0.231131 0.15057 0.230897 0.183773 0.232002 0.183408 0.2292169 0.150597 0.230897 0.183773 0.231131 0.15057 0.189662 0.219357 0.1921499 0.2463189 0.1896409 0.246297 0.194642 0.219357 0.1921499 0.2463189 0.189662 0.219357 0.184893 0.2192209 0.1896409 0.246297 0.184867 0.246122 0.189662 0.219357 0.1896409 0.246297 0.184893 0.2192209 0.1807399 0.218961 0.184867 0.246122 0.180718 0.24579 0.184893 0.2192209 0.184867 0.246122 0.1807399 0.218961 0.177547 0.218601 0.180718 0.24579 0.177537 0.245332 0.1807399 0.218961 0.180718 0.24579 0.177547 0.218601 0.298665 0.152842 0.305946 0.153982 0.30358 0.160992 0.296224 0.159965 0.298665 0.152842 0.30358 0.160992 0.304374 0.14746 0.303786 0.1716639 0.304444 0.169973 0.302923 0.14749 0.303786 0.1716639 0.304374 0.14746 0.304374 0.14746 0.304444 0.169973 0.305245 0.167893 0.304374 0.14746 0.305245 0.167893 0.306181 0.165396 0.304374 0.14746 0.306181 0.165396 0.306181 0.147446 0.298665 0.152842 0.300578 0.1455579 0.305946 0.153982 0.147325 0.06979995 0.128937 0.04036498 0.131869 0.03820896 0.140705 0.03259193 0.131869 0.03820896 0.1311669 0.03075093 0.152145 0.06609797 0.131869 0.03820896 0.140705 0.03259193 0.152145 0.06609797 0.147325 0.06979995 0.131869 0.03820896 0.145829 0.02164489 0.1311669 0.03075093 0.130338 0.024836 0.146466 0.02955991 0.140705 0.03259193 0.1311669 0.03075093 0.145829 0.02164489 0.146466 0.02955991 0.1311669 0.03075093 0.145102 0.01558488 0.130338 0.024836 0.129453 0.02067589 0.145102 0.01558488 0.145829 0.02164489 0.130338 0.024836 0.1443279 0.01165795 0.129453 0.02067589 0.128526 0.01842099 0.1443279 0.01165795 0.145102 0.01558488 0.129453 0.02067589 0.143521 0.01004892 0.128526 0.01842099 0.127573 0.01820099 0.143521 0.01004892 0.1443279 0.01165795 0.128526 0.01842099 0.142698 0.01090788 0.127573 0.01820099 0.126614 0.02010893 0.142698 0.01090788 0.143521 0.01004892 0.127573 0.01820099 0.1418769 0.01434499 0.126614 0.02010893 0.12567 0.02420395 0.1418769 0.01434499 0.142698 0.01090788 0.126614 0.02010893 0.1410779 0.02040892 0.12567 0.02420395 0.124761 0.03049188 0.1410779 0.02040892 0.1418769 0.01434499 0.12567 0.02420395 0.140325 0.02907699 0.124761 0.03049188 0.123912 0.03892296 0.140325 0.02907699 0.1410779 0.02040892 0.124761 0.03049188 0.139638 0.04024291 0.123912 0.03892296 0.123145 0.04938089 0.139638 0.04024291 0.140325 0.02907699 0.123912 0.03892296 0.139039 0.05370599 0.123145 0.04938089 0.122481 0.06167799 0.139039 0.05370599 0.139638 0.04024291 0.123145 0.04938089 0.13855 0.06916499 0.122481 0.06167799 0.121942 0.075558 0.13855 0.06916499 0.139039 0.05370599 0.122481 0.06167799 0.138187 0.08622395 0.121942 0.075558 0.121544 0.09069299 0.138187 0.08622395 0.13855 0.06916499 0.121942 0.075558 0.1379629 0.104402 0.121544 0.09069299 0.121299 0.106701 0.1379629 0.104402 0.138187 0.08622395 0.121544 0.09069299 0.157272 0.06282895 0.140705 0.03259193 0.146466 0.02955991 0.157272 0.06282895 0.152145 0.06609797 0.140705 0.03259193 0.153497 0.02645099 0.146466 0.02955991 0.145829 0.02164489 0.162666 0.06001991 0.146466 0.02955991 0.153497 0.02645099 0.162666 0.06001991 0.157272 0.06282895 0.146466 0.02955991 0.161526 0.01554197 0.145829 0.02164489 0.145102 0.01558488 0.1619679 0.02348995 0.153497 0.02645099 0.145829 0.02164489 0.161526 0.01554197 0.1619679 0.02348995 0.145829 0.02164489 0.161023 0.009521961 0.145102 0.01558488 0.1443279 0.01165795 0.161023 0.009521961 0.161526 0.01554197 0.145102 0.01558488 0.160489 0.005699992 0.1443279 0.01165795 0.143521 0.01004892 0.160489 0.005699992 0.161023 0.009521961 0.1443279 0.01165795 0.159934 0.004264891 0.143521 0.01004892 0.142698 0.01090788 0.159934 0.004264891 0.160489 0.005699992 0.143521 0.01004892 0.159368 0.005370974 0.142698 0.01090788 0.1418769 0.01434499 0.159368 0.005370974 0.159934 0.004264891 0.142698 0.01090788 0.1588039 0.009130954 0.1418769 0.01434499 0.1410779 0.02040892 0.1588039 0.009130954 0.159368 0.005370974 0.1418769 0.01434499 0.158255 0.01559793 0.1410779 0.02040892 0.140325 0.02907699 0.158255 0.01559793 0.1588039 0.009130954 0.1410779 0.02040892 0.157738 0.02475088 0.140325 0.02907699 0.139638 0.04024291 0.157738 0.02475088 0.158255 0.01559793 0.140325 0.02907699 0.157267 0.03648293 0.139638 0.04024291 0.139039 0.05370599 0.157267 0.03648293 0.157738 0.02475088 0.139638 0.04024291 0.156856 0.05058896 0.139039 0.05370599 0.13855 0.06916499 0.156856 0.05058896 0.157267 0.03648293 0.139039 0.05370599 0.156521 0.06676 0.13855 0.06916499 0.138187 0.08622395 0.156521 0.06676 0.156856 0.05058896 0.13855 0.06916499 0.1562719 0.08458596 0.138187 0.08622395 0.1379629 0.104402 0.1562719 0.08458596 0.156521 0.06676 0.138187 0.08622395 0.156118 0.103573 0.1562719 0.08458596 0.1379629 0.104402 0.168288 0.05768996 0.153497 0.02645099 0.1619679 0.02348995 0.168288 0.05768996 0.162666 0.06001991 0.153497 0.02645099 0.167047 0.02209496 0.1619679 0.02348995 0.161526 0.01554197 0.174093 0.05585998 0.1619679 0.02348995 0.167047 0.02209496 0.174093 0.05585998 0.168288 0.05768996 0.1619679 0.02348995 0.177873 0.01200091 0.161526 0.01554197 0.161023 0.009521961 0.178089 0.01998496 0.167047 0.02209496 0.161526 0.01554197 0.177873 0.01200091 0.178089 0.01998496 0.161526 0.01554197 0.177633 0.005999982 0.161023 0.009521961 0.160489 0.005699992 0.177633 0.005999982 0.177873 0.01200091 0.161023 0.009521961 0.1773779 0.002233982 0.160489 0.005699992 0.159934 0.004264891 0.1773779 0.002233982 0.177633 0.005999982 0.160489 0.005699992 0.1771129 8.93e-4 0.159934 0.004264891 0.159368 0.005370974 0.1771129 8.93e-4 0.1773779 0.002233982 0.159934 0.004264891 0.176843 0.002137959 0.159368 0.005370974 0.1588039 0.009130954 0.176843 0.002137959 0.1771129 8.93e-4 0.159368 0.005370974 0.176574 0.006081998 0.1588039 0.009130954 0.158255 0.01559793 0.176574 0.006081998 0.176843 0.002137959 0.1588039 0.009130954 0.176313 0.01278096 0.158255 0.01559793 0.157738 0.02475088 0.176313 0.01278096 0.176574 0.006081998 0.158255 0.01559793 0.1760669 0.02221399 0.157738 0.02475088 0.157267 0.03648293 0.1760669 0.02221399 0.176313 0.01278096 0.157738 0.02475088 0.175842 0.03427499 0.157267 0.03648293 0.156856 0.05058896 0.175842 0.03427499 0.1760669 0.02221399 0.157267 0.03648293 0.175647 0.048756 0.156856 0.05058896 0.156521 0.06676 0.175647 0.048756 0.175842 0.03427499 0.156856 0.05058896 0.175487 0.06534397 0.156521 0.06676 0.1562719 0.08458596 0.175487 0.06534397 0.175647 0.048756 0.156521 0.06676 0.175368 0.08362197 0.1562719 0.08458596 0.156118 0.103573 0.175368 0.08362197 0.175487 0.06534397 0.1562719 0.08458596 0.1752949 0.103084 0.175368 0.08362197 0.156118 0.103573 0.180036 0.054542 0.167047 0.02209496 0.178089 0.01998496 0.180036 0.054542 0.174093 0.05585998 0.167047 0.02209496 0.181048 0.01962596 0.178089 0.01998496 0.177873 0.01200091 0.180036 0.054542 0.178089 0.01998496 0.181048 0.01962596 0.194525 0.01104897 0.177873 0.01200091 0.177633 0.005999982 0.194487 0.01905995 0.181048 0.01962596 0.177873 0.01200091 0.194525 0.01104897 0.194487 0.01905995 0.177873 0.01200091 0.1945649 0.00505799 0.177633 0.005999982 0.1773779 0.002233982 0.1945649 0.00505799 0.194525 0.01104897 0.177633 0.005999982 0.194608 0.001310884 0.1773779 0.002233982 0.1771129 8.93e-4 0.194608 0.001310884 0.1945649 0.00505799 0.1773779 0.002233982 0.194652 0 0.1771129 8.93e-4 0.176843 0.002137959 0.194652 0 0.194608 0.001310884 0.1771129 8.93e-4 0.194697 0.001284897 0.176843 0.002137959 0.176574 0.006081998 0.194697 0.001284897 0.194652 0 0.176843 0.002137959 0.194742 0.005279958 0.176574 0.006081998 0.176313 0.01278096 0.194742 0.005279958 0.194697 0.001284897 0.176574 0.006081998 0.194786 0.01204097 0.176313 0.01278096 0.1760669 0.02221399 0.194786 0.01204097 0.194742 0.005279958 0.176313 0.01278096 0.194827 0.02154994 0.1760669 0.02221399 0.175842 0.03427499 0.194827 0.02154994 0.194786 0.01204097 0.1760669 0.02221399 0.194865 0.03369891 0.175842 0.03427499 0.175647 0.048756 0.194865 0.03369891 0.194827 0.02154994 0.175842 0.03427499 0.1948969 0.04827892 0.175647 0.048756 0.175487 0.06534397 0.1948969 0.04827892 0.194865 0.03369891 0.175647 0.048756 0.1949239 0.06497496 0.175487 0.06534397 0.175368 0.08362197 0.1949239 0.06497496 0.1948969 0.04827892 0.175487 0.06534397 0.194944 0.08337098 0.175368 0.08362197 0.1752949 0.103084 0.194944 0.08337098 0.1949239 0.06497496 0.175368 0.08362197 0.194956 0.102957 0.194944 0.08337098 0.1752949 0.103084 0.186071 0.05374795 0.181048 0.01962596 0.194487 0.01905995 0.186071 0.05374795 0.180036 0.054542 0.181048 0.01962596 0.195261 0.01907998 0.194487 0.01905995 0.194525 0.01104897 0.192152 0.05348193 0.194487 0.01905995 0.195261 0.01907998 0.192152 0.05348193 0.186071 0.05374795 0.194487 0.01905995 0.211454 0.006595969 0.194525 0.01104897 0.1945649 0.00505799 0.211136 0.01252198 0.195261 0.01907998 0.194525 0.01104897 0.211454 0.006595969 0.211136 0.01252198 0.194525 0.01104897 0.21179 0.002892971 0.1945649 0.00505799 0.194608 0.001310884 0.21179 0.002892971 0.211454 0.006595969 0.1945649 0.00505799 0.21214 0.001599967 0.194608 0.001310884 0.194652 0 0.21214 0.001599967 0.21179 0.002892971 0.194608 0.001310884 0.2124969 0.00287497 0.194652 0 0.194697 0.001284897 0.2124969 0.00287497 0.21214 0.001599967 0.194652 0 0.212851 0.006826937 0.194697 0.001284897 0.194742 0.005279958 0.212851 0.006826937 0.2124969 0.00287497 0.194697 0.001284897 0.213196 0.013511 0.194742 0.005279958 0.194786 0.01204097 0.213196 0.013511 0.212851 0.006826937 0.194742 0.005279958 0.21352 0.02290499 0.194786 0.01204097 0.194827 0.02154994 0.21352 0.02290499 0.213196 0.013511 0.194786 0.01204097 0.213816 0.03490191 0.194827 0.02154994 0.194865 0.03369891 0.213816 0.03490191 0.21352 0.02290499 0.194827 0.02154994 0.214074 0.04929399 0.194865 0.03369891 0.1948969 0.04827892 0.214074 0.04929399 0.213816 0.03490191 0.194865 0.03369891 0.214284 0.06576997 0.1948969 0.04827892 0.1949239 0.06497496 0.214284 0.06576997 0.214074 0.04929399 0.1948969 0.04827892 0.21444 0.08391696 0.1949239 0.06497496 0.194944 0.08337098 0.21444 0.08391696 0.214284 0.06576997 0.1949239 0.06497496 0.214536 0.103235 0.194944 0.08337098 0.194956 0.102957 0.214536 0.103235 0.21444 0.08391696 0.194944 0.08337098 0.210831 0.02043795 0.20943 0.02047199 0.195261 0.01907998 0.198234 0.05374795 0.195261 0.01907998 0.20943 0.02047199 0.211136 0.01252198 0.210831 0.02043795 0.195261 0.01907998 0.198234 0.05374795 0.192152 0.05348193 0.195261 0.01907998 0.224555 0.02307695 0.20943 0.02047199 0.210831 0.02043795 0.204269 0.054542 0.20943 0.02047199 0.224555 0.02307695 0.204269 0.054542 0.198234 0.05374795 0.20943 0.02047199 0.224334 0.02117788 0.210831 0.02043795 0.211136 0.01252198 0.224555 0.02307695 0.210831 0.02043795 0.224334 0.02117788 0.227531 0.01453298 0.211136 0.01252198 0.211454 0.006595969 0.2269909 0.021555 0.211136 0.01252198 0.227531 0.01453298 0.224334 0.02117788 0.211136 0.01252198 0.2269909 0.021555 0.228099 0.009412944 0.211454 0.006595969 0.21179 0.002892971 0.227531 0.01453298 0.211454 0.006595969 0.228099 0.009412944 0.228698 0.006415963 0.21179 0.002892971 0.21214 0.001599967 0.228099 0.009412944 0.21179 0.002892971 0.228698 0.006415963 0.229317 0.005703985 0.21214 0.001599967 0.2124969 0.00287497 0.228698 0.006415963 0.21214 0.001599967 0.229317 0.005703985 0.229943 0.007408976 0.2124969 0.00287497 0.212851 0.006826937 0.229317 0.005703985 0.2124969 0.00287497 0.229943 0.007408976 0.2305639 0.01161897 0.212851 0.006826937 0.213196 0.013511 0.229943 0.007408976 0.212851 0.006826937 0.2305639 0.01161897 0.231164 0.018368 0.213196 0.013511 0.21352 0.02290499 0.2305639 0.01161897 0.213196 0.013511 0.231164 0.018368 0.231728 0.027619 0.21352 0.02290499 0.213816 0.03490191 0.231164 0.018368 0.21352 0.02290499 0.231728 0.027619 0.23224 0.039258 0.213816 0.03490191 0.214074 0.04929399 0.231728 0.027619 0.213816 0.03490191 0.23224 0.039258 0.232684 0.05308389 0.214074 0.04929399 0.214284 0.06576997 0.23224 0.039258 0.214074 0.04929399 0.232684 0.05308389 0.2330459 0.06880396 0.214284 0.06576997 0.21444 0.08391696 0.232684 0.05308389 0.214284 0.06576997 0.2330459 0.06880396 0.233314 0.08603596 0.21444 0.08391696 0.214536 0.103235 0.2330459 0.06880396 0.21444 0.08391696 0.233314 0.08603596 0.233314 0.08603596 0.214536 0.103235 0.233479 0.104324 0.31031 0.117727 0.311259 0.118409 0.311198 0.12076 0.310386 0.119538 0.31031 0.117727 0.311198 0.12076 0.310432 0.121351 0.310386 0.119538 0.311198 0.12076 0.310205 0.115929 0.311358 0.116151 0.311259 0.118409 0.31031 0.117727 0.310205 0.115929 0.311259 0.118409 0.309895 0.112253 0.311496 0.11403 0.311358 0.116151 0.310069 0.114129 0.309895 0.112253 0.311358 0.116151 0.310205 0.115929 0.310069 0.114129 0.311358 0.116151 0.309385 0.108048 0.311668 0.1120859 0.311496 0.11403 0.309895 0.112253 0.309385 0.108048 0.311496 0.11403 0.308633 0.103446 0.311872 0.110359 0.311668 0.1120859 0.309385 0.108048 0.308633 0.103446 0.311668 0.1120859 0.30725 0.09708696 0.312103 0.108884 0.311872 0.110359 0.30753 0.09823501 0.30725 0.09708696 0.311872 0.110359 0.308633 0.103446 0.30753 0.09823501 0.311872 0.110359 0.307692 0.09417396 0.312358 0.107691 0.312103 0.108884 0.30725 0.09708696 0.307692 0.09417396 0.312103 0.108884 0.308212 0.09189796 0.312631 0.106807 0.312358 0.107691 0.307692 0.09417396 0.308212 0.09189796 0.312358 0.107691 0.308769 0.09029096 0.312917 0.10625 0.312631 0.106807 0.308212 0.09189796 0.308769 0.09029096 0.312631 0.106807 0.30935 0.08939695 0.313211 0.106035 0.312917 0.10625 0.308769 0.09029096 0.30935 0.08939695 0.312917 0.10625 0.309943 0.08924597 0.313506 0.106168 0.313211 0.106035 0.30935 0.08939695 0.309943 0.08924597 0.313211 0.106035 0.310536 0.08985298 0.313796 0.106649 0.313506 0.106168 0.309943 0.08924597 0.310536 0.08985298 0.313506 0.106168 0.311113 0.09121495 0.314076 0.107471 0.313796 0.106649 0.310536 0.08985298 0.311113 0.09121495 0.313796 0.106649 0.311663 0.09331095 0.314339 0.108619 0.314076 0.107471 0.311113 0.09121495 0.311663 0.09331095 0.314076 0.107471 0.312171 0.09610396 0.31458 0.110071 0.314339 0.108619 0.311663 0.09331095 0.312171 0.09610396 0.314339 0.108619 0.312626 0.09953695 0.314794 0.111798 0.31458 0.110071 0.312171 0.09610396 0.312626 0.09953695 0.31458 0.110071 0.313015 0.103534 0.314976 0.113765 0.314794 0.111798 0.312626 0.09953695 0.313015 0.103534 0.314794 0.111798 0.313329 0.108005 0.315121 0.115931 0.314976 0.113765 0.313015 0.103534 0.313329 0.108005 0.314976 0.113765 0.31356 0.112844 0.315228 0.118252 0.315121 0.115931 0.313329 0.108005 0.31356 0.112844 0.315121 0.115931 0.3137 0.117936 0.315293 0.120678 0.315228 0.118252 0.31356 0.112844 0.3137 0.117936 0.315228 0.118252 0.309346 0.107983 0.3137 0.117936 0.31356 0.112844 0.309346 0.107983 0.309542 0.115474 0.3137 0.117936 0.309025 0.100865 0.31356 0.112844 0.313329 0.108005 0.309025 0.100865 0.309346 0.107983 0.31356 0.112844 0.308589 0.09429198 0.313329 0.108005 0.313015 0.103534 0.308589 0.09429198 0.309025 0.100865 0.313329 0.108005 0.308048 0.08841496 0.313015 0.103534 0.312626 0.09953695 0.308048 0.08841496 0.308589 0.09429198 0.313015 0.103534 0.307418 0.08336496 0.312626 0.09953695 0.312171 0.09610396 0.307418 0.08336496 0.308048 0.08841496 0.312626 0.09953695 0.306714 0.07924699 0.312171 0.09610396 0.311663 0.09331095 0.306714 0.07924699 0.307418 0.08336496 0.312171 0.09610396 0.305954 0.076137 0.311663 0.09331095 0.311113 0.09121495 0.305954 0.076137 0.306714 0.07924699 0.311663 0.09331095 0.305157 0.07408601 0.311113 0.09121495 0.310536 0.08985298 0.305157 0.07408601 0.305954 0.076137 0.311113 0.09121495 0.30434 0.07311499 0.310536 0.08985298 0.309943 0.08924597 0.30434 0.07311499 0.305157 0.07408601 0.310536 0.08985298 0.303522 0.07322496 0.309943 0.08924597 0.30935 0.08939695 0.303522 0.07322496 0.30434 0.07311499 0.309943 0.08924597 0.302721 0.07438695 0.30935 0.08939695 0.308769 0.09029096 0.302721 0.07438695 0.303522 0.07322496 0.30935 0.08939695 0.301952 0.07655799 0.308769 0.09029096 0.308212 0.09189796 0.301952 0.07655799 0.302721 0.07438695 0.308769 0.09029096 0.301269 0.079683 0.308212 0.09189796 0.307692 0.09417396 0.301269 0.079683 0.301952 0.07655799 0.308212 0.09189796 0.305968 0.09240198 0.307692 0.09417396 0.30725 0.09708696 0.303754 0.085783 0.307692 0.09417396 0.305968 0.09240198 0.303754 0.085783 0.301269 0.079683 0.307692 0.09417396 0.300578 0.100754 0.30725 0.09708696 0.30753 0.09823501 0.298665 0.09346997 0.305968 0.09240198 0.30725 0.09708696 0.300578 0.100754 0.298665 0.09346997 0.30725 0.09708696 0.300578 0.100754 0.30753 0.09823501 0.308633 0.103446 0.301954 0.108169 0.308633 0.103446 0.309385 0.108048 0.301954 0.108169 0.300578 0.100754 0.308633 0.103446 0.301954 0.108169 0.309385 0.108048 0.309895 0.112253 0.301954 0.108169 0.309895 0.112253 0.310069 0.114129 0.30278 0.115655 0.310069 0.114129 0.310205 0.115929 0.30278 0.115655 0.301954 0.108169 0.310069 0.114129 0.30278 0.115655 0.310205 0.115929 0.31031 0.117727 0.30278 0.115655 0.31031 0.117727 0.310386 0.119538 0.30278 0.115655 0.310386 0.119538 0.310432 0.121351 0.298665 0.09346997 0.303754 0.085783 0.305968 0.09240198 0.302545 0.1037639 0.309542 0.115474 0.309346 0.107983 0.302545 0.1037639 0.302772 0.113342 0.309542 0.115474 0.302172 0.09465098 0.309346 0.107983 0.309025 0.100865 0.302172 0.09465098 0.302545 0.1037639 0.309346 0.107983 0.301665 0.08621299 0.309025 0.100865 0.308589 0.09429198 0.301665 0.08621299 0.302172 0.09465098 0.309025 0.100865 0.301037 0.07863897 0.308589 0.09429198 0.308048 0.08841496 0.301037 0.07863897 0.301665 0.08621299 0.308589 0.09429198 0.300305 0.07208496 0.308048 0.08841496 0.307418 0.08336496 0.300305 0.07208496 0.301037 0.07863897 0.308048 0.08841496 0.299487 0.066679 0.307418 0.08336496 0.306714 0.07924699 0.299487 0.066679 0.300305 0.07208496 0.307418 0.08336496 0.298603 0.06251198 0.306714 0.07924699 0.305954 0.076137 0.298603 0.06251198 0.299487 0.066679 0.306714 0.07924699 0.297674 0.05964189 0.305954 0.076137 0.305157 0.07408601 0.297674 0.05964189 0.298603 0.06251198 0.305954 0.076137 0.29672 0.05809491 0.305157 0.07408601 0.30434 0.07311499 0.29672 0.05809491 0.297674 0.05964189 0.305157 0.07408601 0.295762 0.05786699 0.30434 0.07311499 0.303522 0.07322496 0.295762 0.05786699 0.29672 0.05809491 0.30434 0.07311499 0.294818 0.05892693 0.303522 0.07322496 0.302721 0.07438695 0.294818 0.05892693 0.295762 0.05786699 0.303522 0.07322496 0.293907 0.06121999 0.302721 0.07438695 0.301952 0.07655799 0.293907 0.06121999 0.294818 0.05892693 0.302721 0.07438695 0.30052 0.07803601 0.301952 0.07655799 0.301269 0.079683 0.296701 0.070616 0.301952 0.07655799 0.30052 0.07803601 0.293083 0.06470096 0.293907 0.06121999 0.301952 0.07655799 0.296701 0.070616 0.293083 0.06470096 0.301952 0.07655799 0.296225 0.08634698 0.301269 0.079683 0.303754 0.085783 0.293258 0.07939696 0.30052 0.07803601 0.301269 0.079683 0.296225 0.08634698 0.293258 0.07939696 0.301269 0.079683 0.298665 0.09346997 0.296225 0.08634698 0.303754 0.085783 0.293258 0.07939696 0.296701 0.070616 0.30052 0.07803601 0.29316 0.09960198 0.302772 0.113342 0.302545 0.1037639 0.29316 0.09960198 0.29341 0.111233 0.302772 0.113342 0.292752 0.08854299 0.302545 0.1037639 0.302172 0.09465098 0.292752 0.08854299 0.29316 0.09960198 0.302545 0.1037639 0.292197 0.07831299 0.302172 0.09465098 0.301665 0.08621299 0.292197 0.07831299 0.292752 0.08854299 0.302172 0.09465098 0.29151 0.06913799 0.301665 0.08621299 0.301037 0.07863897 0.29151 0.06913799 0.292197 0.07831299 0.301665 0.08621299 0.290711 0.06120693 0.301037 0.07863897 0.300305 0.07208496 0.290711 0.06120693 0.29151 0.06913799 0.301037 0.07863897 0.289819 0.05466598 0.300305 0.07208496 0.299487 0.066679 0.289819 0.05466598 0.290711 0.06120693 0.300305 0.07208496 0.288857 0.04961997 0.299487 0.066679 0.298603 0.06251198 0.288857 0.04961997 0.289819 0.05466598 0.299487 0.066679 0.287847 0.04613095 0.298603 0.06251198 0.297674 0.05964189 0.287847 0.04613095 0.288857 0.04961997 0.298603 0.06251198 0.286812 0.04421997 0.297674 0.05964189 0.29672 0.05809491 0.286812 0.04421997 0.287847 0.04613095 0.297674 0.05964189 0.285774 0.0438739 0.29672 0.05809491 0.295762 0.05786699 0.285774 0.0438739 0.286812 0.04421997 0.29672 0.05809491 0.284752 0.04505091 0.295762 0.05786699 0.294818 0.05892693 0.284752 0.04505091 0.285774 0.0438739 0.295762 0.05786699 0.283766 0.04767799 0.294818 0.05892693 0.293907 0.06121999 0.283766 0.04767799 0.284752 0.04505091 0.294818 0.05892693 0.292308 0.063542 0.293907 0.06121999 0.293083 0.06470096 0.286414 0.05569398 0.293907 0.06121999 0.292308 0.063542 0.283076 0.05186992 0.283766 0.04767799 0.293907 0.06121999 0.286414 0.05569398 0.283076 0.05186992 0.293907 0.06121999 0.289773 0.07265299 0.293083 0.06470096 0.296701 0.070616 0.285793 0.06616997 0.292308 0.063542 0.293083 0.06470096 0.289773 0.07265299 0.285793 0.06616997 0.293083 0.06470096 0.293258 0.07939696 0.289773 0.07265299 0.296701 0.070616 0.285793 0.06616997 0.286414 0.05569398 0.292308 0.063542 0.281544 0.108161 0.29341 0.111233 0.29316 0.09960198 0.281247 0.09360599 0.29316 0.09960198 0.292752 0.08854299 0.281247 0.09360599 0.281544 0.108161 0.29316 0.09960198 0.280763 0.07990497 0.292752 0.08854299 0.292197 0.07831299 0.280763 0.07990497 0.281247 0.09360599 0.292752 0.08854299 0.280109 0.06743395 0.292197 0.07831299 0.29151 0.06913799 0.280109 0.06743395 0.280763 0.07990497 0.292197 0.07831299 0.279307 0.05650889 0.29151 0.06913799 0.290711 0.06120693 0.279307 0.05650889 0.280109 0.06743395 0.29151 0.06913799 0.278382 0.04738193 0.290711 0.06120693 0.289819 0.05466598 0.278382 0.04738193 0.279307 0.05650889 0.290711 0.06120693 0.277363 0.04022896 0.289819 0.05466598 0.288857 0.04961997 0.277363 0.04022896 0.278382 0.04738193 0.289819 0.05466598 0.276279 0.03515791 0.288857 0.04961997 0.287847 0.04613095 0.276279 0.03515791 0.277363 0.04022896 0.288857 0.04961997 0.275158 0.03221189 0.287847 0.04613095 0.286812 0.04421997 0.275158 0.03221189 0.276279 0.03515791 0.287847 0.04613095 0.274029 0.03137499 0.286812 0.04421997 0.285774 0.0438739 0.274029 0.03137499 0.275158 0.03221189 0.286812 0.04421997 0.272918 0.032579 0.285774 0.0438739 0.284752 0.04505091 0.272918 0.032579 0.274029 0.03137499 0.285774 0.0438739 0.271847 0.03571891 0.284752 0.04505091 0.283766 0.04767799 0.271847 0.03571891 0.272918 0.032579 0.284752 0.04505091 0.277894 0.04662793 0.283766 0.04767799 0.283076 0.05186992 0.271847 0.03571891 0.283766 0.04767799 0.277894 0.04662793 0.281345 0.05999696 0.283076 0.05186992 0.286414 0.05569398 0.276445 0.05415689 0.277894 0.04662793 0.283076 0.05186992 0.281345 0.05999696 0.276445 0.05415689 0.283076 0.05186992 0.285793 0.06616997 0.281345 0.05999696 0.286414 0.05569398 0.27101 0.04072993 0.271847 0.03571891 0.277894 0.04662793 0.271115 0.04868096 0.27101 0.04072993 0.277894 0.04662793 0.276445 0.05415689 0.271115 0.04868096 0.277894 0.04662793 0.267165 0.091991 0.281544 0.108161 0.281247 0.09360599 0.267165 0.091991 0.267411 0.107366 0.281544 0.108161 0.266764 0.07742697 0.281247 0.09360599 0.280763 0.07990497 0.266764 0.07742697 0.267165 0.091991 0.281247 0.09360599 0.26622 0.06403195 0.280763 0.07990497 0.280109 0.06743395 0.26622 0.06403195 0.266764 0.07742697 0.280763 0.07990497 0.26555 0.05211198 0.280109 0.06743395 0.279307 0.05650889 0.26555 0.05211198 0.26622 0.06403195 0.280109 0.06743395 0.264774 0.04191297 0.279307 0.05650889 0.278382 0.04738193 0.264774 0.04191297 0.26555 0.05211198 0.279307 0.05650889 0.263912 0.03361588 0.278382 0.04738193 0.277363 0.04022896 0.263912 0.03361588 0.264774 0.04191297 0.278382 0.04738193 0.262988 0.0273379 0.277363 0.04022896 0.276279 0.03515791 0.262988 0.0273379 0.263912 0.03361588 0.277363 0.04022896 0.262025 0.02313399 0.276279 0.03515791 0.275158 0.03221189 0.262025 0.02313399 0.262988 0.0273379 0.276279 0.03515791 0.261044 0.021007 0.275158 0.03221189 0.274029 0.03137499 0.261044 0.021007 0.262025 0.02313399 0.275158 0.03221189 0.260066 0.02091199 0.274029 0.03137499 0.272918 0.032579 0.260066 0.02091199 0.261044 0.021007 0.274029 0.03137499 0.259111 0.02276599 0.272918 0.032579 0.271847 0.03571891 0.259111 0.02276599 0.260066 0.02091199 0.272918 0.032579 0.258195 0.02645593 0.271847 0.03571891 0.27101 0.04072993 0.258195 0.02645593 0.259111 0.02276599 0.271847 0.03571891 0.258195 0.02645593 0.27101 0.04072993 0.266461 0.0373879 0.26538 0.04360193 0.266461 0.0373879 0.27101 0.04072993 0.271115 0.04868096 0.26538 0.04360193 0.27101 0.04072993 0.257315 0.03178691 0.258195 0.02645593 0.266461 0.0373879 0.259285 0.03895998 0.257315 0.03178691 0.266461 0.0373879 0.26538 0.04360193 0.259285 0.03895998 0.266461 0.0373879 0.251258 0.105716 0.267411 0.107366 0.267165 0.091991 0.251042 0.08875596 0.267165 0.091991 0.266764 0.07742697 0.251042 0.08875596 0.251258 0.105716 0.267165 0.091991 0.250692 0.07273095 0.266764 0.07742697 0.26622 0.06403195 0.250692 0.07273095 0.251042 0.08875596 0.266764 0.07742697 0.250217 0.05804896 0.26622 0.06403195 0.26555 0.05211198 0.250217 0.05804896 0.250692 0.07273095 0.26622 0.06403195 0.249634 0.04505497 0.26555 0.05211198 0.264774 0.04191297 0.249634 0.04505497 0.250217 0.05804896 0.26555 0.05211198 0.248959 0.03402096 0.264774 0.04191297 0.263912 0.03361588 0.248959 0.03402096 0.249634 0.04505497 0.264774 0.04191297 0.248214 0.02513897 0.263912 0.03361588 0.262988 0.0273379 0.248214 0.02513897 0.248959 0.03402096 0.263912 0.03361588 0.247417 0.01852697 0.262988 0.0273379 0.262025 0.02313399 0.247417 0.01852697 0.248214 0.02513897 0.262988 0.0273379 0.24659 0.01423192 0.262025 0.02313399 0.261044 0.021007 0.24659 0.01423192 0.247417 0.01852697 0.262025 0.02313399 0.245751 0.01223999 0.261044 0.021007 0.260066 0.02091199 0.245751 0.01223999 0.24659 0.01423192 0.261044 0.021007 0.244918 0.0124849 0.260066 0.02091199 0.259111 0.02276599 0.244918 0.0124849 0.245751 0.01223999 0.260066 0.02091199 0.244108 0.01486092 0.259111 0.02276599 0.258195 0.02645593 0.244108 0.01486092 0.244918 0.0124849 0.259111 0.02276599 0.243336 0.01922988 0.258195 0.02645593 0.257315 0.03178691 0.243336 0.01922988 0.244108 0.01486092 0.258195 0.02645593 0.243336 0.01922988 0.257315 0.03178691 0.253145 0.02967 0.252854 0.03477489 0.253145 0.02967 0.257315 0.03178691 0.259285 0.03895998 0.252854 0.03477489 0.257315 0.03178691 0.2426069 0.02539098 0.243336 0.01922988 0.253145 0.02967 0.246128 0.031075 0.2426069 0.02539098 0.253145 0.02967 0.252854 0.03477489 0.246128 0.031075 0.253145 0.02967 0.233479 0.104324 0.251258 0.105716 0.251042 0.08875596 0.233314 0.08603596 0.251042 0.08875596 0.250692 0.07273095 0.233314 0.08603596 0.233479 0.104324 0.251042 0.08875596 0.2330459 0.06880396 0.250692 0.07273095 0.250217 0.05804896 0.2330459 0.06880396 0.233314 0.08603596 0.250692 0.07273095 0.232684 0.05308389 0.250217 0.05804896 0.249634 0.04505497 0.232684 0.05308389 0.2330459 0.06880396 0.250217 0.05804896 0.23224 0.039258 0.249634 0.04505497 0.248959 0.03402096 0.23224 0.039258 0.232684 0.05308389 0.249634 0.04505497 0.231728 0.027619 0.248959 0.03402096 0.248214 0.02513897 0.231728 0.027619 0.23224 0.039258 0.248959 0.03402096 0.231164 0.018368 0.248214 0.02513897 0.247417 0.01852697 0.231164 0.018368 0.231728 0.027619 0.248214 0.02513897 0.2305639 0.01161897 0.247417 0.01852697 0.24659 0.01423192 0.2305639 0.01161897 0.231164 0.018368 0.247417 0.01852697 0.229943 0.007408976 0.24659 0.01423192 0.245751 0.01223999 0.229943 0.007408976 0.2305639 0.01161897 0.24659 0.01423192 0.229317 0.005703985 0.245751 0.01223999 0.244918 0.0124849 0.229317 0.005703985 0.229943 0.007408976 0.245751 0.01223999 0.228698 0.006415963 0.244918 0.0124849 0.244108 0.01486092 0.228698 0.006415963 0.229317 0.005703985 0.244918 0.0124849 0.228099 0.009412944 0.244108 0.01486092 0.243336 0.01922988 0.228099 0.009412944 0.228698 0.006415963 0.244108 0.01486092 0.227531 0.01453298 0.243336 0.01922988 0.2426069 0.02539098 0.227531 0.01453298 0.228099 0.009412944 0.243336 0.01922988 0.227531 0.01453298 0.2426069 0.02539098 0.239049 0.024266 0.239142 0.0278809 0.239049 0.024266 0.2426069 0.02539098 0.246128 0.031075 0.239142 0.0278809 0.2426069 0.02539098 0.2269909 0.021555 0.227531 0.01453298 0.239049 0.024266 0.231936 0.02520895 0.2269909 0.021555 0.239049 0.024266 0.239142 0.0278809 0.231936 0.02520895 0.239049 0.024266 0.224555 0.02307695 0.224334 0.02117788 0.2269909 0.021555 0.231936 0.02520895 0.224555 0.02307695 0.2269909 0.021555 0.216017 0.05768996 0.224555 0.02307695 0.231936 0.02520895 0.210212 0.05585998 0.204269 0.054542 0.224555 0.02307695 0.216017 0.05768996 0.210212 0.05585998 0.224555 0.02307695 0.221638 0.06001991 0.231936 0.02520895 0.239142 0.0278809 0.221638 0.06001991 0.216017 0.05768996 0.231936 0.02520895 0.227032 0.06282895 0.239142 0.0278809 0.246128 0.031075 0.227032 0.06282895 0.221638 0.06001991 0.239142 0.0278809 0.227032 0.06282895 0.246128 0.031075 0.252854 0.03477489 0.232159 0.06609797 0.252854 0.03477489 0.259285 0.03895998 0.232159 0.06609797 0.227032 0.06282895 0.252854 0.03477489 0.23698 0.06979995 0.259285 0.03895998 0.26538 0.04360193 0.23698 0.06979995 0.232159 0.06609797 0.259285 0.03895998 0.2414579 0.07390797 0.26538 0.04360193 0.271115 0.04868096 0.2414579 0.07390797 0.23698 0.06979995 0.26538 0.04360193 0.245561 0.07839095 0.271115 0.04868096 0.276445 0.05415689 0.245561 0.07839095 0.2414579 0.07390797 0.271115 0.04868096 0.245561 0.07839095 0.276445 0.05415689 0.281345 0.05999696 0.249256 0.08321499 0.281345 0.05999696 0.285793 0.06616997 0.249256 0.08321499 0.245561 0.07839095 0.281345 0.05999696 0.252516 0.08834099 0.285793 0.06616997 0.289773 0.07265299 0.252516 0.08834099 0.249256 0.08321499 0.285793 0.06616997 0.255317 0.09373098 0.289773 0.07265299 0.293258 0.07939696 0.255317 0.09373098 0.252516 0.08834099 0.289773 0.07265299 0.257637 0.09934395 0.293258 0.07939696 0.296225 0.08634698 0.257637 0.09934395 0.255317 0.09373098 0.293258 0.07939696 0.257637 0.09934395 0.296225 0.08634698 0.298665 0.09346997 0.259459 0.105136 0.298665 0.09346997 0.300578 0.100754 0.259459 0.105136 0.257637 0.09934395 0.298665 0.09346997 0.260771 0.111066 0.300578 0.100754 0.301954 0.108169 0.260771 0.111066 0.259459 0.105136 0.300578 0.100754 0.261562 0.117087 0.301954 0.108169 0.30278 0.115655 0.261562 0.117087 0.260771 0.111066 0.301954 0.108169 0.261562 0.117087 0.30278 0.115655 0.303055 0.123156 0.261826 0.123156 0.303055 0.123156 0.30278 0.130657 0.261562 0.117087 0.303055 0.123156 0.261826 0.123156 0.261562 0.129225 0.30278 0.130657 0.301954 0.138144 0.261562 0.129225 0.261826 0.123156 0.30278 0.130657 0.260771 0.135246 0.301954 0.138144 0.300578 0.1455579 0.260771 0.135246 0.261562 0.129225 0.301954 0.138144 0.286745 0.145876 0.300578 0.1455579 0.298665 0.152842 0.286745 0.145876 0.260771 0.135246 0.300578 0.1455579 0.284816 0.153282 0.298665 0.152842 0.296224 0.159965 0.284816 0.153282 0.286745 0.145876 0.298665 0.152842 0.282347 0.160542 0.296224 0.159965 0.293258 0.1669149 0.282347 0.160542 0.284816 0.153282 0.296224 0.159965 0.281442 0.162752 0.293258 0.1669149 0.289774 0.173659 0.281442 0.162752 0.282347 0.160542 0.293258 0.1669149 0.278534 0.168118 0.289774 0.173659 0.285793 0.180142 0.280636 0.164485 0.281442 0.162752 0.289774 0.173659 0.279912 0.165877 0.280636 0.164485 0.289774 0.173659 0.279231 0.167052 0.279912 0.165877 0.289774 0.173659 0.278534 0.168118 0.279231 0.167052 0.289774 0.173659 0.256701 0.162756 0.285793 0.180142 0.281345 0.186315 0.277786 0.169082 0.278534 0.168118 0.285793 0.180142 0.277127 0.169714 0.277786 0.169082 0.285793 0.180142 0.276676 0.169897 0.277127 0.169714 0.285793 0.180142 0.25905 0.160416 0.276676 0.169897 0.285793 0.180142 0.258389 0.1613309 0.25905 0.160416 0.285793 0.180142 0.257697 0.162136 0.258389 0.1613309 0.285793 0.180142 0.257099 0.162642 0.257697 0.162136 0.285793 0.180142 0.256701 0.162756 0.257099 0.162642 0.285793 0.180142 0.249256 0.163097 0.281345 0.186315 0.276445 0.192155 0.256701 0.162756 0.281345 0.186315 0.249256 0.163097 0.245561 0.167921 0.276445 0.192155 0.271116 0.19763 0.245561 0.167921 0.249256 0.163097 0.276445 0.192155 0.2414579 0.172404 0.271116 0.19763 0.265381 0.20271 0.2414579 0.172404 0.245561 0.167921 0.271116 0.19763 0.23698 0.176512 0.265381 0.20271 0.259286 0.207352 0.23698 0.176512 0.2414579 0.172404 0.265381 0.20271 0.232159 0.180214 0.259286 0.207352 0.252855 0.211536 0.232159 0.180214 0.23698 0.176512 0.259286 0.207352 0.232159 0.180214 0.252855 0.211536 0.246128 0.215236 0.227032 0.183483 0.246128 0.215236 0.239143 0.2184309 0.227032 0.183483 0.232159 0.180214 0.246128 0.215236 0.221638 0.1862919 0.239143 0.2184309 0.231936 0.221103 0.221638 0.1862919 0.227032 0.183483 0.239143 0.2184309 0.216017 0.1886219 0.231936 0.221103 0.224556 0.2232339 0.216017 0.1886219 0.221638 0.1862919 0.231936 0.221103 0.210212 0.190452 0.216017 0.1886219 0.224556 0.2232339 0.254487 0.128929 0.261826 0.123156 0.261562 0.129225 0.254487 0.117383 0.261562 0.117087 0.261826 0.123156 0.254487 0.128929 0.254487 0.117383 0.261826 0.123156 0.254487 0.128929 0.261562 0.129225 0.260771 0.135246 0.283843 0.145682 0.259459 0.141176 0.260771 0.135246 0.252369 0.140278 0.260771 0.135246 0.259459 0.141176 0.285281 0.145778 0.260771 0.135246 0.286745 0.145876 0.285281 0.145778 0.283843 0.145682 0.260771 0.135246 0.252369 0.140278 0.254487 0.128929 0.260771 0.135246 0.262971 0.144289 0.257637 0.146969 0.259459 0.141176 0.252369 0.140278 0.259459 0.141176 0.257637 0.146969 0.283843 0.145682 0.281947 0.15282 0.259459 0.141176 0.265547 0.144461 0.259459 0.141176 0.281947 0.15282 0.264246 0.144374 0.259459 0.141176 0.265547 0.144461 0.264246 0.144374 0.262971 0.144289 0.259459 0.141176 0.259523 0.154145 0.255317 0.152581 0.257637 0.146969 0.2482039 0.151046 0.257637 0.146969 0.255317 0.152581 0.261412 0.149269 0.259523 0.154145 0.257637 0.146969 0.262971 0.144289 0.261412 0.149269 0.257637 0.146969 0.2482039 0.151046 0.252369 0.140278 0.257637 0.146969 0.257142 0.159918 0.252516 0.157971 0.255317 0.152581 0.2482039 0.151046 0.255317 0.152581 0.252516 0.157971 0.257571 0.158802 0.257142 0.159918 0.255317 0.152581 0.258118 0.15746 0.257571 0.158802 0.255317 0.152581 0.258793 0.1558589 0.258118 0.15746 0.255317 0.152581 0.259523 0.154145 0.258793 0.1558589 0.255317 0.152581 0.256701 0.162756 0.249256 0.163097 0.252516 0.157971 0.242132 0.160866 0.252516 0.157971 0.249256 0.163097 0.25652 0.162499 0.256701 0.162756 0.252516 0.157971 0.256553 0.161876 0.25652 0.162499 0.252516 0.157971 0.25679 0.160949 0.256553 0.161876 0.252516 0.157971 0.257142 0.159918 0.25679 0.160949 0.252516 0.157971 0.242132 0.160866 0.2482039 0.151046 0.252516 0.157971 0.242132 0.160866 0.249256 0.163097 0.245561 0.167921 0.234356 0.169405 0.245561 0.167921 0.2414579 0.172404 0.234356 0.169405 0.242132 0.160866 0.245561 0.167921 0.225139 0.17637 0.2414579 0.172404 0.23698 0.176512 0.225139 0.17637 0.234356 0.169405 0.2414579 0.172404 0.225139 0.17637 0.23698 0.176512 0.232159 0.180214 0.214793 0.181524 0.232159 0.180214 0.227032 0.183483 0.214793 0.181524 0.225139 0.17637 0.232159 0.180214 0.20367 0.1846899 0.227032 0.183483 0.221638 0.1862919 0.20367 0.1846899 0.214793 0.181524 0.227032 0.183483 0.162666 0.1862919 0.221638 0.1862919 0.216017 0.1886219 0.192152 0.185757 0.221638 0.1862919 0.162666 0.1862919 0.192152 0.185757 0.20367 0.1846899 0.221638 0.1862919 0.168288 0.1886219 0.216017 0.1886219 0.210212 0.190452 0.162666 0.1862919 0.216017 0.1886219 0.168288 0.1886219 0.174093 0.190452 0.210212 0.190452 0.204269 0.19177 0.168288 0.1886219 0.210212 0.190452 0.174093 0.190452 0.180036 0.19177 0.204269 0.19177 0.198234 0.192564 0.174093 0.190452 0.204269 0.19177 0.180036 0.19177 0.186071 0.192564 0.198234 0.192564 0.192152 0.19283 0.180036 0.19177 0.198234 0.192564 0.186071 0.192564 0.192152 0.185757 0.162666 0.1862919 0.157272 0.183483 0.169512 0.181524 0.157272 0.183483 0.152145 0.180214 0.180634 0.1846899 0.192152 0.185757 0.157272 0.183483 0.169512 0.181524 0.180634 0.1846899 0.157272 0.183483 0.169512 0.181524 0.152145 0.180214 0.147325 0.176512 0.159165 0.17637 0.147325 0.176512 0.142846 0.172404 0.159165 0.17637 0.169512 0.181524 0.147325 0.176512 0.149948 0.169405 0.142846 0.172404 0.1387439 0.167921 0.149948 0.169405 0.159165 0.17637 0.142846 0.172404 0.149948 0.169405 0.1387439 0.167921 0.135048 0.163097 0.12742 0.160753 0.131788 0.157971 0.135048 0.163097 0.142172 0.160866 0.135048 0.163097 0.131788 0.157971 0.127667 0.161686 0.12742 0.160753 0.135048 0.163097 0.1277199 0.162344 0.127667 0.161686 0.135048 0.163097 0.127555 0.162633 0.1277199 0.162344 0.135048 0.163097 0.142172 0.160866 0.149948 0.169405 0.135048 0.163097 0.125433 0.155696 0.128988 0.152581 0.131788 0.157971 0.142172 0.160866 0.131788 0.157971 0.128988 0.152581 0.126107 0.157303 0.125433 0.155696 0.131788 0.157971 0.126649 0.158637 0.126107 0.157303 0.131788 0.157971 0.127072 0.15974 0.126649 0.158637 0.131788 0.157971 0.12742 0.160753 0.127072 0.15974 0.131788 0.157971 0.12286 0.14919 0.126668 0.146969 0.128988 0.152581 0.1360999 0.151046 0.128988 0.152581 0.126668 0.146969 0.124711 0.1539919 0.12286 0.14919 0.128988 0.152581 0.125433 0.155696 0.124711 0.1539919 0.128988 0.152581 0.1360999 0.151046 0.142172 0.160866 0.128988 0.152581 0.121328 0.14429 0.124845 0.141176 0.126668 0.146969 0.1360999 0.151046 0.126668 0.146969 0.124845 0.141176 0.12286 0.14919 0.121328 0.14429 0.126668 0.146969 0.131935 0.140278 0.124845 0.141176 0.123534 0.135246 0.120054 0.144374 0.124845 0.141176 0.121328 0.14429 0.120054 0.144374 0.118752 0.144461 0.124845 0.141176 0.131935 0.140278 0.1360999 0.151046 0.124845 0.141176 0.131935 0.140278 0.123534 0.135246 0.122743 0.129225 0.129818 0.128929 0.122743 0.129225 0.122478 0.123156 0.129818 0.128929 0.131935 0.140278 0.122743 0.129225 0.129818 0.117383 0.122478 0.123156 0.122743 0.117087 0.129818 0.117383 0.129818 0.128929 0.122478 0.123156 0.282347 0.145909 0.286745 0.145876 0.284816 0.153282 0.276417 0.145803 0.285281 0.145778 0.286745 0.145876 0.27662 0.145843 0.276417 0.145803 0.286745 0.145876 0.277482 0.145878 0.27662 0.145843 0.286745 0.145876 0.278873 0.145903 0.277482 0.145878 0.286745 0.145876 0.282347 0.145909 0.278873 0.145903 0.286745 0.145876 0.282347 0.145909 0.284816 0.153282 0.282347 0.160542 0.282347 0.145909 0.282347 0.160542 0.281442 0.162752 0.282347 0.145909 0.281442 0.162752 0.280636 0.164485 0.280583 0.145914 0.280636 0.164485 0.279912 0.165877 0.282347 0.145909 0.280636 0.164485 0.280583 0.145914 0.280583 0.145914 0.279912 0.165877 0.279231 0.167052 0.278873 0.145903 0.279231 0.167052 0.278534 0.168118 0.280583 0.145914 0.279231 0.167052 0.278873 0.145903 0.278873 0.145903 0.278534 0.168118 0.277786 0.169082 0.277482 0.145878 0.277786 0.169082 0.277127 0.169714 0.278873 0.145903 0.277786 0.169082 0.277482 0.145878 0.277482 0.145878 0.277127 0.169714 0.276676 0.169897 0.259705 0.15939 0.276441 0.169664 0.276676 0.169897 0.27662 0.145843 0.276676 0.169897 0.276441 0.169664 0.25905 0.160416 0.259705 0.15939 0.276676 0.169897 0.277482 0.145878 0.276676 0.169897 0.27662 0.145843 0.259705 0.15939 0.276423 0.169 0.276441 0.169664 0.276417 0.145803 0.276441 0.169664 0.276423 0.169 0.27662 0.145843 0.276441 0.169664 0.276417 0.145803 0.259705 0.15939 0.276642 0.167905 0.276423 0.169 0.276417 0.145803 0.276423 0.169 0.276642 0.167905 0.260433 0.158109 0.277077 0.166443 0.276642 0.167905 0.276901 0.145765 0.276642 0.167905 0.277077 0.166443 0.259705 0.15939 0.260433 0.158109 0.276642 0.167905 0.276417 0.145803 0.276642 0.167905 0.276901 0.145765 0.261235 0.156523 0.277687 0.164683 0.277077 0.166443 0.276901 0.145765 0.277077 0.166443 0.277687 0.164683 0.260433 0.158109 0.261235 0.156523 0.277077 0.166443 0.261235 0.156523 0.278495 0.162515 0.277687 0.164683 0.277995 0.1457329 0.277687 0.164683 0.278495 0.162515 0.276901 0.145765 0.277687 0.164683 0.277995 0.1457329 0.261998 0.154816 0.279533 0.159815 0.278495 0.162515 0.277995 0.1457329 0.278495 0.162515 0.279533 0.159815 0.261235 0.156523 0.261998 0.154816 0.278495 0.162515 0.283843 0.145682 0.279533 0.159815 0.281947 0.15282 0.263948 0.1496919 0.281947 0.15282 0.279533 0.159815 0.279533 0.145714 0.279533 0.159815 0.283843 0.145682 0.261998 0.154816 0.263948 0.1496919 0.279533 0.159815 0.277995 0.1457329 0.279533 0.159815 0.279533 0.145714 0.263948 0.1496919 0.265547 0.144461 0.281947 0.15282 0.279533 0.145714 0.283843 0.145682 0.285281 0.145778 0.277995 0.1457329 0.279533 0.145714 0.285281 0.145778 0.276901 0.145765 0.277995 0.1457329 0.285281 0.145778 0.276417 0.145803 0.276901 0.145765 0.285281 0.145778 0.261998 0.144484 0.265547 0.144461 0.263948 0.1496919 0.256528 0.144389 0.264246 0.144374 0.265547 0.144461 0.256686 0.144424 0.256528 0.144389 0.265547 0.144461 0.257464 0.144455 0.256686 0.144424 0.265547 0.144461 0.258748 0.144477 0.257464 0.144455 0.265547 0.144461 0.261998 0.144484 0.258748 0.144477 0.265547 0.144461 0.261998 0.144484 0.263948 0.1496919 0.261998 0.154816 0.261998 0.144484 0.261998 0.154816 0.261235 0.156523 0.261998 0.144484 0.261235 0.156523 0.260433 0.158109 0.260341 0.144488 0.260433 0.158109 0.259705 0.15939 0.261998 0.144484 0.260433 0.158109 0.260341 0.144488 0.260341 0.144488 0.259705 0.15939 0.25905 0.160416 0.258748 0.144477 0.25905 0.160416 0.258389 0.1613309 0.260341 0.144488 0.25905 0.160416 0.258748 0.144477 0.258748 0.144477 0.258389 0.1613309 0.257697 0.162136 0.257464 0.144455 0.257697 0.162136 0.257099 0.162642 0.258748 0.144477 0.257697 0.162136 0.257464 0.144455 0.257464 0.144455 0.257099 0.162642 0.256701 0.162756 0.256686 0.144424 0.256701 0.162756 0.25652 0.162499 0.257464 0.144455 0.256701 0.162756 0.256686 0.144424 0.256528 0.144389 0.25652 0.162499 0.256553 0.161876 0.256686 0.144424 0.25652 0.162499 0.256528 0.144389 0.256528 0.144389 0.256553 0.161876 0.25679 0.160949 0.257013 0.1443549 0.25679 0.160949 0.257142 0.159918 0.256528 0.144389 0.25679 0.160949 0.257013 0.1443549 0.257013 0.1443549 0.257142 0.159918 0.257571 0.158802 0.258065 0.1443279 0.257571 0.158802 0.258118 0.15746 0.257013 0.1443549 0.257571 0.158802 0.258065 0.1443279 0.258065 0.1443279 0.258118 0.15746 0.258793 0.1558589 0.258065 0.1443279 0.258793 0.1558589 0.259523 0.154145 0.262971 0.144289 0.259523 0.154145 0.261412 0.149269 0.259523 0.144311 0.259523 0.154145 0.262971 0.144289 0.258065 0.1443279 0.259523 0.154145 0.259523 0.144311 0.259523 0.144311 0.262971 0.144289 0.264246 0.144374 0.258065 0.1443279 0.259523 0.144311 0.264246 0.144374 0.257013 0.1443549 0.258065 0.1443279 0.264246 0.144374 0.256528 0.144389 0.257013 0.1443549 0.264246 0.144374 0.124711 0.144311 0.121328 0.14429 0.12286 0.14919 0.12722 0.1443549 0.120054 0.144374 0.121328 0.14429 0.126169 0.1443279 0.12722 0.1443549 0.121328 0.14429 0.124711 0.144311 0.126169 0.1443279 0.121328 0.14429 0.124711 0.144311 0.12286 0.14919 0.124711 0.1539919 0.124711 0.144311 0.124711 0.1539919 0.125433 0.155696 0.124711 0.144311 0.125433 0.155696 0.126107 0.157303 0.126169 0.1443279 0.126107 0.157303 0.126649 0.158637 0.124711 0.144311 0.126107 0.157303 0.126169 0.1443279 0.126169 0.1443279 0.126649 0.158637 0.127072 0.15974 0.12722 0.1443549 0.127072 0.15974 0.12742 0.160753 0.126169 0.1443279 0.127072 0.15974 0.12722 0.1443549 0.12722 0.1443549 0.12742 0.160753 0.127667 0.161686 0.127705 0.144388 0.127667 0.161686 0.1277199 0.162344 0.12722 0.1443549 0.127667 0.161686 0.127705 0.144388 0.127705 0.144388 0.1277199 0.162344 0.127555 0.162633 0.127548 0.144423 0.127555 0.162633 0.12718 0.162553 0.127705 0.144388 0.127555 0.162633 0.127548 0.144423 0.126769 0.144455 0.12718 0.162553 0.126598 0.162079 0.127548 0.144423 0.12718 0.162553 0.126769 0.144455 0.126769 0.144455 0.126598 0.162079 0.125896 0.161274 0.125485 0.144477 0.125896 0.161274 0.125214 0.160335 0.126769 0.144455 0.125896 0.161274 0.125485 0.144477 0.125485 0.144477 0.125214 0.160335 0.124548 0.159288 0.123893 0.144488 0.124548 0.159288 0.123812 0.157992 0.125485 0.144477 0.124548 0.159288 0.123893 0.144488 0.123893 0.144488 0.123812 0.157992 0.123008 0.156397 0.123893 0.144488 0.123008 0.156397 0.122236 0.154658 0.118752 0.144461 0.122236 0.154658 0.120324 0.149612 0.122236 0.144484 0.122236 0.154658 0.118752 0.144461 0.123893 0.144488 0.122236 0.154658 0.122236 0.144484 0.126769 0.144455 0.118752 0.144461 0.120054 0.144374 0.125485 0.144477 0.122236 0.144484 0.118752 0.144461 0.126769 0.144455 0.125485 0.144477 0.118752 0.144461 0.127548 0.144423 0.126769 0.144455 0.120054 0.144374 0.127705 0.144388 0.127548 0.144423 0.120054 0.144374 0.12722 0.1443549 0.127705 0.144388 0.120054 0.144374 0.129818 0.117383 0.122743 0.117087 0.123534 0.111066 0.131935 0.106034 0.123534 0.111066 0.124845 0.105136 0.131935 0.106034 0.129818 0.117383 0.123534 0.111066 0.131935 0.106034 0.124845 0.105136 0.126668 0.09934395 0.1360999 0.09526598 0.126668 0.09934395 0.128988 0.09373098 0.1360999 0.09526598 0.131935 0.106034 0.126668 0.09934395 0.1360999 0.09526598 0.128988 0.09373098 0.131788 0.08834099 0.142172 0.085446 0.131788 0.08834099 0.135048 0.08321499 0.142172 0.085446 0.1360999 0.09526598 0.131788 0.08834099 0.142172 0.085446 0.135048 0.08321499 0.1387439 0.07839095 0.149948 0.07690697 0.1387439 0.07839095 0.142846 0.07390797 0.149948 0.07690697 0.142172 0.085446 0.1387439 0.07839095 0.159165 0.06994199 0.142846 0.07390797 0.147325 0.06979995 0.159165 0.06994199 0.149948 0.07690697 0.142846 0.07390797 0.159165 0.06994199 0.147325 0.06979995 0.152145 0.06609797 0.169512 0.06478798 0.152145 0.06609797 0.157272 0.06282895 0.169512 0.06478798 0.159165 0.06994199 0.152145 0.06609797 0.180634 0.06162291 0.157272 0.06282895 0.162666 0.06001991 0.180634 0.06162291 0.169512 0.06478798 0.157272 0.06282895 0.221638 0.06001991 0.162666 0.06001991 0.168288 0.05768996 0.192152 0.06055498 0.162666 0.06001991 0.221638 0.06001991 0.180634 0.06162291 0.162666 0.06001991 0.192152 0.06055498 0.216017 0.05768996 0.168288 0.05768996 0.174093 0.05585998 0.221638 0.06001991 0.168288 0.05768996 0.216017 0.05768996 0.210212 0.05585998 0.174093 0.05585998 0.180036 0.054542 0.216017 0.05768996 0.174093 0.05585998 0.210212 0.05585998 0.204269 0.054542 0.180036 0.054542 0.186071 0.05374795 0.210212 0.05585998 0.180036 0.054542 0.204269 0.054542 0.198234 0.05374795 0.186071 0.05374795 0.192152 0.05348193 0.204269 0.054542 0.186071 0.05374795 0.198234 0.05374795 0.192152 0.06055498 0.221638 0.06001991 0.227032 0.06282895 0.214793 0.06478798 0.227032 0.06282895 0.232159 0.06609797 0.20367 0.06162291 0.192152 0.06055498 0.227032 0.06282895 0.214793 0.06478798 0.20367 0.06162291 0.227032 0.06282895 0.214793 0.06478798 0.232159 0.06609797 0.23698 0.06979995 0.225139 0.06994199 0.23698 0.06979995 0.2414579 0.07390797 0.225139 0.06994199 0.214793 0.06478798 0.23698 0.06979995 0.234356 0.07690697 0.2414579 0.07390797 0.245561 0.07839095 0.234356 0.07690697 0.225139 0.06994199 0.2414579 0.07390797 0.234356 0.07690697 0.245561 0.07839095 0.249256 0.08321499 0.242132 0.085446 0.249256 0.08321499 0.252516 0.08834099 0.242132 0.085446 0.234356 0.07690697 0.249256 0.08321499 0.242132 0.085446 0.252516 0.08834099 0.255317 0.09373098 0.2482039 0.09526598 0.255317 0.09373098 0.257637 0.09934395 0.2482039 0.09526598 0.242132 0.085446 0.255317 0.09373098 0.2482039 0.09526598 0.257637 0.09934395 0.259459 0.105136 0.252369 0.106034 0.259459 0.105136 0.260771 0.111066 0.252369 0.106034 0.2482039 0.09526598 0.259459 0.105136 0.252369 0.106034 0.260771 0.111066 0.261562 0.117087 0.254487 0.117383 0.252369 0.106034 0.261562 0.117087 0.192152 0.06325995 0.192152 0.06055498 0.20367 0.06162291 0.181133 0.06428098 0.180634 0.06162291 0.192152 0.06055498 0.181133 0.06428098 0.192152 0.06055498 0.192152 0.06325995 0.203172 0.06428098 0.20367 0.06162291 0.214793 0.06478798 0.203172 0.06428098 0.192152 0.06325995 0.20367 0.06162291 0.2138119 0.06730896 0.214793 0.06478798 0.225139 0.06994199 0.203172 0.06428098 0.214793 0.06478798 0.2138119 0.06730896 0.223711 0.07223999 0.225139 0.06994199 0.234356 0.07690697 0.2138119 0.06730896 0.225139 0.06994199 0.223711 0.07223999 0.2325299 0.07890397 0.234356 0.07690697 0.242132 0.085446 0.223711 0.07223999 0.234356 0.07690697 0.2325299 0.07890397 0.239971 0.08707398 0.242132 0.085446 0.2482039 0.09526598 0.2325299 0.07890397 0.242132 0.085446 0.239971 0.08707398 0.245782 0.09647095 0.2482039 0.09526598 0.252369 0.106034 0.239971 0.08707398 0.2482039 0.09526598 0.245782 0.09647095 0.249767 0.106775 0.252369 0.106034 0.254487 0.117383 0.245782 0.09647095 0.252369 0.106034 0.249767 0.106775 0.251793 0.117633 0.254487 0.117383 0.254487 0.128929 0.249767 0.106775 0.254487 0.117383 0.251793 0.117633 0.251793 0.128679 0.254487 0.128929 0.252369 0.140278 0.251793 0.117633 0.254487 0.128929 0.251793 0.128679 0.249767 0.139537 0.252369 0.140278 0.2482039 0.151046 0.251793 0.128679 0.252369 0.140278 0.249767 0.139537 0.245782 0.149841 0.2482039 0.151046 0.242132 0.160866 0.249767 0.139537 0.2482039 0.151046 0.245782 0.149841 0.239971 0.159238 0.242132 0.160866 0.234356 0.169405 0.245782 0.149841 0.242132 0.160866 0.239971 0.159238 0.2325299 0.167408 0.234356 0.169405 0.225139 0.17637 0.239971 0.159238 0.234356 0.169405 0.2325299 0.167408 0.223711 0.174072 0.225139 0.17637 0.214793 0.181524 0.2325299 0.167408 0.225139 0.17637 0.223711 0.174072 0.2138119 0.179003 0.214793 0.181524 0.20367 0.1846899 0.223711 0.174072 0.214793 0.181524 0.2138119 0.179003 0.203172 0.182031 0.20367 0.1846899 0.192152 0.185757 0.2138119 0.179003 0.20367 0.1846899 0.203172 0.182031 0.192152 0.183052 0.192152 0.185757 0.180634 0.1846899 0.203172 0.182031 0.192152 0.185757 0.192152 0.183052 0.181133 0.182031 0.180634 0.1846899 0.169512 0.181524 0.192152 0.183052 0.180634 0.1846899 0.181133 0.182031 0.1704919 0.179003 0.169512 0.181524 0.159165 0.17637 0.181133 0.182031 0.169512 0.181524 0.1704919 0.179003 0.160594 0.174072 0.159165 0.17637 0.149948 0.169405 0.1704919 0.179003 0.159165 0.17637 0.160594 0.174072 0.151775 0.167408 0.149948 0.169405 0.142172 0.160866 0.160594 0.174072 0.149948 0.169405 0.151775 0.167408 0.144334 0.159238 0.142172 0.160866 0.1360999 0.151046 0.151775 0.167408 0.142172 0.160866 0.144334 0.159238 0.138522 0.149841 0.1360999 0.151046 0.131935 0.140278 0.144334 0.159238 0.1360999 0.151046 0.138522 0.149841 0.134537 0.139537 0.131935 0.140278 0.129818 0.128929 0.138522 0.149841 0.131935 0.140278 0.134537 0.139537 0.132511 0.128679 0.129818 0.128929 0.129818 0.117383 0.134537 0.139537 0.129818 0.128929 0.132511 0.128679 0.132511 0.117633 0.129818 0.117383 0.131935 0.106034 0.132511 0.128679 0.129818 0.117383 0.132511 0.117633 0.134537 0.106775 0.131935 0.106034 0.1360999 0.09526598 0.132511 0.117633 0.131935 0.106034 0.134537 0.106775 0.138522 0.09647095 0.1360999 0.09526598 0.142172 0.085446 0.134537 0.106775 0.1360999 0.09526598 0.138522 0.09647095 0.144334 0.08707398 0.142172 0.085446 0.149948 0.07690697 0.138522 0.09647095 0.142172 0.085446 0.144334 0.08707398 0.151775 0.07890397 0.149948 0.07690697 0.159165 0.06994199 0.144334 0.08707398 0.149948 0.07690697 0.151775 0.07890397 0.160594 0.07223999 0.159165 0.06994199 0.169512 0.06478798 0.151775 0.07890397 0.159165 0.06994199 0.160594 0.07223999 0.1704919 0.06730896 0.169512 0.06478798 0.180634 0.06162291 0.160594 0.07223999 0.169512 0.06478798 0.1704919 0.06730896 0.1704919 0.06730896 0.180634 0.06162291 0.181133 0.06428098 0.175728 0.217263 0.208576 0.217263 0.209352 0.217715 0.174952 0.217715 0.175728 0.217263 0.209352 0.217715 0.208736 0.218174 0.174952 0.217715 0.209352 0.217715 0.177816 0.216853 0.206488 0.216853 0.208576 0.217263 0.175728 0.217263 0.177816 0.216853 0.208576 0.217263 0.181033 0.216516 0.203271 0.216516 0.206488 0.216853 0.177816 0.216853 0.181033 0.216516 0.206488 0.216853 0.185117 0.216278 0.199187 0.216278 0.203271 0.216516 0.181033 0.216516 0.185117 0.216278 0.203271 0.216516 0.189745 0.2161549 0.194559 0.2161549 0.199187 0.216278 0.185117 0.216278 0.189745 0.2161549 0.199187 0.216278 0.208736 0.218174 0.175568 0.218174 0.174952 0.217715 0.206758 0.218601 0.177547 0.218601 0.175568 0.218174 0.208736 0.218174 0.206758 0.218601 0.175568 0.218174 0.203564 0.218961 0.1807399 0.218961 0.177547 0.218601 0.206758 0.218601 0.203564 0.218961 0.177547 0.218601 0.199411 0.2192209 0.184893 0.2192209 0.1807399 0.218961 0.203564 0.218961 0.199411 0.2192209 0.1807399 0.218961 0.194642 0.219357 0.189662 0.219357 0.184893 0.2192209 0.199411 0.2192209 0.194642 0.219357 0.184893 0.2192209 0.287341 0.149321 0.291232 0.149296 0.293151 0.149314 0.285952 0.14936 0.287341 0.149321 0.293151 0.149314 0.287341 0.149321 0.289194 0.149298 0.291232 0.149296 0.227126 0.1506969 0.2379 0.1506749 0.238071 0.150734 0.22781 0.150641 0.236925 0.150623 0.2379 0.1506749 0.227126 0.1506969 0.22781 0.150641 0.2379 0.1506749 0.2292169 0.150597 0.235297 0.150584 0.236925 0.150623 0.22781 0.150641 0.2292169 0.150597 0.236925 0.150623 0.231131 0.15057 0.233264 0.150566 0.235297 0.150584 0.2292169 0.150597 0.231131 0.15057 0.235297 0.150584 0.1467649 0.150649 0.1572149 0.150725 0.156678 0.150782 0.1467649 0.150649 0.156912 0.1506659 0.1572149 0.150725 0.1467649 0.150649 0.155822 0.150615 0.156912 0.1506659 0.14807 0.1506029 0.154112 0.15058 0.155822 0.150615 0.1467649 0.150649 0.14807 0.1506029 0.155822 0.150615 0.149922 0.150573 0.152042 0.150565 0.154112 0.15058 0.14807 0.1506029 0.149922 0.150573 0.154112 0.15058 0.282347 0.145909 0.280583 0.145914 0.278873 0.145903 0.261998 0.144484 0.260341 0.144488 0.258748 0.144477 0.125485 0.144477 0.123893 0.144488 0.122236 0.144484 0.09754198 0.14586 0.08999496 0.145855 0.08937799 0.145817 0.098266 0.145824 0.09754198 0.14586 0.08937799 0.145817 0.09625101 0.145888 0.09120297 0.145884 0.08999496 0.145855 0.09754198 0.14586 0.09625101 0.145888 0.08999496 0.145855 0.09459096 0.145902 0.092817 0.145901 0.09120297 0.145884 0.09625101 0.145888 0.09459096 0.145902 0.09120297 0.145884 0.07204198 0.149621 0.08226799 0.14967 0.08190596 0.149724 0.07204198 0.149621 0.08182197 0.149617 0.08226799 0.14967 0.07317 0.1495749 0.08064198 0.149572 0.08182197 0.149617 0.07204198 0.149621 0.07317 0.1495749 0.08182197 0.149617 0.07486897 0.149544 0.07890796 0.149543 0.08064198 0.149572 0.07317 0.1495749 0.07486897 0.149544 0.08064198 0.149572 0.07486897 0.149544 0.076882 0.149533 0.07890796 0.149543 0.181133 0.182031 0.181133 0.06428098 0.192152 0.06325995 0.192152 0.183052 0.181133 0.182031 0.192152 0.06325995 0.203172 0.06428098 0.192152 0.183052 0.192152 0.06325995 0.1704919 0.179003 0.1704919 0.06730896 0.181133 0.06428098 0.181133 0.182031 0.1704919 0.179003 0.181133 0.06428098 0.160594 0.174072 0.160594 0.07223999 0.1704919 0.06730896 0.1704919 0.179003 0.160594 0.174072 0.1704919 0.06730896 0.151775 0.167408 0.151775 0.07890397 0.160594 0.07223999 0.160594 0.174072 0.151775 0.167408 0.160594 0.07223999 0.144334 0.159238 0.144334 0.08707398 0.151775 0.07890397 0.151775 0.167408 0.144334 0.159238 0.151775 0.07890397 0.138522 0.149841 0.138522 0.09647095 0.144334 0.08707398 0.144334 0.159238 0.138522 0.149841 0.144334 0.08707398 0.134537 0.139537 0.134537 0.106775 0.138522 0.09647095 0.138522 0.149841 0.134537 0.139537 0.138522 0.09647095 0.132511 0.128679 0.132511 0.117633 0.134537 0.106775 0.134537 0.139537 0.132511 0.128679 0.134537 0.106775 0.203172 0.06428098 0.203172 0.182031 0.192152 0.183052 0.2138119 0.06730896 0.2138119 0.179003 0.203172 0.182031 0.203172 0.06428098 0.2138119 0.06730896 0.203172 0.182031 0.223711 0.07223999 0.223711 0.174072 0.2138119 0.179003 0.2138119 0.06730896 0.223711 0.07223999 0.2138119 0.179003 0.2325299 0.07890397 0.2325299 0.167408 0.223711 0.174072 0.223711 0.07223999 0.2325299 0.07890397 0.223711 0.174072 0.239971 0.08707398 0.239971 0.159238 0.2325299 0.167408 0.2325299 0.07890397 0.239971 0.08707398 0.2325299 0.167408 0.245782 0.09647095 0.245782 0.149841 0.239971 0.159238 0.239971 0.08707398 0.245782 0.09647095 0.239971 0.159238 0.249767 0.106775 0.249767 0.139537 0.245782 0.149841 0.245782 0.09647095 0.249767 0.106775 0.245782 0.149841 0.251793 0.117633 0.251793 0.128679 0.249767 0.139537 0.249767 0.106775 0.251793 0.117633 0.249767 0.139537 2.54e-4 0.108819 0.02567398 0.1106989 0.02586597 0.123156 0 0.123156 2.54e-4 0.108819 0.02586597 0.123156 0.02567398 0.135613 0 0.123156 0.02586597 0.123156 0.001001954 0.09508597 0.02510493 0.098589 0.02567398 0.1106989 2.54e-4 0.108819 0.001001954 0.09508597 0.02567398 0.1106989 0.002208948 0.08251798 0.02416998 0.08716499 0.02510493 0.098589 0.001001954 0.09508597 0.002208948 0.08251798 0.02510493 0.098589 0.003816962 0.071603 0.02288889 0.07676297 0.02416998 0.08716499 0.002208948 0.08251798 0.003816962 0.071603 0.02416998 0.08716499 0.005752921 0.06272995 0.02129089 0.06770497 0.02288889 0.07676297 0.003816962 0.071603 0.005752921 0.06272995 0.02288889 0.07676297 0.007931947 0.05617499 0.01941496 0.06029593 0.02129089 0.06770497 0.005752921 0.06272995 0.007931947 0.05617499 0.02129089 0.06770497 0.01026499 0.05210191 0.01730996 0.05481588 0.01941496 0.06029593 0.007931947 0.05617499 0.01026499 0.05210191 0.01941496 0.06029593 0.01266098 0.05056095 0.01503592 0.05150789 0.01730996 0.05481588 0.01026499 0.05210191 0.01266098 0.05056095 0.01730996 0.05481588 0.02567398 0.135613 2.54e-4 0.137493 0 0.123156 0.02510493 0.147723 0.001001954 0.151226 2.54e-4 0.137493 0.02567398 0.135613 0.02510493 0.147723 2.54e-4 0.137493 0.02416998 0.159147 0.002208948 0.163794 0.001001954 0.151226 0.02510493 0.147723 0.02416998 0.159147 0.001001954 0.151226 0.02288889 0.169549 0.003816962 0.174709 0.002208948 0.163794 0.02416998 0.159147 0.02288889 0.169549 0.002208948 0.163794 0.02129089 0.178607 0.005752921 0.183582 0.003816962 0.174709 0.02288889 0.169549 0.02129089 0.178607 0.003816962 0.174709 0.01941496 0.186016 0.007931947 0.190137 0.005752921 0.183582 0.02129089 0.178607 0.01941496 0.186016 0.005752921 0.183582 0.01730996 0.191496 0.01026499 0.1942099 0.007931947 0.190137 0.01941496 0.186016 0.01730996 0.191496 0.007931947 0.190137 0.01503592 0.194804 0.01266098 0.195751 0.01026499 0.1942099 0.01730996 0.191496 0.01503592 0.194804 0.01026499 0.1942099 0.02444595 0.001239955 0.0245729 0.001059949 0.02439999 8.8e-4 0.02439999 0.007600963 0.02439999 8.8e-4 0.0245729 0.001059949 0.019939 1.74e-4 0.02444595 0.001239955 0.02439999 8.8e-4 0.019939 0.006844997 0.019939 1.74e-4 0.02439999 8.8e-4 0.019939 0.006844997 0.02439999 8.8e-4 0.02439999 0.007600963 0.0245729 0.007792949 0.0245729 0.001059949 0.02444595 0.001239955 0.0245729 0.007792949 0.02439999 0.007600963 0.0245729 0.001059949 0.019939 1.74e-4 0.020087 0.001970887 0.02444595 0.001239955 0.02444595 0.007985949 0.02444595 0.001239955 0.020087 0.001970887 0.0245729 0.007792949 0.02444595 0.001239955 0.02444595 0.007985949 0.01837396 7.6e-5 0.01850491 0.00207597 0.020087 0.001970887 0.020087 0.008767962 0.020087 0.001970887 0.01850491 0.00207597 0.019939 1.74e-4 0.01837396 7.6e-5 0.020087 0.001970887 0.02444595 0.007985949 0.020087 0.001970887 0.020087 0.008767962 0.01664799 0 0.01674896 0.0021559 0.01850491 0.00207597 0.01850491 0.008879959 0.01850491 0.00207597 0.01674896 0.0021559 0.01837396 7.6e-5 0.01664799 0 0.01850491 0.00207597 0.020087 0.008767962 0.01850491 0.00207597 0.01850491 0.008879959 0.007924973 0 0.007823944 0.0021559 0.01674896 0.0021559 0.01674896 0.008966982 0.01674896 0.0021559 0.007823944 0.0021559 0.01664799 0 0.007924973 0 0.01674896 0.0021559 0.01850491 0.008879959 0.01674896 0.0021559 0.01674896 0.008966982 0.006197929 7.6e-5 0.006067991 0.00207597 0.007823944 0.0021559 0.007823944 0.008966982 0.007823944 0.0021559 0.006067991 0.00207597 0.007924973 0 0.006197929 7.6e-5 0.007823944 0.0021559 0.01674896 0.008966982 0.007823944 0.0021559 0.007823944 0.008966982 0.004633963 1.74e-4 0.004485905 0.001970887 0.006067991 0.00207597 0.006067991 0.008879959 0.006067991 0.00207597 0.004485905 0.001970887 0.006197929 7.6e-5 0.004633963 1.74e-4 0.006067991 0.00207597 0.007823944 0.008966982 0.006067991 0.00207597 0.006067991 0.008879959 1.73e-4 8.8e-4 1.27e-4 0.001239955 0.004485905 0.001970887 0.004485905 0.008767962 0.004485905 0.001970887 1.27e-4 0.001239955 0.004633963 1.74e-4 1.73e-4 8.8e-4 0.004485905 0.001970887 0.006067991 0.008879959 0.004485905 0.001970887 0.004485905 0.008767962 1.73e-4 8.8e-4 0 0.001059949 1.27e-4 0.001239955 1.27e-4 0.007985949 1.27e-4 0.001239955 0 0.001059949 0.004485905 0.008767962 1.27e-4 0.001239955 1.27e-4 0.007985949 0 0.007792949 0 0.001059949 1.73e-4 8.8e-4 1.27e-4 0.007985949 0 0.001059949 0 0.007792949 1.73e-4 0.007600963 1.73e-4 8.8e-4 0.004633963 1.74e-4 0 0.007792949 1.73e-4 8.8e-4 1.73e-4 0.007600963 0.004633963 0.006844997 0.004633963 1.74e-4 0.006197929 7.6e-5 1.73e-4 0.007600963 0.004633963 1.74e-4 0.004633963 0.006844997 0.006197929 0.006739974 0.006197929 7.6e-5 0.007924973 0 0.004633963 0.006844997 0.006197929 7.6e-5 0.006197929 0.006739974 0.007924973 0.006658971 0.007924973 0 0.01664799 0 0.006197929 0.006739974 0.007924973 0 0.007924973 0.006658971 0.01664799 0.006658971 0.01664799 0 0.01837396 7.6e-5 0.007924973 0.006658971 0.01664799 0 0.01664799 0.006658971 0.01837396 0.006739974 0.01837396 7.6e-5 0.019939 1.74e-4 0.01664799 0.006658971 0.01837396 7.6e-5 0.01837396 0.006739974 0.01837396 0.006739974 0.019939 1.74e-4 0.019939 0.006844997 0.004633963 0.006844997 0.00346899 0.007369995 0.002456963 0.007795989 0.002456963 0.01322489 0.002456963 0.007795989 0.00346899 0.007369995 1.27e-4 0.007985949 0.002456963 0.007795989 0.003393948 0.00822699 0.003391981 0.01367795 0.003393948 0.00822699 0.002456963 0.007795989 1.27e-4 0.007985949 0.004633963 0.006844997 0.002456963 0.007795989 0.003391981 0.01367795 0.002456963 0.007795989 0.002456963 0.01322489 0.006197929 0.006739974 0.006207883 0.007030904 0.00346899 0.007369995 0.003466904 0.01277589 0.00346899 0.007369995 0.006207883 0.007030904 0.004633963 0.006844997 0.006197929 0.006739974 0.00346899 0.007369995 0.003466904 0.01277589 0.002456963 0.01322489 0.00346899 0.007369995 0.007924973 0.006658971 0.01011598 0.006845951 0.006207883 0.007030904 0.006207883 0.01241993 0.006207883 0.007030904 0.01011598 0.006845951 0.006197929 0.006739974 0.007924973 0.006658971 0.006207883 0.007030904 0.003466904 0.01277589 0.006207883 0.007030904 0.006207883 0.01241993 0.01664799 0.006658971 0.01445692 0.006845951 0.01011598 0.006845951 0.01012599 0.01222389 0.01011598 0.006845951 0.01445692 0.006845951 0.007924973 0.006658971 0.01664799 0.006658971 0.01011598 0.006845951 0.006207883 0.01241993 0.01011598 0.006845951 0.01012599 0.01222389 0.01664799 0.006658971 0.01836395 0.007030904 0.01445692 0.006845951 0.01444697 0.01222389 0.01445692 0.006845951 0.01836395 0.007030904 0.01012599 0.01222389 0.01445692 0.006845951 0.01444697 0.01222389 0.019939 0.006844997 0.02110391 0.007369995 0.01836395 0.007030904 0.01836395 0.01241993 0.01836395 0.007030904 0.02110391 0.007369995 0.01837396 0.006739974 0.019939 0.006844997 0.01836395 0.007030904 0.01664799 0.006658971 0.01837396 0.006739974 0.01836395 0.007030904 0.01444697 0.01222389 0.01836395 0.007030904 0.01836395 0.01241993 0.02439999 0.007600963 0.022116 0.007795989 0.02110391 0.007369995 0.02110499 0.01277589 0.02110391 0.007369995 0.022116 0.007795989 0.019939 0.006844997 0.02439999 0.007600963 0.02110391 0.007369995 0.01836395 0.01241993 0.02110391 0.007369995 0.02110499 0.01277589 0.020087 0.008767962 0.02117896 0.00822699 0.022116 0.007795989 0.022116 0.01322489 0.022116 0.007795989 0.02117896 0.00822699 0.020087 0.008767962 0.022116 0.007795989 0.02439999 0.007600963 0.02110499 0.01277589 0.022116 0.007795989 0.022116 0.01322489 0.01850491 0.008879959 0.01845896 0.008577942 0.02117896 0.00822699 0.02118092 0.01367795 0.02117896 0.00822699 0.01845896 0.008577942 0.020087 0.008767962 0.01850491 0.008879959 0.02117896 0.00822699 0.022116 0.01322489 0.02117896 0.00822699 0.02118092 0.01367795 0.01674896 0.008966982 0.01449888 0.008773982 0.01845896 0.008577942 0.01845788 0.01404798 0.01845896 0.008577942 0.01449888 0.008773982 0.01850491 0.008879959 0.01674896 0.008966982 0.01845896 0.008577942 0.02118092 0.01367795 0.01845896 0.008577942 0.01845788 0.01404798 0.007823944 0.008966982 0.0100739 0.008773982 0.01449888 0.008773982 0.01448899 0.01425397 0.01449888 0.008773982 0.0100739 0.008773982 0.01674896 0.008966982 0.007823944 0.008966982 0.01449888 0.008773982 0.01845788 0.01404798 0.01449888 0.008773982 0.01448899 0.01425397 0.007823944 0.008966982 0.006113946 0.008577942 0.0100739 0.008773982 0.01008397 0.01425397 0.0100739 0.008773982 0.006113946 0.008577942 0.01448899 0.01425397 0.0100739 0.008773982 0.01008397 0.01425397 0.004485905 0.008767962 0.003393948 0.00822699 0.006113946 0.008577942 0.006113946 0.01404798 0.006113946 0.008577942 0.003393948 0.00822699 0.006067991 0.008879959 0.004485905 0.008767962 0.006113946 0.008577942 0.007823944 0.008966982 0.006067991 0.008879959 0.006113946 0.008577942 0.01008397 0.01425397 0.006113946 0.008577942 0.006113946 0.01404798 0.004485905 0.008767962 1.27e-4 0.007985949 0.003393948 0.00822699 0.006113946 0.01404798 0.003393948 0.00822699 0.003391981 0.01367795 0.02444595 0.007985949 0.020087 0.008767962 0.02439999 0.007600963 0.0245729 0.007792949 0.02444595 0.007985949 0.02439999 0.007600963 1.27e-4 0.007985949 1.73e-4 0.007600963 0.004633963 0.006844997 1.27e-4 0.007985949 0 0.007792949 1.73e-4 0.007600963 0.005380988 0.01365 0.003391981 0.01367795 0.002456963 0.01322489 0.004340946 0.01322597 0.002456963 0.01322489 0.003466904 0.01277589 0.005380988 0.01365 0.002456963 0.01322489 0.004340946 0.01322597 0.008283972 0.01396197 0.006113946 0.01404798 0.003391981 0.01367795 0.005380988 0.01365 0.008283972 0.01396197 0.003391981 0.01367795 0.01448899 0.01425397 0.01008397 0.01425397 0.006113946 0.01404798 0.01228588 0.01407796 0.01448899 0.01425397 0.006113946 0.01404798 0.008283972 0.01396197 0.01228588 0.01407796 0.006113946 0.01404798 0.01228588 0.01407796 0.01845788 0.01404798 0.01448899 0.01425397 0.01628899 0.01396197 0.02118092 0.01367795 0.01845788 0.01404798 0.01228588 0.01407796 0.01628899 0.01396197 0.01845788 0.01404798 0.02023196 0.01322597 0.022116 0.01322489 0.02118092 0.01367795 0.01919198 0.01365 0.02023196 0.01322597 0.02118092 0.01367795 0.01628899 0.01396197 0.01919198 0.01365 0.02118092 0.01367795 0.01913696 0.0128079 0.02110499 0.01277589 0.022116 0.01322489 0.02023196 0.01322597 0.01913696 0.0128079 0.022116 0.01322489 0.01623398 0.01250499 0.01836395 0.01241993 0.02110499 0.01277589 0.01913696 0.0128079 0.01623398 0.01250499 0.02110499 0.01277589 0.01012599 0.01222389 0.01444697 0.01222389 0.01836395 0.01241993 0.01228588 0.01239496 0.01012599 0.01222389 0.01836395 0.01241993 0.01623398 0.01250499 0.01228588 0.01239496 0.01836395 0.01241993 0.01228588 0.01239496 0.006207883 0.01241993 0.01012599 0.01222389 0.008338987 0.01250499 0.003466904 0.01277589 0.006207883 0.01241993 0.01228588 0.01239496 0.008338987 0.01250499 0.006207883 0.01241993 0.00543493 0.0128079 0.004340946 0.01322597 0.003466904 0.01277589 0.008338987 0.01250499 0.00543493 0.0128079 0.003466904 0.01277589 0.004340946 0.01889199 0.004340946 0.01322597 0.00543493 0.0128079 0.005379915 0.01933693 0.005380988 0.01365 0.004340946 0.01322597 0.005379915 0.01933693 0.004340946 0.01322597 0.004340946 0.01889199 0.00543493 0.01845192 0.00543493 0.0128079 0.008338987 0.01250499 0.00543493 0.01845192 0.004340946 0.01889199 0.00543493 0.0128079 0.008340954 0.01813197 0.008338987 0.01250499 0.01228588 0.01239496 0.00543493 0.01845192 0.008338987 0.01250499 0.008340954 0.01813197 0.01228588 0.01801699 0.01228588 0.01239496 0.01623398 0.01250499 0.008340954 0.01813197 0.01228588 0.01239496 0.01228588 0.01801699 0.01623195 0.01813197 0.01623398 0.01250499 0.01913696 0.0128079 0.01228588 0.01801699 0.01623398 0.01250499 0.01623195 0.01813197 0.01913791 0.01845192 0.01913696 0.0128079 0.02023196 0.01322597 0.01623195 0.01813197 0.01913696 0.0128079 0.01913791 0.01845192 0.02023196 0.01889199 0.02023196 0.01322597 0.01919198 0.01365 0.01913791 0.01845192 0.02023196 0.01322597 0.02023196 0.01889199 0.01919198 0.01933693 0.01919198 0.01365 0.01628899 0.01396197 0.02023196 0.01889199 0.01919198 0.01365 0.01919198 0.01933693 0.0162869 0.01966595 0.01628899 0.01396197 0.01228588 0.01407796 0.01919198 0.01933693 0.01628899 0.01396197 0.0162869 0.01966595 0.01228588 0.01978695 0.01228588 0.01407796 0.008283972 0.01396197 0.0162869 0.01966595 0.01228588 0.01407796 0.01228588 0.01978695 0.008285999 0.01966595 0.008283972 0.01396197 0.005380988 0.01365 0.01228588 0.01978695 0.008283972 0.01396197 0.008285999 0.01966595 0.008285999 0.01966595 0.005380988 0.01365 0.005379915 0.01933693 0.01919198 0.01933693 0.005379915 0.01933693 0.004340946 0.01889199 0.02023196 0.01889199 0.01919198 0.01933693 0.004340946 0.01889199 0.00543493 0.01845192 0.02023196 0.01889199 0.004340946 0.01889199 0.0162869 0.01966595 0.008285999 0.01966595 0.005379915 0.01933693 0.01919198 0.01933693 0.0162869 0.01966595 0.005379915 0.01933693 0.0162869 0.01966595 0.01228588 0.01978695 0.008285999 0.01966595 0.00543493 0.01845192 0.01913791 0.01845192 0.02023196 0.01889199 0.008340954 0.01813197 0.01623195 0.01813197 0.01913791 0.01845192 0.00543493 0.01845192 0.008340954 0.01813197 0.01913791 0.01845192 0.008340954 0.01813197 0.01228588 0.01801699 0.01623195 0.01813197 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 6 6 10 2 2 11 8 8 12 9 9 13 10 10 14 11 11 15 12 12 16 4 4 17 3 3 18 11 11 19 4 4 20 13 13 21 14 14 22 1 1 23 15 15 24 5 5 25 16 16 26 17 17 27 13 13 28 1 1 29 0 0 30 17 17 31 1 1 32 15 15 33 3 3 34 5 5 35 18 18 36 19 19 37 14 14 38 20 20 39 16 16 40 21 21 41 13 13 42 18 18 43 14 14 44 22 22 45 15 15 46 16 16 47 20 20 48 22 22 49 16 16 50 23 23 51 24 24 52 19 19 53 25 25 54 21 21 55 26 26 56 27 27 57 19 19 58 18 18 59 28 28 60 23 23 61 19 19 62 29 29 63 28 28 64 19 19 65 30 30 66 29 29 67 19 19 68 31 31 69 30 30 70 19 19 71 32 32 72 31 31 73 19 19 74 33 33 75 32 32 76 19 19 77 34 34 78 33 33 79 19 19 80 27 35 81 34 35 82 19 35 83 35 36 84 20 20 85 21 21 86 36 37 87 35 36 88 21 21 89 37 38 90 36 37 91 21 21 92 38 39 93 37 38 94 21 21 95 39 40 96 38 39 97 21 21 98 40 41 99 39 40 100 21 21 101 25 25 102 40 41 103 21 21 104 41 42 105 42 43 106 24 24 107 43 44 108 26 26 109 44 45 110 45 46 111 41 42 112 24 24 113 23 23 114 45 46 115 24 24 116 46 47 117 25 25 118 26 26 119 47 48 120 46 47 121 26 26 122 43 44 123 47 48 124 26 26 125 48 49 126 49 50 127 42 43 128 50 51 129 44 45 130 51 52 131 52 53 132 48 49 133 42 43 134 41 42 135 52 53 136 42 43 137 50 51 138 53 54 139 44 45 140 43 44 141 44 45 142 53 54 143 54 55 144 55 56 145 49 50 146 56 57 147 51 52 148 57 58 149 58 59 150 54 55 151 49 50 152 48 49 153 58 59 154 49 50 155 56 57 156 50 51 157 51 52 158 59 60 159 60 61 160 61 62 161 59 60 162 62 63 163 60 61 164 63 64 165 64 65 166 65 66 167 66 67 168 56 57 169 57 58 170 67 68 171 68 68 172 69 68 173 70 68 174 71 68 175 68 68 176 70 68 177 68 68 178 67 68 179 72 68 180 69 68 181 73 68 182 72 68 183 67 68 184 69 68 185 72 68 186 73 68 187 74 68 188 75 69 189 76 70 190 52 53 191 77 68 192 74 68 193 78 68 194 79 71 195 52 53 196 41 42 197 79 71 198 75 69 199 52 53 200 77 68 201 72 68 202 74 68 203 80 72 204 81 73 205 76 70 206 77 74 207 78 74 208 82 74 209 83 75 210 80 72 211 76 70 212 75 69 213 83 75 214 76 70 215 84 76 216 85 77 217 81 73 218 86 68 219 82 68 220 87 68 221 88 78 222 84 76 223 81 73 224 89 79 225 88 78 226 81 73 227 90 80 228 89 79 229 81 73 230 80 72 231 90 80 232 81 73 233 86 68 234 77 68 235 82 68 236 27 27 237 18 18 238 85 77 239 86 81 240 87 81 241 91 81 242 92 82 243 27 27 244 85 77 245 93 83 246 92 82 247 85 77 248 94 84 249 93 83 250 85 77 251 84 76 252 94 84 253 85 77 254 95 68 255 91 68 256 96 68 257 95 85 258 86 85 259 91 85 260 95 68 261 96 68 262 97 68 263 98 68 264 97 68 265 99 68 266 98 68 267 95 68 268 97 68 269 100 86 270 99 86 271 101 86 272 100 87 273 98 87 274 99 87 275 7 7 276 102 88 277 6 6 278 103 89 279 101 89 280 104 89 281 103 90 282 100 90 283 101 90 284 105 91 285 106 92 286 102 88 287 107 68 288 104 68 289 108 68 290 7 7 291 105 91 292 102 88 293 107 93 294 103 93 295 104 93 296 109 68 297 108 68 298 110 68 299 111 94 300 112 95 301 106 92 302 113 68 303 108 68 304 109 68 305 105 91 306 111 94 307 106 92 308 113 68 309 107 68 310 108 68 311 114 68 312 110 68 313 115 68 314 116 96 315 117 97 316 112 95 317 109 68 318 110 68 319 114 68 320 111 94 321 116 96 322 112 95 323 118 68 324 115 68 325 119 68 326 120 98 327 121 99 328 117 97 329 114 68 330 115 68 331 118 68 332 116 96 333 120 98 334 117 97 335 122 68 336 119 68 337 123 68 338 124 100 339 125 101 340 121 99 341 118 68 342 119 68 343 122 68 344 120 98 345 124 100 346 121 99 347 126 68 348 123 68 349 127 68 350 128 102 351 129 103 352 125 101 353 122 68 354 123 68 355 126 68 356 124 100 357 128 102 358 125 101 359 130 104 360 131 105 361 129 103 362 128 102 363 130 104 364 129 103 365 132 106 366 133 107 367 131 105 368 134 108 369 132 106 370 131 105 371 130 104 372 134 108 373 131 105 374 135 109 375 136 110 376 133 107 377 132 106 378 135 109 379 133 107 380 137 111 381 138 112 382 136 110 383 135 109 384 137 111 385 136 110 386 139 113 387 140 114 388 138 112 389 137 111 390 139 113 391 138 112 392 141 115 393 142 116 394 140 114 395 113 68 396 109 68 397 143 68 398 139 113 399 141 115 400 140 114 401 144 117 402 145 118 403 142 116 404 146 119 405 143 119 406 147 119 407 141 115 408 144 117 409 142 116 410 146 68 411 113 68 412 143 68 413 148 120 414 149 121 415 145 118 416 150 122 417 147 122 418 151 122 419 144 117 420 148 120 421 145 118 422 150 68 423 146 68 424 147 68 425 152 123 426 153 124 427 149 121 428 154 68 429 151 68 430 155 68 431 148 120 432 152 123 433 149 121 434 154 125 435 150 125 436 151 125 437 156 126 438 157 127 439 153 124 440 154 128 441 155 128 442 158 128 443 159 129 444 156 126 445 153 124 446 152 123 447 159 129 448 153 124 449 160 130 450 161 131 451 157 127 452 162 68 453 158 68 454 163 68 455 156 126 456 160 130 457 157 127 458 162 132 459 154 132 460 158 132 461 164 133 462 165 134 463 161 131 464 162 68 465 163 68 466 166 68 467 160 130 468 167 135 469 161 131 470 168 136 471 161 131 472 167 135 473 169 137 474 164 133 475 161 131 476 170 138 477 169 137 478 161 131 479 168 136 480 170 138 481 161 131 482 171 139 483 172 140 484 165 134 485 173 68 486 166 68 487 174 68 488 175 141 489 171 139 490 165 134 491 176 142 492 175 141 493 165 134 494 177 143 495 176 142 496 165 134 497 164 133 498 177 143 499 165 134 500 173 68 501 162 68 502 166 68 503 178 144 504 179 145 505 172 140 506 173 68 507 174 68 508 180 68 509 181 146 510 178 144 511 172 140 512 171 139 513 181 146 514 172 140 515 182 147 516 183 148 517 179 145 518 184 68 519 180 68 520 185 68 521 178 144 522 182 147 523 179 145 524 184 68 525 173 68 526 180 68 527 186 149 528 187 150 529 183 148 530 184 68 531 185 68 532 188 68 533 189 151 534 186 149 535 183 148 536 190 152 537 183 148 538 182 147 539 190 152 540 189 151 541 183 148 542 191 153 543 192 154 544 187 150 545 193 68 546 188 68 547 194 68 548 186 149 549 191 153 550 187 150 551 193 68 552 184 68 553 188 68 554 195 155 555 196 156 556 192 154 557 193 68 558 194 68 559 197 68 560 198 157 561 195 155 562 192 154 563 191 153 564 198 157 565 192 154 566 199 158 567 200 159 568 201 160 569 202 161 570 200 159 571 199 158 572 203 68 573 197 68 574 204 68 575 203 68 576 193 68 577 197 68 578 205 162 579 206 163 580 207 164 581 208 165 582 209 166 583 210 167 584 208 165 585 210 167 586 211 168 587 212 169 588 207 164 589 213 170 590 205 162 591 207 164 592 212 169 593 212 169 594 213 170 595 214 171 596 189 151 597 215 172 598 186 149 599 216 173 600 214 171 601 217 174 602 212 169 603 214 171 604 216 173 605 218 175 606 219 176 607 215 172 608 216 173 609 217 174 610 220 177 611 189 151 612 218 175 613 215 172 614 221 178 615 222 179 616 219 176 617 223 180 618 220 177 619 224 181 620 225 182 621 221 178 622 219 176 623 218 175 624 225 182 625 219 176 626 216 173 627 220 177 628 223 180 629 226 183 630 167 135 631 222 179 632 223 180 633 224 181 634 227 184 635 228 185 636 226 183 637 222 179 638 229 186 639 228 185 640 222 179 641 230 187 642 229 186 643 222 179 644 231 188 645 230 187 646 222 179 647 221 178 648 231 188 649 222 179 650 232 189 651 227 184 652 233 190 653 234 191 654 168 191 655 167 191 656 226 183 657 234 192 658 167 135 659 223 180 660 227 184 661 232 189 662 232 189 663 233 190 664 235 193 665 236 194 666 235 193 667 237 195 668 232 189 669 235 193 670 236 194 671 238 196 672 237 195 673 239 197 674 236 194 675 237 195 676 238 196 677 238 196 678 239 197 679 240 198 680 241 199 681 240 198 682 242 200 683 238 196 684 240 198 685 241 199 686 241 199 687 242 200 688 243 201 689 244 202 690 243 201 691 245 203 692 241 199 693 243 201 694 244 202 695 244 202 696 245 203 697 246 204 698 247 205 699 246 204 700 248 206 701 244 202 702 246 204 703 247 205 704 247 205 705 248 206 706 249 207 707 250 208 708 249 207 709 251 209 710 247 205 711 249 207 712 250 208 713 252 210 714 251 209 715 253 211 716 250 208 717 251 209 718 252 210 719 252 210 720 253 211 721 254 212 722 255 213 723 254 212 724 256 214 725 252 210 726 254 212 727 255 213 728 255 213 729 256 214 730 257 215 731 258 216 732 257 215 733 259 217 734 255 213 735 257 215 736 258 216 737 258 216 738 259 217 739 260 218 740 261 219 741 260 218 742 262 220 743 258 216 744 260 218 745 261 219 746 261 219 747 262 220 748 9 9 749 261 219 750 9 9 751 263 221 752 8 8 753 263 221 754 9 9 755 264 222 756 265 222 757 266 222 758 267 223 759 268 223 760 269 223 761 264 224 762 266 224 763 270 224 764 271 225 765 272 226 766 273 227 767 271 225 768 273 227 769 274 228 770 275 229 771 274 228 772 276 230 773 271 225 774 274 228 775 275 229 776 275 229 777 276 230 778 277 231 779 278 232 780 277 231 781 279 233 782 275 229 783 277 231 784 278 232 785 278 232 786 279 233 787 280 234 788 281 235 789 280 234 790 282 236 791 278 232 792 280 234 793 281 235 794 281 235 795 282 236 796 283 237 797 284 238 798 283 237 799 285 239 800 281 235 801 283 237 802 284 238 803 286 240 804 285 239 805 287 241 806 284 238 807 285 239 808 286 240 809 286 240 810 287 241 811 288 242 812 289 243 813 288 242 814 290 244 815 286 240 816 288 242 817 289 243 818 289 243 819 290 244 820 291 245 821 292 246 822 291 245 823 293 247 824 289 243 825 291 245 826 292 246 827 292 246 828 293 247 829 294 248 830 292 246 831 294 248 832 295 249 833 296 250 834 297 250 835 298 250 836 299 251 837 297 251 838 296 251 839 292 246 840 295 249 841 300 252 842 267 223 843 301 223 844 268 223 845 302 223 846 303 223 847 301 223 848 267 223 849 302 223 850 301 223 851 304 253 852 305 253 853 306 253 854 307 223 855 308 223 856 309 223 857 309 223 858 310 223 859 307 223 860 311 223 861 309 223 862 308 223 863 304 254 864 306 254 865 312 254 866 313 255 867 314 256 868 315 257 869 313 255 870 315 257 871 316 258 872 317 259 873 316 258 874 318 260 875 313 255 876 316 258 877 317 259 878 317 259 879 318 260 880 319 261 881 320 262 882 319 261 883 321 263 884 317 259 885 319 261 886 320 262 887 320 262 888 321 263 889 322 264 890 323 265 891 322 264 892 324 266 893 320 262 894 322 264 895 323 265 896 323 265 897 324 266 898 325 267 899 326 268 900 325 267 901 327 269 902 323 265 903 325 267 904 326 268 905 328 270 906 327 269 907 329 271 908 326 268 909 327 269 910 328 270 911 328 270 912 329 271 913 330 272 914 331 273 915 330 272 916 332 274 917 328 270 918 330 272 919 331 273 920 331 273 921 332 274 922 333 275 923 334 276 924 333 275 925 335 277 926 331 273 927 333 275 928 334 276 929 334 276 930 335 277 931 336 278 932 334 276 933 336 278 934 337 279 935 338 280 936 339 280 937 340 280 938 341 281 939 339 281 940 338 281 941 334 276 942 337 279 943 342 282 944 343 283 945 344 284 946 62 63 947 345 285 948 65 66 949 346 286 950 347 287 951 343 283 952 62 63 953 59 60 954 347 287 955 62 63 956 348 288 957 63 64 958 65 66 959 345 285 960 348 288 961 65 66 962 349 289 963 350 290 964 344 284 965 351 291 966 346 286 967 352 292 968 343 283 969 349 289 970 344 284 971 351 291 972 345 285 973 346 286 974 353 293 975 354 294 976 350 290 977 355 295 978 352 292 979 356 296 980 357 297 981 353 293 982 350 290 983 349 289 984 357 297 985 350 290 986 358 298 987 351 291 988 352 292 989 355 295 990 358 298 991 352 292 992 359 299 993 360 300 994 354 294 995 361 301 996 356 296 997 362 302 998 353 293 999 359 299 1000 354 294 1001 361 301 1002 355 295 1003 356 296 1004 363 303 1005 364 304 1006 360 300 1007 365 305 1008 362 302 1009 366 306 1010 367 307 1011 363 303 1012 360 300 1013 359 299 1014 367 307 1015 360 300 1016 365 305 1017 361 301 1018 362 302 1019 368 308 1020 369 309 1021 364 304 1022 370 310 1023 366 306 1024 371 311 1025 372 312 1026 368 308 1027 364 304 1028 363 303 1029 372 312 1030 364 304 1031 373 313 1032 365 305 1033 366 306 1034 370 310 1035 373 313 1036 366 306 1037 374 314 1038 375 315 1039 369 309 1040 376 316 1041 377 317 1042 378 318 1043 368 308 1044 374 314 1045 369 309 1046 379 319 1047 371 311 1048 380 320 1049 379 319 1050 370 310 1051 371 311 1052 374 314 1053 381 321 1054 375 315 1055 382 322 1056 378 318 1057 383 323 1058 382 322 1059 376 316 1060 378 318 1061 384 324 1062 385 325 1063 381 321 1064 386 326 1065 383 323 1066 387 327 1067 374 314 1068 384 324 1069 381 321 1070 386 326 1071 382 322 1072 383 323 1073 388 328 1074 389 329 1075 385 325 1076 386 326 1077 387 327 1078 390 330 1079 384 324 1080 388 328 1081 385 325 1082 391 331 1083 392 332 1084 389 329 1085 393 333 1086 390 330 1087 394 334 1088 388 328 1089 391 331 1090 389 329 1091 393 333 1092 386 326 1093 390 330 1094 395 335 1095 396 336 1096 392 332 1097 393 333 1098 394 334 1099 397 337 1100 391 331 1101 395 335 1102 392 332 1103 398 338 1104 399 339 1105 396 336 1106 400 340 1107 397 337 1108 401 341 1109 395 335 1110 398 338 1111 396 336 1112 400 340 1113 393 333 1114 397 337 1115 402 342 1116 403 343 1117 399 339 1118 400 340 1119 401 341 1120 404 344 1121 398 338 1122 402 342 1123 399 339 1124 405 345 1125 406 346 1126 403 343 1127 407 347 1128 404 344 1129 408 348 1130 402 342 1131 405 345 1132 403 343 1133 407 347 1134 400 340 1135 404 344 1136 409 349 1137 410 350 1138 406 346 1139 411 351 1140 408 348 1141 412 352 1142 405 345 1143 409 349 1144 406 346 1145 411 351 1146 407 347 1147 408 348 1148 409 349 1149 413 353 1150 410 350 1151 411 351 1152 412 352 1153 414 354 1154 415 355 1155 416 356 1156 413 353 1157 417 357 1158 414 354 1159 418 358 1160 409 349 1161 415 355 1162 413 353 1163 417 357 1164 411 351 1165 414 354 1166 419 359 1167 420 360 1168 416 356 1169 417 357 1170 418 358 1171 421 361 1172 415 355 1173 419 359 1174 416 356 1175 422 362 1176 423 363 1177 420 360 1178 424 364 1179 421 361 1180 425 365 1181 419 359 1182 422 362 1183 420 360 1184 424 364 1185 417 357 1186 421 361 1187 426 366 1188 427 367 1189 423 363 1190 424 364 1191 425 365 1192 428 368 1193 422 362 1194 426 366 1195 423 363 1196 429 369 1197 430 370 1198 427 367 1199 431 371 1200 428 368 1201 432 372 1202 426 366 1203 429 369 1204 427 367 1205 431 371 1206 424 364 1207 428 368 1208 433 373 1209 434 374 1210 430 370 1211 431 371 1212 432 372 1213 435 375 1214 429 369 1215 433 373 1216 430 370 1217 436 376 1218 437 377 1219 434 374 1220 438 378 1221 435 375 1222 439 379 1223 433 373 1224 436 376 1225 434 374 1226 438 378 1227 431 371 1228 435 375 1229 440 380 1230 441 381 1231 437 377 1232 442 382 1233 439 379 1234 443 383 1235 436 376 1236 440 380 1237 437 377 1238 442 382 1239 438 378 1240 439 379 1241 440 380 1242 444 384 1243 441 381 1244 442 382 1245 443 383 1246 445 385 1247 446 386 1248 447 387 1249 444 384 1250 448 388 1251 445 385 1252 449 389 1253 440 380 1254 446 386 1255 444 384 1256 448 388 1257 442 382 1258 445 385 1259 450 390 1260 451 391 1261 447 387 1262 448 388 1263 449 389 1264 452 392 1265 446 386 1266 450 390 1267 447 387 1268 453 393 1269 454 394 1270 451 391 1271 455 395 1272 452 392 1273 456 396 1274 450 390 1275 453 393 1276 451 391 1277 455 395 1278 448 388 1279 452 392 1280 457 397 1281 458 398 1282 454 394 1283 455 395 1284 456 396 1285 459 399 1286 453 393 1287 457 397 1288 454 394 1289 460 400 1290 461 401 1291 458 398 1292 462 402 1293 459 399 1294 463 403 1295 457 397 1296 460 400 1297 458 398 1298 462 402 1299 455 395 1300 459 399 1301 464 404 1302 465 405 1303 461 401 1304 462 402 1305 463 403 1306 466 406 1307 460 400 1308 464 404 1309 461 401 1310 202 161 1311 199 158 1312 465 405 1313 208 165 1314 466 406 1315 209 166 1316 464 404 1317 202 161 1318 465 405 1319 208 165 1320 462 402 1321 466 406 1322 467 68 1323 204 68 1324 468 68 1325 467 68 1326 203 68 1327 204 68 1328 467 68 1329 468 68 1330 469 68 1331 470 68 1332 469 68 1333 471 68 1334 470 68 1335 467 68 1336 469 68 1337 470 407 1338 471 407 1339 472 407 1340 473 68 1341 472 68 1342 474 68 1343 473 68 1344 470 68 1345 472 68 1346 473 408 1347 474 408 1348 475 408 1349 476 68 1350 475 68 1351 477 68 1352 476 409 1353 473 409 1354 475 409 1355 476 68 1356 477 68 1357 478 68 1358 479 68 1359 478 68 1360 480 68 1361 479 68 1362 476 68 1363 478 68 1364 481 122 1365 480 122 1366 482 122 1367 481 125 1368 479 125 1369 480 125 1370 483 119 1371 482 119 1372 484 119 1373 483 410 1374 481 410 1375 482 410 1376 485 68 1377 484 68 1378 486 68 1379 485 411 1380 483 411 1381 484 411 1382 487 68 1383 486 68 1384 488 68 1385 489 68 1386 486 68 1387 487 68 1388 489 68 1389 485 68 1390 486 68 1391 490 68 1392 488 68 1393 491 68 1394 487 68 1395 488 68 1396 490 68 1397 492 68 1398 491 68 1399 493 68 1400 490 68 1401 491 68 1402 492 68 1403 494 68 1404 493 68 1405 495 68 1406 492 68 1407 493 68 1408 494 68 1409 496 68 1410 495 68 1411 497 68 1412 494 68 1413 495 68 1414 496 68 1415 489 68 1416 487 68 1417 498 68 1418 499 89 1419 498 89 1420 500 89 1421 499 68 1422 489 68 1423 498 68 1424 501 86 1425 500 86 1426 502 86 1427 501 68 1428 499 68 1429 500 68 1430 503 68 1431 502 68 1432 504 68 1433 503 87 1434 501 87 1435 502 87 1436 503 412 1437 504 412 1438 505 412 1439 506 68 1440 505 68 1441 507 68 1442 506 413 1443 503 413 1444 505 413 1445 506 68 1446 507 68 1447 508 68 1448 509 68 1449 508 68 1450 510 68 1451 509 68 1452 506 68 1453 508 68 1454 509 68 1455 510 68 1456 511 68 1457 512 68 1458 511 68 1459 513 68 1460 512 68 1461 509 68 1462 511 68 1463 512 68 1464 513 68 1465 514 68 1466 70 68 1467 514 68 1468 71 68 1469 70 68 1470 512 68 1471 514 68 1472 515 414 1473 516 414 1474 517 415 1475 518 416 1476 519 417 1477 520 418 1478 518 416 1479 520 418 1480 521 418 1481 522 419 1482 517 415 1483 523 420 1484 522 419 1485 515 414 1486 517 415 1487 524 420 1488 523 420 1489 525 421 1490 522 419 1491 523 420 1492 524 420 1493 526 421 1494 525 421 1495 527 422 1496 524 420 1497 525 421 1498 526 421 1499 528 423 1500 527 422 1501 529 424 1502 526 421 1503 527 422 1504 528 423 1505 530 424 1506 529 424 1507 531 425 1508 528 423 1509 529 424 1510 530 424 1511 532 425 1512 531 425 1513 533 426 1514 530 424 1515 531 425 1516 532 425 1517 534 427 1518 533 426 1519 535 428 1520 532 425 1521 533 426 1522 534 427 1523 536 428 1524 535 428 1525 537 429 1526 534 427 1527 535 428 1528 536 428 1529 538 429 1530 537 429 1531 539 430 1532 536 428 1533 537 429 1534 538 429 1535 540 431 1536 539 430 1537 541 432 1538 538 429 1539 539 430 1540 540 431 1541 542 433 1542 541 432 1543 543 434 1544 540 431 1545 541 432 1546 542 433 1547 544 434 1548 543 434 1549 545 435 1550 542 433 1551 543 434 1552 544 434 1553 546 435 1554 545 435 1555 547 436 1556 544 434 1557 545 435 1558 546 435 1559 548 437 1560 547 436 1561 549 438 1562 546 435 1563 547 436 1564 548 437 1565 550 438 1566 549 438 1567 551 439 1568 548 437 1569 549 438 1570 550 438 1571 552 440 1572 551 439 1573 553 441 1574 550 438 1575 551 439 1576 552 440 1577 554 442 1578 555 443 1579 556 444 1580 552 440 1581 553 441 1582 557 445 1583 558 444 1584 556 444 1585 559 446 1586 554 442 1587 556 444 1588 558 444 1589 560 446 1590 559 446 1591 561 447 1592 558 444 1593 559 446 1594 560 446 1595 562 447 1596 561 447 1597 563 448 1598 560 446 1599 561 447 1600 562 447 1601 564 448 1602 563 448 1603 565 449 1604 562 447 1605 563 448 1606 564 448 1607 566 450 1608 565 449 1609 567 451 1610 564 448 1611 565 449 1612 566 450 1613 568 451 1614 567 451 1615 569 452 1616 566 450 1617 567 451 1618 568 451 1619 570 453 1620 569 452 1621 571 454 1622 568 451 1623 569 452 1624 570 453 1625 572 454 1626 571 454 1627 573 455 1628 570 453 1629 571 454 1630 572 454 1631 574 455 1632 573 455 1633 575 456 1634 572 454 1635 573 455 1636 574 455 1637 576 457 1638 575 456 1639 577 458 1640 574 455 1641 575 456 1642 576 457 1643 578 459 1644 577 458 1645 579 460 1646 576 457 1647 577 458 1648 578 459 1649 580 460 1650 579 460 1651 581 461 1652 578 459 1653 579 460 1654 580 460 1655 582 461 1656 581 461 1657 583 462 1658 580 460 1659 581 461 1660 582 461 1661 584 463 1662 583 462 1663 585 464 1664 582 461 1665 583 462 1666 584 463 1667 586 464 1668 585 464 1669 519 417 1670 584 463 1671 585 464 1672 586 464 1673 586 464 1674 519 417 1675 518 416 1676 587 465 1677 588 466 1678 589 467 1679 590 468 1680 591 469 1681 592 470 1682 593 471 1683 594 472 1684 595 473 1685 596 474 1686 597 475 1687 591 469 1688 598 476 1689 596 474 1690 591 469 1691 590 468 1692 598 476 1693 591 469 1694 599 477 1695 600 478 1696 588 466 1697 590 468 1698 592 470 1699 601 479 1700 602 480 1701 599 477 1702 588 466 1703 587 465 1704 602 480 1705 588 466 1706 603 481 1707 600 478 1708 599 477 1709 604 482 1710 601 479 1711 605 483 1712 604 482 1713 590 468 1714 601 479 1715 602 480 1716 606 484 1717 599 477 1718 607 485 1719 599 477 1720 606 484 1721 608 486 1722 603 481 1723 599 477 1724 607 485 1725 608 486 1726 599 477 1727 609 487 1728 610 488 1729 606 484 1730 611 489 1731 606 484 1732 610 488 1733 602 480 1734 609 487 1735 606 484 1736 611 489 1737 607 485 1738 606 484 1739 609 487 1740 612 490 1741 610 488 1742 613 491 1743 614 492 1744 615 493 1745 616 494 1746 611 489 1747 610 488 1748 613 491 1749 617 495 1750 614 492 1751 609 487 1752 618 496 1753 612 490 1754 619 497 1755 615 493 1756 620 498 1757 613 491 1758 615 493 1759 619 497 1760 609 487 1761 621 499 1762 618 496 1763 622 500 1764 620 498 1765 623 501 1766 624 502 1767 620 498 1768 622 500 1769 619 497 1770 620 498 1771 624 502 1772 625 503 1773 626 504 1774 621 499 1775 627 505 1776 623 501 1777 628 506 1778 609 487 1779 625 503 1780 621 499 1781 622 500 1782 623 501 1783 627 505 1784 625 503 1785 629 507 1786 626 504 1787 627 505 1788 628 506 1789 630 508 1790 631 509 1791 632 510 1792 629 507 1793 633 511 1794 634 512 1795 635 513 1796 625 503 1797 631 509 1798 629 507 1799 627 505 1800 630 508 1801 636 514 1802 631 509 1803 637 515 1804 632 510 1805 638 516 1806 635 513 1807 639 517 1808 638 516 1809 633 511 1810 635 513 1811 631 509 1812 640 518 1813 637 515 1814 641 519 1815 639 517 1816 642 520 1817 638 516 1818 639 517 1819 641 519 1820 631 509 1821 643 521 1822 640 518 1823 644 522 1824 642 520 1825 645 523 1826 641 519 1827 642 520 1828 644 522 1829 646 524 1830 647 525 1831 643 521 1832 648 526 1833 645 523 1834 649 527 1835 631 509 1836 646 524 1837 643 521 1838 644 522 1839 645 523 1840 648 526 1841 646 524 1842 650 528 1843 647 525 1844 651 529 1845 647 525 1846 650 528 1847 652 530 1848 649 527 1849 653 531 1850 648 526 1851 649 527 1852 652 530 1853 654 532 1854 655 533 1855 650 528 1856 656 534 1857 650 528 1858 655 533 1859 646 524 1860 654 532 1861 650 528 1862 657 535 1863 650 528 1864 656 534 1865 651 529 1866 650 528 1867 657 535 1868 658 536 1869 659 537 1870 655 533 1871 660 538 1872 655 533 1873 659 537 1874 654 532 1875 658 536 1876 655 533 1877 656 534 1878 655 533 1879 660 538 1880 661 539 1881 662 540 1882 659 537 1883 663 541 1884 659 537 1885 662 540 1886 658 536 1887 661 539 1888 659 537 1889 660 538 1890 659 537 1891 663 541 1892 664 542 1893 665 543 1894 662 540 1895 666 544 1896 662 540 1897 665 543 1898 661 539 1899 664 542 1900 662 540 1901 663 541 1902 662 540 1903 666 544 1904 667 545 1905 668 546 1906 665 543 1907 669 547 1908 665 543 1909 668 546 1910 664 542 1911 667 545 1912 665 543 1913 666 544 1914 665 543 1915 669 547 1916 670 548 1917 671 549 1918 668 546 1919 672 550 1920 668 546 1921 671 549 1922 667 545 1923 670 548 1924 668 546 1925 669 547 1926 668 546 1927 672 550 1928 673 551 1929 674 552 1930 671 549 1931 675 553 1932 671 549 1933 674 552 1934 670 548 1935 673 551 1936 671 549 1937 672 550 1938 671 549 1939 675 553 1940 676 554 1941 677 555 1942 674 552 1943 678 556 1944 674 552 1945 677 555 1946 673 551 1947 676 554 1948 674 552 1949 675 553 1950 674 552 1951 678 556 1952 679 557 1953 680 558 1954 677 555 1955 681 559 1956 677 555 1957 680 558 1958 682 560 1959 679 557 1960 677 555 1961 676 554 1962 682 560 1963 677 555 1964 678 556 1965 677 555 1966 681 559 1967 683 561 1968 684 562 1969 685 563 1970 686 564 1971 681 559 1972 680 558 1973 687 565 1974 688 566 1975 684 562 1976 683 561 1977 687 565 1978 684 562 1979 683 561 1980 685 563 1981 689 567 1982 690 568 1983 682 560 1984 676 554 1985 691 569 1986 689 567 1987 692 570 1988 691 569 1989 683 561 1990 689 567 1991 693 571 1992 676 554 1993 673 551 1994 694 572 1995 690 568 1996 676 554 1997 693 571 1998 694 572 1999 676 554 2000 695 573 2001 673 551 2002 670 548 2003 695 573 2004 693 571 2005 673 551 2006 696 574 2007 670 548 2008 667 545 2009 697 575 2010 695 573 2011 670 548 2012 698 576 2013 697 575 2014 670 548 2015 696 574 2016 698 576 2017 670 548 2018 699 577 2019 667 545 2020 664 542 2021 700 578 2022 667 545 2023 699 577 2024 701 579 2025 667 545 2026 700 578 2027 702 580 2028 696 574 2029 667 545 2030 703 581 2031 702 580 2032 667 545 2033 704 582 2034 703 581 2035 667 545 2036 705 583 2037 704 582 2038 667 545 2039 706 584 2040 705 583 2041 667 545 2042 701 579 2043 706 584 2044 667 545 2045 707 585 2046 664 542 2047 661 539 2048 699 577 2049 664 542 2050 707 585 2051 708 586 2052 661 539 2053 658 536 2054 707 585 2055 661 539 2056 708 586 2057 709 587 2058 658 536 2059 654 532 2060 708 586 2061 658 536 2062 709 587 2063 710 588 2064 654 532 2065 646 524 2066 709 587 2067 654 532 2068 710 588 2069 711 589 2070 646 524 2071 631 509 2072 712 590 2073 646 524 2074 711 589 2075 710 588 2076 646 524 2077 712 590 2078 713 591 2079 631 509 2080 625 503 2081 711 589 2082 631 509 2083 713 591 2084 714 592 2085 625 503 2086 609 487 2087 713 591 2088 625 503 2089 714 592 2090 715 593 2091 609 487 2092 602 480 2093 714 592 2094 609 487 2095 715 593 2096 716 594 2097 602 480 2098 587 465 2099 715 593 2100 602 480 2101 717 595 2102 716 594 2103 717 595 2104 602 480 2105 593 471 2106 718 596 2107 594 472 2108 719 597 2109 605 483 2110 720 598 2111 719 597 2112 604 482 2113 605 483 2114 721 599 2115 608 486 2116 607 485 2117 722 600 2118 720 598 2119 723 601 2120 722 600 2121 719 597 2122 720 598 2123 724 602 2124 607 485 2125 611 489 2126 725 603 2127 721 599 2128 607 485 2129 724 602 2130 725 603 2131 607 485 2132 726 604 2133 727 605 2134 611 489 2135 728 606 2136 611 489 2137 727 605 2138 729 607 2139 726 604 2140 611 489 2141 730 608 2142 729 607 2143 611 489 2144 731 609 2145 730 608 2146 611 489 2147 616 494 2148 731 609 2149 611 489 2150 728 606 2151 724 602 2152 611 489 2153 732 610 2154 733 611 2155 734 612 2156 735 613 2157 728 606 2158 727 605 2159 736 614 2160 735 613 2161 727 605 2162 732 610 2163 737 615 2164 733 611 2165 738 616 2166 734 612 2167 739 617 2168 732 610 2169 734 612 2170 738 616 2171 740 618 2172 739 617 2173 741 619 2174 738 616 2175 739 617 2176 740 618 2177 742 620 2178 741 619 2179 743 621 2180 740 618 2181 741 619 2182 742 620 2183 744 622 2184 743 621 2185 617 495 2186 742 620 2187 743 621 2188 744 622 2189 744 622 2190 617 495 2191 613 491 2192 745 623 2193 723 601 2194 746 624 2195 745 623 2196 722 600 2197 723 601 2198 747 625 2199 725 603 2200 724 602 2201 747 625 2202 748 626 2203 725 603 2204 749 627 2205 746 624 2206 750 628 2207 749 627 2208 745 623 2209 746 624 2210 751 629 2211 724 602 2212 728 606 2213 751 629 2214 747 625 2215 724 602 2216 752 630 2217 728 606 2218 735 613 2219 752 630 2220 751 629 2221 728 606 2222 753 631 2223 754 632 2224 735 613 2225 755 633 2226 735 613 2227 754 632 2228 756 634 2229 753 631 2230 735 613 2231 757 635 2232 756 634 2233 735 613 2234 736 614 2235 757 635 2236 735 613 2237 755 633 2238 752 630 2239 735 613 2240 657 535 2241 758 636 2242 754 632 2243 759 637 2244 754 632 2245 758 636 2246 753 631 2247 657 535 2248 754 632 2249 759 637 2250 755 633 2251 754 632 2252 656 534 2253 760 638 2254 758 636 2255 761 639 2256 758 636 2257 760 638 2258 657 535 2259 656 534 2260 758 636 2261 761 639 2262 759 637 2263 758 636 2264 660 538 2265 762 640 2266 760 638 2267 763 641 2268 760 638 2269 762 640 2270 656 534 2271 660 538 2272 760 638 2273 763 641 2274 761 639 2275 760 638 2276 663 541 2277 764 642 2278 762 640 2279 765 643 2280 762 640 2281 764 642 2282 660 538 2283 663 541 2284 762 640 2285 765 643 2286 763 641 2287 762 640 2288 666 544 2289 766 644 2290 764 642 2291 765 643 2292 764 642 2293 766 644 2294 663 541 2295 666 544 2296 764 642 2297 669 547 2298 767 645 2299 766 644 2300 768 646 2301 766 644 2302 767 645 2303 666 544 2304 669 547 2305 766 644 2306 768 646 2307 765 643 2308 766 644 2309 672 550 2310 769 647 2311 767 645 2312 770 648 2313 767 645 2314 769 647 2315 669 547 2316 672 550 2317 767 645 2318 771 649 2319 768 646 2320 767 645 2321 772 650 2322 771 649 2323 767 645 2324 773 651 2325 772 650 2326 767 645 2327 770 648 2328 773 651 2329 767 645 2330 675 553 2331 774 652 2332 769 647 2333 775 653 2334 776 654 2335 777 655 2336 672 550 2337 675 553 2338 769 647 2339 775 653 2340 778 656 2341 776 654 2342 675 553 2343 779 657 2344 774 652 2345 780 658 2346 777 655 2347 781 659 2348 775 653 2349 777 655 2350 780 658 2351 675 553 2352 782 660 2353 779 657 2354 780 658 2355 781 659 2356 783 661 2357 678 556 2358 784 662 2359 782 660 2360 785 663 2361 783 661 2362 786 664 2363 675 553 2364 678 556 2365 782 660 2366 780 658 2367 783 661 2368 785 663 2369 678 556 2370 787 665 2371 784 662 2372 785 663 2373 786 664 2374 788 666 2375 678 556 2376 789 667 2377 787 665 2378 790 668 2379 791 668 2380 792 668 2381 793 669 2382 791 669 2383 790 669 2384 785 663 2385 788 666 2386 794 670 2387 678 556 2388 795 671 2389 789 667 2390 796 672 2391 789 667 2392 795 671 2393 790 673 2394 792 673 2395 797 673 2396 681 559 2397 798 674 2398 795 671 2399 799 675 2400 795 671 2401 798 674 2402 678 556 2403 681 559 2404 795 671 2405 799 675 2406 796 672 2407 795 671 2408 800 676 2409 801 677 2410 798 674 2411 802 678 2412 798 674 2413 801 677 2414 803 679 2415 800 676 2416 798 674 2417 681 559 2418 803 679 2419 798 674 2420 799 675 2421 798 674 2422 802 678 2423 804 680 2424 805 681 2425 806 682 2426 807 683 2427 802 678 2428 801 677 2429 808 684 2430 809 685 2431 805 681 2432 804 680 2433 808 684 2434 805 681 2435 804 680 2436 806 682 2437 810 686 2438 686 564 2439 803 679 2440 681 559 2441 687 565 2442 810 686 2443 688 566 2444 687 565 2445 804 680 2446 810 686 2447 811 687 2448 657 535 2449 753 631 2450 812 688 2451 651 529 2452 657 535 2453 813 689 2454 812 688 2455 657 535 2456 814 690 2457 813 689 2458 657 535 2459 811 687 2460 814 690 2461 657 535 2462 815 691 2463 816 692 2464 817 693 2465 818 694 2466 819 695 2467 816 692 2468 818 694 2469 816 692 2470 815 691 2471 815 691 2472 817 693 2473 820 696 2474 821 697 2475 822 698 2476 737 615 2477 815 691 2478 820 696 2479 823 699 2480 821 697 2481 737 615 2482 732 610 2483 747 625 2484 824 700 2485 748 626 2486 825 701 2487 750 628 2488 826 702 2489 825 701 2490 749 627 2491 750 628 2492 261 219 2493 824 700 2494 747 625 2495 261 219 2496 827 703 2497 824 700 2498 825 701 2499 826 702 2500 828 704 2501 258 216 2502 747 625 2503 751 629 2504 258 216 2505 261 219 2506 747 625 2507 255 213 2508 751 629 2509 752 630 2510 255 213 2511 258 216 2512 751 629 2513 252 210 2514 752 630 2515 755 633 2516 252 210 2517 255 213 2518 752 630 2519 250 208 2520 755 633 2521 759 637 2522 250 208 2523 252 210 2524 755 633 2525 247 205 2526 759 637 2527 761 639 2528 247 205 2529 250 208 2530 759 637 2531 244 202 2532 761 639 2533 763 641 2534 244 202 2535 247 205 2536 761 639 2537 241 199 2538 763 641 2539 765 643 2540 241 199 2541 244 202 2542 763 641 2543 238 196 2544 765 643 2545 768 646 2546 238 196 2547 241 199 2548 765 643 2549 236 194 2550 768 646 2551 771 649 2552 236 194 2553 238 196 2554 768 646 2555 829 705 2556 830 706 2557 771 649 2558 232 189 2559 771 649 2560 830 706 2561 831 707 2562 829 705 2563 771 649 2564 832 708 2565 831 707 2566 771 649 2567 833 709 2568 832 708 2569 771 649 2570 834 710 2571 833 709 2572 771 649 2573 772 650 2574 834 710 2575 771 649 2576 232 189 2577 236 194 2578 771 649 2579 835 711 2580 836 712 2581 830 706 2582 223 180 2583 830 706 2584 836 712 2585 837 713 2586 835 711 2587 830 706 2588 838 714 2589 837 713 2590 830 706 2591 839 715 2592 838 714 2593 830 706 2594 829 705 2595 839 715 2596 830 706 2597 223 180 2598 232 189 2599 830 706 2600 840 716 2601 802 678 2602 836 712 2603 216 173 2604 836 712 2605 802 678 2606 835 711 2607 840 716 2608 836 712 2609 216 173 2610 223 180 2611 836 712 2612 807 683 2613 841 717 2614 802 678 2615 212 169 2616 802 678 2617 841 717 2618 842 718 2619 799 675 2620 802 678 2621 840 716 2622 842 718 2623 802 678 2624 212 169 2625 216 173 2626 802 678 2627 808 684 2628 843 719 2629 809 685 2630 844 720 2631 212 169 2632 841 717 2633 845 721 2634 846 722 2635 843 719 2636 808 684 2637 845 721 2638 843 719 2639 847 223 2640 848 223 2641 849 223 2642 850 223 2643 848 223 2644 847 223 2645 851 723 2646 852 723 2647 853 723 2648 854 223 2649 850 223 2650 847 223 2651 851 724 2652 853 724 2653 855 724 2654 856 725 2655 857 726 2656 858 727 2657 859 728 2658 858 727 2659 860 729 2660 856 725 2661 858 727 2662 859 728 2663 859 728 2664 860 729 2665 861 730 2666 862 731 2667 861 730 2668 863 732 2669 859 728 2670 861 730 2671 862 731 2672 862 731 2673 863 732 2674 864 733 2675 865 734 2676 864 733 2677 866 735 2678 862 731 2679 864 733 2680 865 734 2681 865 734 2682 866 735 2683 867 736 2684 868 737 2685 867 736 2686 869 738 2687 865 734 2688 867 736 2689 868 737 2690 868 737 2691 869 738 2692 870 739 2693 775 653 2694 870 739 2695 778 656 2696 868 737 2697 870 739 2698 775 653 2699 261 219 2700 263 221 2701 827 703 2702 871 740 2703 828 704 2704 872 741 2705 871 740 2706 825 701 2707 828 704 2708 873 742 2709 872 741 2710 12 12 2711 873 742 2712 871 740 2713 872 741 2714 844 720 2715 205 162 2716 212 169 2717 845 721 2718 211 168 2719 846 722 2720 845 721 2721 208 165 2722 211 168 2723 11 11 2724 873 742 2725 12 12 2726 874 743 2727 875 223 2728 876 744 2729 877 745 2730 878 746 2731 879 747 2732 880 748 2733 874 743 2734 876 744 2735 881 749 2736 880 748 2737 876 744 2738 882 750 2739 881 749 2740 876 744 2741 883 751 2742 882 750 2743 876 744 2744 884 752 2745 883 751 2746 876 744 2747 885 753 2748 884 752 2749 876 744 2750 886 754 2751 885 753 2752 876 744 2753 887 755 2754 886 754 2755 876 744 2756 888 756 2757 887 755 2758 876 744 2759 889 757 2760 888 756 2761 876 744 2762 890 758 2763 889 757 2764 876 744 2765 891 759 2766 890 758 2767 876 744 2768 892 760 2769 891 759 2770 876 744 2771 893 761 2772 892 760 2773 876 744 2774 894 762 2775 893 761 2776 876 744 2777 895 763 2778 894 762 2779 876 744 2780 896 764 2781 895 763 2782 876 744 2783 897 765 2784 896 764 2785 876 744 2786 898 766 2787 897 765 2788 876 744 2789 899 767 2790 898 766 2791 876 744 2792 900 768 2793 899 767 2794 876 744 2795 901 769 2796 900 768 2797 876 744 2798 902 770 2799 903 771 2800 878 746 2801 904 772 2802 878 746 2803 877 745 2804 905 773 2805 878 746 2806 904 772 2807 906 774 2808 878 746 2809 905 773 2810 907 775 2811 878 746 2812 906 774 2813 908 776 2814 878 746 2815 907 775 2816 909 777 2817 878 746 2818 908 776 2819 910 778 2820 878 746 2821 909 777 2822 911 779 2823 878 746 2824 910 778 2825 912 780 2826 878 746 2827 911 779 2828 913 781 2829 878 746 2830 912 780 2831 914 782 2832 878 746 2833 913 781 2834 915 783 2835 878 746 2836 914 782 2837 916 784 2838 878 746 2839 915 783 2840 917 785 2841 878 746 2842 916 784 2843 918 786 2844 878 746 2845 917 785 2846 919 787 2847 878 746 2848 918 786 2849 920 788 2850 878 746 2851 919 787 2852 921 789 2853 878 746 2854 920 788 2855 922 790 2856 878 746 2857 921 789 2858 902 770 2859 878 746 2860 922 790 2861 877 745 2862 879 747 2863 923 791 2864 924 792 2865 874 743 2866 880 748 2867 925 793 2868 923 791 2869 926 794 2870 925 793 2871 877 745 2872 923 791 2873 927 795 2874 880 748 2875 881 749 2876 928 796 2877 924 792 2878 880 748 2879 927 795 2880 928 796 2881 880 748 2882 929 797 2883 881 749 2884 882 750 2885 930 798 2886 927 795 2887 881 749 2888 929 797 2889 930 798 2890 881 749 2891 931 799 2892 882 750 2893 883 751 2894 932 800 2895 929 797 2896 882 750 2897 931 799 2898 932 800 2899 882 750 2900 933 801 2901 883 751 2902 884 752 2903 933 801 2904 931 799 2905 883 751 2906 934 802 2907 884 752 2908 885 753 2909 934 802 2910 933 801 2911 884 752 2912 935 803 2913 885 753 2914 886 754 2915 935 803 2916 934 802 2917 885 753 2918 936 804 2919 886 754 2920 887 755 2921 937 805 2922 935 803 2923 886 754 2924 936 804 2925 937 805 2926 886 754 2927 938 806 2928 887 755 2929 888 756 2930 938 806 2931 936 804 2932 887 755 2933 939 807 2934 888 756 2935 889 757 2936 939 807 2937 938 806 2938 888 756 2939 940 808 2940 889 757 2941 890 758 2942 941 809 2943 939 807 2944 889 757 2945 940 808 2946 941 809 2947 889 757 2948 942 810 2949 890 758 2950 891 759 2951 942 810 2952 940 808 2953 890 758 2954 943 811 2955 891 759 2956 892 760 2957 944 812 2958 942 810 2959 891 759 2960 943 811 2961 944 812 2962 891 759 2963 945 813 2964 892 760 2965 893 761 2966 946 814 2967 943 811 2968 892 760 2969 945 813 2970 946 814 2971 892 760 2972 947 815 2973 893 761 2974 894 762 2975 947 815 2976 945 813 2977 893 761 2978 948 816 2979 894 762 2980 895 763 2981 948 816 2982 947 815 2983 894 762 2984 949 817 2985 895 763 2986 896 764 2987 949 817 2988 948 816 2989 895 763 2990 950 818 2991 896 764 2992 897 765 2993 950 818 2994 949 817 2995 896 764 2996 951 819 2997 897 765 2998 898 766 2999 951 819 3000 950 818 3001 897 765 3002 952 820 3003 898 766 3004 899 767 3005 952 820 3006 951 819 3007 898 766 3008 953 821 3009 899 767 3010 900 768 3011 953 821 3012 952 820 3013 899 767 3014 954 822 3015 900 768 3016 901 769 3017 954 822 3018 953 821 3019 900 768 3020 954 822 3021 901 769 3022 955 823 3023 902 770 3024 956 824 3025 903 771 3026 957 825 3027 954 822 3028 955 823 3029 957 825 3030 955 823 3031 958 826 3032 959 827 3033 960 828 3034 956 824 3035 959 827 3036 956 824 3037 902 770 3038 961 829 3039 962 830 3040 963 831 3041 964 832 3042 965 833 3043 962 830 3044 961 829 3045 964 832 3046 962 830 3047 961 829 3048 963 831 3049 966 834 3050 961 829 3051 966 834 3052 967 835 3053 961 829 3054 967 835 3055 968 836 3056 969 837 3057 968 836 3058 970 838 3059 969 837 3060 961 829 3061 968 836 3062 969 837 3063 970 838 3064 971 839 3065 969 837 3066 971 839 3067 972 840 3068 973 841 3069 972 840 3070 974 842 3071 973 841 3072 969 837 3073 972 840 3074 973 841 3075 974 842 3076 975 843 3077 976 844 3078 975 843 3079 977 845 3080 976 844 3081 973 841 3082 975 843 3083 978 846 3084 937 805 3085 936 804 3086 976 844 3087 977 845 3088 979 847 3089 980 848 3090 936 804 3091 938 806 3092 978 846 3093 936 804 3094 980 848 3095 981 849 3096 938 806 3097 939 807 3098 982 850 3099 938 806 3100 981 849 3101 980 848 3102 938 806 3103 982 850 3104 983 851 3105 984 852 3106 939 807 3107 985 853 3108 939 807 3109 984 852 3110 941 809 3111 983 851 3112 939 807 3113 981 849 3114 939 807 3115 985 853 3116 986 854 3117 987 854 3118 988 854 3119 989 855 3120 987 855 3121 986 855 3122 990 856 3123 985 853 3124 984 852 3125 991 223 3126 992 223 3127 993 223 3128 994 855 3129 989 855 3130 986 855 3131 995 223 3132 993 223 3133 996 223 3134 997 223 3135 991 223 3136 993 223 3137 998 223 3138 997 223 3139 993 223 3140 995 223 3141 998 223 3142 993 223 3143 999 223 3144 996 223 3145 1000 223 3146 999 223 3147 995 223 3148 996 223 3149 1001 223 3150 1000 223 3151 1002 223 3152 1003 223 3153 999 223 3154 1000 223 3155 1001 223 3156 1003 223 3157 1000 223 3158 946 814 3159 1004 855 3160 943 811 3161 1005 857 3162 1006 857 3163 1007 857 3164 1008 223 3165 1001 223 3166 1002 223 3167 1009 223 3168 1008 223 3169 1002 223 3170 1005 858 3171 1007 858 3172 1010 858 3173 1011 859 3174 946 814 3175 945 813 3176 1012 860 3177 1013 861 3178 946 814 3179 1005 857 3180 1010 857 3181 1014 857 3182 1011 859 3183 1012 860 3184 946 814 3185 1015 862 3186 945 813 3187 947 815 3188 1015 862 3189 1011 859 3190 945 813 3191 1016 863 3192 947 815 3193 948 816 3194 1016 863 3195 1015 862 3196 947 815 3197 1017 864 3198 948 816 3199 949 817 3200 1017 864 3201 1016 863 3202 948 816 3203 1018 865 3204 949 817 3205 950 818 3206 1018 865 3207 1017 864 3208 949 817 3209 1019 866 3210 950 818 3211 951 819 3212 1019 866 3213 1018 865 3214 950 818 3215 1020 867 3216 951 819 3217 952 820 3218 1020 867 3219 1019 866 3220 951 819 3221 1021 868 3222 952 820 3223 953 821 3224 1021 868 3225 1020 867 3226 952 820 3227 957 825 3228 953 821 3229 954 822 3230 957 825 3231 1021 868 3232 953 821 3233 1022 869 3234 957 825 3235 958 826 3236 1022 869 3237 958 826 3238 1023 870 3239 1024 871 3240 1025 872 3241 960 828 3242 1024 871 3243 960 828 3244 959 827 3245 1026 873 3246 1027 874 3247 1028 875 3248 1011 859 3249 1029 876 3250 1012 860 3251 1026 873 3252 1028 875 3253 1030 877 3254 1011 859 3255 1031 878 3256 1029 876 3257 1032 879 3258 1030 877 3259 1033 880 3260 1026 873 3261 1030 877 3262 1032 879 3263 1011 859 3264 1034 881 3265 1031 878 3266 1032 879 3267 1033 880 3268 1035 882 3269 1036 883 3270 1034 881 3271 1011 859 3272 1037 884 3273 1038 885 3274 1034 881 3275 1032 879 3276 1035 882 3277 1039 886 3278 1036 883 3279 1037 884 3280 1034 881 3281 1040 887 3282 1011 859 3283 1015 862 3284 1040 887 3285 1036 883 3286 1011 859 3287 1041 888 3288 1015 862 3289 1016 863 3290 1041 888 3291 1040 887 3292 1015 862 3293 1042 889 3294 1016 863 3295 1017 864 3296 1042 889 3297 1041 888 3298 1016 863 3299 1043 890 3300 1017 864 3301 1018 865 3302 1043 890 3303 1042 889 3304 1017 864 3305 1044 891 3306 1018 865 3307 1019 866 3308 1044 891 3309 1043 890 3310 1018 865 3311 1045 892 3312 1019 866 3313 1020 867 3314 1045 892 3315 1044 891 3316 1019 866 3317 1046 893 3318 1020 867 3319 1021 868 3320 1046 893 3321 1045 892 3322 1020 867 3323 1047 894 3324 1021 868 3325 957 825 3326 1047 894 3327 1046 893 3328 1021 868 3329 1022 869 3330 1047 894 3331 957 825 3332 1048 895 3333 1022 869 3334 1023 870 3335 1048 895 3336 1023 870 3337 1049 896 3338 1050 897 3339 1051 898 3340 1025 872 3341 1050 897 3342 1025 872 3343 1024 871 3344 1037 884 3345 1052 899 3346 1038 885 3347 1053 900 3348 1039 886 3349 1054 901 3350 1032 879 3351 1039 886 3352 1053 900 3353 1037 884 3354 1055 902 3355 1052 899 3356 1053 900 3357 1054 901 3358 1056 903 3359 1037 884 3360 1057 904 3361 1055 902 3362 1058 905 3363 1056 903 3364 1059 906 3365 1053 900 3366 1056 903 3367 1058 905 3368 1037 884 3369 1060 907 3370 1057 904 3371 1058 905 3372 1059 906 3373 1061 908 3374 1062 909 3375 1063 910 3376 1060 907 3377 1064 911 3378 1061 908 3379 1065 912 3380 1037 884 3381 1062 909 3382 1060 907 3383 1058 905 3384 1061 908 3385 1064 911 3386 1062 909 3387 1066 913 3388 1063 910 3389 1064 911 3390 1065 912 3391 1067 914 3392 1062 909 3393 1068 915 3394 1066 913 3395 1069 916 3396 1067 914 3397 1070 917 3398 1064 911 3399 1067 914 3400 1069 916 3401 1062 909 3402 1071 918 3403 1068 915 3404 1069 916 3405 1070 917 3406 1072 919 3407 1062 909 3408 1073 920 3409 1071 918 3410 1074 921 3411 1072 919 3412 1075 922 3413 1069 916 3414 1072 919 3415 1074 921 3416 1062 909 3417 1076 923 3418 1073 920 3419 1074 921 3420 1075 922 3421 1077 924 3422 1062 909 3423 985 853 3424 1076 923 3425 1078 925 3426 1076 923 3427 985 853 3428 1074 921 3429 1077 924 3430 1079 926 3431 1080 927 3432 981 849 3433 985 853 3434 1062 909 3435 1080 927 3436 985 853 3437 1081 928 3438 1078 925 3439 985 853 3440 1082 929 3441 1081 928 3442 985 853 3443 990 856 3444 1082 929 3445 985 853 3446 1083 930 3447 982 850 3448 981 849 3449 1084 931 3450 1083 930 3451 981 849 3452 1085 932 3453 1084 931 3454 981 849 3455 1080 927 3456 1085 932 3457 981 849 3458 1086 933 3459 1087 934 3460 1088 935 3461 1086 933 3462 1089 936 3463 1087 934 3464 1090 937 3465 1088 935 3466 1091 938 3467 1090 937 3468 1086 933 3469 1088 935 3470 1092 939 3471 1091 938 3472 1093 940 3473 1092 939 3474 1090 937 3475 1091 938 3476 1094 941 3477 1085 932 3478 1080 927 3479 1092 939 3480 1093 940 3481 1095 942 3482 1096 943 3483 1080 927 3484 1062 909 3485 1097 944 3486 1094 941 3487 1080 927 3488 1098 945 3489 1097 944 3490 1080 927 3491 1096 943 3492 1098 945 3493 1080 927 3494 1099 946 3495 1062 909 3496 1037 884 3497 1099 946 3498 1096 943 3499 1062 909 3500 1100 947 3501 1037 884 3502 1036 883 3503 1100 947 3504 1099 946 3505 1037 884 3506 1101 948 3507 1036 883 3508 1040 887 3509 1101 948 3510 1100 947 3511 1036 883 3512 1102 949 3513 1040 887 3514 1041 888 3515 1102 949 3516 1101 948 3517 1040 887 3518 1103 950 3519 1041 888 3520 1042 889 3521 1103 950 3522 1102 949 3523 1041 888 3524 1104 951 3525 1042 889 3526 1043 890 3527 1104 951 3528 1103 950 3529 1042 889 3530 1105 952 3531 1043 890 3532 1044 891 3533 1105 952 3534 1104 951 3535 1043 890 3536 1106 953 3537 1044 891 3538 1045 892 3539 1106 953 3540 1105 952 3541 1044 891 3542 1107 954 3543 1045 892 3544 1046 893 3545 1108 955 3546 1106 953 3547 1045 892 3548 1109 956 3549 1108 955 3550 1045 892 3551 1107 954 3552 1109 956 3553 1045 892 3554 1110 957 3555 1046 893 3556 1047 894 3557 1110 957 3558 1107 954 3559 1046 893 3560 1111 958 3561 1047 894 3562 1022 869 3563 1112 959 3564 1110 957 3565 1047 894 3566 1113 960 3567 1112 959 3568 1047 894 3569 1111 958 3570 1113 960 3571 1047 894 3572 1048 895 3573 1111 958 3574 1022 869 3575 1114 961 3576 1048 895 3577 1049 896 3578 1114 961 3579 1049 896 3580 1115 962 3581 1116 963 3582 1117 964 3583 1051 898 3584 1116 963 3585 1051 898 3586 1050 897 3587 1118 965 3588 1095 942 3589 1119 966 3590 1118 965 3591 1092 939 3592 1095 942 3593 1120 967 3594 1119 966 3595 1121 968 3596 1120 967 3597 1118 965 3598 1119 966 3599 1122 969 3600 1098 945 3601 1096 943 3602 1123 970 3603 1121 968 3604 1124 971 3605 1123 970 3606 1120 967 3607 1121 968 3608 1125 972 3609 1096 943 3610 1099 946 3611 1126 973 3612 1122 969 3613 1096 943 3614 1125 972 3615 1126 973 3616 1096 943 3617 1127 974 3618 1099 946 3619 1100 947 3620 1127 974 3621 1125 972 3622 1099 946 3623 1128 975 3624 1100 947 3625 1101 948 3626 1128 975 3627 1127 974 3628 1100 947 3629 1129 976 3630 1101 948 3631 1102 949 3632 1129 976 3633 1128 975 3634 1101 948 3635 1130 977 3636 1102 949 3637 1103 950 3638 1130 977 3639 1129 976 3640 1102 949 3641 1131 978 3642 1103 950 3643 1104 951 3644 1131 978 3645 1130 977 3646 1103 950 3647 1132 979 3648 1104 951 3649 1105 952 3650 1132 979 3651 1131 978 3652 1104 951 3653 1133 980 3654 1105 952 3655 1106 953 3656 1134 981 3657 1135 982 3658 1105 952 3659 1136 983 3660 1105 952 3661 1135 982 3662 1137 984 3663 1134 981 3664 1105 952 3665 1133 980 3666 1137 984 3667 1105 952 3668 1136 983 3669 1132 979 3670 1105 952 3671 1138 985 3672 1139 986 3673 1140 987 3674 1138 985 3675 1141 988 3676 1139 986 3677 1138 985 3678 1140 987 3679 1142 989 3680 1143 990 3681 1144 990 3682 1145 990 3683 1146 991 3684 1144 991 3685 1143 991 3686 1138 985 3687 1142 989 3688 1147 992 3689 1148 223 3690 1149 223 3691 1150 223 3692 1151 223 3693 1152 223 3694 1149 223 3695 1153 223 3696 1151 223 3697 1149 223 3698 1148 223 3699 1153 223 3700 1149 223 3701 1154 223 3702 1150 223 3703 1155 223 3704 1156 223 3705 1148 223 3706 1150 223 3707 1154 223 3708 1156 223 3709 1150 223 3710 1157 993 3711 1113 960 3712 1111 958 3713 1154 223 3714 1155 223 3715 1158 223 3716 1114 961 3717 1111 958 3718 1048 895 3719 1159 994 3720 1157 993 3721 1111 958 3722 1114 961 3723 1159 994 3724 1111 958 3725 1160 995 3726 1114 961 3727 1115 962 3728 1160 995 3729 1115 962 3730 1161 996 3731 1162 997 3732 1163 998 3733 1117 964 3734 1162 997 3735 1117 964 3736 1116 963 3737 1164 999 3738 1165 1000 3739 1157 993 3740 1166 1001 3741 1167 1001 3742 1168 1001 3743 1159 994 3744 1164 999 3745 1157 993 3746 1164 999 3747 1169 1002 3748 1165 1000 3749 1166 1003 3750 1168 1003 3751 1170 1003 3752 1171 1004 3753 1172 1005 3754 1169 1002 3755 1173 1006 3756 1174 1007 3757 1175 1008 3758 1164 999 3759 1171 1004 3760 1169 1002 3761 1171 1004 3762 1176 1009 3763 1172 1005 3764 1173 1006 3765 1175 1008 3766 1177 1010 3767 1171 1004 3768 1178 1011 3769 1176 1009 3770 1179 1012 3771 1177 1010 3772 1180 1013 3773 1173 1006 3774 1177 1010 3775 1179 1012 3776 1136 983 3777 1181 1014 3778 1178 1011 3779 1179 1012 3780 1180 1013 3781 1182 1015 3782 1171 1004 3783 1136 983 3784 1178 1011 3785 1136 983 3786 1183 1016 3787 1181 1014 3788 1184 1017 3789 1182 1015 3790 1185 1018 3791 1179 1012 3792 1182 1015 3793 1184 1017 3794 1136 983 3795 1186 1019 3796 1183 1016 3797 1184 1017 3798 1185 1018 3799 1187 1020 3800 1136 983 3801 1188 1021 3802 1186 1019 3803 1189 1022 3804 1187 1020 3805 1190 1023 3806 1184 1017 3807 1187 1020 3808 1189 1022 3809 1136 983 3810 1191 1024 3811 1188 1021 3812 1189 1022 3813 1190 1023 3814 1192 1025 3815 1136 983 3816 1193 1026 3817 1191 1024 3818 1194 1027 3819 1192 1025 3820 1195 1028 3821 1189 1022 3822 1192 1025 3823 1194 1027 3824 1136 983 3825 1196 1029 3826 1193 1026 3827 1194 1027 3828 1195 1028 3829 1197 1030 3830 1136 983 3831 1135 982 3832 1196 1029 3833 1198 1031 3834 1197 1030 3835 1199 1032 3836 1194 1027 3837 1197 1030 3838 1198 1031 3839 1200 1033 3840 1199 1032 3841 1201 1034 3842 1198 1031 3843 1199 1032 3844 1200 1033 3845 1200 1033 3846 1201 1034 3847 1202 1035 3848 1138 985 3849 1202 1035 3850 1141 988 3851 1200 1033 3852 1202 1035 3853 1138 985 3854 1203 1036 3855 1124 971 3856 1204 1037 3857 1203 1036 3858 1123 970 3859 1124 971 3860 1205 1038 3861 1126 973 3862 1125 972 3863 1205 1038 3864 1206 1039 3865 1126 973 3866 1207 1040 3867 1204 1037 3868 1208 1041 3869 1207 1040 3870 1203 1036 3871 1204 1037 3872 1209 1042 3873 1125 972 3874 1127 974 3875 1209 1042 3876 1205 1038 3877 1125 972 3878 1210 1043 3879 1127 974 3880 1128 975 3881 1210 1043 3882 1209 1042 3883 1127 974 3884 1211 1044 3885 1128 975 3886 1129 976 3887 1211 1044 3888 1210 1043 3889 1128 975 3890 1212 1045 3891 1129 976 3892 1130 977 3893 1212 1045 3894 1211 1044 3895 1129 976 3896 1213 1046 3897 1130 977 3898 1131 978 3899 1213 1046 3900 1212 1045 3901 1130 977 3902 1214 1047 3903 1131 978 3904 1132 979 3905 1214 1047 3906 1213 1046 3907 1131 978 3908 1215 1048 3909 1132 979 3910 1136 983 3911 1215 1048 3912 1214 1047 3913 1132 979 3914 1216 1049 3915 1136 983 3916 1171 1004 3917 1216 1049 3918 1215 1048 3919 1136 983 3920 1217 1050 3921 1171 1004 3922 1164 999 3923 1217 1050 3924 1216 1049 3925 1171 1004 3926 1218 1051 3927 1164 999 3928 1159 994 3929 1218 1051 3930 1217 1050 3931 1164 999 3932 1219 1052 3933 1159 994 3934 1114 961 3935 1219 1052 3936 1218 1051 3937 1159 994 3938 1160 995 3939 1219 1052 3940 1114 961 3941 1220 1053 3942 1160 995 3943 1161 996 3944 1220 1053 3945 1161 996 3946 1221 1054 3947 1222 1055 3948 1223 1056 3949 1163 998 3950 1222 1055 3951 1163 998 3952 1162 997 3953 1205 1038 3954 1224 1057 3955 1206 1039 3956 1225 1058 3957 1208 1041 3958 1226 1059 3959 1225 1058 3960 1207 1040 3961 1208 1041 3962 1227 1060 3963 1224 1057 3964 1205 1038 3965 1227 1060 3966 1228 1061 3967 1224 1057 3968 1229 1062 3969 1226 1059 3970 1230 1063 3971 1229 1062 3972 1225 1058 3973 1226 1059 3974 1231 1064 3975 1205 1038 3976 1209 1042 3977 1231 1064 3978 1227 1060 3979 1205 1038 3980 1232 1065 3981 1209 1042 3982 1210 1043 3983 1232 1065 3984 1231 1064 3985 1209 1042 3986 1233 1066 3987 1210 1043 3988 1211 1044 3989 1233 1066 3990 1232 1065 3991 1210 1043 3992 1234 1067 3993 1211 1044 3994 1212 1045 3995 1234 1067 3996 1233 1066 3997 1211 1044 3998 1235 1068 3999 1212 1045 4000 1213 1046 4001 1235 1068 4002 1234 1067 4003 1212 1045 4004 1236 1069 4005 1213 1046 4006 1214 1047 4007 1236 1069 4008 1235 1068 4009 1213 1046 4010 1237 1070 4011 1214 1047 4012 1215 1048 4013 1237 1070 4014 1236 1069 4015 1214 1047 4016 1238 1071 4017 1215 1048 4018 1216 1049 4019 1238 1071 4020 1237 1070 4021 1215 1048 4022 1239 1072 4023 1216 1049 4024 1217 1050 4025 1239 1072 4026 1238 1071 4027 1216 1049 4028 1240 1073 4029 1217 1050 4030 1218 1051 4031 1240 1073 4032 1239 1072 4033 1217 1050 4034 1241 1074 4035 1218 1051 4036 1219 1052 4037 1241 1074 4038 1240 1073 4039 1218 1051 4040 1220 1053 4041 1219 1052 4042 1160 995 4043 1220 1053 4044 1241 1074 4045 1219 1052 4046 694 572 4047 1220 1053 4048 1221 1054 4049 694 572 4050 1221 1054 4051 690 568 4052 1242 1075 4053 692 570 4054 1223 1056 4055 1242 1075 4056 1223 1056 4057 1222 1055 4058 1227 1060 4059 1243 1076 4060 1228 1061 4061 1244 1077 4062 1230 1063 4063 1245 1078 4064 1244 1077 4065 1229 1062 4066 1230 1063 4067 715 593 4068 1243 1076 4069 1227 1060 4070 715 593 4071 1246 1079 4072 1243 1076 4073 1247 1080 4074 1245 1078 4075 1248 1081 4076 1247 1080 4077 1244 1077 4078 1245 1078 4079 714 592 4080 1227 1060 4081 1231 1064 4082 714 592 4083 715 593 4084 1227 1060 4085 713 591 4086 1231 1064 4087 1232 1065 4088 713 591 4089 714 592 4090 1231 1064 4091 711 589 4092 1232 1065 4093 1233 1066 4094 711 589 4095 713 591 4096 1232 1065 4097 712 590 4098 1233 1066 4099 1234 1067 4100 712 590 4101 711 589 4102 1233 1066 4103 710 588 4104 1234 1067 4105 1235 1068 4106 710 588 4107 712 590 4108 1234 1067 4109 709 587 4110 1235 1068 4111 1236 1069 4112 709 587 4113 710 588 4114 1235 1068 4115 708 586 4116 1236 1069 4117 1237 1070 4118 708 586 4119 709 587 4120 1236 1069 4121 707 585 4122 1237 1070 4123 1238 1071 4124 707 585 4125 708 586 4126 1237 1070 4127 699 577 4128 1238 1071 4129 1239 1072 4130 699 577 4131 707 585 4132 1238 1071 4133 700 578 4134 1239 1072 4135 1240 1073 4136 700 578 4137 699 577 4138 1239 1072 4139 1249 1082 4140 1240 1073 4141 1241 1074 4142 1250 1083 4143 700 578 4144 1240 1073 4145 1251 1084 4146 1250 1083 4147 1240 1073 4148 1252 1085 4149 1251 1084 4150 1240 1073 4151 1253 1086 4152 1252 1085 4153 1240 1073 4154 1249 1082 4155 1253 1086 4156 1240 1073 4157 1254 1087 4158 1241 1074 4159 1220 1053 4160 1255 1088 4161 1249 1082 4162 1241 1074 4163 1256 1089 4164 1255 1088 4165 1241 1074 4166 1257 1090 4167 1256 1089 4168 1241 1074 4169 1254 1087 4170 1257 1090 4171 1241 1074 4172 1258 1091 4173 1254 1087 4174 1220 1053 4175 1259 1092 4176 1258 1091 4177 1220 1053 4178 694 572 4179 1259 1092 4180 1220 1053 4181 691 569 4182 692 570 4183 1242 1075 4184 715 593 4185 717 595 4186 1246 1079 4187 1260 1093 4188 1248 1081 4189 1261 1094 4190 1260 1093 4191 1247 1080 4192 1248 1081 4193 593 471 4194 1261 1094 4195 718 596 4196 593 471 4197 1260 1093 4198 1261 1094 4199 1262 1095 4200 1263 1096 4201 1264 1097 4202 1262 1095 4203 1265 1098 4204 1263 1096 4205 1266 1099 4206 1264 1097 4207 1267 1100 4208 1262 1095 4209 1264 1097 4210 1266 1099 4211 1268 1101 4212 1267 1100 4213 1269 1102 4214 1266 1099 4215 1267 1100 4216 1268 1101 4217 1268 1101 4218 1269 1102 4219 1270 1103 4220 1271 1104 4221 1270 1103 4222 1272 1105 4223 1268 1101 4224 1270 1103 4225 1271 1104 4226 1271 1104 4227 1272 1105 4228 1273 1106 4229 1274 1107 4230 1273 1106 4231 1275 1108 4232 1271 1104 4233 1273 1106 4234 1274 1107 4235 1274 1107 4236 1275 1108 4237 1276 1109 4238 1277 1110 4239 1278 1110 4240 1279 1110 4241 1280 1111 4242 1278 1111 4243 1277 1111 4244 1274 1107 4245 1276 1109 4246 1281 1112 4247 1282 223 4248 1283 223 4249 1284 223 4250 1282 223 4251 1285 223 4252 1283 223 4253 1286 1113 4254 1259 1092 4255 694 572 4256 1282 223 4257 1284 223 4258 1287 223 4259 693 571 4260 1286 1113 4261 694 572 4262 1282 223 4263 1287 223 4264 1288 223 4265 1289 1114 4266 1290 1114 4267 1291 1114 4268 1289 1115 4269 1291 1115 4270 1292 1115 4271 1293 1116 4272 1294 1117 4273 1295 1118 4274 1293 1116 4275 1295 1118 4276 1296 1119 4277 1297 1120 4278 1296 1119 4279 1298 1121 4280 1293 1116 4281 1296 1119 4282 1297 1120 4283 1297 1120 4284 1298 1121 4285 1299 1122 4286 1297 1120 4287 1299 1122 4288 1300 1123 4289 1301 1124 4290 1300 1123 4291 1302 1125 4292 1297 1120 4293 1300 1123 4294 1301 1124 4295 1301 1124 4296 1302 1125 4297 1303 1126 4298 1262 1095 4299 1303 1126 4300 1265 1098 4301 1301 1124 4302 1303 1126 4303 1262 1095 4304 1304 1127 4305 653 531 4306 1305 1128 4307 652 530 4308 653 531 4309 1304 1127 4310 1306 1129 4311 1305 1128 4312 1307 1130 4313 1304 1127 4314 1305 1128 4315 1306 1129 4316 1308 1131 4317 1307 1130 4318 1309 1132 4319 1306 1129 4320 1307 1130 4321 1308 1131 4322 818 694 4323 1309 1132 4324 819 695 4325 1308 1131 4326 1309 1132 4327 818 694 4328 1310 1133 4329 979 847 4330 1089 936 4331 1086 933 4332 1310 1133 4333 1089 936 4334 1311 1134 4335 1079 926 4336 1312 1135 4337 1074 921 4338 1079 926 4339 1311 1134 4340 1311 1134 4341 1312 1135 4342 1313 1136 4343 1311 1134 4344 1313 1136 4345 1314 1137 4346 1311 1134 4347 1314 1137 4348 1315 1138 4349 1310 1133 4350 976 844 4351 979 847 4352 379 319 4353 380 320 4354 1316 1139 4355 1317 1140 4356 382 322 4357 386 326 4358 1318 1141 4359 1316 1139 4360 1319 1142 4361 1318 1141 4362 379 319 4363 1316 1139 4364 1320 1143 4365 386 326 4366 393 333 4367 1321 1144 4368 1317 1140 4369 386 326 4370 1320 1143 4371 1321 1144 4372 386 326 4373 1322 1145 4374 393 333 4375 400 340 4376 1322 1145 4377 1320 1143 4378 393 333 4379 1323 1146 4380 400 340 4381 407 347 4382 1323 1146 4383 1322 1145 4384 400 340 4385 1324 1147 4386 407 347 4387 411 351 4388 1324 1147 4389 1323 1146 4390 407 347 4391 1325 1148 4392 411 351 4393 417 357 4394 1325 1148 4395 1324 1147 4396 411 351 4397 1326 1149 4398 417 357 4399 424 364 4400 1326 1149 4401 1325 1148 4402 417 357 4403 1327 1150 4404 424 364 4405 431 371 4406 1327 1150 4407 1326 1149 4408 424 364 4409 1328 1151 4410 431 371 4411 438 378 4412 1328 1151 4413 1327 1150 4414 431 371 4415 1329 1152 4416 438 378 4417 442 382 4418 1329 1152 4419 1328 1151 4420 438 378 4421 1330 1153 4422 442 382 4423 448 388 4424 1330 1153 4425 1329 1152 4426 442 382 4427 1331 1154 4428 448 388 4429 455 395 4430 1331 1154 4431 1330 1153 4432 448 388 4433 1332 1155 4434 455 395 4435 462 402 4436 1332 1155 4437 1331 1154 4438 455 395 4439 845 721 4440 462 402 4441 208 165 4442 845 721 4443 1332 1155 4444 462 402 4445 1333 1156 4446 1319 1142 4447 1334 1157 4448 1333 1156 4449 1318 1141 4450 1319 1142 4451 1335 1158 4452 1321 1144 4453 1320 1143 4454 1336 1159 4455 1334 1157 4456 1337 1160 4457 1336 1159 4458 1333 1156 4459 1334 1157 4460 1338 1161 4461 1320 1143 4462 1322 1145 4463 1339 1162 4464 1335 1158 4465 1320 1143 4466 1338 1161 4467 1339 1162 4468 1320 1143 4469 1340 1163 4470 1322 1145 4471 1323 1146 4472 1340 1163 4473 1338 1161 4474 1322 1145 4475 1341 1164 4476 1323 1146 4477 1324 1147 4478 1341 1164 4479 1340 1163 4480 1323 1146 4481 1342 1165 4482 1324 1147 4483 1325 1148 4484 1342 1165 4485 1341 1164 4486 1324 1147 4487 1343 1166 4488 1325 1148 4489 1326 1149 4490 1343 1166 4491 1342 1165 4492 1325 1148 4493 1344 1167 4494 1326 1149 4495 1327 1150 4496 1344 1167 4497 1343 1166 4498 1326 1149 4499 1345 1168 4500 1327 1150 4501 1328 1151 4502 1345 1168 4503 1344 1167 4504 1327 1150 4505 1346 1169 4506 1328 1151 4507 1329 1152 4508 1346 1169 4509 1345 1168 4510 1328 1151 4511 1347 1170 4512 1329 1152 4513 1330 1153 4514 1347 1170 4515 1346 1169 4516 1329 1152 4517 1348 1171 4518 1330 1153 4519 1331 1154 4520 1348 1171 4521 1347 1170 4522 1330 1153 4523 1349 1172 4524 1331 1154 4525 1332 1155 4526 1349 1172 4527 1348 1171 4528 1331 1154 4529 1350 1173 4530 1332 1155 4531 845 721 4532 1350 1173 4533 1349 1172 4534 1332 1155 4535 808 684 4536 1350 1173 4537 845 721 4538 1351 1174 4539 1337 1160 4540 1352 1175 4541 1351 1174 4542 1336 1159 4543 1337 1160 4544 1353 1176 4545 1339 1162 4546 1338 1161 4547 1354 1177 4548 1352 1175 4549 1355 1178 4550 1354 1177 4551 1351 1174 4552 1352 1175 4553 1356 1179 4554 1338 1161 4555 1340 1163 4556 1357 1180 4557 1353 1176 4558 1338 1161 4559 1356 1179 4560 1357 1180 4561 1338 1161 4562 1358 1181 4563 1340 1163 4564 1341 1164 4565 1358 1181 4566 1356 1179 4567 1340 1163 4568 1359 1182 4569 1341 1164 4570 1342 1165 4571 1359 1182 4572 1358 1181 4573 1341 1164 4574 1360 1183 4575 1342 1165 4576 1343 1166 4577 1360 1183 4578 1359 1182 4579 1342 1165 4580 1361 1184 4581 1343 1166 4582 1344 1167 4583 1361 1184 4584 1360 1183 4585 1343 1166 4586 1362 1185 4587 1344 1167 4588 1345 1168 4589 1362 1185 4590 1361 1184 4591 1344 1167 4592 1363 1186 4593 1345 1168 4594 1346 1169 4595 1363 1186 4596 1362 1185 4597 1345 1168 4598 1364 1187 4599 1346 1169 4600 1347 1170 4601 1364 1187 4602 1363 1186 4603 1346 1169 4604 1365 1188 4605 1347 1170 4606 1348 1171 4607 1365 1188 4608 1364 1187 4609 1347 1170 4610 1366 1189 4611 1348 1171 4612 1349 1172 4613 1366 1189 4614 1365 1188 4615 1348 1171 4616 1367 1190 4617 1349 1172 4618 1350 1173 4619 1367 1190 4620 1366 1189 4621 1349 1172 4622 1368 1191 4623 1350 1173 4624 808 684 4625 1368 1191 4626 1367 1190 4627 1350 1173 4628 804 680 4629 1368 1191 4630 808 684 4631 1369 1192 4632 1355 1178 4633 1370 1193 4634 1369 1192 4635 1354 1177 4636 1355 1178 4637 1371 1194 4638 1357 1180 4639 1356 1179 4640 1369 1192 4641 1370 1193 4642 1372 1195 4643 1373 1196 4644 1356 1179 4645 1358 1181 4646 1374 1197 4647 1371 1194 4648 1356 1179 4649 1373 1196 4650 1374 1197 4651 1356 1179 4652 1375 1198 4653 1358 1181 4654 1359 1182 4655 1375 1198 4656 1373 1196 4657 1358 1181 4658 1376 1199 4659 1359 1182 4660 1360 1183 4661 1376 1199 4662 1375 1198 4663 1359 1182 4664 1377 1200 4665 1360 1183 4666 1361 1184 4667 1377 1200 4668 1376 1199 4669 1360 1183 4670 1378 1201 4671 1361 1184 4672 1362 1185 4673 1378 1201 4674 1377 1200 4675 1361 1184 4676 1379 1202 4677 1362 1185 4678 1363 1186 4679 1379 1202 4680 1378 1201 4681 1362 1185 4682 1380 1203 4683 1363 1186 4684 1364 1187 4685 1380 1203 4686 1379 1202 4687 1363 1186 4688 1381 1204 4689 1364 1187 4690 1365 1188 4691 1381 1204 4692 1380 1203 4693 1364 1187 4694 1382 1205 4695 1365 1188 4696 1366 1189 4697 1382 1205 4698 1381 1204 4699 1365 1188 4700 1383 1206 4701 1366 1189 4702 1367 1190 4703 1383 1206 4704 1382 1205 4705 1366 1189 4706 1384 1207 4707 1367 1190 4708 1368 1191 4709 1384 1207 4710 1383 1206 4711 1367 1190 4712 1385 1208 4713 1368 1191 4714 804 680 4715 1385 1208 4716 1384 1207 4717 1368 1191 4718 687 565 4719 1385 1208 4720 804 680 4721 1386 1209 4722 1372 1195 4723 1387 1210 4724 1386 1209 4725 1369 1192 4726 1372 1195 4727 1388 1211 4728 1374 1197 4729 1373 1196 4730 1389 1212 4731 1387 1210 4732 1390 1213 4733 1389 1212 4734 1386 1209 4735 1387 1210 4736 1391 1214 4737 1373 1196 4738 1375 1198 4739 1392 1215 4740 1388 1211 4741 1373 1196 4742 1391 1214 4743 1392 1215 4744 1373 1196 4745 1393 1216 4746 1375 1198 4747 1376 1199 4748 1393 1216 4749 1391 1214 4750 1375 1198 4751 1394 1217 4752 1376 1199 4753 1377 1200 4754 1394 1217 4755 1393 1216 4756 1376 1199 4757 1395 1218 4758 1377 1200 4759 1378 1201 4760 1395 1218 4761 1394 1217 4762 1377 1200 4763 1396 1219 4764 1378 1201 4765 1379 1202 4766 1396 1219 4767 1395 1218 4768 1378 1201 4769 1397 1220 4770 1379 1202 4771 1380 1203 4772 1397 1220 4773 1396 1219 4774 1379 1202 4775 1398 1221 4776 1380 1203 4777 1381 1204 4778 1398 1221 4779 1397 1220 4780 1380 1203 4781 1399 1222 4782 1381 1204 4783 1382 1205 4784 1399 1222 4785 1398 1221 4786 1381 1204 4787 1400 1223 4788 1382 1205 4789 1383 1206 4790 1400 1223 4791 1399 1222 4792 1382 1205 4793 1401 1224 4794 1383 1206 4795 1384 1207 4796 1401 1224 4797 1400 1223 4798 1383 1206 4799 1402 1225 4800 1384 1207 4801 1385 1208 4802 1402 1225 4803 1401 1224 4804 1384 1207 4805 683 561 4806 1385 1208 4807 687 565 4808 683 561 4809 1402 1225 4810 1385 1208 4811 1403 1226 4812 1404 1227 4813 1388 1211 4814 1405 1228 4815 1390 1213 4816 1406 1229 4817 1392 1215 4818 1403 1226 4819 1388 1211 4820 1405 1228 4821 1389 1212 4822 1390 1213 4823 1407 1230 4824 1408 1231 4825 1409 1232 4826 1410 1233 4827 1406 1229 4828 1411 1234 4829 1410 1233 4830 1405 1228 4831 1406 1229 4832 1412 1235 4833 1403 1226 4834 1392 1215 4835 1407 1230 4836 1409 1232 4837 1413 1236 4838 1414 1237 4839 1392 1215 4840 1391 1214 4841 1415 1238 4842 1392 1215 4843 1414 1237 4844 1412 1235 4845 1392 1215 4846 1415 1238 4847 1416 1239 4848 1391 1214 4849 1393 1216 4850 1414 1237 4851 1391 1214 4852 1416 1239 4853 1417 1240 4854 1393 1216 4855 1394 1217 4856 1416 1239 4857 1393 1216 4858 1417 1240 4859 1418 1241 4860 1394 1217 4861 1395 1218 4862 1417 1240 4863 1394 1217 4864 1418 1241 4865 1419 1242 4866 1395 1218 4867 1396 1219 4868 1418 1241 4869 1395 1218 4870 1419 1242 4871 1420 1243 4872 1396 1219 4873 1397 1220 4874 1419 1242 4875 1396 1219 4876 1420 1243 4877 1421 1244 4878 1397 1220 4879 1398 1221 4880 1420 1243 4881 1397 1220 4882 1421 1244 4883 1422 1245 4884 1398 1221 4885 1399 1222 4886 1421 1244 4887 1398 1221 4888 1422 1245 4889 1423 1246 4890 1399 1222 4891 1400 1223 4892 1422 1245 4893 1399 1222 4894 1423 1246 4895 1424 1247 4896 1400 1223 4897 1401 1224 4898 1423 1246 4899 1400 1223 4900 1424 1247 4901 1425 1248 4902 1401 1224 4903 1402 1225 4904 1424 1247 4905 1401 1224 4906 1425 1248 4907 1426 1249 4908 1402 1225 4909 683 561 4910 1425 1248 4911 1402 1225 4912 1426 1249 4913 1426 1249 4914 683 561 4915 691 569 4916 1427 1250 4917 904 772 4918 877 745 4919 1428 1251 4920 1427 1250 4921 877 745 4922 925 793 4923 1428 1251 4924 877 745 4925 1429 1252 4926 905 773 4927 904 772 4928 1427 1250 4929 1429 1252 4930 904 772 4931 1430 1253 4932 906 774 4933 905 773 4934 1431 1254 4935 1430 1253 4936 905 773 4937 1429 1252 4938 1431 1254 4939 905 773 4940 1432 1255 4941 907 775 4942 906 774 4943 1430 1253 4944 1432 1255 4945 906 774 4946 1433 1256 4947 908 776 4948 907 775 4949 1432 1255 4950 1433 1256 4951 907 775 4952 1434 1257 4953 909 777 4954 908 776 4955 1435 1258 4956 1434 1257 4957 908 776 4958 1433 1256 4959 1435 1258 4960 908 776 4961 1436 1259 4962 910 778 4963 909 777 4964 1434 1257 4965 1436 1259 4966 909 777 4967 1437 1260 4968 911 779 4969 910 778 4970 1436 1259 4971 1437 1260 4972 910 778 4973 1438 1261 4974 912 780 4975 911 779 4976 1437 1260 4977 1438 1261 4978 911 779 4979 1439 1262 4980 913 781 4981 912 780 4982 1438 1261 4983 1439 1262 4984 912 780 4985 1440 1263 4986 914 782 4987 913 781 4988 1439 1262 4989 1440 1263 4990 913 781 4991 1441 1264 4992 915 783 4993 914 782 4994 1440 1263 4995 1441 1264 4996 914 782 4997 1442 1265 4998 916 784 4999 915 783 5000 1441 1264 5001 1442 1265 5002 915 783 5003 1443 1266 5004 917 785 5005 916 784 5006 1442 1265 5007 1443 1266 5008 916 784 5009 1444 1267 5010 918 786 5011 917 785 5012 1443 1266 5013 1444 1267 5014 917 785 5015 1445 1268 5016 919 787 5017 918 786 5018 1444 1267 5019 1445 1268 5020 918 786 5021 1446 1269 5022 920 788 5023 919 787 5024 1445 1268 5025 1446 1269 5026 919 787 5027 1447 1270 5028 921 789 5029 920 788 5030 1446 1269 5031 1447 1270 5032 920 788 5033 1448 1271 5034 922 790 5035 921 789 5036 1447 1270 5037 1448 1271 5038 921 789 5039 959 827 5040 902 770 5041 922 790 5042 1448 1271 5043 959 827 5044 922 790 5045 1449 1272 5046 959 827 5047 1448 1271 5048 1449 1272 5049 1024 871 5050 959 827 5051 1450 1273 5052 1448 1271 5053 1447 1270 5054 1450 1273 5055 1449 1272 5056 1448 1271 5057 1451 1274 5058 1447 1270 5059 1446 1269 5060 1451 1274 5061 1450 1273 5062 1447 1270 5063 1452 1275 5064 1446 1269 5065 1445 1268 5066 1452 1275 5067 1451 1274 5068 1446 1269 5069 1453 1276 5070 1445 1268 5071 1444 1267 5072 1453 1276 5073 1452 1275 5074 1445 1268 5075 1454 1277 5076 1444 1267 5077 1443 1266 5078 1454 1277 5079 1453 1276 5080 1444 1267 5081 1455 1278 5082 1443 1266 5083 1442 1265 5084 1455 1278 5085 1454 1277 5086 1443 1266 5087 1456 1279 5088 1442 1265 5089 1441 1264 5090 1456 1279 5091 1455 1278 5092 1442 1265 5093 1457 1280 5094 1441 1264 5095 1440 1263 5096 1457 1280 5097 1456 1279 5098 1441 1264 5099 1458 1281 5100 1440 1263 5101 1439 1262 5102 1458 1281 5103 1457 1280 5104 1440 1263 5105 1459 1282 5106 1439 1262 5107 1438 1261 5108 1459 1282 5109 1458 1281 5110 1439 1262 5111 1460 1283 5112 1438 1261 5113 1437 1260 5114 1460 1283 5115 1459 1282 5116 1438 1261 5117 1461 1284 5118 1437 1260 5119 1436 1259 5120 1461 1284 5121 1460 1283 5122 1437 1260 5123 1462 1285 5124 1436 1259 5125 1434 1257 5126 1463 1286 5127 1436 1259 5128 1462 1285 5129 1463 1286 5130 1461 1284 5131 1436 1259 5132 1464 1287 5133 1465 1288 5134 1466 1289 5135 1467 1290 5136 1468 1291 5137 1465 1288 5138 1464 1287 5139 1467 1290 5140 1465 1288 5141 1464 1287 5142 1466 1289 5143 1469 1292 5144 1470 1293 5145 1469 1292 5146 1471 1294 5147 1470 1293 5148 1464 1287 5149 1469 1292 5150 1470 1293 5151 1471 1294 5152 1472 1295 5153 1470 1293 5154 1472 1295 5155 1473 1296 5156 964 832 5157 1473 1296 5158 1474 1297 5159 964 832 5160 1470 1293 5161 1473 1296 5162 964 832 5163 1474 1297 5164 1475 1298 5165 964 832 5166 1475 1298 5167 1476 1299 5168 964 832 5169 1476 1299 5170 965 833 5171 1467 1290 5172 1477 1300 5173 1468 1291 5174 1478 1301 5175 1024 871 5176 1449 1272 5177 1478 1301 5178 1050 897 5179 1024 871 5180 1479 1302 5181 1449 1272 5182 1450 1273 5183 1479 1302 5184 1478 1301 5185 1449 1272 5186 1480 1303 5187 1450 1273 5188 1451 1274 5189 1480 1303 5190 1479 1302 5191 1450 1273 5192 1481 1304 5193 1451 1274 5194 1452 1275 5195 1481 1304 5196 1480 1303 5197 1451 1274 5198 1482 1305 5199 1452 1275 5200 1453 1276 5201 1482 1305 5202 1481 1304 5203 1452 1275 5204 1483 1306 5205 1453 1276 5206 1454 1277 5207 1483 1306 5208 1482 1305 5209 1453 1276 5210 1484 1307 5211 1454 1277 5212 1455 1278 5213 1484 1307 5214 1483 1306 5215 1454 1277 5216 1485 1308 5217 1455 1278 5218 1456 1279 5219 1485 1308 5220 1484 1307 5221 1455 1278 5222 1486 1309 5223 1456 1279 5224 1457 1280 5225 1486 1309 5226 1485 1308 5227 1456 1279 5228 1487 1310 5229 1457 1280 5230 1458 1281 5231 1487 1310 5232 1486 1309 5233 1457 1280 5234 1488 1311 5235 1458 1281 5236 1459 1282 5237 1488 1311 5238 1487 1310 5239 1458 1281 5240 1489 1312 5241 1459 1282 5242 1460 1283 5243 1489 1312 5244 1488 1311 5245 1459 1282 5246 1490 1313 5247 1460 1283 5248 1461 1284 5249 1491 1314 5250 1460 1283 5251 1490 1313 5252 1492 1315 5253 1489 1312 5254 1460 1283 5255 1491 1314 5256 1492 1315 5257 1460 1283 5258 1493 1316 5259 1494 1317 5260 1477 1300 5261 1495 1318 5262 1496 1319 5263 1494 1317 5264 1493 1316 5265 1495 1318 5266 1494 1317 5267 1467 1290 5268 1493 1316 5269 1477 1300 5270 1495 1318 5271 1497 1320 5272 1496 1319 5273 1498 1321 5274 1050 897 5275 1478 1301 5276 1498 1321 5277 1116 963 5278 1050 897 5279 1499 1322 5280 1478 1301 5281 1479 1302 5282 1499 1322 5283 1498 1321 5284 1478 1301 5285 1500 1323 5286 1479 1302 5287 1480 1303 5288 1500 1323 5289 1499 1322 5290 1479 1302 5291 1501 1324 5292 1480 1303 5293 1481 1304 5294 1501 1324 5295 1500 1323 5296 1480 1303 5297 1502 1325 5298 1481 1304 5299 1482 1305 5300 1502 1325 5301 1501 1324 5302 1481 1304 5303 1503 1326 5304 1482 1305 5305 1483 1306 5306 1503 1326 5307 1502 1325 5308 1482 1305 5309 1504 1327 5310 1483 1306 5311 1484 1307 5312 1504 1327 5313 1503 1326 5314 1483 1306 5315 1505 1328 5316 1484 1307 5317 1485 1308 5318 1505 1328 5319 1504 1327 5320 1484 1307 5321 1506 1329 5322 1485 1308 5323 1486 1309 5324 1506 1329 5325 1505 1328 5326 1485 1308 5327 1507 1330 5328 1486 1309 5329 1487 1310 5330 1507 1330 5331 1506 1329 5332 1486 1309 5333 1508 1331 5334 1487 1310 5335 1488 1311 5336 1508 1331 5337 1507 1330 5338 1487 1310 5339 1509 1332 5340 1488 1311 5341 1489 1312 5342 1509 1332 5343 1508 1331 5344 1488 1311 5345 1510 1333 5346 1489 1312 5347 1492 1315 5348 1511 1334 5349 1489 1312 5350 1510 1333 5351 1512 1335 5352 1509 1332 5353 1489 1312 5354 1511 1334 5355 1512 1335 5356 1489 1312 5357 1513 1336 5358 1514 1337 5359 1497 1320 5360 1515 1338 5361 1516 1339 5362 1514 1337 5363 1513 1336 5364 1515 1338 5365 1514 1337 5366 1495 1318 5367 1513 1336 5368 1497 1320 5369 1515 1338 5370 1517 1340 5371 1516 1339 5372 1162 997 5373 1116 963 5374 1498 1321 5375 1518 1341 5376 1498 1321 5377 1499 1322 5378 1518 1341 5379 1162 997 5380 1498 1321 5381 1519 1342 5382 1499 1322 5383 1500 1323 5384 1519 1342 5385 1518 1341 5386 1499 1322 5387 1520 1343 5388 1500 1323 5389 1501 1324 5390 1520 1343 5391 1519 1342 5392 1500 1323 5393 1521 1344 5394 1501 1324 5395 1502 1325 5396 1521 1344 5397 1520 1343 5398 1501 1324 5399 1522 1345 5400 1502 1325 5401 1503 1326 5402 1522 1345 5403 1521 1344 5404 1502 1325 5405 1523 1346 5406 1503 1326 5407 1504 1327 5408 1523 1346 5409 1522 1345 5410 1503 1326 5411 1524 1347 5412 1504 1327 5413 1505 1328 5414 1524 1347 5415 1523 1346 5416 1504 1327 5417 1525 1348 5418 1505 1328 5419 1506 1329 5420 1525 1348 5421 1524 1347 5422 1505 1328 5423 1526 1349 5424 1506 1329 5425 1507 1330 5426 1526 1349 5427 1525 1348 5428 1506 1329 5429 1527 1350 5430 1507 1330 5431 1508 1331 5432 1527 1350 5433 1526 1349 5434 1507 1330 5435 1528 1351 5436 1508 1331 5437 1509 1332 5438 1528 1351 5439 1527 1350 5440 1508 1331 5441 1529 1352 5442 1509 1332 5443 1512 1335 5444 1528 1351 5445 1509 1332 5446 1529 1352 5447 1530 1353 5448 1531 1354 5449 1517 1340 5450 1532 1355 5451 1533 1356 5452 1531 1354 5453 1530 1353 5454 1532 1355 5455 1531 1354 5456 1515 1338 5457 1530 1353 5458 1517 1340 5459 1534 1357 5460 1528 1351 5461 1529 1352 5462 1535 1358 5463 1536 1359 5464 1533 1356 5465 1532 1355 5466 1535 1358 5467 1533 1356 5468 1537 1360 5469 1162 997 5470 1518 1341 5471 1537 1360 5472 1222 1055 5473 1162 997 5474 1538 1361 5475 1518 1341 5476 1519 1342 5477 1538 1361 5478 1537 1360 5479 1518 1341 5480 1539 1362 5481 1519 1342 5482 1520 1343 5483 1539 1362 5484 1538 1361 5485 1519 1342 5486 1540 1363 5487 1520 1343 5488 1521 1344 5489 1540 1363 5490 1539 1362 5491 1520 1343 5492 1541 1364 5493 1521 1344 5494 1522 1345 5495 1541 1364 5496 1540 1363 5497 1521 1344 5498 1542 1365 5499 1522 1345 5500 1523 1346 5501 1542 1365 5502 1541 1364 5503 1522 1345 5504 1543 1366 5505 1523 1346 5506 1524 1347 5507 1543 1366 5508 1542 1365 5509 1523 1346 5510 1544 1367 5511 1524 1347 5512 1525 1348 5513 1544 1367 5514 1543 1366 5515 1524 1347 5516 1545 1368 5517 1525 1348 5518 1526 1349 5519 1545 1368 5520 1544 1367 5521 1525 1348 5522 1546 1369 5523 1526 1349 5524 1527 1350 5525 1546 1369 5526 1545 1368 5527 1526 1349 5528 1547 1370 5529 1527 1350 5530 1528 1351 5531 1547 1370 5532 1546 1369 5533 1527 1350 5534 1548 1371 5535 1528 1351 5536 1534 1357 5537 1548 1371 5538 1547 1370 5539 1528 1351 5540 1548 1371 5541 1534 1357 5542 1549 1372 5543 1550 1373 5544 1551 1374 5545 1536 1359 5546 1535 1358 5547 1550 1373 5548 1536 1359 5549 1552 1375 5550 1548 1371 5551 1549 1372 5552 1553 1376 5553 1554 1377 5554 1551 1374 5555 1550 1373 5556 1553 1376 5557 1551 1374 5558 1242 1075 5559 1222 1055 5560 1537 1360 5561 1555 1378 5562 1537 1360 5563 1538 1361 5564 1555 1378 5565 1242 1075 5566 1537 1360 5567 1556 1379 5568 1538 1361 5569 1539 1362 5570 1556 1379 5571 1555 1378 5572 1538 1361 5573 1557 1380 5574 1539 1362 5575 1540 1363 5576 1557 1380 5577 1556 1379 5578 1539 1362 5579 1558 1381 5580 1540 1363 5581 1541 1364 5582 1558 1381 5583 1557 1380 5584 1540 1363 5585 1559 1382 5586 1541 1364 5587 1542 1365 5588 1559 1382 5589 1558 1381 5590 1541 1364 5591 1560 1383 5592 1542 1365 5593 1543 1366 5594 1560 1383 5595 1559 1382 5596 1542 1365 5597 1561 1384 5598 1543 1366 5599 1544 1367 5600 1561 1384 5601 1560 1383 5602 1543 1366 5603 1562 1385 5604 1544 1367 5605 1545 1368 5606 1562 1385 5607 1561 1384 5608 1544 1367 5609 1563 1386 5610 1545 1368 5611 1546 1369 5612 1563 1386 5613 1562 1385 5614 1545 1368 5615 1564 1387 5616 1546 1369 5617 1547 1370 5618 1564 1387 5619 1563 1386 5620 1546 1369 5621 1565 1388 5622 1547 1370 5623 1548 1371 5624 1565 1388 5625 1564 1387 5626 1547 1370 5627 1566 1389 5628 1548 1371 5629 1552 1375 5630 1566 1389 5631 1565 1388 5632 1548 1371 5633 1566 1389 5634 1552 1375 5635 1567 1390 5636 1568 1391 5637 1569 1392 5638 1554 1377 5639 1553 1376 5640 1568 1391 5641 1554 1377 5642 1570 1393 5643 1566 1389 5644 1567 1390 5645 1571 1394 5646 1572 1395 5647 1569 1392 5648 1568 1391 5649 1571 1394 5650 1569 1392 5651 691 569 5652 1242 1075 5653 1555 1378 5654 1426 1249 5655 1555 1378 5656 1556 1379 5657 1426 1249 5658 691 569 5659 1555 1378 5660 1425 1248 5661 1556 1379 5662 1557 1380 5663 1425 1248 5664 1426 1249 5665 1556 1379 5666 1424 1247 5667 1557 1380 5668 1558 1381 5669 1424 1247 5670 1425 1248 5671 1557 1380 5672 1423 1246 5673 1558 1381 5674 1559 1382 5675 1423 1246 5676 1424 1247 5677 1558 1381 5678 1422 1245 5679 1559 1382 5680 1560 1383 5681 1422 1245 5682 1423 1246 5683 1559 1382 5684 1421 1244 5685 1560 1383 5686 1561 1384 5687 1421 1244 5688 1422 1245 5689 1560 1383 5690 1420 1243 5691 1561 1384 5692 1562 1385 5693 1420 1243 5694 1421 1244 5695 1561 1384 5696 1419 1242 5697 1562 1385 5698 1563 1386 5699 1419 1242 5700 1420 1243 5701 1562 1385 5702 1418 1241 5703 1563 1386 5704 1564 1387 5705 1418 1241 5706 1419 1242 5707 1563 1386 5708 1417 1240 5709 1564 1387 5710 1565 1388 5711 1417 1240 5712 1418 1241 5713 1564 1387 5714 1416 1239 5715 1565 1388 5716 1566 1389 5717 1416 1239 5718 1417 1240 5719 1565 1388 5720 1414 1237 5721 1566 1389 5722 1570 1393 5723 1414 1237 5724 1416 1239 5725 1566 1389 5726 1414 1237 5727 1570 1393 5728 1573 1396 5729 1574 1397 5730 1575 1398 5731 1572 1395 5732 1571 1394 5733 1574 1397 5734 1572 1395 5735 1415 1238 5736 1414 1237 5737 1573 1396 5738 1576 1399 5739 1577 1400 5740 1575 1398 5741 1574 1397 5742 1576 1399 5743 1575 1398 5744 1407 1230 5745 1413 1236 5746 1577 1400 5747 1576 1399 5748 1407 1230 5749 1577 1400 5750 1578 1401 5751 1411 1234 5752 1579 1402 5753 1580 1403 5754 1410 1233 5755 1411 1234 5756 1578 1401 5757 1580 1403 5758 1411 1234 5759 1581 1404 5760 1579 1402 5761 1582 1405 5762 1581 1404 5763 1578 1401 5764 1579 1402 5765 1583 1406 5766 1582 1405 5767 1584 1407 5768 1583 1406 5769 1581 1404 5770 1582 1405 5771 1583 1406 5772 1584 1407 5773 1585 1408 5774 1586 1409 5775 1585 1408 5776 1587 1410 5777 1586 1409 5778 1583 1406 5779 1585 1408 5780 1588 1411 5781 1587 1410 5782 1589 1412 5783 1588 1411 5784 1586 1409 5785 1587 1410 5786 1590 1413 5787 1589 1412 5788 1591 1414 5789 1590 1413 5790 1588 1411 5791 1589 1412 5792 1592 1415 5793 1591 1414 5794 1593 1416 5795 1592 1415 5796 1590 1413 5797 1591 1414 5798 1592 1415 5799 1593 1416 5800 1594 1417 5801 1595 1418 5802 1594 1417 5803 1596 1419 5804 1595 1418 5805 1592 1415 5806 1594 1417 5807 1597 1420 5808 1596 1419 5809 1598 1421 5810 1597 1420 5811 1595 1418 5812 1596 1419 5813 1599 1422 5814 1598 1421 5815 1600 1423 5816 1599 1422 5817 1597 1420 5818 1598 1421 5819 1601 1424 5820 1600 1423 5821 1602 1425 5822 1601 1424 5823 1599 1422 5824 1600 1423 5825 1601 1424 5826 1602 1425 5827 1603 1426 5828 1604 1427 5829 1603 1426 5830 1605 1428 5831 1604 1427 5832 1601 1424 5833 1603 1426 5834 1606 1429 5835 1605 1428 5836 1607 1430 5837 1606 1429 5838 1604 1427 5839 1605 1428 5840 1608 1431 5841 1607 1430 5842 1609 1432 5843 1608 1431 5844 1606 1429 5845 1607 1430 5846 1608 1431 5847 1609 1432 5848 1610 1433 5849 1611 1434 5850 1612 1435 5851 1613 1436 5852 1608 1431 5853 1610 1433 5854 1614 1437 5855 1615 1438 5856 1613 1436 5857 1616 1439 5858 1615 1438 5859 1611 1434 5860 1613 1436 5861 1617 1440 5862 1616 1439 5863 1618 1441 5864 1617 1440 5865 1615 1438 5866 1616 1439 5867 1619 1442 5868 1618 1441 5869 1620 1443 5870 1619 1442 5871 1617 1440 5872 1618 1441 5873 1621 1444 5874 1620 1443 5875 1622 1445 5876 1621 1444 5877 1619 1442 5878 1620 1443 5879 1623 1446 5880 1622 1445 5881 1624 1447 5882 1623 1446 5883 1621 1444 5884 1622 1445 5885 1625 1448 5886 1624 1447 5887 1626 1449 5888 1625 1448 5889 1623 1446 5890 1624 1447 5891 1627 1450 5892 1626 1449 5893 1628 1451 5894 1629 1452 5895 1625 1448 5896 1626 1449 5897 1630 1453 5898 1629 1452 5899 1626 1449 5900 1631 1454 5901 1630 1453 5902 1626 1449 5903 1627 1450 5904 1631 1454 5905 1626 1449 5906 1632 1455 5907 1628 1451 5908 1633 1456 5909 1634 1457 5910 1627 1450 5911 1628 1451 5912 1635 1458 5913 1634 1457 5914 1628 1451 5915 1636 1459 5916 1635 1458 5917 1628 1451 5918 1637 1460 5919 1636 1459 5920 1628 1451 5921 1638 1461 5922 1637 1460 5923 1628 1451 5924 1639 1462 5925 1638 1461 5926 1628 1451 5927 1640 1463 5928 1639 1462 5929 1628 1451 5930 1632 1464 5931 1640 1464 5932 1628 1464 5933 1641 1465 5934 1633 1456 5935 1642 1466 5936 1632 1455 5937 1633 1456 5938 1641 1465 5939 1643 1467 5940 1642 1466 5941 1644 1468 5942 1643 1467 5943 1641 1465 5944 1642 1466 5945 1645 1469 5946 1644 1468 5947 1646 1470 5948 1645 1469 5949 1643 1467 5950 1644 1468 5951 1647 1471 5952 1646 1470 5953 1648 1472 5954 1647 1471 5955 1645 1469 5956 1646 1470 5957 1649 1473 5958 1648 1472 5959 1650 1474 5960 1649 1473 5961 1647 1471 5962 1648 1472 5963 1649 1473 5964 1650 1474 5965 1651 1475 5966 1652 1476 5967 1651 1475 5968 1653 1477 5969 1652 1476 5970 1649 1473 5971 1651 1475 5972 1654 1478 5973 1653 1477 5974 1655 1479 5975 1654 1478 5976 1652 1476 5977 1653 1477 5978 1656 1480 5979 1655 1479 5980 597 475 5981 1656 1480 5982 1654 1478 5983 1655 1479 5984 596 474 5985 1656 1480 5986 597 475 5987 1657 1481 5988 1658 1481 5989 1659 1481 5990 1660 1482 5991 1661 1482 5992 1658 1482 5993 1657 857 5994 1660 857 5995 1658 857 5996 1657 1483 5997 1659 1483 5998 1662 1483 5999 1663 1484 6000 1664 1485 6001 1617 1440 6002 1665 1486 6003 1662 1486 6004 1666 1486 6005 1667 1487 6006 1617 1440 6007 1619 1442 6008 1667 1487 6009 1663 1484 6010 1617 1440 6011 1665 1488 6012 1657 1488 6013 1662 1488 6014 1668 1489 6015 1669 1490 6016 1664 1485 6017 1665 1491 6018 1666 1491 6019 1670 1491 6020 1663 1484 6021 1671 1492 6022 1664 1485 6023 1672 1493 6024 1664 1485 6025 1671 1492 6026 1673 1494 6027 1664 1485 6028 1672 1493 6029 1673 1494 6030 1668 1489 6031 1664 1485 6032 1674 1495 6033 1675 1496 6034 1669 1490 6035 1676 1497 6036 1670 1497 6037 1677 1497 6038 1678 1498 6039 1674 1495 6040 1669 1490 6041 1668 1489 6042 1678 1498 6043 1669 1490 6044 1676 1499 6045 1665 1499 6046 1670 1499 6047 1679 1500 6048 1680 1501 6049 1675 1496 6050 1676 1502 6051 1677 1502 6052 1681 1502 6053 1682 1503 6054 1679 1500 6055 1675 1496 6056 1683 1504 6057 1682 1503 6058 1675 1496 6059 1684 1505 6060 1683 1504 6061 1675 1496 6062 1674 1495 6063 1684 1505 6064 1675 1496 6065 1632 1455 6066 1641 1465 6067 1680 1501 6068 1685 1506 6069 1681 1506 6070 1686 1506 6071 1687 1507 6072 1632 1455 6073 1680 1501 6074 1688 1508 6075 1687 1507 6076 1680 1501 6077 1689 1509 6078 1688 1508 6079 1680 1501 6080 1679 1500 6081 1689 1509 6082 1680 1501 6083 1685 857 6084 1676 857 6085 1681 857 6086 1685 857 6087 1686 857 6088 1690 857 6089 1691 857 6090 1690 857 6091 1692 857 6092 1691 1510 6093 1685 1510 6094 1690 1510 6095 1693 1511 6096 1692 1511 6097 1694 1511 6098 1693 857 6099 1691 857 6100 1692 857 6101 1693 1512 6102 1694 1512 6103 1695 1512 6104 1696 1513 6105 1695 1513 6106 1697 1513 6107 1696 1514 6108 1693 1514 6109 1695 1514 6110 1698 1515 6111 1697 1515 6112 1699 1515 6113 1698 1516 6114 1696 1516 6115 1697 1516 6116 1700 1517 6117 1699 1517 6118 1701 1517 6119 1702 857 6120 1699 857 6121 1700 857 6122 1702 1518 6123 1698 1518 6124 1699 1518 6125 1703 1519 6126 1701 1519 6127 1704 1519 6128 1700 857 6129 1701 857 6130 1703 857 6131 1705 1520 6132 1704 1520 6133 1706 1520 6134 1703 1521 6135 1704 1521 6136 1705 1521 6137 1707 1522 6138 1706 1522 6139 1708 1522 6140 1705 857 6141 1706 857 6142 1707 857 6143 1709 857 6144 1708 857 6145 1710 857 6146 1707 1523 6147 1708 1523 6148 1709 1523 6149 1702 1524 6150 1700 1524 6151 1711 1524 6152 1712 1513 6153 1711 1513 6154 1713 1513 6155 1714 857 6156 1702 857 6157 1711 857 6158 1712 1516 6159 1714 1516 6160 1711 1516 6161 1712 1525 6162 1713 1525 6163 1715 1525 6164 1716 1511 6165 1715 1511 6166 1717 1511 6167 1716 857 6168 1712 857 6169 1715 857 6170 1718 857 6171 1717 857 6172 1719 857 6173 1718 857 6174 1716 857 6175 1717 857 6176 1718 1526 6177 1719 1526 6178 1720 1526 6179 1721 1527 6180 1722 1528 6181 22 22 6182 1723 1506 6183 1720 1506 6184 1724 1506 6185 1725 1529 6186 1721 1527 6187 22 22 6188 1726 1530 6189 1725 1529 6190 22 22 6191 20 20 6192 1726 1530 6193 22 22 6194 1723 857 6195 1718 857 6196 1720 857 6197 1727 1531 6198 1728 1532 6199 1722 1528 6200 1723 1533 6201 1724 1533 6202 1729 1533 6203 1730 1534 6204 1727 1531 6205 1722 1528 6206 1731 1535 6207 1730 1534 6208 1722 1528 6209 1732 1536 6210 1731 1535 6211 1722 1528 6212 1721 1527 6213 1732 1536 6214 1722 1528 6215 1733 1537 6216 1734 1538 6217 1728 1532 6218 1735 1497 6219 1729 1497 6220 1736 1497 6221 1737 1539 6222 1733 1537 6223 1728 1532 6224 1727 1531 6225 1737 1539 6226 1728 1532 6227 1735 857 6228 1723 857 6229 1729 857 6230 1738 1540 6231 53 54 6232 1734 1538 6233 1735 1541 6234 1736 1541 6235 1739 1541 6236 1733 1537 6237 1738 1540 6238 1734 1538 6239 1740 1486 6240 1739 1486 6241 1741 1486 6242 1742 1542 6243 53 54 6244 1738 1540 6245 1742 1542 6246 43 44 6247 53 54 6248 1740 857 6249 1735 857 6250 1739 857 6251 1740 1543 6252 1741 1543 6253 1743 1543 6254 1744 1481 6255 1743 1481 6256 1745 1481 6257 1744 857 6258 1740 857 6259 1743 857 6260 1746 1482 6261 1745 1482 6262 1747 1482 6263 1746 857 6264 1744 857 6265 1745 857 6266 1748 1544 6267 1749 1544 6268 1750 1544 6269 1751 223 6270 1752 223 6271 1753 223 6272 1754 223 6273 1751 223 6274 1753 223 6275 1755 223 6276 1754 223 6277 1753 223 6278 1756 223 6279 1755 223 6280 1753 223 6281 1757 223 6282 1756 223 6283 1753 223 6284 1748 1545 6285 1750 1545 6286 1758 1545 6287 1759 1546 6288 1760 1547 6289 1761 1548 6290 1759 1546 6291 1761 1548 6292 1762 1549 6293 1763 1550 6294 1762 1549 6295 1764 1551 6296 1759 1546 6297 1762 1549 6298 1763 1550 6299 1763 1550 6300 1764 1551 6301 1765 1552 6302 1766 1553 6303 1765 1552 6304 1767 1554 6305 1763 1550 6306 1765 1552 6307 1766 1553 6308 1766 1553 6309 1767 1554 6310 1768 1555 6311 1769 1556 6312 1768 1555 6313 1770 1557 6314 1766 1553 6315 1768 1555 6316 1769 1556 6317 1769 1556 6318 1770 1557 6319 1771 1558 6320 1772 1559 6321 1773 1560 6322 1636 1459 6323 1774 1561 6324 1771 1558 6325 1775 1562 6326 1637 1460 6327 1772 1559 6328 1636 1459 6329 1769 1556 6330 1771 1558 6331 1774 1561 6332 1772 1559 6333 1776 1563 6334 1773 1560 6335 1777 1564 6336 1775 1562 6337 1778 1565 6338 1774 1561 6339 1775 1562 6340 1777 1564 6341 1772 1559 6342 1779 1566 6343 1776 1563 6344 1777 1564 6345 1778 1565 6346 1780 1567 6347 1781 1568 6348 1782 1569 6349 1779 1566 6350 1783 1570 6351 1780 1567 6352 1784 1571 6353 1772 1559 6354 1781 1568 6355 1779 1566 6356 1777 1564 6357 1780 1567 6358 1783 1570 6359 1785 1572 6360 1786 1573 6361 1782 1569 6362 1783 1570 6363 1784 1571 6364 1787 1574 6365 1781 1568 6366 1785 1572 6367 1782 1569 6368 1785 1572 6369 1788 1575 6370 1786 1573 6371 1789 1576 6372 1787 1574 6373 1790 1577 6374 1783 1570 6375 1787 1574 6376 1789 1576 6377 1791 1578 6378 1792 1579 6379 1788 1575 6380 1789 1576 6381 1790 1577 6382 1793 1580 6383 1785 1572 6384 1791 1578 6385 1788 1575 6386 1794 1581 6387 1795 1581 6388 1796 1581 6389 1797 1582 6390 1671 1492 6391 1792 1579 6392 1798 1583 6393 1795 1583 6394 1794 1583 6395 1791 1578 6396 1797 1582 6397 1792 1579 6398 1789 1576 6399 1793 1580 6400 1799 1584 6401 1797 1582 6402 1672 1493 6403 1671 1492 6404 1800 223 6405 1801 223 6406 1752 223 6407 1802 223 6408 1800 223 6409 1752 223 6410 1803 223 6411 1802 223 6412 1752 223 6413 1751 223 6414 1803 223 6415 1752 223 6416 1804 1585 6417 1805 1585 6418 1806 1585 6419 1807 223 6420 1808 223 6421 1809 223 6422 1810 223 6423 1807 223 6424 1809 223 6425 1811 223 6426 1810 223 6427 1809 223 6428 1812 223 6429 1811 223 6430 1809 223 6431 1813 223 6432 1812 223 6433 1809 223 6434 1804 1586 6435 1806 1586 6436 1814 1586 6437 1815 1587 6438 1816 1588 6439 1817 1589 6440 1815 1587 6441 1817 1589 6442 1818 1590 6443 1819 1591 6444 1818 1590 6445 1820 1592 6446 1815 1587 6447 1818 1590 6448 1819 1591 6449 1819 1591 6450 1820 1592 6451 1821 1593 6452 1822 1594 6453 1821 1593 6454 1823 1595 6455 1819 1591 6456 1821 1593 6457 1822 1594 6458 1822 1594 6459 1823 1595 6460 1824 1596 6461 1825 1597 6462 1824 1596 6463 1826 1598 6464 1822 1594 6465 1824 1596 6466 1825 1597 6467 1825 1597 6468 1826 1598 6469 1827 1599 6470 1828 1600 6471 1827 1599 6472 1829 1601 6473 1825 1597 6474 1827 1599 6475 1828 1600 6476 1830 1602 6477 1829 1601 6478 1831 1603 6479 1828 1600 6480 1829 1601 6481 1830 1602 6482 1830 1602 6483 1831 1603 6484 1832 1604 6485 1833 1605 6486 1832 1604 6487 1834 1606 6488 1830 1602 6489 1832 1604 6490 1833 1605 6491 1833 1605 6492 1834 1606 6493 1835 1607 6494 1836 1608 6495 1835 1607 6496 1837 1609 6497 1833 1605 6498 1835 1607 6499 1836 1608 6500 1836 1608 6501 1837 1609 6502 1838 1610 6503 1836 1608 6504 1838 1610 6505 1839 1611 6506 1840 1612 6507 1841 1612 6508 1842 1612 6509 1843 1613 6510 1841 1613 6511 1840 1613 6512 1836 1608 6513 1839 1611 6514 1844 1584 6515 1845 223 6516 1846 223 6517 1808 223 6518 1847 223 6519 1845 223 6520 1808 223 6521 1848 223 6522 1847 223 6523 1808 223 6524 1807 223 6525 1848 223 6526 1808 223 6527 1849 1614 6528 1850 1614 6529 1851 1614 6530 1852 223 6531 1853 223 6532 1854 223 6533 1855 223 6534 1852 223 6535 1854 223 6536 1856 223 6537 1855 223 6538 1854 223 6539 1849 1615 6540 1851 1615 6541 1857 1615 6542 1858 1616 6543 1859 1617 6544 1860 1618 6545 1858 1616 6546 1860 1618 6547 1861 1619 6548 1862 1620 6549 1861 1619 6550 1863 1621 6551 1858 1616 6552 1861 1619 6553 1862 1620 6554 1862 1620 6555 1863 1621 6556 1864 1622 6557 1865 1623 6558 1864 1622 6559 1866 1624 6560 1862 1620 6561 1864 1622 6562 1865 1623 6563 1865 1623 6564 1866 1624 6565 1867 1625 6566 1868 1626 6567 1867 1625 6568 1869 1627 6569 1865 1623 6570 1867 1625 6571 1868 1626 6572 1868 1626 6573 1869 1627 6574 1870 1628 6575 1871 1629 6576 1870 1628 6577 1872 1630 6578 1868 1626 6579 1870 1628 6580 1871 1629 6581 1873 1631 6582 1872 1630 6583 1874 1632 6584 1871 1629 6585 1872 1630 6586 1873 1631 6587 1873 1631 6588 1874 1632 6589 1875 1633 6590 1876 1634 6591 1875 1633 6592 1877 1635 6593 1873 1631 6594 1875 1633 6595 1876 1634 6596 1876 1634 6597 1877 1635 6598 1878 1636 6599 1879 1637 6600 1878 1636 6601 1880 1638 6602 1876 1634 6603 1878 1636 6604 1879 1637 6605 1879 1637 6606 1880 1638 6607 1881 1639 6608 1879 1637 6609 1881 1639 6610 1882 1640 6611 1883 1641 6612 1884 1641 6613 1885 1641 6614 1886 1642 6615 1884 1642 6616 1883 1642 6617 1879 1637 6618 1882 1640 6619 1887 1643 6620 1888 223 6621 1889 223 6622 1853 223 6623 1890 223 6624 1891 223 6625 1889 223 6626 1888 223 6627 1890 223 6628 1889 223 6629 1892 223 6630 1888 223 6631 1853 223 6632 1893 223 6633 1892 223 6634 1853 223 6635 1852 223 6636 1893 223 6637 1853 223 6638 1746 1644 6639 1747 1644 6640 1894 1644 6641 1895 1645 6642 1894 1645 6643 1896 1645 6644 1895 1646 6645 1746 1646 6646 1894 1646 6647 1895 1647 6648 1896 1647 6649 1897 1647 6650 1898 1648 6651 1897 1648 6652 1899 1648 6653 1898 1649 6654 1895 1649 6655 1897 1649 6656 1898 1650 6657 1899 1650 6658 1900 1650 6659 1901 1651 6660 1900 1651 6661 1902 1651 6662 1901 857 6663 1898 857 6664 1900 857 6665 1901 857 6666 1902 857 6667 1903 857 6668 1904 857 6669 1903 857 6670 1905 857 6671 1904 1652 6672 1901 1652 6673 1903 1652 6674 1906 1653 6675 1905 1653 6676 1907 1653 6677 1906 857 6678 1904 857 6679 1905 857 6680 1906 1654 6681 1907 1654 6682 1908 1654 6683 1909 1655 6684 1908 1655 6685 1910 1655 6686 1909 1656 6687 1906 1656 6688 1908 1656 6689 1911 1657 6690 1910 1657 6691 1912 1657 6692 1911 1658 6693 1909 1658 6694 1910 1658 6695 1913 1659 6696 1912 1659 6697 1914 1659 6698 1915 857 6699 1912 857 6700 1913 857 6701 1911 1660 6702 1912 1660 6703 1915 1660 6704 1916 1661 6705 1914 1661 6706 1917 1661 6707 1913 857 6708 1914 857 6709 1916 857 6710 1918 1662 6711 1917 1662 6712 1919 1662 6713 1916 1663 6714 1917 1663 6715 1918 1663 6716 1920 1664 6717 1919 1664 6718 1921 1664 6719 1918 857 6720 1919 857 6721 1920 857 6722 1922 857 6723 1921 857 6724 1923 857 6725 1920 1665 6726 1921 1665 6727 1922 1665 6728 1915 1666 6729 1913 1666 6730 1924 1666 6731 1925 1655 6732 1924 1655 6733 1926 1655 6734 1927 857 6735 1915 857 6736 1924 857 6737 1925 1658 6738 1927 1658 6739 1924 1658 6740 1925 1667 6741 1926 1667 6742 1928 1667 6743 1929 1653 6744 1928 1653 6745 1930 1653 6746 1929 857 6747 1925 857 6748 1928 857 6749 1931 857 6750 1930 857 6751 1932 857 6752 1931 857 6753 1929 857 6754 1930 857 6755 1931 1668 6756 1932 1668 6757 1933 1668 6758 1934 1651 6759 1933 1651 6760 1935 1651 6761 1934 857 6762 1931 857 6763 1933 857 6764 1934 1669 6765 1935 1669 6766 1936 1669 6767 1937 1648 6768 1936 1648 6769 1938 1648 6770 1937 857 6771 1934 857 6772 1936 857 6773 1937 1670 6774 1938 1670 6775 1939 1670 6776 1940 1645 6777 1939 1645 6778 1941 1645 6779 1940 857 6780 1937 857 6781 1939 857 6782 1940 1671 6783 1941 1671 6784 1661 1671 6785 1660 857 6786 1940 857 6787 1661 857 6788 1942 1672 6789 1943 1672 6790 1944 1673 6791 1945 1674 6792 1946 1675 6793 1947 1676 6794 1945 1674 6795 1947 1676 6796 1948 1676 6797 1949 1677 6798 1944 1673 6799 1950 1678 6800 1949 1677 6801 1942 1672 6802 1944 1673 6803 1951 1678 6804 1950 1678 6805 1952 1679 6806 1949 1677 6807 1950 1678 6808 1951 1678 6809 1953 1680 6810 1952 1679 6811 1954 1681 6812 1951 1678 6813 1952 1679 6814 1953 1680 6815 1955 1682 6816 1954 1681 6817 1956 1683 6818 1953 1680 6819 1954 1681 6820 1955 1682 6821 1957 1683 6822 1956 1683 6823 1958 1684 6824 1955 1682 6825 1956 1683 6826 1957 1683 6827 1959 1684 6828 1958 1684 6829 1960 1685 6830 1957 1683 6831 1958 1684 6832 1959 1684 6833 1961 1686 6834 1960 1685 6835 1962 1687 6836 1959 1684 6837 1960 1685 6838 1961 1686 6839 1963 1687 6840 1962 1687 6841 1964 1688 6842 1961 1686 6843 1962 1687 6844 1963 1687 6845 1965 1688 6846 1964 1688 6847 1966 1689 6848 1963 1687 6849 1964 1688 6850 1965 1688 6851 1967 1690 6852 1966 1689 6853 1968 1691 6854 1965 1688 6855 1966 1689 6856 1967 1690 6857 1969 1691 6858 1968 1691 6859 1970 1692 6860 1967 1690 6861 1968 1691 6862 1969 1691 6863 1971 1692 6864 1970 1692 6865 1972 1693 6866 1969 1691 6867 1970 1692 6868 1971 1692 6869 1973 1694 6870 1972 1693 6871 1974 1695 6872 1971 1692 6873 1972 1693 6874 1973 1694 6875 1975 1696 6876 1974 1695 6877 1976 1697 6878 1973 1694 6879 1974 1695 6880 1975 1696 6881 1977 1697 6882 1976 1697 6883 1978 1698 6884 1975 1696 6885 1976 1697 6886 1977 1697 6887 1979 1699 6888 1978 1698 6889 1980 1700 6890 1977 1697 6891 1978 1698 6892 1979 1699 6893 1981 1701 6894 1982 1701 6895 1983 1702 6896 1979 1699 6897 1980 1700 6898 1984 1700 6899 1985 1703 6900 1983 1702 6901 1986 1704 6902 1981 1701 6903 1983 1702 6904 1985 1703 6905 1987 1704 6906 1986 1704 6907 1988 1705 6908 1985 1703 6909 1986 1704 6910 1987 1704 6911 1989 1706 6912 1988 1705 6913 1990 1707 6914 1987 1704 6915 1988 1705 6916 1989 1706 6917 1991 1708 6918 1990 1707 6919 1992 1709 6920 1989 1706 6921 1990 1707 6922 1991 1708 6923 1993 1709 6924 1992 1709 6925 1994 1710 6926 1991 1708 6927 1992 1709 6928 1993 1709 6929 1995 1710 6930 1994 1710 6931 1996 1711 6932 1993 1709 6933 1994 1710 6934 1995 1710 6935 1997 1712 6936 1996 1711 6937 1998 1713 6938 1995 1710 6939 1996 1711 6940 1997 1712 6941 1999 1713 6942 1998 1713 6943 2000 1714 6944 1997 1712 6945 1998 1713 6946 1999 1713 6947 2001 1714 6948 2000 1714 6949 2002 1715 6950 1999 1713 6951 2000 1714 6952 2001 1714 6953 2003 1716 6954 2002 1715 6955 2004 1717 6956 2001 1714 6957 2002 1715 6958 2003 1716 6959 2005 1717 6960 2004 1717 6961 2006 1718 6962 2003 1716 6963 2004 1717 6964 2005 1717 6965 2007 1718 6966 2006 1718 6967 2008 1719 6968 2005 1717 6969 2006 1718 6970 2007 1718 6971 2009 1720 6972 2008 1719 6973 2010 1721 6974 2007 1718 6975 2008 1719 6976 2009 1720 6977 2011 1722 6978 2010 1721 6979 2012 1723 6980 2009 1720 6981 2010 1721 6982 2011 1722 6983 2013 1723 6984 2012 1723 6985 1946 1675 6986 2011 1722 6987 2012 1723 6988 2013 1723 6989 2013 1723 6990 1946 1675 6991 1945 1674 6992 2014 223 6993 2015 223 6994 2016 223 6995 2017 223 6996 2014 223 6997 2016 223 6998 2018 223 6999 2017 223 7000 2016 223 7001 2019 223 7002 2020 223 7003 2015 223 7004 2014 223 7005 2019 223 7006 2015 223 7007 2021 223 7008 2022 223 7009 2020 223 7010 2019 223 7011 2021 223 7012 2020 223 7013 2023 223 7014 2024 223 7015 2022 223 7016 2021 223 7017 2023 223 7018 2022 223 7019 2025 223 7020 2026 223 7021 2024 223 7022 2023 223 7023 2025 223 7024 2024 223 7025 2018 223 7026 2027 223 7027 2017 223 7028 2028 223 7029 2029 223 7030 2027 223 7031 2018 223 7032 2028 223 7033 2027 223 7034 2030 223 7035 2031 223 7036 2029 223 7037 2028 223 7038 2030 223 7039 2029 223 7040 2032 223 7041 2033 223 7042 2031 223 7043 2030 223 7044 2032 223 7045 2031 223 7046 2034 223 7047 2035 223 7048 2033 223 7049 2032 223 7050 2034 223 7051 2033 223 7052 2036 223 7053 2037 223 7054 1152 223 7055 1151 223 7056 2036 223 7057 1152 223 7058 2036 223 7059 2038 223 7060 2037 223 7061 1282 223 7062 2039 223 7063 1285 223 7064 2040 223 7065 2041 223 7066 2039 223 7067 1282 223 7068 2040 223 7069 2039 223 7070 2042 223 7071 2043 223 7072 2041 223 7073 2040 223 7074 2042 223 7075 2041 223 7076 2044 223 7077 2045 223 7078 2043 223 7079 2042 223 7080 2044 223 7081 2043 223 7082 854 223 7083 2046 223 7084 850 223 7085 854 223 7086 2047 223 7087 2046 223 7088 854 223 7089 2048 223 7090 2047 223 7091 2049 223 7092 2050 223 7093 2048 223 7094 854 223 7095 2049 223 7096 2048 223 7097 2051 223 7098 2052 223 7099 2050 223 7100 2049 223 7101 2051 223 7102 2050 223 7103 1757 223 7104 2053 223 7105 1756 223 7106 1813 223 7107 2054 223 7108 1812 223 7109 1890 223 7110 2055 223 7111 1891 223 7112 2056 223 7113 2057 223 7114 303 223 7115 302 223 7116 2056 223 7117 303 223 7118 2058 223 7119 2059 223 7120 2057 223 7121 2056 223 7122 2058 223 7123 2057 223 7124 2060 223 7125 2061 223 7126 2059 223 7127 2058 223 7128 2060 223 7129 2059 223 7130 311 223 7131 2062 223 7132 309 223 7133 311 223 7134 2063 223 7135 2062 223 7136 2064 223 7137 2065 223 7138 2063 223 7139 311 223 7140 2064 223 7141 2063 223 7142 2066 223 7143 2067 223 7144 2065 223 7145 2064 223 7146 2066 223 7147 2065 223 7148 2066 223 7149 2068 223 7150 2067 223 7151 2069 857 7152 2070 857 7153 2071 857 7154 2072 857 7155 2069 857 7156 2071 857 7157 2073 857 7158 2072 857 7159 2071 857 7160 2074 857 7161 2075 857 7162 2070 857 7163 2069 857 7164 2074 857 7165 2070 857 7166 2076 857 7167 2077 857 7168 2075 857 7169 2074 857 7170 2076 857 7171 2075 857 7172 2078 857 7173 2079 857 7174 2077 857 7175 2076 857 7176 2078 857 7177 2077 857 7178 2080 857 7179 2081 857 7180 2079 857 7181 2078 857 7182 2080 857 7183 2079 857 7184 2082 857 7185 2083 857 7186 2081 857 7187 2080 857 7188 2082 857 7189 2081 857 7190 2084 857 7191 2085 857 7192 2083 857 7193 2082 857 7194 2084 857 7195 2083 857 7196 2086 857 7197 2087 857 7198 2085 857 7199 2084 857 7200 2086 857 7201 2085 857 7202 2073 857 7203 2088 857 7204 2072 857 7205 2089 857 7206 2090 857 7207 2088 857 7208 2073 857 7209 2089 857 7210 2088 857 7211 2091 857 7212 2092 857 7213 2090 857 7214 2089 857 7215 2091 857 7216 2090 857 7217 2093 857 7218 2094 857 7219 2092 857 7220 2091 857 7221 2093 857 7222 2092 857 7223 2095 857 7224 2096 857 7225 2094 857 7226 2093 857 7227 2095 857 7228 2094 857 7229 2097 857 7230 2098 857 7231 2096 857 7232 2095 857 7233 2097 857 7234 2096 857 7235 2099 857 7236 2100 857 7237 2098 857 7238 2097 857 7239 2099 857 7240 2098 857 7241 2101 857 7242 2102 857 7243 2100 857 7244 2099 857 7245 2101 857 7246 2100 857 7247 2103 68 7248 2104 68 7249 2105 68 7250 2106 68 7251 2103 68 7252 2105 68 7253 2107 68 7254 2106 68 7255 2105 68 7256 2108 68 7257 2109 68 7258 2104 68 7259 2103 68 7260 2108 68 7261 2104 68 7262 2110 68 7263 2111 68 7264 2109 68 7265 2108 68 7266 2110 68 7267 2109 68 7268 2112 68 7269 2113 68 7270 2111 68 7271 2110 68 7272 2112 68 7273 2111 68 7274 2114 68 7275 2115 68 7276 2113 68 7277 2112 68 7278 2114 68 7279 2113 68 7280 2116 68 7281 2117 68 7282 2115 68 7283 2114 68 7284 2116 68 7285 2115 68 7286 2118 68 7287 2119 68 7288 2117 68 7289 2116 68 7290 2118 68 7291 2117 68 7292 2120 68 7293 2121 68 7294 2119 68 7295 2118 68 7296 2120 68 7297 2119 68 7298 2107 68 7299 2122 68 7300 2106 68 7301 2123 68 7302 2124 68 7303 2122 68 7304 2107 68 7305 2123 68 7306 2122 68 7307 2125 68 7308 2126 68 7309 2124 68 7310 2123 68 7311 2125 68 7312 2124 68 7313 2127 68 7314 2128 68 7315 2126 68 7316 2125 68 7317 2127 68 7318 2126 68 7319 2129 68 7320 2130 68 7321 2128 68 7322 2127 68 7323 2129 68 7324 2128 68 7325 2131 68 7326 2132 68 7327 2130 68 7328 2129 68 7329 2131 68 7330 2130 68 7331 2133 68 7332 2134 68 7333 2132 68 7334 2131 68 7335 2133 68 7336 2132 68 7337 2135 68 7338 2136 68 7339 2134 68 7340 2133 68 7341 2135 68 7342 2134 68 7343 2137 1724 7344 2138 1724 7345 2139 1724 7346 2140 1725 7347 2141 1725 7348 2142 1726 7349 2143 1727 7350 2137 1727 7351 2139 1727 7352 2144 1728 7353 2145 1728 7354 2146 1728 7355 2144 1729 7356 2146 1729 7357 2147 1729 7358 2148 1726 7359 2142 1726 7360 2149 1730 7361 2148 1726 7362 2140 1725 7363 2142 1726 7364 2143 1731 7365 2150 1731 7366 2137 1731 7367 2151 1732 7368 2152 1732 7369 2153 1732 7370 2148 1726 7371 2149 1730 7372 2154 1730 7373 2155 1733 7374 2156 1733 7375 2150 1733 7376 2157 1734 7377 2158 1734 7378 2159 1735 7379 2143 1724 7380 2155 1724 7381 2150 1724 7382 2151 1736 7383 2153 1736 7384 2160 1736 7385 2161 1737 7386 2162 1737 7387 2156 1737 7388 2163 1735 7389 2159 1735 7390 2164 1738 7391 2155 1739 7392 2161 1739 7393 2156 1739 7394 2157 1734 7395 2159 1735 7396 2163 1735 7397 2165 1724 7398 2166 1724 7399 2162 1724 7400 2167 855 7401 2168 855 7402 2169 855 7403 2161 1724 7404 2165 1724 7405 2162 1724 7406 2163 1735 7407 2164 1738 7408 2170 1738 7409 2171 1740 7410 2172 1740 7411 2166 1740 7412 2173 1741 7413 2174 1741 7414 2175 1742 7415 2165 1743 7416 2171 1743 7417 2166 1743 7418 2167 855 7419 2169 855 7420 2176 855 7421 2177 1744 7422 2178 1744 7423 2172 1744 7424 2179 1742 7425 2175 1742 7426 2180 1745 7427 2171 1724 7428 2177 1724 7429 2172 1724 7430 2173 1741 7431 2175 1742 7432 2179 1742 7433 2181 1724 7434 2182 1724 7435 2178 1724 7436 2183 1746 7437 2184 1746 7438 2185 1746 7439 2177 1747 7440 2181 1747 7441 2178 1747 7442 2179 1742 7443 2180 1745 7444 2186 1745 7445 2181 1724 7446 2187 1724 7447 2182 1724 7448 2188 1748 7449 2189 1748 7450 2190 68 7451 2183 1749 7452 2185 1749 7453 2191 1749 7454 2192 68 7455 2190 68 7456 2193 1750 7457 2188 1748 7458 2190 68 7459 2192 68 7460 2194 1751 7461 2195 1751 7462 2196 1751 7463 2192 68 7464 2193 1750 7465 2197 1750 7466 2198 1752 7467 2199 1752 7468 2200 1753 7469 2194 1754 7470 2196 1754 7471 2201 1754 7472 2202 1753 7473 2200 1753 7474 2203 1755 7475 2198 1752 7476 2200 1753 7477 2202 1753 7478 2204 857 7479 2205 857 7480 2206 857 7481 2202 1753 7482 2203 1755 7483 2207 1755 7484 2208 1756 7485 2209 1756 7486 2210 1757 7487 2204 857 7488 2206 857 7489 2211 857 7490 2212 1757 7491 2210 1757 7492 2213 1758 7493 2208 1756 7494 2210 1757 7495 2212 1757 7496 2212 1757 7497 2213 1758 7498 2214 1758 7499 2215 1759 7500 2216 1759 7501 2217 1759 7502 2218 1760 7503 2219 1761 7504 2220 1762 7505 2221 223 7506 2217 223 7507 2222 223 7508 2223 1763 7509 2224 1764 7510 2225 1765 7511 2221 223 7512 2215 223 7513 2217 223 7514 2223 1763 7515 2225 1765 7516 2226 1766 7517 2227 223 7518 2228 223 7519 2216 223 7520 2229 1767 7521 2220 1762 7522 2230 1768 7523 2215 223 7524 2227 223 7525 2216 223 7526 2229 1767 7527 2218 1760 7528 2220 1762 7529 2231 1769 7530 2232 1769 7531 2228 1769 7532 2233 1770 7533 2230 1768 7534 2234 1771 7535 2227 1772 7536 2231 1772 7537 2228 1772 7538 2229 1767 7539 2230 1768 7540 2233 1770 7541 2235 223 7542 2236 223 7543 2232 223 7544 2237 1773 7545 2234 1771 7546 2238 1774 7547 2231 223 7548 2235 223 7549 2232 223 7550 2233 1770 7551 2234 1771 7552 2237 1773 7553 2235 1775 7554 2239 1775 7555 2236 1775 7556 2240 1776 7557 2238 1774 7558 2241 1777 7559 2237 1773 7560 2238 1774 7561 2240 1776 7562 2242 223 7563 2243 223 7564 2239 223 7565 2244 1778 7566 2241 1777 7567 2245 1779 7568 2246 1780 7569 2242 1780 7570 2239 1780 7571 2235 1781 7572 2246 1781 7573 2239 1781 7574 2240 1776 7575 2241 1777 7576 2244 1778 7577 2247 223 7578 2248 223 7579 2243 223 7580 2249 1782 7581 2245 1779 7582 2250 1783 7583 2242 1784 7584 2247 1784 7585 2243 1784 7586 2244 1778 7587 2245 1779 7588 2249 1782 7589 2251 1785 7590 2252 1785 7591 2248 1785 7592 2253 1786 7593 2254 1787 7594 2255 1788 7595 2251 1789 7596 2248 1789 7597 2247 1789 7598 2249 1782 7599 2250 1783 7600 2256 1790 7601 2257 1791 7602 2258 1791 7603 2252 1791 7604 2259 1792 7605 2255 1788 7606 2260 1793 7607 2251 223 7608 2257 223 7609 2252 223 7610 2253 1786 7611 2255 1788 7612 2259 1792 7613 2261 223 7614 2262 223 7615 2258 223 7616 2263 1794 7617 2260 1793 7618 2264 1795 7619 2257 223 7620 2261 223 7621 2258 223 7622 2259 1792 7623 2260 1793 7624 2263 1794 7625 2265 223 7626 2266 223 7627 2262 223 7628 2267 1796 7629 2264 1795 7630 2268 1797 7631 2261 223 7632 2265 223 7633 2262 223 7634 2263 1794 7635 2264 1795 7636 2267 1796 7637 2265 223 7638 2269 223 7639 2266 223 7640 2270 1798 7641 2268 1797 7642 2271 1799 7643 2267 1796 7644 2268 1797 7645 2270 1798 7646 2272 1800 7647 2222 1800 7648 2269 1800 7649 2273 1801 7650 2271 1799 7651 2224 1764 7652 2274 223 7653 2272 223 7654 2269 223 7655 2265 1802 7656 2274 1802 7657 2269 1802 7658 2270 1798 7659 2271 1799 7660 2273 1801 7661 2272 1803 7662 2221 1803 7663 2222 1803 7664 2273 1801 7665 2224 1764 7666 2223 1763 7667 2275 1804 7668 2251 1804 7669 2247 1804 7670 2276 223 7671 2275 223 7672 2247 223 7673 2221 1805 7674 2277 1805 7675 2215 1805 7676 2221 223 7677 2278 223 7678 2277 223 7679 2279 1806 7680 2280 1806 7681 2281 1806 7682 2282 223 7683 2281 223 7684 2283 223 7685 2279 223 7686 2281 223 7687 2282 223 7688 2284 223 7689 2285 223 7690 2280 223 7691 2279 223 7692 2284 223 7693 2280 223 7694 2286 223 7695 2287 223 7696 2285 223 7697 2288 223 7698 2286 223 7699 2285 223 7700 2284 223 7701 2288 223 7702 2285 223 7703 2288 223 7704 2289 223 7705 2286 223 7706 2290 223 7707 2291 223 7708 2289 223 7709 2288 223 7710 2290 223 7711 2289 223 7712 2292 223 7713 2293 223 7714 2291 223 7715 2294 1807 7716 2292 1807 7717 2291 1807 7718 2290 1808 7719 2294 1808 7720 2291 1808 7721 2295 223 7722 2296 223 7723 2293 223 7724 2292 223 7725 2295 223 7726 2293 223 7727 2297 223 7728 2298 223 7729 2296 223 7730 2295 223 7731 2297 223 7732 2296 223 7733 2299 223 7734 2300 223 7735 2298 223 7736 2301 223 7737 2299 223 7738 2298 223 7739 2297 223 7740 2301 223 7741 2298 223 7742 2301 223 7743 2302 223 7744 2299 223 7745 2303 223 7746 2283 223 7747 2302 223 7748 2301 223 7749 2303 223 7750 2302 223 7751 2304 223 7752 2282 223 7753 2283 223 7754 2303 1809 7755 2304 1809 7756 2283 1809 7757 2305 1810 7758 2306 1811 7759 2307 1812 7760 2308 1813 7761 2309 1814 7762 2310 1815 7763 2308 1813 7764 2310 1815 7765 2311 1816 7766 2312 1817 7767 2307 1812 7768 2313 1818 7769 2312 1817 7770 2305 1810 7771 2307 1812 7772 2314 1819 7773 2313 1818 7774 2315 1820 7775 2312 1817 7776 2313 1818 7777 2314 1819 7778 2316 1821 7779 2315 1820 7780 2317 1822 7781 2314 1819 7782 2315 1820 7783 2316 1821 7784 2318 1823 7785 2317 1822 7786 2319 1824 7787 2316 1821 7788 2317 1822 7789 2318 1823 7790 2320 1825 7791 2319 1824 7792 2321 1826 7793 2318 1823 7794 2319 1824 7795 2320 1825 7796 2322 1827 7797 2323 1828 7798 2324 1829 7799 2320 1825 7800 2321 1826 7801 2325 1830 7802 2326 1831 7803 2324 1829 7804 2327 1832 7805 2322 1827 7806 2324 1829 7807 2326 1831 7808 2328 1833 7809 2327 1832 7810 2329 1834 7811 2326 1831 7812 2327 1832 7813 2328 1833 7814 2330 1834 7815 2329 1834 7816 2331 1835 7817 2328 1833 7818 2329 1834 7819 2330 1834 7820 2332 1836 7821 2331 1835 7822 2309 1814 7823 2330 1834 7824 2331 1835 7825 2332 1836 7826 2332 1836 7827 2309 1814 7828 2308 1813 7829 2333 223 7830 2334 223 7831 2335 223 7832 2336 223 7833 2333 223 7834 2335 223 7835 2337 223 7836 2336 223 7837 2335 223 7838 2338 223 7839 2339 223 7840 2334 223 7841 2333 223 7842 2338 223 7843 2334 223 7844 2338 223 7845 2340 223 7846 2339 223 7847 2337 223 7848 2341 223 7849 2336 223 7850 2342 223 7851 2343 223 7852 2341 223 7853 2337 223 7854 2342 223 7855 2341 223 7856 2342 223 7857 2344 223 7858 2343 223 7859

+
+
+
+
+ + + + + 7.54969e-11 1.19208e-10 9.99987e-4 0 0 9.99987e-4 -1.19208e-10 -0.6104 -9.99987e-4 0 7.54969e-11 0 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl new file mode 100644 index 0000000000000000000000000000000000000000..0c4575ec6b0447a9f5383bcb978c3d4841bfdaef GIT binary patch literal 18184 zcmb81dz??z`p1_`NbWOkxg-veOfF-D?_Qf6CYM1?2<6VWEBE+Sa>*gNN2-&{Nyjy* zkTLta-Es>xQRg5EA(}Zw7ef3#&)$2@eD?SF{qdXEt7bLNdOy#z?$26luUd|OcErfh z{rgoJFmlAODvu8BKfGW6k#*`PG-_O>=BP1!s?@Ee{$D?X^C&gm*=G&i{i1EaJ=I28 zarZ5C3MZKtF|Toh$rkJ+f(X)KvW2bN!P1c?~SZ)JvL~J zW9WCz4$n#ZC4U=49uU7hdp41E-HG;z{K&lol=KRtS0pAaHa_<(UDb*Qum5&IP zm^9PAjWEn)8%7)(}`0Zque9D?x<#?pR zwq(a>dcS5%c=b;Z8$nzzpO$DOY(w<2CZ*qHaL2#H2;9p?w>}Fk(kz9EuGYr9E#hsV5R9Oxm|0V|+wF?5**v zb^4PlO*d3+?+D!sbnD}7y|mG!)CdqWGxk}t#{Rtl>x!jw3Gr&0vkxUwYA;IoR)&?~ zdBq-*J*9+bY6y6B>XR$m#4AJBNBx+zU-ID~vNHBLM<{(xTVUzKsGHQH#^6x>Al{+&Lm)!lZp0g+O3F@rcsp|7sl=U(9LKse>7{&aK6* za?-wyYiC>9{|pG$btl><;E@f_{>v-lq1cdF0ot6`>b6437ZJe{lNP;(_HF!#5sR_z z*+45rP%mD|nJ{VJMp=y5SphNRr$dnvPj+|y@l%Rp=#xX+<)nQZ$6(_f5Or_oO=Mkn zqJ2VEHT13j@``ON@K;XfKh;uD@~R-Ps(A!UB#r*$mC4Y)jR!Ge(c?X0arO5;M347! zF~OQJmk@Dvf8)rSxx<|oQ&Jp5pBd6JC+*wNpY5}n!Nx1+-rmBx?nL`U7mQfUC;#OY z+sMG!$E@Mhy^@TQw+Df-?h!08Y0+zF-$rwczq^CF>Wz`<1Z~cQN&7Y$6Y<3S*E6EE z2RH?y9UMcuTUzI&eH*Po6bfvxt~=2_aTO!>^`KuFy&^Gbv5^^H&^dtK{zaUuI5$De z4+xf+G}FEftg|jwPp_^xmr0A>0@<~lYgx6OA_ZhFSqb9$S)X8uNsC@X`!+B$xC?`E z{uO-P0iQ*}gh~50?g23;Ai5N)=iL6Nx^rz$ieu=kTWxdFzKvQSh6V)dx)bda|3E$M z2p%xi_~Py&^Gbv2g%BeF%DdnKjbphyYx(;;_V|nf7g9t#x0-swQ(g z=Q3&0D`P)CVQhoSQ`#e+5GwyfU<$2T0odOma;w-@0#4(q+g$QC)uhx}XM+8fF?__o|zE`VG#x*iFSR!?1_BG*1-;^7> zL6;?Gua}PW`OmR!qBlr4^=+g~&Hl*Ph_Bv%+mQ}+y?t$5pT-&TcgbbuV4tY-XZMc{ z!Cu|LUSPw|E&rb6vJKW7o<*5p8|*u4!hF^EjZHo^$>sLonr2P87Q`#=CEWh3Nh$6n zW(-Q5n4T|b)}++(lM8bC70-!gUJ-&dg?kCtiCHs*U`;q9+ga_7?ZNfKnv|N{dTpYV z|Mu;dLM7+Y{@-=Q*4g)P$v<7UFQ;FzF7|{q<+g`-6(VQ_2;2B(-cBp=$BFvapT^o9 z*Hnwt+;xm?it zV!%9W9!~L^?Y=FGKNlTuqw&vp)HCdQ+m&t=k@=n9`<*|S4IvGy&3uQ*ICvQoZ@Be&x{=J@;8e$VLmT0 zRc~rDO^>ZR+-6-&hl#r`-Ox7@$LlwWbq;yOHYVeIZrR~zq}8A?sH;~J7t?Y|wXe8u*1#&(OqB6+t@IZ1&4klQWQtv00vhy5$O&|H9Wr*Nh(`$CN=I;6} zGNO1JcvWI?Z+qI=DSFW51Nu^t=d8R|0qe6iwJfQZCvM$}yo`Ec+c-)6roNq)I9;bV zdeCNFOoxe8Gy2;D|Cp@rDZEv)gl$N>Pygfd$YS&Zr8ed5Zcp4gUeBy@NwXvyeM@Sg zIrsxuoWJP8m9%4;ORhT};K0bJ=9CeD-`WIwiHlJ5V=swhj?22Sj)TfM%DEJRd@{m1lS_UR=Pbju2JqbxCPkT`8w zj8|oT=w_b-Q6&GRsOb$A3t!A&f;B1CWk-^oI`?J$ON|HIuewdJhAqx(eV%@=lZ@W} z!&8@~w>zv!srbWbcC8nu>0gGg4SB_Mm^k^2ZO8YSth0+$a?MDspAsL^%l4F#TZZAg zSARSg(Kt)^^jt=;IaODx`oEjmnekKfccm+Y2+qZ}aaVMsqFtcj6rK8*?N$wDwWsw-5syG?=>Cu>)8hjXz#rG7aVXE*tEogVdw_M#Wes`Tdcl2SGbxF)%=rB>E=c{_)zc%XRt^M5=!Ro9(N^v+B+f!=X z6-Pg`AgU)F?CP4xTkf{_mW(wimACpieY?yK?JnrxvM#2>#IB=Tt)lPj(22)}xF_H5 z|Dntb=h7c{I2YSfs;-q!*Q>r)_n0*(XK&!&1Lp2tSd&uO4La+j^n-f(sD3W%GLfaw zVWPxmpEyHr?A1%B4|aQDo)WK`qOQWZa_uRVp4BmW;pv@vVxF{|7*2LVyz^pBN~N95 z8?BbPOV4RB*p;Zr?7U1&C3KkhbkU4x3Dnik`}(+#VWttUen7wCTx?INFSEXlW@T;E z8#+Ddny6Uzmb^=4O-ij;oDuE1Zn3 zY)`2kv+s8s?R-oBxh}~y5v%OOc}LHhlxnxClw0SS<+|L5&0W^TbeMQ(<-P8CjKT3E zBJLxY*~F`d@SAh7J*A4AYU)-h_^N&`?Y{k9|ik|geNtbmo9VTQhERH!*->B&JM6F6WilLS{7u!?n``~QX#Z1i- zKEIk)v$Hc1@zuEEZ5*YFF7EBlLVPvg@`31uBF{N@A-+1)rk0a}bD1WHuf}1;VcXbk z!^Wd~A8d3Y#s=$UO-lXce4_h7r|J5g0yRTkajvk9)ie6LLlBXv!ds&(VXsc&jAkq% zvKPG7d0XD@?hA;>Mpd~KWyxiX5vjLo7&EL1V=nJt_ZA|uPqJ4=ITzCoPF((mh^!+b z4yF1g40F39zDhnfC(07U51x(Em@QZnc6F=9dc>PucRJ@Wvxz6E7sfSUf;A~sZ{%pV z6C$!%+e<|kR>mBHh^)zyo03UZ~vj2dk93s{Fn6O!H8;sXoCsXq*VDGNp5RIWQ`tpz(!2vjP@fk zt1-sMene!iWBbE2KLP0_p3huT+H`w_rjv2)>EY)`2N z50{A^{rg1Sy5$&qe({wV_wT8%>Egik!erv`>tpT1`^OH8CMzs-(C>mD6V?+3V9=C9#CpK3?H+ZAgkGyyApsYGXrwvxH~r@C;{& zQ78vXc!uM7#m{g06-#)W^C$=tEa9HdeL9zTWKp|@EHOPs{>D8tmyi@oxK|oF+!KXh z3HLGXJ(5p;CfSLL+9k1sdkpslKfkFfmT>!X%jOc*7PZ^N5^hayr(8l(EaA4{S`QN} z;hN?;%q99Ho=;>6*BjSJE+HwFa4m58!URjWOzdqg(PWeUm?i8X+x7{WOC-e-w#S;3 z`f6RK^9I@+PG_br7|KR0h+4{16hdQbmaZt~|N ztm91*oL))s4u9hnoQeeBsvQF{5yX8l1m`l}s`+2geG6hJhzcP1%RC2X?&9J0rU?$) zR_Z*6F(Be%Y_MK)|0Q4SDRmV@QxL^s2+qZ}mD+{eMFu5DH^T(_19-NEs*pzyDeVRQ2b{?v^I?8pzbye$)zgsIZ4+iVgw5S@O;zvBU6jLg5L?KAH+!L2l88~#9e*el20y=)&p_0;X?1P z_kc(%)z2yXadl@e2-t9PZG1K^#on7-+8y$)3VFqzlsWjQwGH-s8*l#pc60^2azL2r zlky`{Q>sDx%h8umjxr!nyH3#CE!0&;P*>K9UyC@yP`eV_;e@4IWBb>E$@;r~wQP8W zzu>F7qC-KfS!nc6}pe&TQboiKcY#gJ|L=r*bRbp@oko$-w?$|-_S=s*sP<&+hSzp`p#vN zbJ*P5rC&zf&}}zv*6U*k&c%0AN_BvZM?owA!8c> zO12jz58Bp?+r#bbm))tW^9JrXj9TeeoQwNd*xuoF zna*f`rZzUb9vAMf?A3?mnnf=hjB_{SdgT$^cf<6d%u3ev4YpejUU4oSD`6svUXl-U z;wPvpmW11Yy~>C7us3dwu7g)h@E8o!!T5-Ni}As^cua(e#=H93KVuecT64ALT*2() z%?5log;^BDHy~blAWU$s@GY4Q;u?tJu)%kNJkHrRcH1DDJ-J*rit&o|^39)8Ngzst zs1AZ9Y%gqMF={pMp*UNWZ>G7leE-E|QtFxYY3_4q#hS3e=P*2Tau3Ch9z=f-l|ZnB z&oaX2C0Ev^xmP1I^ux7QYd*PQd#ni&D{Q<38?|C=uwK@LyNS^gy)pQ;UvgQCymk)C z;jMjP8(2A|nbOj;NBM|4vb52_h985@vaKhF4sc1uHcm$copULfZm)agK3ZsLE3RGS%Bh8LU7-ba(1PBoK&_S&EisL6SdJC4 zrI(C^S7@o6Tqtc$v>YZ7$$0BHA{jGky*3Ei!|TUf(_U})2=sQTtDN>gfAwMpiIACA zsw?8ez8Fz0;1%cMJK^xXGiC;RCWtr?d;^YAn{)dfw$TT~;~?&jvB7#-lQ;WF^s1}H z5S%M)L-qzEK~zNC&c1V*_>B?nogZyrmk05Ezc9hM%=b+GYbV*U3)!>s}ve*wYwb$r{08P1EAWoPN{IpaYz0l^aXFlMSDt=P}O9qPKG{9uwg^ zmbD<}fJgzsw>=zRVbtdAEO5gMLUwqiL9m4Fg>9S$F&>0O`Yd64tO<8s80RlwoL9ko z#j6^>aO0P6-riZi=osrt--} zOoxfzx;1vEU`M|jvnbEIJlC2pjQv+B{{rzC_UA`Hm~VFFeT?~LTi)Y@d;8ZQHo*q= zQ7(@=wimV`#E&4p0l^Zs7q)@Z5BE5T(=i0+V%s>=?VTBY9cMBMEyyt(zw_evUx*n% zJPSf1046w>d9UWbqU!+SWe_Dn@LM~6smC#+Qu9F!1yMZ42J2-_O7#RGXG_@8hitH3 z_SQQoaxV@{mVK?u^}{V_-eCDJ!}gn`R74+6Y%nT(qf78JK3*H+9@9X5-d{euU=5ts>%kN1ppXssM zmo+K%9=$O!^&`4W8%UZpDYcmh)B7Zs>FttcP4cE8F6ZTod6z1=On;R$YYLY`<|~xa zkzD+ymNhBWHh7OCZvo8gEQFciB+Z(_Hq6Pt + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-15T14:40:02 + 2019-01-15T14:40:02 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.973 0.71 0 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + + + + 96.63961 822.28 -45.4537 99.58848 824.0162 -44.73399 100.3009 822.5781 -44.22518 102.2305 825.6064 -44.10003 100.3009 822.5781 -44.22518 99.58848 824.0162 -44.73399 98.81455 821.7077 -44.59094 98.81455 821.7077 -44.59094 100.3009 822.5781 -44.22518 97.35289 820.8485 -44.94186 103.0888 823.0031 -43.06891 102.4791 823.9492 -43.70977 102.4791 823.9492 -43.70977 95.78633 823.7277 -45.41882 98.732 825.4668 -44.69404 101.3344 826.9566 -44.10634 98.732 825.4668 -44.69404 94.89007 825.0267 -44.84073 97.82931 826.764 -44.1095 100.4032 828.1838 -43.60338 97.82931 826.764 -44.1095 94.05198 826.0305 -43.7847 96.98281 827.7606 -43.04671 99.53475 829.1593 -42.64395 96.98281 827.7606 -43.04671 94.8309 827.4833 -42.00791 96.29096 828.3419 -41.63231 99.08172 829.932 -41.3139 96.29096 828.3419 -41.63231 93.36914 826.6239 -42.376 66.87915 815.8128 -36.57975 96.29096 828.3419 -41.63231 94.8309 827.4833 -42.00791 91.03065 827.1286 -38.24599 94.5586 829.5798 -37.15718 96.29096 828.3419 -41.63231 91.03065 827.1286 -38.24599 99.08172 829.932 -41.3139 93.36914 826.6239 -42.376 82.38558 819.1723 -46.42704 93.36914 826.6239 -42.376 94.05198 826.0305 -43.7847 83.20429 820.6342 -44.76264 83.20429 820.6342 -44.76264 83.16931 818.204 -47.44021 94.89007 825.0267 -44.84073 84.01802 816.9689 -48.01707 95.78633 823.7277 -45.41882 84.84444 815.5946 -48.09809 96.63961 822.28 -45.4537 97.35289 820.8485 -44.94186 89.78161 816.5842 -46.73441 97.35289 820.8485 -44.94186 86.53163 814.7584 -47.4607 97.22507 816.6182 -43.4109 97.35289 820.8485 -44.94186 103.0888 823.0031 -43.06891 89.78161 816.5842 -46.73441 126.3658 848.138 -39.59248 122.9972 853.8332 -40.77885 122.9813 854.0506 -40.77388 122.5459 853.6271 -40.85788 122.9813 854.0506 -40.77388 122.9972 853.8332 -40.77885 126.6314 856.4227 -39.94916 122.9076 859.4448 -40.58209 126.6314 856.4227 -39.94916 122.9813 854.0506 -40.77388 121.8066 854.0563 -40.87001 122.9076 859.4448 -40.58209 122.9813 854.0506 -40.77388 121.8396 853.6424 -40.88691 121.8066 854.0563 -40.87001 122.0749 853.6376 -40.88835 123.0112 853.615 -40.78322 123.0112 853.615 -40.78322 122.9759 851.9521 -40.81676 122.5459 853.6271 -40.85788 123.0112 853.615 -40.78322 122.9759 851.9521 -40.81676 122.7545 850.2697 -40.8462 122.2552 850.7108 -40.95146 122.7545 850.2697 -40.8462 122.3393 848.5747 -40.88467 122.3393 848.5747 -40.88467 121.7676 846.8433 -40.92945 121.434 847.9445 -41.0604 121.7676 846.8433 -40.92945 120.9755 844.9235 -40.9898 120.288 845.3042 -41.18836 120.9755 844.9235 -40.9898 123.7472 839.2442 -38.72842 120.1634 843.2412 -41.05213 120.1634 843.2412 -41.05213 131.6624 851.4304 -38.2397 132.5773 847.8466 -37.14473 133.4368 844.9106 -35.84304 131.2948 853.0414 -38.58212 133.6607 848.7818 -36.68614 131.6624 851.4304 -38.2397 131.2948 853.0414 -38.58212 132.5773 847.8466 -37.14473 130.7148 855.85 -38.9846 132.57 853.7291 -38.01493 130.7148 855.85 -38.9846 130.1761 858.7857 -39.16753 130.1761 858.7857 -39.16753 130.1761 858.7857 -39.16753 129.7046 862.9567 -39.2102 130.0502 867.2322 -39.03238 130.1761 858.7857 -39.16753 129.7046 862.9567 -39.2102 130.8236 867.3078 -38.67462 131.71 858.9349 -38.56543 131.71 858.9349 -38.56543 119.1268 841.3548 -41.13626 118.908 842.7618 -41.33905 119.1268 841.3548 -41.13626 117.9432 839.4354 -41.2396 117.3367 840.3011 -41.5174 117.9432 839.4354 -41.2396 116.5804 837.4562 -41.37215 116.5804 837.4562 -41.37215 115.0098 835.3923 -41.54201 115.596 837.9152 -41.72971 115.0098 835.3923 -41.54201 113.7895 833.9255 -41.68958 113.7059 835.614 -41.9822 113.7895 833.9255 -41.68958 121.7037 831.6785 -36.78449 115.2597 828.4114 -38.98679 112.5321 832.514 -41.85503 112.5321 832.514 -41.85503 128.4031 835.3474 -34.48127 134.947 844.2312 -34.54032 133.4368 844.9106 -35.84304 133.9633 843.2614 -34.92213 133.9633 843.2614 -34.92213 109.059 825.5263 -41.08322 111.1721 831.0858 -42.04923 111.6669 833.3928 -42.28318 111.1721 831.0858 -42.04923 108.9007 828.9141 -42.41382 109.4939 831.2684 -42.63869 108.9007 828.9141 -42.41382 106.3776 826.7628 -42.87363 107.1902 829.2504 -43.05638 106.3776 826.7628 -42.87363 104.5042 825.3461 -43.25953 104.7672 827.3576 -43.54169 104.5042 825.3461 -43.25953 109.059 825.5263 -41.08322 104.3088 816.6144 -39.68877 115.2597 828.4114 -38.98679 121.7037 831.6785 -36.78449 110.9404 816.6098 -35.59943 128.4031 835.3474 -34.48127 135.3475 839.4111 -32.08028 135.3475 839.4111 -32.08028 136.3576 840.2106 -31.58448 135.3475 839.4111 -32.08028 116.9984 816.6045 -31.17918 136.4499 836.6348 -29.44046 137.9292 836.2534 -27.66033 136.4499 836.6348 -29.44046 135.3475 839.4111 -32.08028 136.3576 840.2106 -31.58448 122.8234 864.872 -40.40821 122.8234 864.872 -40.40821 129.2301 867.1531 -39.25193 122.5049 876.5244 -40.10868 129.2301 867.1531 -39.25193 122.8234 864.872 -40.40821 121.9715 864.8721 -40.47755 122.5049 876.5244 -40.10868 122.8234 864.872 -40.40821 121.9715 864.8721 -40.47755 129.2301 867.1531 -39.25193 122.4838 877.0347 -40.09796 127.8447 879.516 -39.34615 124.9302 918.7655 -39.21965 129.2301 867.1531 -39.25193 127.8447 879.516 -39.34615 130.0502 867.2322 -39.03238 120.2931 864.858 -40.18024 120.0931 859.3576 -40.29303 119.517 864.8444 -39.82251 115.9878 861.3115 -37.80797 119.517 864.8444 -39.82251 120.0931 859.3576 -40.29303 119.3378 876.4132 -39.4775 120.2931 864.858 -40.18024 119.517 864.8444 -39.82251 118.9433 870.7209 -39.2923 116.0766 867.6079 -37.09818 118.9433 870.7209 -39.2923 120.642 854.0506 -40.68865 115.7227 855.0606 -38.52877 120.642 854.0506 -40.68865 121.1195 864.8674 -40.40108 120.6603 853.855 -40.70168 120.642 854.0506 -40.68865 120.6603 853.855 -40.70168 121.1348 853.6541 -40.81576 120.6761 853.66 -40.71397 121.6031 853.6467 -40.87426 121.4128 876.4819 -40.13354 121.1195 864.8674 -40.40108 120.3389 876.4493 -39.92034 118.7332 888.2786 -39.19315 117.9535 882.6265 -38.41393 117.5169 888.1918 -38.14724 115.1068 887.1198 -35.03 117.5169 888.1918 -38.14724 117.9535 882.6265 -38.41393 118.2263 891.7055 -39.14393 118.7332 888.2786 -39.19315 117.5169 888.1918 -38.14724 117.047 891.4428 -38.09558 115.1068 887.1198 -35.03 117.047 891.4428 -38.09558 117.5169 888.1918 -38.14724 118.4155 876.9236 -38.79073 115.6424 880.3112 -35.71014 118.4155 876.9236 -38.79073 118.458 876.399 -38.82933 118.458 876.399 -38.82933 115.9681 873.9399 -36.39908 120.2227 888.3742 -39.79951 122.4838 877.0347 -40.09796 121.8234 888.4683 -39.90036 121.8234 888.4683 -39.90036 121.2369 892.3251 -39.87262 121.8234 888.4683 -39.90036 120.2227 888.3742 -39.79951 126.4223 892.2186 -39.412 121.2369 892.3251 -39.87262 119.6688 892.0253 -39.75721 -40.95819 756.9003 21.16058 -40.87191 756.9262 21.29193 -40.86539 756.9 21.30298 117.1597 894.9561 -39.10882 116.0405 894.5249 -38.02728 114.4759 890.0855 -34.55942 116.0405 894.5249 -38.02728 114.4647 900.7906 -38.99804 117.1597 894.9561 -39.10882 116.0405 894.5249 -38.02728 114.7937 897.3363 -37.92744 116.0405 894.5249 -38.02728 113.3762 900.2973 -37.78983 113.5036 896.4718 -35.86352 114.7937 897.3363 -37.92744 114.5365 893.679 -35.84715 114.5365 893.679 -35.84715 118.5446 895.4949 -39.75284 120.043 896.0821 -39.88854 120.043 896.0821 -39.88854 -42.78251 756.9 17.60024 -42.94599 757.1629 17.25689 -43.60866 757.0657 15.8037 118.8036 899.0205 -39.90953 120.043 896.0821 -39.88854 118.5446 895.4949 -39.75284 118.8036 899.0205 -39.90953 115.8607 901.424 -39.73756 117.4005 902.1232 -39.92086 113.3762 900.2973 -37.78983 112.5642 902.5535 -38.21789 114.4647 900.7906 -38.99804 113.3762 900.2973 -37.78983 112.6046 900.2908 -36.984 112.5642 902.5535 -38.21789 113.3762 900.2973 -37.78983 113.5036 896.4718 -35.86352 117.4005 902.1232 -39.92086 113.7839 905.6068 -39.82262 117.4005 902.1232 -39.92086 115.8607 901.424 -39.73756 116.1417 904.4844 -39.92755 116.1417 904.4844 -39.92755 112.7351 904.8718 -39.34645 112.0375 903.7823 -38.45359 107.9124 911.9072 -39.79281 106.4995 912.6536 -39.67431 104.8784 914.7015 -39.79062 104.4634 914.4802 -39.71433 104.8784 914.7015 -39.79062 106.4995 912.6536 -39.67431 105.1641 915.0373 -39.86838 104.127 915.6387 -39.82101 105.1641 915.0373 -39.86838 104.8784 914.7015 -39.79062 102.3078 917.065 -39.8171 104.127 915.6387 -39.82101 104.8784 914.7015 -39.79062 104.4634 914.4802 -39.71433 106.8844 912.1488 -39.63413 108.2143 909.1361 -39.0623 106.8844 912.1488 -39.63413 105.3821 912.0302 -39.44074 104.0454 914.2536 -39.68529 108.6624 909.6759 -39.3782 108.6624 909.6759 -39.3782 110.4807 908.5613 -39.61805 109.9506 907.6937 -39.11391 109.9506 907.6937 -39.11391 110.2177 907.2536 -39.04916 110.9919 904.2917 -38.04355 110.2177 907.2536 -39.04916 109.5879 905.4799 -38.07789 111.5216 904.8729 -38.6565 111.5216 904.8729 -38.6565 112.0375 903.7823 -38.45359 111.6362 900.7736 -36.6109 111.22 909.2433 -39.88789 108.3988 912.4432 -39.91779 105.3088 915.2073 -39.89245 105.3088 915.2073 -39.89245 105.4539 915.3775 -39.90648 105.4539 915.3775 -39.90648 114.6334 906.759 -39.93593 110.7272 911.238 -39.94303 112.8562 908.9759 -39.94253 108.3496 913.488 -39.93131 105.7449 915.7183 -39.90445 105.7449 915.7183 -39.90445 124.964 905.2604 -39.45148 108.3496 913.488 -39.93131 105.7449 915.7183 -39.90445 104.1876 917.0498 -39.87772 104.1876 917.0498 -39.87772 114.6334 906.759 -39.93593 112.8562 908.9759 -39.94253 110.7272 911.238 -39.94303 102.1898 918.042 -39.83635 102.0809 918.7595 -39.83027 102.3539 918.6521 -39.83146 105.3215 918.6506 -39.78065 102.3539 918.6521 -39.83146 102.0809 918.7595 -39.83027 103.304 917.8117 -39.85877 103.304 917.8117 -39.85877 102.3539 918.6521 -39.83146 105.3215 918.6506 -39.78065 101.0211 919.5717 -39.80072 101.7747 918.9539 -39.82463 123.4706 918.6409 -39.46994 101.7747 918.9539 -39.82463 101.4227 919.2172 -39.81539 101.4227 919.2172 -39.81539 101.0211 919.5717 -39.80072 100.5076 920.0678 -39.77748 101.0211 919.5717 -39.80072 102.1898 918.042 -39.83635 123.4211 919.5814 -39.4158 100.5076 920.0678 -39.77748 103.2362 916.7457 -39.83912 103.2362 916.7457 -39.83912 99.99839 920.5518 -39.75283 126.4223 892.2186 -39.412 124.964 905.2604 -39.45148 123.4706 918.6409 -39.46994 123.4706 918.6409 -39.46994 124.7983 920.6039 -39.10908 124.9302 918.7655 -39.21965 123.4706 918.6409 -39.46994 124.5188 920.5902 -39.19145 123.4211 919.5814 -39.4158 132.6344 867.4899 -36.89392 127.3099 918.9406 -37.54774 128.0462 918.9772 -36.27764 127.9836 919.7941 -36.23212 128.0462 918.9772 -36.27764 127.3099 918.9406 -37.54774 128.917 910.0979 -36.27208 127.9836 919.7941 -36.23212 128.917 910.0979 -36.27208 128.0462 918.9772 -36.27764 132.1367 867.4387 -37.58807 126.2435 918.8682 -38.56114 126.5789 920.6547 -38.08487 126.2435 918.8682 -38.56114 127.9252 920.6104 -36.17528 127.3605 920.6456 -37.20397 127.1848 920.6505 -37.44117 130.8236 867.3078 -38.67462 125.6137 920.6359 -38.75999 131.5267 867.3773 -38.1882 126.1147 920.6488 -38.45192 131.5267 867.3773 -38.1882 132.1367 867.4387 -37.58807 132.9647 859.0614 -37.49254 132.6344 867.4899 -36.89392 132.9238 868.4552 -36.13468 133.0059 867.5297 -36.12742 133.0059 867.5297 -36.12742 130.5536 893.2473 -36.23859 136.3429 868.772 -25.48204 133.0059 867.5297 -36.12742 132.9238 868.4552 -36.13468 133.4032 863.3398 -36.09855 133.4032 863.3398 -36.09855 130.1468 902.922 -34.83712 130.5536 893.2473 -36.23859 134.582 883.9559 -26.72184 133.9329 885.6323 -28.46388 133.2871 887.4611 -30.01383 132.6661 889.4246 -31.3619 131.5576 893.6783 -33.41914 130.6988 898.244 -34.58691 129.5595 910.1627 -34.51994 129.5904 909.7661 -34.53731 127.9252 920.6104 -36.17528 127.7267 926.5746 -35.14918 139.5671 868.9575 3.388088 143.1579 827.939 5.734078 143.3643 827.4586 -3e-6 143.3012 826.0701 0 143.3643 827.4586 -3e-6 143.1579 827.939 5.734078 139.6239 868.7347 2.039108 139.6233 868.737 -2.057874 143.1485 827.9603 -5.863436 143.0552 826.6248 -6.282001 143.1485 827.9603 -5.863436 143.3643 827.4586 -3e-6 143.3012 826.0701 0 138.5625 868.9774 14.51246 142.8816 828.5879 8.756622 143.0547 826.6259 6.283241 142.8816 828.5879 8.756622 142.4804 829.5326 11.83533 142.361 828.2103 12.24535 142.4804 829.5326 11.83533 141.9534 830.7908 14.92265 141.9534 830.7908 14.92265 136.3432 868.772 25.48079 141.297 832.3806 18.01872 141.3204 830.6381 17.70509 141.297 832.3806 18.01872 140.503 834.3419 21.1327 140.503 834.3419 21.1327 139.5903 836.6267 24.19011 140.0413 833.7045 22.60368 139.5903 836.6267 24.19011 138.5869 839.1967 27.11442 138.612 837.2388 26.96593 138.5869 839.1967 27.11442 132.9238 868.4552 36.13486 137.4944 842.0653 29.93016 137.4944 842.0653 29.93016 136.3567 845.4484 32.47555 137.0927 841.1191 30.84845 137.4944 842.0653 29.93016 136.3567 845.4484 32.47555 137.0927 841.1191 30.84845 135.3003 849.5056 34.42562 135.779 844.9494 33.68421 135.3003 849.5056 34.42562 134.8411 851.7266 35.12348 134.6131 849.3018 35.734 134.8411 851.7266 35.12348 134.4357 854.075 35.63267 134.4357 854.075 35.63267 134.0899 856.5495 35.94763 133.6641 854.0498 36.99082 134.0899 856.5495 35.94763 133.4032 863.3399 36.09856 133.8004 859.1506 36.06969 133.8004 859.1506 36.06969 132.6345 867.49 36.89372 133.8004 859.1506 36.06969 133.4032 863.3399 36.09856 132.9646 859.0614 37.49256 132.9646 859.0614 37.49256 133.0059 867.5297 36.12741 133.0059 867.5297 36.12741 127.3146 918.9409 37.53897 133.0059 867.5297 36.12741 132.9238 868.4552 36.13486 132.6345 867.49 36.89372 131.5577 893.6779 33.41898 128.9165 910.0979 36.27341 130.5527 893.2471 36.24093 130.5527 893.2471 36.24093 130.1468 902.922 34.83712 130.6988 898.2439 34.58691 135.2394 882.4541 24.8023 132.6669 889.4222 31.36039 133.2879 887.4588 30.01202 133.9335 885.6305 28.46219 134.5824 883.9549 26.72071 139.371 869.7337 6.015368 137.3591 877.1428 17.28558 138.9048 871.6922 9.639678 129.5947 867.9478 2.053213 139.5671 868.9575 3.388088 139.6239 868.7347 2.039108 129.5146 868.9653 6.033399 139.371 869.7337 6.015368 129.5947 867.9478 -2.0535 139.6233 868.737 -2.057874 139.5669 868.9584 -3.392788 139.5669 868.9584 -3.392788 142.453 829.5972 -12.01607 138.5621 868.9774 -14.51512 139.3699 869.7383 -6.027314 142.8634 828.6302 -8.920443 139.3699 869.7383 -6.027314 139.5584 836.708 -24.28902 137.3591 877.1428 -17.28544 140.4641 834.4384 -21.27277 141.2572 832.478 -18.18894 141.9182 830.8756 -15.10584 138.9051 871.6923 -9.639678 133.8004 859.1506 -36.06969 134.0903 856.5468 -35.94738 134.4364 854.0704 -35.63197 134.8421 851.721 -35.12205 135.3016 849.4999 -34.42351 136.3579 845.4445 -32.47325 137.4944 842.0653 -29.93017 138.5677 839.2455 -27.1672 135.2398 882.4542 -24.8023 133.8004 859.1506 -36.06969 132.9647 859.0614 -37.49254 133.8004 859.1506 -36.06969 134.0903 856.5468 -35.94738 133.6641 854.0498 -36.99079 134.4364 854.0704 -35.63197 134.8421 851.721 -35.12205 134.6132 849.3018 -35.73392 135.3016 849.4999 -34.42351 135.779 844.9495 -33.68419 136.3579 845.4445 -32.47325 137.4944 842.0653 -29.93017 137.0927 841.1191 -30.84844 137.4944 842.0653 -29.93017 138.5677 839.2455 -27.1672 137.0927 841.1191 -30.84844 138.6115 837.2401 -26.96671 139.5584 836.708 -24.28902 140.041 833.7053 -22.60442 140.4641 834.4384 -21.27277 141.2572 832.478 -18.18894 141.3205 830.6378 -17.70416 141.9182 830.8756 -15.10584 142.453 829.5972 -12.01607 142.3613 828.2095 -12.24408 142.8634 828.6302 -8.920443 128.9165 910.0979 36.27341 129.5904 909.7661 34.53731 129.5595 910.1627 34.51994 127.9836 919.794 36.23212 128.0463 918.9772 36.27764 128.0463 918.9772 36.27764 125.7858 916.3447 34.23794 129.5595 910.1627 34.51994 129.5904 909.7661 34.53731 127.9252 920.6104 36.17529 127.7266 926.5471 35.1567 129.0347 916.6004 34.23794 129.0347 916.6004 34.23794 130.1468 902.922 34.83712 126.8625 902.6635 34.83712 130.1468 902.922 34.83712 130.6988 898.2439 34.58691 126.8625 902.6635 34.83712 127.2389 897.8814 34.57314 131.5577 893.6779 33.41898 127.6039 893.2432 33.37425 132.6669 889.4222 31.36039 127.9435 888.9289 31.28688 133.2879 887.4588 30.01202 133.9335 885.6305 28.46219 128.2443 885.1062 28.39206 134.5824 883.9549 26.72071 135.2394 882.4541 24.8023 128.4948 881.9233 24.8023 135.2394 882.4541 24.8023 137.3591 877.1428 17.28558 128.4948 881.9233 24.8023 138.9048 871.6922 9.639678 129.3591 870.941 9.639678 138.9048 871.6922 9.639678 129.3591 870.941 9.639678 127.3605 920.6456 37.20409 128.0463 918.9772 36.27764 127.9836 919.794 36.23212 127.3146 918.9409 37.53897 127.9252 920.6104 36.17529 127.3605 920.6456 37.20409 127.9252 920.6104 36.17529 127.7266 926.5471 35.1567 128.7303 923.3433 33.26499 127.9364 932.3805 32.97206 127.1629 926.9227 36.12649 127.9364 932.3805 32.97206 128.8782 930.0548 30.85227 128.4863 937.8391 29.64143 127.3887 932.8817 33.91877 128.4863 937.8391 29.64143 128.7515 926.7415 32.23795 129.4002 936.1706 27.10119 129.2494 942.6716 25.25912 128.6865 943.1541 26.49909 129.2494 942.6716 25.25912 129.1083 933.2332 29.11908 127.9387 938.3433 30.67211 129.7447 938.8656 24.81575 129.6655 944.8053 22.69896 129.6655 944.8053 22.69896 130.1156 941.334 22.24767 130.0774 946.708 19.92429 129.4962 947.1883 21.52464 130.0774 946.708 19.92429 130.8404 945.372 16.50157 130.4675 948.3737 16.93998 130.4675 948.3737 16.93998 130.8156 949.7644 13.79026 130.2363 950.3331 15.88587 130.8156 949.7644 13.79026 131.4074 948.0896 10.25294 131.1057 950.8742 10.49296 131.1057 950.8742 10.49296 131.3222 951.6738 7.119486 130.8015 952.4959 9.745577 131.3222 951.6738 7.119486 131.7261 949.5084 3.510437 131.4582 952.1645 3.678002 131.4582 952.1645 3.678002 131.5077 952.3397 0.1952069 131.1072 953.5996 3.285838 131.5077 952.3397 0.1952069 131.7282 949.5183 -3.415012 131.468 952.1997 -3.291884 131.1071 953.5995 -3.286304 131.468 952.1997 -3.291884 131.3411 951.7426 -6.746467 131.3411 951.7426 -6.746467 131.6024 948.9771 -6.892071 131.1321 950.9731 -10.14081 130.8015 952.4959 -9.746229 131.1321 950.9731 -10.14081 131.4045 948.0778 -10.28975 130.8474 949.8888 -13.46649 130.8474 949.8888 -13.46649 131.1363 946.838 -13.55845 130.5023 948.5167 -16.65008 130.2365 950.3331 -15.88685 130.5023 948.5167 -16.65008 130.8147 945.2409 -16.7336 130.1124 946.8617 -19.67341 130.1124 946.8617 -19.67341 130.448 943.2946 -19.76618 129.6983 944.9621 -22.48851 129.4958 947.1877 -21.52445 129.6983 944.9621 -22.48851 130.0682 941.0363 -22.5865 129.278 942.8237 -25.09 129.278 942.8237 -25.09 129.3599 935.8105 -27.37289 128.8736 940.4887 -27.44325 128.6855 943.1534 -26.49745 128.8736 940.4887 -27.44325 129.696 938.5127 -25.1426 128.8637 929.7872 -30.97928 128.5027 937.9624 -29.5483 128.5027 937.9624 -29.5483 127.9419 932.4565 -32.93466 127.9387 938.3439 -30.67176 127.9419 932.4565 -32.93466 129.0347 916.6004 -34.23794 127.3891 932.8815 -33.91855 127.7267 926.5746 -35.14918 128.7312 923.2493 -33.28806 127.1628 926.9234 -36.12641 127.9252 920.6104 -36.17528 127.3605 920.6456 -37.20397 126.8625 902.6635 -34.83712 129.5595 910.1627 -34.51994 129.0347 916.6004 -34.23794 129.5904 909.7661 -34.53731 125.7858 916.3447 -34.23794 129.0347 916.6004 -34.23794 128.7312 923.2493 -33.28806 125.7858 916.3447 -34.23794 125.243 923.2413 -33.22167 128.8637 929.7872 -30.97928 124.7276 929.7897 -30.82175 129.3599 935.8105 -27.37289 124.2632 935.6913 -27.15947 129.696 938.5127 -25.1426 130.0682 941.0363 -22.5865 123.8676 940.718 -22.3899 130.448 943.2946 -19.76618 130.8147 945.2409 -16.7336 123.5545 944.6964 -16.68411 131.1363 946.838 -13.55845 123.3385 947.4402 -10.29736 131.4045 948.0778 -10.28975 131.6024 948.9771 -6.892071 123.2282 948.8416 -3.490015 131.7282 949.5183 -3.415012 123.228 948.8441 3.464874 131.7261 949.5084 3.510437 131.4074 948.0896 10.25294 123.3384 947.4419 10.29131 130.8404 945.372 16.50157 123.5555 944.6834 16.70721 130.1156 941.334 22.24767 123.8705 940.6809 22.4328 129.7447 938.8656 24.81575 129.4002 936.1706 27.10119 124.2675 935.6369 27.20138 129.1083 933.2332 29.11908 124.7319 929.7355 30.84803 128.8782 930.0548 30.85227 128.7515 926.7415 32.23795 125.2457 923.207 33.23033 128.7303 923.3433 33.26499 129.0347 916.6004 34.23794 125.7858 916.3447 34.23794 129.5146 868.9654 -6.033578 138.9051 871.6923 -9.639678 129.3591 870.941 -9.639678 138.9051 871.6923 -9.639678 137.3591 877.1428 -17.28544 129.3591 870.941 -9.639678 135.2398 882.4542 -24.8023 128.4948 881.9233 -24.8023 135.2398 882.4542 -24.8023 134.582 883.9559 -26.72184 128.4948 881.9233 -24.8023 128.2443 885.1062 -28.39206 133.9329 885.6323 -28.46388 133.2871 887.4611 -30.01383 127.9435 888.9289 -31.28688 132.6661 889.4246 -31.3619 127.6039 893.2432 -33.37425 131.5576 893.6783 -33.41914 127.2389 897.8814 -34.57314 130.6988 898.244 -34.58691 130.1468 902.922 -34.83712 130.1468 902.922 -34.83712 126.8625 902.6635 -34.83712 142.848 824.7522 0 142.5868 825.3287 -6.487818 142.848 824.7522 0 142.5863 825.3298 6.488985 141.852 826.9725 12.631 140.756 829.4799 18.23106 139.417 832.6331 23.22996 137.9297 836.2521 27.65963 136.3575 840.2105 31.58454 134.9469 844.231 34.54037 136.3575 840.2105 31.58454 136.6261 836.195 28.99015 135.3474 839.4114 32.08058 133.9639 843.2587 34.92061 135.3474 839.4114 32.08058 142.0496 823.6112 0 141.9178 823.898 -4.608072 142.0496 823.6112 0 141.5431 824.7125 9.011344 141.842 824.0759 5.837203 140.5285 826.9774 15.57968 141.113 825.6724 12.26144 139.7832 828.6753 18.96641 137.8111 833.3204 25.75347 138.8802 830.7847 22.3666 117.0195 816.6045 31.16236 136.6261 836.195 28.99015 135.3474 839.4114 32.08058 123.7471 839.2442 38.72842 135.3474 839.4114 32.08058 133.9639 843.2587 34.92061 128.4038 835.3477 34.481 128.4038 835.3477 34.481 135.4948 816.5819 10e-7 142.0496 823.6112 0 141.842 824.0759 5.837203 134.9391 816.5828 -5.532523 142.0496 823.6112 0 135.4948 816.5819 10e-7 141.9178 823.898 -4.608072 134.9398 816.5828 5.529152 141.5431 824.7125 9.011344 133.2979 816.5854 10.98375 141.113 825.6724 12.26144 140.5285 826.9774 15.57968 130.6096 816.5892 16.3187 139.7832 828.6753 18.96641 126.9437 816.5939 21.48931 138.8802 830.7847 22.3666 137.8111 833.3204 25.75347 122.3805 816.5991 26.45132 133.6605 848.7817 36.68626 132.5699 853.7291 38.01499 131.7098 858.9349 38.56552 131.5267 867.3773 38.18819 131.7098 858.9349 38.56552 132.1369 867.4387 37.58791 130.715 855.8483 38.98445 130.176 858.7857 39.16754 130.05 867.2322 39.03246 130.176 858.7857 39.16754 130.8235 867.3077 38.67472 133.4366 844.9102 35.84298 131.9201 850.3676 37.96505 132.5781 847.8427 37.14339 131.6607 851.4362 38.24123 131.2952 853.0383 38.58163 126.6314 856.4227 39.94916 130.715 855.8483 38.98445 130.176 858.7857 39.16754 129.7046 862.9567 39.2102 122.9071 859.4451 40.58218 130.176 858.7857 39.16754 129.7046 862.9567 39.2102 122.9814 854.0507 40.77393 126.6314 856.4227 39.94916 133.4366 844.9102 35.84298 126.3457 848.1257 39.59766 132.5781 847.8427 37.14339 120.976 844.9239 40.9897 131.9201 850.3676 37.96505 131.6607 851.4362 38.24123 131.2952 853.0383 38.58163 122.9814 854.0507 40.77393 122.9972 853.8332 40.77884 123.0112 853.615 40.78322 129.2301 867.1531 39.25193 129.2301 867.1531 39.25193 127.8451 879.4953 39.34627 129.2301 867.1531 39.25193 130.05 867.2322 39.03246 122.8234 864.872 40.40821 129.2301 867.1531 39.25193 127.8451 879.4953 39.34627 122.8234 864.872 40.40821 124.9208 918.7646 39.2209 130.8235 867.3077 38.67472 123.4904 918.6412 39.46746 124.9644 905.2396 39.45153 126.4229 892.191 39.41211 131.5267 867.3773 38.18819 126.2437 918.8684 38.56097 132.1369 867.4387 37.58791 123.4199 919.581 39.41373 123.4904 918.6412 39.46746 124.9208 918.7646 39.2209 114.6004 906.7994 39.93623 124.9644 905.2396 39.45153 123.4904 918.6412 39.46746 102.0805 918.7595 39.83206 123.4904 918.6412 39.46746 123.4199 919.581 39.41373 102.3536 918.6522 39.8332 105.3215 918.6506 39.78185 103.2511 917.8596 39.85745 105.3215 918.6506 39.78185 104.1147 917.1116 39.87629 104.9456 916.4006 39.89176 105.745 915.7183 39.90445 108.3745 913.4779 39.93101 112.7982 909.0377 39.94281 110.7237 911.25 39.94271 124.7988 920.6039 39.10903 126.2437 918.8684 38.56097 123.3564 920.5201 39.35204 124.5189 920.5902 39.19149 126.579 920.6547 38.08509 125.6138 920.6359 38.76018 126.1148 920.6488 38.45215 127.1846 920.6505 37.44161 121.8234 888.4683 39.90036 126.4229 892.191 39.41211 122.5049 876.5245 40.10868 122.4837 877.0357 40.09794 121.2369 892.3253 39.87262 -44.39982 756.9 13.93945 120.0429 896.0822 39.88854 118.8021 899.0239 39.90954 117.4006 902.1232 39.92086 116.1325 904.4937 39.92776 100.5079 920.0677 39.77952 123.3564 920.5201 39.35204 101.7749 918.9538 39.82648 101.423 919.2171 39.81728 101.0208 919.5722 39.80266 124.3138 927.4183 38.05457 123.3564 920.5201 39.35204 124.5189 920.5902 39.19149 99.99843 920.552 39.75493 123.1448 927.5365 38.18885 99.99843 920.552 39.75493 123.3564 920.5201 39.35204 123.1448 927.5365 38.18885 125.413 927.312 37.63742 124.7988 920.6039 39.10903 125.6138 920.6359 38.76018 126.3807 927.1437 36.98257 126.1148 920.6488 38.45215 126.579 920.6547 38.08509 127.1846 920.6505 37.44161 102.0961 918.1702 39.83518 102.3536 918.6522 39.8332 102.0805 918.7595 39.83206 102.3536 918.6522 39.8332 103.2511 917.8596 39.85745 101.7749 918.9538 39.82648 101.423 919.2171 39.81728 101.0208 919.5722 39.80266 102.0085 917.5321 39.82312 101.0208 919.5722 39.80266 100.5079 920.0677 39.77952 102.0961 918.1702 39.83518 99.99843 920.552 39.75493 88 920.566 39.95563 88 917.4 40.05699 99.99843 920.552 39.75493 88 920.566 39.95563 102.0085 917.5321 39.82312 103.1013 916.9078 39.83985 104.1147 917.1116 39.87629 104.032 915.7561 39.82368 104.9456 916.4006 39.89176 105.454 915.3775 39.90653 105.745 915.7183 39.90445 105.3088 915.2073 39.89252 105.164 915.0373 39.86842 104.8785 914.7015 39.79062 107.8173 913.044 39.91899 105.745 915.7183 39.90445 105.454 915.3775 39.90653 108.3745 913.4779 39.93101 107.3747 912.5442 39.81581 105.3088 915.2073 39.89252 105.164 915.0373 39.86842 106.4988 912.6548 39.67447 104.8785 914.7015 39.79062 106.8839 912.1497 39.63427 104.4605 914.4786 39.71438 104.8785 914.7015 39.79062 104.032 915.7561 39.82368 104.4605 914.4786 39.71438 105.3521 912.084 39.44811 104.8785 914.7015 39.79062 106.4988 912.6548 39.67447 104.0454 914.2536 39.68529 103.1013 916.9078 39.83985 121.4128 876.482 40.13354 122.8234 864.872 40.40821 122.5049 876.5245 40.10868 121.9715 864.8721 40.47755 122.9071 859.4451 40.58218 122.8234 864.872 40.40821 121.9715 864.8721 40.47755 120.2235 888.3743 39.79911 122.4837 877.0357 40.09794 121.8234 888.4683 39.90036 120.2235 888.3743 39.79911 121.8234 888.4683 39.90036 121.2369 892.3253 39.87262 -43.60866 757.0657 15.8037 -42.94599 757.1629 17.25689 -44.39982 756.9 13.93945 119.6687 892.0253 39.75721 118.5446 895.4949 39.75284 120.0429 896.0822 39.88854 115.8605 901.4239 39.73825 120.0429 896.0822 39.88854 118.8021 899.0239 39.90954 118.5446 895.4949 39.75284 117.4006 902.1232 39.92086 115.8605 901.4239 39.73825 117.4006 902.1232 39.92086 116.1325 904.4937 39.92776 114.2468 904.8197 39.80636 114.6004 906.7994 39.93623 112.2884 907.8459 39.86549 112.7982 909.0377 39.94281 110.1178 910.5621 39.90443 110.7237 911.25 39.94271 122.9814 854.0507 40.77393 121.8066 854.0562 40.87001 122.9972 853.8332 40.77884 122.9814 854.0507 40.77393 121.8066 854.0562 40.87001 123.0112 853.615 40.78322 122.9749 851.9451 40.81702 122.2956 850.9064 40.94459 122.9749 851.9451 40.81702 123.0112 853.615 40.78322 122.5459 853.627 40.85791 122.5459 853.627 40.85791 121.7646 846.8342 40.92959 122.3363 848.5637 40.88488 122.7524 850.259 40.84643 120.5506 845.8501 41.1597 120.976 844.9239 40.9897 121.7646 846.8342 40.92959 120.1625 843.2394 41.05216 119.317 843.4682 41.29409 120.1625 843.2394 41.05216 121.5706 848.3198 41.04421 122.3363 848.5637 40.88488 122.7524 850.259 40.84643 115.017 835.4008 41.54104 113.7935 833.9299 41.68902 121.7049 831.679 36.78407 116.5805 837.4561 41.37209 117.9428 839.4351 41.23969 119.1273 841.3557 41.13624 112.8496 834.6514 42.10485 113.7935 833.9299 41.68902 115.017 835.4008 41.54104 115.2609 828.4119 38.98633 112.5386 832.5211 41.85418 112.5386 832.5211 41.85418 114.6703 836.7551 41.8503 116.5805 837.4561 41.37209 116.3521 838.9153 41.63529 117.9428 839.4351 41.23969 117.9103 841.1591 41.45104 119.1273 841.3557 41.13624 110.9677 816.6097 35.58115 121.7049 831.679 36.78407 115.2609 828.4119 38.98633 108.1023 828.2022 42.55206 109.0601 825.5267 41.08283 104.3425 816.6144 39.66959 109.0601 825.5267 41.08283 109.6882 829.6423 42.28274 111.1799 831.0939 42.04812 104.5137 825.3532 43.25754 103.0894 823.0034 43.06869 103.0894 823.0034 43.06869 106.3885 826.7714 42.87145 98.81452 821.7077 44.59096 97.35247 820.8483 44.94198 97.26519 816.6182 43.39142 97.35247 820.8483 44.94198 100.3009 822.5781 44.2252 102.485 823.9533 43.70849 99.5885 824.0161 44.73398 97.35247 820.8483 44.94198 98.81452 821.7077 44.59096 96.63951 822.2802 45.4537 84.86185 815.6048 48.09411 97.35247 820.8483 44.94198 96.63951 822.2802 45.4537 89.85622 816.6152 46.71382 89.85622 816.6152 46.71382 100.3009 822.5781 44.2252 99.5885 824.0161 44.73398 100.3009 822.5781 44.2252 102.485 823.9533 43.70849 102.0457 825.4873 44.14255 104.5137 825.3532 43.25754 104.4147 827.1004 43.61626 106.3885 826.7714 42.87145 106.6865 828.8381 43.15335 108.1023 828.2022 42.55206 109.6882 829.6423 42.28274 108.8465 830.6784 42.75177 111.1799 831.0939 42.04812 110.9056 832.6222 42.40356 120.642 854.0506 40.68863 120.6603 853.855 40.70168 120.676 853.6598 40.71396 115.312 848.8668 39.26469 120.676 853.6598 40.71396 120.6603 853.855 40.70168 121.1348 853.6541 40.81579 120.085 851.4066 40.72256 121.1348 853.6541 40.81579 120.676 853.6598 40.71396 115.312 848.8668 39.26469 120.085 851.4066 40.72256 120.676 853.6598 40.71396 120.642 854.0506 40.68863 121.6031 853.6467 40.87428 120.093 859.3574 40.29296 120.642 854.0506 40.68863 115.7233 855.0706 38.52759 120.093 859.3574 40.29296 122.075 853.6376 40.88836 121.8396 853.6424 40.88692 120.293 864.858 40.18021 119.517 864.8443 39.8225 121.1195 864.8674 40.40108 121.7408 851.0461 40.98669 122.075 853.6376 40.88836 121.1843 851.1834 40.96302 121.8396 853.6424 40.88692 121.6031 853.6467 40.87428 120.6335 851.3166 40.87392 99.35521 829.0547 42.67078 98.21279 829.4124 41.41084 96.2909 828.3418 41.63232 94.55615 829.579 37.15581 96.2909 828.3418 41.63232 98.21279 829.4124 41.41084 96.98281 827.7604 43.04682 94.05181 826.0307 43.7844 96.98281 827.7604 43.04682 96.2909 828.3418 41.63232 94.83088 827.4833 42.00795 68.69729 812.0592 47.6857 94.83088 827.4833 42.00795 96.2909 828.3418 41.63232 91.04274 827.1311 38.25501 91.04274 827.1311 38.25501 100.0135 830.512 41.21683 100.0135 830.512 41.21683 101.6677 830.4695 42.34325 101.6144 831.5631 41.06837 101.6144 831.5631 41.06837 103.9106 831.9912 42.06219 101.6966 831.6187 41.06171 100.0268 833.3928 37.25405 101.6966 831.6187 41.06171 104.0257 833.2709 40.89819 104.0257 833.2709 40.89819 106.0683 833.6017 41.82527 106.1351 834.9028 40.78632 106.1351 834.9028 40.78632 108.1514 835.3029 41.62664 107.816 836.3023 40.72071 107.816 836.3023 40.72071 110.1448 837.0797 41.46234 108.0766 836.5268 40.7131 108.2744 839.8704 38.4513 108.0766 836.5268 40.7131 100.847 836.3925 35.19604 109.8533 838.1243 40.67061 109.8533 838.1243 40.67061 112.0389 838.9229 41.3274 111.4277 839.6414 40.64946 111.4277 839.6414 40.64946 113.8182 840.817 41.21794 112.846 841.1002 40.6436 112.846 841.1002 40.6436 114.1254 842.502 40.64823 114.1254 842.502 40.64823 115.5004 842.786 41.12781 115.2119 843.7706 40.65759 115.2119 843.7706 40.65759 117.0563 844.8134 41.05279 115.2864 843.8604 40.65848 114.5769 848.2745 39.03366 115.2864 843.8604 40.65848 109.3784 844.4636 37.18497 116.3603 845.2092 40.67144 116.3603 845.2092 40.67144 118.4639 846.9035 40.98808 117.3447 846.5452 40.6861 117.3447 846.5452 40.6861 118.2025 847.8196 40.69953 118.2025 847.8196 40.69953 119.6829 849.0655 40.92969 118.9446 849.0504 40.71001 118.9446 849.0504 40.71001 119.573 850.242 40.71794 119.573 850.242 40.71794 120.3069 848.8236 41.06026 119.1514 846.5637 41.16828 117.7982 844.3827 41.28962 116.288 842.27 41.42749 114.6426 840.2206 41.58603 112.8914 838.2517 41.76824 111.0176 836.3389 41.98121 109.0372 834.4989 42.22831 106.9596 832.7414 42.51381 104.8005 831.0829 42.84066 102.5494 829.5218 43.21485 100.2224 828.0773 43.63751 97.82933 826.7639 44.10958 94.8899 825.027 44.84055 97.82933 826.7639 44.10958 101.1519 826.8448 44.146 98.73204 825.4667 44.69408 95.78619 823.728 45.41874 98.73204 825.4667 44.69408 120.9401 848.5735 41.09867 119.8527 846.2096 41.22596 118.5598 843.9295 41.37091 117.1019 841.7206 41.53665 115.5006 839.5767 41.72735 113.7849 837.5157 41.94579 111.9386 835.5121 42.19999 109.9777 833.5834 42.49362 107.9112 831.7402 42.83114 105.754 829.9998 43.21549 103.4958 828.3611 43.65342 93.36917 826.6239 42.37608 93.36917 826.6239 42.37608 83.27864 820.6784 44.74552 94.05181 826.0307 43.7844 93.36917 826.6239 42.37608 83.27864 820.6784 44.74552 84.03742 816.9805 48.01265 95.78619 823.728 45.41874 83.19112 818.2172 47.43517 94.8899 825.027 44.84055 82.41016 819.1872 46.42119 38.85072 794.8016 51.40095 23.89223 786.7396 51.57627 31.15691 790.5802 51.67125 35.85374 792.3453 52.64204 31.15691 790.5802 51.67125 23.89223 786.7396 51.57627 19.00859 784.2606 51.27798 24.15266 786.1592 52.57764 19.00859 784.2606 51.27798 24.15266 786.1592 52.57764 23.89223 786.7396 51.57627 38.85072 794.8016 51.40095 47.52556 798.851 51.89384 41.0798 796.0496 51.25895 41.0798 796.0496 51.25895 55.55648 804.3496 49.75762 47.00964 799.4151 50.75516 47.00964 799.4151 50.75516 64.3999 809.5261 48.4304 39.40974 799.3629 42.5282 14.08579 781.8502 50.77355 55.55648 804.3496 49.75762 59.1632 805.5448 50.53491 64.3999 809.5261 48.4304 70.78514 812.345 48.68265 68.69729 812.0592 47.6857 73.62217 814.9689 46.76115 73.62217 814.9689 46.76115 66.87905 815.813 36.579 71.50614 811.4096 49.65756 59.81768 804.6455 51.47333 48.1024 797.9901 52.79718 36.33682 791.5256 53.50995 24.23593 785.9807 52.80495 24.23593 785.9807 52.80495 24.5204 785.3845 53.40709 16.84811 782.3249 52.22959 24.5204 785.3845 53.40709 72.29828 810.2336 50.23626 60.54825 803.5299 52.05586 48.75956 796.9358 53.38592 36.90369 790.5349 54.10634 24.73831 784.9375 53.73996 24.73831 784.9375 53.73996 24.97445 784.4603 54.00923 17.25212 781.3226 53.1433 24.97445 784.4603 54.00923 73.08731 808.9273 50.3645 61.29306 802.2923 52.23317 49.44739 795.7678 53.61556 37.51676 789.4389 54.39167 25.35625 783.7005 54.29008 25.35625 783.7005 54.29008 25.48905 783.439 54.34984 17.77774 780.1406 53.71718 25.48905 783.439 54.34984 81.32271 811.8273 48.56457 89.23085 816.2634 46.85568 73.6519 807.5382 50.05944 59.03035 799.4121 52.40525 66.24102 803.393 51.33299 48.38925 793.655 53.63646 51.99261 795.5892 53.27133 32.18207 785.348 54.49921 45.16223 791.9449 53.91514 38.5587 788.5338 54.32919 26.0331 782.3823 54.41256 26.0331 782.3823 54.41256 26.7635 770.7086 53.2744 32.18207 785.348 54.49921 26.0331 782.3823 54.41256 19.18492 779.2378 53.98412 20.73796 770.6902 53.51503 26.0331 782.3823 54.41256 19.18492 779.2378 53.98412 20.73796 770.6902 53.51503 77.32096 793.6918 44.12339 89.23085 816.2634 46.85568 70.24884 793.6939 47.26134 81.32271 811.8273 48.56457 73.6519 807.5382 50.05944 62.99538 793.6934 49.90782 66.24102 803.393 51.33299 59.03035 799.4121 52.40525 55.6737 793.6894 52.04004 51.99261 795.5892 53.27133 48.38925 793.655 53.63646 39.17115 770.7317 51.32629 45.16223 791.9449 53.91514 32.92752 770.7223 52.54581 38.5587 788.5338 54.32919 9.369278 779.621 50.09883 9.449625 778.8548 51.20565 12.86346 781.2648 50.61743 14.08579 781.8502 50.77355 4.793039 777.5397 49.24356 2.096187 775.5989 49.70719 9.758913 777.887 52.09827 -3.933196 773.7857 47.03597 -5.139601 772.5883 47.70478 2.312551 774.6586 50.57894 0.287192 775.5648 48.20545 -11.89241 770.6198 44.24214 -12.17881 769.8516 45.16756 -5.016316 771.6679 48.55542 -8.134219 772.0848 45.66157 -16.56712 768.8731 42.1929 -18.92153 767.4064 42.07899 -12.15068 768.9427 45.99603 -15.39932 769.3005 42.73904 -23.73027 766.3764 38.27744 -25.25899 765.2653 38.42862 -18.99211 766.5005 42.8818 -19.28725 767.9067 40.80994 -27.82905 765.0387 35.52417 -31.08151 763.4387 34.21219 -25.43312 764.3538 39.19918 -34.65762 762.9643 29.73189 -36.27386 761.9216 29.46411 -31.36484 762.5129 34.94046 -31.36289 763.9411 32.75059 -39.59837 761.5718 24.11051 -40.71865 760.703 24.23377 -36.66963 760.9743 30.13438 -37.3636 762.1868 26.87069 -41.67632 761.0189 21.1053 -44.30499 759.7718 18.57973 -41.2265 759.7295 24.82384 -45.34208 760.0789 13.97997 -46.94388 759.1163 12.59107 -44.91918 758.77 19.06197 -43.69307 760.4937 17.60755 -46.45667 759.7993 10.83478 -48.55935 758.7263 6.364321 -47.64735 758.089 12.93613 -48.07806 759.4079 -6e-6 -49.10628 758.5971 -10e-7 -49.32313 757.6811 6.544657 -47.75965 759.482 4.866301 -47.91673 759.4463 -3.438587 -49.10628 758.5971 -10e-7 -48.07806 759.4079 -6e-6 -49.89212 757.5452 -10e-7 -48.47212 758.7462 -6.880445 -49.89212 757.5452 -10e-7 -43.7532 761.9663 -10e-7 -48.07806 759.4079 -6e-6 -47.75965 759.482 4.866301 -43.09181 762.087 -7.459362 -47.91673 759.4463 -3.438587 -43.11808 762.0819 7.310119 -46.45667 759.7993 10.83478 -45.34208 760.0789 13.97997 -41.19666 762.4481 14.52244 -43.69307 760.4937 17.60755 -41.67632 761.0189 21.1053 -38.03592 763.1048 21.35387 -39.59837 761.5718 24.11051 -37.3636 762.1868 26.87069 -33.79207 764.0991 27.51586 -34.65762 762.9643 29.73189 -31.36289 763.9411 32.75059 -28.61921 765.4989 32.85301 -27.82905 765.0387 35.52417 -22.67718 767.3845 37.22455 -23.73027 766.3764 38.27744 -17.06942 769.4624 40.1074 -19.28725 767.9067 40.80994 -16.56712 768.8731 42.1929 -9.856452 772.6096 42.35595 -15.39932 769.3005 42.73904 -16.31 769.7685 40.41832 -11.89241 770.6198 44.24214 1.646165 778.0004 44.71033 -8.134219 772.0848 45.66157 12.09747 782.76 46.83872 -3.933196 773.7857 47.03597 0.287192 775.5648 48.20545 4.793039 777.5397 49.24356 9.369278 779.621 50.09883 12.86346 781.2648 50.61743 22.10997 788.0576 47.13203 13.16653 783.2395 47.05585 17.69994 785.472 47.54053 10.19475 776.7512 52.68895 2.660353 773.5595 51.1803 -4.755814 770.5952 49.16175 -11.97784 767.8861 46.60159 -18.90794 765.449 43.47949 -25.43913 763.2966 39.77998 -31.46263 761.4393 35.4932 -36.85876 759.8757 30.64443 -41.50357 758.6 25.27258 -45.27685 757.6074 19.42767 -48.07094 756.8965 13.19679 -49.79044 756.4678 6.680483 -50.37518 756.3242 -10e-7 -49.23342 757.7017 -7.071477 -50.37518 756.3242 -10e-7 12.66647 776.3655 53.23078 6.539922 773.7766 52.19754 0.802283 771.4539 50.92126 -4.613345 769.3491 49.41516 -14.50433 765.7459 45.78041 -9.681407 767.4671 47.708 -19.07221 764.1859 43.63946 -27.02206 761.6102 39.00819 -21.93635 763.2337 42.11726 -23.25105 762.8033 41.36663 -33.48423 759.6559 34.09585 -30.43435 760.5633 36.57149 -38.79347 758.1422 28.88532 -43.11706 756.9575 23.3362 -46.40786 756.0834 17.61451 -48.70777 755.4863 11.80585 -50.07782 755.1347 5.889109 -50.52575 755.0203 -10e-7 -49.699 756.4893 -7.214983 -50.52575 755.0203 -10e-7 10.82011 763.2304 52.6397 12.66647 776.3655 53.23078 17.34372 763.1956 52.93972 4.163714 763.2432 51.72873 6.539922 773.7766 52.19754 0.802283 771.4539 50.92126 -2.534927 763.2515 50.20745 -4.613345 769.3491 49.41516 -9.181291 763.2556 48.08655 -9.681407 767.4671 47.708 -14.50433 765.7459 45.78041 -15.67527 763.2565 45.38491 -19.07221 764.1859 43.63946 -21.93635 763.2337 42.11726 -23.60488 744.0228 42.52841 -23.25105 762.8033 41.36663 -29.30298 744.0132 38.72866 -27.02206 761.6102 39.00819 -30.43435 760.5633 36.57149 -34.50137 744.0023 34.35669 -33.48423 759.6559 34.09585 -39.10133 743.9904 29.47379 -38.79347 758.1422 28.88532 -43.01125 743.9783 24.14875 -43.11706 756.9575 23.3362 -46.15095 743.9664 18.45722 -46.40786 756.0834 17.61451 -48.45123 743.9551 12.47914 -48.70777 755.4863 11.80585 -49.8576 743.945 6.298303 -50.07782 755.1347 5.889109 -50.52575 755.0203 -10e-7 -50.33228 743.9365 10e-7 -50.11894 755.1223 -5.625079 -50.33228 743.9365 10e-7 -50.52575 755.0203 -10e-7 -50.11894 755.1223 -5.625079 -49.81027 724.9 4.351593 -50 724.9 -2e-6 -49.85733 743.9365 -6.31117 -50 724.9 -2e-6 -49.24263 718.9 8.66892 -49.81027 724.9 4.351593 -50 724.9 -2e-6 -49.81027 724.9 -4.351606 -50 718.9 0 -49.81027 724.9 -4.351606 -49.24202 724.9 8.673124 -46.98724 724.9 17.09384 -48.2987 724.9 12.93193 -45.31734 724.9 21.12673 -43.30224 724.9 24.99831 -38.30188 724.9 32.13978 -40.95749 724.9 28.67898 -35.35535 724.9 35.35532 -28.67901 724.9 40.95746 -32.13982 724.9 38.30185 -24.99835 724.9 43.30222 -17.51157 744.0307 45.70288 -21.12676 724.9 45.31732 -11.13082 744.0361 48.21011 -12.93196 724.9 48.2987 -4.570854 744.0388 50.01796 -17.09387 724.9 46.98723 -8.673139 724.9 49.24202 2.061697 744.0381 51.10652 0 724.9 50 8.657423 744.0159 51.46741 -4.351603 724.9 49.81027 4.351607 724.9 49.81027 8.657423 744.0159 51.46741 0 724.9 50 10.35503 747.7643 51.75515 10.35503 747.7643 51.75515 0.08961498 718.9 49.9991 0 724.9 50 -4.351603 724.9 49.81027 4.351607 724.9 49.81027 -8.579459 718.9 49.25764 -8.673139 724.9 49.24202 -12.93196 724.9 48.2987 -17.00655 718.9 47.0181 -17.09387 724.9 46.98723 -21.12676 724.9 45.31732 -24.93545 718.9 43.33771 -24.99835 724.9 43.30222 -28.62909 718.9 40.99165 -28.67901 724.9 40.95746 -32.11779 718.9 38.31937 -32.13982 724.9 38.30185 -35.34941 718.9 35.35975 -35.35535 724.9 35.35532 -38.30188 724.9 32.13978 -38.31934 718.9 32.11657 -40.95749 724.9 28.67898 -43.30387 718.9 24.99637 -43.30224 724.9 24.99831 -45.31734 724.9 21.12673 -46.98614 718.9 17.0963 -46.98724 724.9 17.09384 -48.2987 724.9 12.93193 -49.24202 724.9 8.673124 15.81375 747.7763 51.51704 17.34372 763.1956 52.93972 -49.24202 724.9 -8.673145 -49.24202 724.9 -8.673145 -48.45064 743.9365 -12.52634 -48.2987 724.9 -12.93196 -49.23646 718.9 -8.704545 -48.2987 724.9 -12.93196 -46.1503 743.9365 -18.55373 -46.98723 724.9 -17.09387 -46.98723 724.9 -17.09387 -45.31732 724.9 -21.12677 -46.97477 718.9 -17.12734 -45.31732 724.9 -21.12677 -43.01107 743.9365 -24.30312 -43.30222 724.9 -24.99835 -43.30222 724.9 -24.99835 -39.10234 743.9365 -29.68809 -40.95746 724.9 -28.67902 -43.28997 718.9 -25.01854 -40.95746 724.9 -28.67902 -34.50446 743.9365 -34.62654 -38.30185 724.9 -32.13982 -38.30185 724.9 -32.13982 -35.35532 724.9 -35.35536 -38.29654 718.9 -32.14511 -35.35532 724.9 -35.35536 -29.30913 743.9365 -39.0432 -32.13978 724.9 -38.30188 -32.14511 718.9 -38.29654 -32.13978 724.9 -38.30188 -23.61512 743.9365 -42.87034 -28.67897 724.9 -40.9575 -28.67897 724.9 -40.9575 -24.99831 724.9 -43.30224 -25.01854 718.9 -43.28997 -24.99831 724.9 -43.30224 -17.52689 743.9365 -46.04841 -21.12673 724.9 -45.31734 -21.12673 724.9 -45.31734 -11.15216 743.9365 -48.52899 -17.09384 724.9 -46.98724 -17.12734 718.9 -46.97477 -17.09384 724.9 -46.98724 -4.599072 743.9365 -50.27346 -12.93193 724.9 -48.29871 -12.93193 724.9 -48.29871 -8.673118 724.9 -49.24202 -8.704545 718.9 -49.23646 -8.673118 724.9 -49.24202 2.025853 743.9365 -51.25542 -4.351621 724.9 -49.81027 -4.351621 724.9 -49.81027 8.621268 743.9365 -51.46132 -8.6e-5 724.9 -50 -8.6e-5 724.9 -50 16.18021 747.777 -51.48316 -8.6e-5 724.9 -50 8.621268 743.9365 -51.46132 0 718.9 -50 4.378001 724.9 -49.80796 0 718.9 -50 -8.6e-5 724.9 -50 4.378001 724.9 -49.80796 10.36351 747.7835 -51.75663 10.36351 747.7835 -51.75663 4.125842 763.018 -52.12049 17.26307 763.018 -52.92609 10.75716 763.018 -52.86061 -2.548381 763.018 -50.71304 -9.171617 763.018 -48.65679 -15.6445 763.018 -45.97836 -21.86335 763.0171 -42.71271 -25.85827 761.7617 -40.28337 -32.70063 759.7453 -35.17599 -29.44219 760.6896 -37.77818 -38.25954 758.1998 -29.78472 -42.98539 756.9506 -23.73622 -46.49929 756.0407 -17.54045 -48.82169 755.4506 -11.48663 27.1714 770.7097 -53.24008 17.26307 763.018 -52.92609 20.74262 770.7009 -53.51587 20.74262 770.7009 -53.51587 13.48523 776.3973 -53.69128 25.90084 782.0905 -54.39017 19.58057 779.1296 -54.20767 7.660595 773.8989 -52.87249 -3.156252 769.5614 -50.43632 2.137165 771.6353 -51.78485 -8.204087 767.6766 -48.84355 -17.58868 764.405 -44.95866 -13.00404 765.9657 -47.01968 -22.06598 764.1458 -42.35543 -21.86335 763.0171 -42.71271 -25.85827 761.7617 -40.28337 -14.77454 766.5861 -46.03746 -17.58868 764.405 -44.95866 -28.83006 762.0545 -37.97055 -29.44219 760.6896 -37.77818 -32.70063 759.7453 -35.17599 -34.92123 760.303 -32.90315 -38.25954 758.1998 -29.78472 -40.19388 758.8798 -27.20555 -42.98539 756.9506 -23.73622 -44.50394 757.7738 -20.95789 -46.49929 756.0407 -17.54045 -47.71144 756.9758 -14.24977 -48.82169 755.4506 -11.48663 32.98033 785.725 -54.48884 25.90084 782.0905 -54.39017 25.30277 783.5043 -54.3176 25.90084 782.0905 -54.39017 19.58057 779.1296 -54.20767 25.93846 782.2175 -54.39987 25.93846 782.2175 -54.39987 17.13969 779.5921 -53.92319 13.48523 776.3973 -53.69128 8.966308 775.9068 -52.92917 7.660595 773.8989 -52.87249 2.137165 771.6353 -51.78485 0.859374 772.4877 -51.30401 -3.156252 769.5614 -50.43632 -7.091088 769.3717 -49.01591 -8.204087 767.6766 -48.84355 -13.00404 765.9657 -47.01968 -47 718.9 0 -50 718.9 0 -49.23646 718.9 -8.704545 -46.27937 718.9 8.198644 -49.24263 718.9 8.66892 -46.81725 718.9 4.129784 -44.16648 718.9 -16.07183 -46.97477 718.9 -17.12734 -46.28787 718.9 -8.149951 -40.70402 718.9 -23.49939 -43.28997 718.9 -25.01854 -36.0195 718.9 -30.1906 -38.29654 718.9 -32.14511 -33.23096 718.9 -33.23587 -32.14511 718.9 -38.29654 -26.91589 718.9 -38.52895 -25.01854 718.9 -43.28997 -30.19496 718.9 -36.01652 -15.9915 718.9 -44.19508 -17.12734 718.9 -46.97477 -23.44416 718.9 -40.73464 0.07673799 718.9 -46.99917 -8.704545 718.9 -49.23646 -8.070898 718.9 -46.30111 8.704545 718.9 -49.23646 0 718.9 -50 17.12734 718.9 -46.97477 8.704545 718.9 -49.23646 8.744272 718.9 49.22862 8.673146 724.9 49.24202 8.673146 724.9 49.24202 12.93196 724.9 48.2987 21.32088 747.7852 50.79938 12.93196 724.9 48.2987 17.13034 718.9 46.9732 17.09386 724.9 46.98723 26.82196 747.7913 49.60231 17.09386 724.9 46.98723 21.12675 724.9 45.31733 32.25825 747.7949 47.93365 21.12675 724.9 45.31733 25.00269 718.9 43.29909 24.99833 724.9 43.30223 37.56957 747.7965 45.80488 24.99833 724.9 43.30223 28.679 724.9 40.95748 42.69428 747.7962 43.23431 28.679 724.9 40.95748 32.13113 718.9 38.30842 32.1398 724.9 38.30186 47.57067 747.7944 40.24349 32.1398 724.9 38.30186 38.29721 718.9 32.14329 35.35534 724.9 35.35533 35.35534 724.9 35.35533 38.30187 724.9 32.1398 52.13829 747.7915 36.86001 38.30187 724.9 32.1398 43.2706 718.9 25.05428 40.95748 724.9 28.67899 56.33791 747.7877 33.1142 40.95748 724.9 28.67899 43.30224 724.9 24.99833 60.11408 747.7835 29.0412 43.30224 724.9 24.99833 46.96085 718.9 17.16614 45.31733 724.9 21.12674 63.41386 747.7789 24.67829 45.31733 724.9 21.12674 46.98723 724.9 17.09385 66.19059 747.7745 20.06634 46.98723 724.9 17.09385 49.23353 718.9 8.721057 48.2987 724.9 12.93194 68.40129 747.7705 15.24771 48.2987 724.9 12.93194 49.24202 724.9 8.67313 70.01139 747.7673 10.26688 49.24202 724.9 8.67313 49.80558 718.9 4.393081 49.81027 724.9 4.351598 70.99109 747.7651 5.169038 49.81027 724.9 4.351598 50 718.9 0 50 724.9 0 50 724.9 0 49.23646 718.9 -8.704545 50 724.9 0 50 718.9 0 49.81054 724.9 -4.348595 71.32131 747.7643 10e-7 50 724.9 0 49.81054 724.9 -4.348595 71.32131 747.7643 10e-7 47 718.9 0 50 718.9 0 49.80558 718.9 4.393081 46.27937 718.9 -8.198644 49.23646 718.9 -8.704545 46.81725 718.9 -4.129784 46.28787 718.9 8.149951 49.23353 718.9 8.721057 44.16648 718.9 16.07183 46.96085 718.9 17.16614 40.70402 718.9 23.49939 43.2706 718.9 25.05428 36.0195 718.9 30.1906 38.29721 718.9 32.14329 33.23096 718.9 33.23587 32.13113 718.9 38.30842 26.91589 718.9 38.52895 25.00269 718.9 43.29909 30.19496 718.9 36.01652 15.9915 718.9 44.19508 17.13034 718.9 46.9732 23.44416 718.9 40.73464 -0.07673799 718.9 46.99917 8.744272 718.9 49.22862 8.070898 718.9 46.30111 -8.579459 718.9 49.25764 0.08961498 718.9 49.9991 -17.00655 718.9 47.0181 -8.211176 718.9 46.27641 -24.93545 718.9 43.33771 -16.09428 718.9 44.15781 -28.62909 718.9 40.99165 -23.49571 718.9 40.70508 -32.11779 718.9 38.31937 -30.19856 718.9 36.01375 -35.34941 718.9 35.35975 -38.31934 718.9 32.11657 -35.99309 718.9 30.22239 -43.30387 718.9 24.99637 -40.6702 718.9 23.5582 -46.98614 718.9 17.0963 -44.1421 718.9 16.13909 44.1421 718.9 -16.13909 46.97477 718.9 -17.12734 48.30121 724.9 -12.92259 46.97477 718.9 -17.12734 49.2431 724.9 -8.666996 40.6702 718.9 -23.5582 43.28997 718.9 -25.01854 45.32436 724.9 -21.11166 43.28997 718.9 -25.01854 46.99174 724.9 -17.08147 35.99309 718.9 -30.22239 38.29654 718.9 -32.14511 40.97064 724.9 -28.66019 38.29654 718.9 -32.14511 43.31218 724.9 -24.98109 30.19856 718.9 -36.01375 32.14511 718.9 -38.29654 35.37553 724.9 -35.33514 32.14511 718.9 -38.29654 38.31836 724.9 -32.12013 23.49571 718.9 -40.70508 25.01854 718.9 -43.28997 28.70945 724.9 -40.93614 25.01854 718.9 -43.28997 32.16456 724.9 -38.28108 8.211176 718.9 -46.27641 21.17142 724.9 -45.29648 17.12734 718.9 -46.97477 16.09428 718.9 -44.15781 25.03631 724.9 -43.28028 12.98158 724.9 -48.28538 17.14361 724.9 -46.9691 8.716361 724.9 -49.23439 47 750.4 0 47 718.9 0 46.28787 718.9 8.149951 46.28787 750.4 -8.149951 46.81725 718.9 -4.129784 47 718.9 0 47 750.4 0 46.27937 750.4 8.198644 44.16648 718.9 16.07183 46.81725 750.4 4.129784 44.1421 750.4 16.13909 40.70402 718.9 23.49939 40.6702 750.4 23.5582 36.0195 718.9 30.1906 35.99309 750.4 30.22239 33.23096 718.9 33.23587 30.19856 750.4 36.01375 30.19496 718.9 36.01652 26.91589 718.9 38.52895 23.49571 750.4 40.70508 23.44416 718.9 40.73464 16.09428 750.4 44.15781 15.9915 718.9 44.19508 8.211176 750.4 46.27641 8.070898 718.9 46.30111 0.07673799 750.4 46.99917 -0.07673799 718.9 46.99917 -8.070898 750.4 46.30111 -8.211176 718.9 46.27641 -15.9915 750.4 44.19508 -16.09428 718.9 44.15781 -23.44416 750.4 40.73464 -23.49571 718.9 40.70508 -26.91589 750.4 38.52895 -30.19856 718.9 36.01375 -33.23096 750.4 33.23587 -35.99309 718.9 30.22239 -30.19496 750.4 36.01652 -36.0195 750.4 30.1906 -40.6702 718.9 23.5582 -40.70402 750.4 23.49939 -44.1421 718.9 16.13909 -44.16648 750.4 16.07183 -46.27937 718.9 8.198644 -46.28787 750.4 8.149951 -46.81725 718.9 4.129784 -47 718.9 0 -47 750.4 0 -47 718.9 0 -46.28787 718.9 -8.149951 -47 750.4 0 -46.27937 750.4 -8.198644 -44.16648 718.9 -16.07183 -46.81725 750.4 -4.129784 -44.1421 750.4 -16.13909 -40.70402 718.9 -23.49939 -40.6702 750.4 -23.5582 -36.0195 718.9 -30.1906 -35.99309 750.4 -30.22239 -33.23096 718.9 -33.23587 -30.19856 750.4 -36.01375 -30.19496 718.9 -36.01652 -26.91589 718.9 -38.52895 -23.49571 750.4 -40.70508 -23.44416 718.9 -40.73464 -16.09428 750.4 -44.15781 -15.9915 718.9 -44.19508 -8.211176 750.4 -46.27641 -8.070898 718.9 -46.30111 -0.07673799 750.4 -46.99917 0.07673799 718.9 -46.99917 8.070898 750.4 -46.30111 8.211176 718.9 -46.27641 15.9915 750.4 -44.19508 16.09428 718.9 -44.15781 23.44416 750.4 -40.73464 23.49571 718.9 -40.70508 26.91589 750.4 -38.52895 30.19856 718.9 -36.01375 33.23096 750.4 -33.23587 35.99309 718.9 -30.22239 30.19496 750.4 -36.01652 36.0195 750.4 -30.1906 40.6702 718.9 -23.5582 40.70402 750.4 -23.49939 44.1421 718.9 -16.13909 44.16648 750.4 -16.07183 46.27937 718.9 -8.198644 70.9458 747.7652 -5.511627 49.2431 724.9 -8.666996 69.83258 747.7677 -10.93876 48.30121 724.9 -12.92259 68.00615 747.7713 -16.22589 46.99174 724.9 -17.08147 65.50381 747.7757 -21.31822 45.32436 724.9 -21.11166 43.31218 724.9 -24.98109 62.3698 747.7805 -26.16238 40.97064 724.9 -28.66019 58.65788 747.7852 -30.70739 38.31836 724.9 -32.12013 54.42741 747.7896 -34.90523 35.37553 724.9 -35.33514 49.74423 747.7932 -38.7117 32.16456 724.9 -38.28108 44.67794 747.7957 -42.08703 28.70945 724.9 -40.93614 25.03631 724.9 -43.28028 39.30151 747.7966 -44.99612 21.17142 724.9 -45.29648 33.68923 747.7955 -47.41031 17.14361 724.9 -46.9691 27.91608 747.7922 -49.30627 12.98158 724.9 -48.28538 22.05575 747.7861 -50.66751 8.716361 724.9 -49.23439 40.57278 789.5609 -54.22637 33.75657 770.7238 -52.41167 48.42269 793.6744 -53.63383 40.42299 770.7331 -51.02418 55.709 793.6895 -52.03111 47.0841 770.7383 -49.08604 63.02792 793.6934 -49.89712 53.64741 770.7399 -46.61193 70.27787 793.6939 -47.24962 60.01427 770.7385 -43.62418 77.34616 793.6917 -44.11115 66.0841 770.7347 -40.15092 84.1151 793.6874 -40.51096 71.75473 770.7291 -36.22726 90.46425 793.6814 -36.48309 76.9266 770.7224 -31.89321 96.27542 793.6743 -32.06681 81.50342 770.715 -27.19349 101.433 793.6668 -27.30467 85.39672 770.7077 -22.17675 105.8312 793.6594 -22.24315 88.52507 770.7009 -16.89457 109.3713 793.6526 -16.93081 90.82044 770.6954 -11.40088 111.9722 793.647 -11.41839 92.22492 770.6916 -5.750843 114.1029 793.642 10e-7 92.70006 770.6902 10e-7 113.5641 793.6433 -5.757491 113.5637 793.6433 5.759802 92.70006 770.6902 10e-7 114.1029 793.642 10e-7 92.28218 770.6914 5.393782 133.2952 816.5854 -10.99037 130.6037 816.5892 -16.32837 126.9335 816.5939 -21.50175 122.3653 816.5991 -26.46617 76.27854 809.0079 -49.56719 86.53163 814.7584 -47.4607 66.60717 803.5972 -51.27408 48.72329 793.8344 -53.60536 57.4072 798.526 -52.62214 49.38068 795.7319 -53.62133 48.42269 793.6744 -53.63383 40.57278 789.5609 -54.22637 48.72329 793.8344 -53.60536 37.43463 789.3961 -54.39488 32.98033 785.725 -54.48884 25.91914 782.3287 -54.40845 25.91914 782.3287 -54.40845 25.36768 783.3798 -54.34405 25.91914 782.3287 -54.40845 25.36768 783.3798 -54.34405 141.4557 824.9111 -9.773571 140.5921 826.8347 -15.25531 139.9914 828.2009 -18.09158 138.434 831.8461 -23.85544 139.2711 829.859 -20.9606 137.4781 834.117 -26.706 76.27854 809.0079 -49.56719 73.05382 808.9076 -50.37134 66.60717 803.5972 -51.27408 61.24377 802.2661 -52.23765 57.4072 798.526 -52.62214 141.4557 824.9111 -9.773571 141.8523 826.9717 -12.6298 140.5921 826.8347 -15.25531 139.9914 828.2009 -18.09158 140.7561 829.4797 -18.22994 139.2711 829.859 -20.9606 139.4167 832.6339 -23.23061 138.434 831.8461 -23.85544 137.4781 834.117 -26.706 36.81172 790.486 -54.10951 25.30277 783.5043 -54.3176 16.5924 780.8023 -53.35862 25.23647 783.6316 -54.2863 25.23647 783.6316 -54.2863 8.530138 777.0588 -52.34431 0.529525 773.5957 -50.70874 -7.317887 770.4495 -48.41851 -14.90059 767.6479 -45.44591 -22.09284 765.2053 -41.77856 -28.75876 763.1247 -37.41912 -34.75297 761.3953 -32.39136 -39.93235 760.0027 -26.75135 -44.15762 758.9306 -20.58307 -47.29426 758.1647 -13.97909 24.84152 784.3945 -54.00286 24.84152 784.3945 -54.00286 24.63983 784.7872 -53.78479 36.23294 791.4694 -53.5135 24.63983 784.7872 -53.78479 16.1691 781.83 -52.4373 24.59791 784.8691 -53.7321 24.59791 784.8691 -53.7321 8.224061 778.0432 -51.45127 0.335249 774.5472 -49.84376 -7.40264 771.3785 -47.58174 -14.87587 768.5652 -44.63884 -21.95693 766.1216 -41.00521 -28.5086 764.0502 -36.68748 -34.3849 762.3393 -31.71536 -39.44607 760.972 -26.15149 -43.55991 759.9282 -20.08682 -46.60021 759.1894 -13.61959 24.37296 785.3109 -53.39895 24.37296 785.3109 -53.39895 24.0927 785.8679 -52.8353 35.73635 792.281 -52.64646 24.0927 785.8679 -52.8353 17.9446 783.6255 -51.38454 24.07334 785.9067 -52.78847 24.07334 785.9067 -52.78847 12.94546 781.1237 -50.96657 6.987076 778.2829 -50.14714 12.15401 780.7365 -50.88008 -3.557575 773.6436 -47.75153 1.84848 775.9602 -49.13809 -8.86096 771.4994 -46.03133 -16.54346 768.6159 -42.81383 -13.32412 769.7924 -44.27602 -22.30826 766.6275 -39.70695 -17.65035 768.2241 -42.26446 -30.15029 764.1542 -34.21226 -26.71074 765.207 -36.83364 -38.37897 761.8331 -25.94769 -33.35501 763.2183 -31.39007 -42.27048 760.8248 -20.33949 -44.06414 760.3768 -17.00394 -46.64092 759.7507 -10.24394 -45.53955 760.0163 -13.57654 -47.43456 759.561 -6.865048 23.989 786.0762 -52.56891 23.989 786.0762 -52.56891 23.71171 786.6465 -51.56863 30.95543 790.4709 -51.67483 23.71171 786.6465 -51.56863 38.63786 794.6826 -51.4137 23.71171 786.6465 -51.56863 17.9446 783.6255 -51.38454 30.95543 790.4709 -51.67483 41.07627 796.0476 -51.25925 12.94546 781.1237 -50.96657 6.987076 778.2829 -50.14714 12.15401 780.7365 -50.88008 1.84848 775.9602 -49.13809 -3.557575 773.6436 -47.75153 12.09774 782.7601 -46.83877 17.58523 785.4104 -47.53919 13.16656 783.2394 -47.05585 -8.86096 771.4994 -46.03133 1.646352 778.0005 -44.71037 -13.32412 769.7924 -44.27602 -16.54346 768.6159 -42.81383 -17.07181 769.4619 -40.10647 -17.65035 768.2241 -42.26446 -16.23861 769.797 -40.44654 -9.856426 772.6095 -42.35595 -22.30826 766.6275 -39.70695 -22.54685 767.4286 -37.30389 -26.71074 765.207 -36.83364 -30.15029 764.1542 -34.21226 -28.46178 765.5436 -32.98941 -33.35501 763.2183 -31.39007 -33.62357 764.1412 -27.71999 -38.37897 761.8331 -25.94769 -37.8954 763.1363 -21.59856 -42.27048 760.8248 -20.33949 -44.06414 760.3768 -17.00394 -41.11388 762.4648 -14.74979 -45.53955 760.0163 -13.57654 -46.64092 759.7507 -10.24394 -47.43456 759.561 -6.865048 72.26081 810.2113 -50.24373 60.4931 803.4998 -52.06107 48.685 796.8949 -53.39217 71.46382 811.3841 -49.66598 59.75539 804.6108 -51.47968 48.01832 797.9431 -52.80437 70.73727 812.3161 -48.69233 59.09275 805.5049 -50.54279 47.43062 798.7973 -51.90244 73.48892 814.8897 -46.78807 68.69527 812.0579 -47.68629 55.34984 804.2307 -49.78272 64.22206 809.422 -48.45883 46.79332 799.292 -50.77524 41.07627 796.0476 -51.25925 38.63786 794.6826 -51.4137 73.48892 814.8897 -46.78807 68.69527 812.0579 -47.68629 39.40956 799.3632 -42.52716 64.22206 809.422 -48.45883 55.34984 804.2307 -49.78272 46.79332 799.292 -50.77524 30.03554 793.9196 -43.6488 26.13886 790.8208 -45.88045 22.00404 787.9903 -47.15288 -18.46122 764.19 -38.56038 -17.07181 769.4619 -40.10647 -22.54685 767.4286 -37.30389 -15.13636 765.7333 -40.17865 -16.23861 769.797 -40.44654 -21.62717 762.7204 -36.61668 -28.46178 765.5436 -32.98941 -27.39353 760.0438 -31.81053 -33.62357 764.1412 -27.71999 -32.23561 757.7962 -25.94529 -37.8954 763.1363 -21.59856 -36.03159 756.0341 -19.17983 -41.11388 762.4648 -14.74979 -38.63088 754.8276 -11.77211 -43.09181 762.087 -7.459362 -39.95194 754.2144 -3.969198 -43.7532 761.9663 -10e-7 -39.95166 754.2145 3.972513 -43.11808 762.0819 7.310119 -38.62562 754.83 11.79207 -41.19666 762.4481 14.52244 -36.01155 756.0434 19.2237 -38.03592 763.1048 21.35387 -32.19611 757.8145 26.00253 -33.79207 764.0991 27.51586 -27.34307 760.0672 31.8611 -28.61921 765.4989 32.85301 -21.58094 762.7419 36.64815 -22.67718 767.3845 37.22455 -17.06942 769.4624 40.1074 -15.10909 765.746 40.19025 -16.31 769.7685 40.41832 14.83479 779.6455 -47.05585 12.09774 782.7601 -46.83877 1.646352 778.0005 -44.71037 13.16656 783.2394 -47.05585 -9.856426 772.6095 -42.35595 -8.166404 768.9687 -42.35595 -9.856426 772.6095 -42.35595 -8.166404 768.9687 -42.35595 36.10726 799.898 -36.79175 38.00378 802.0112 -33.56867 33.34222 796.9572 -40.62983 57.38745 799.3978 -13.21573 38.00378 802.0112 -33.56867 36.10726 799.898 -36.79175 65.51174 818.5321 -25.16099 43.16478 807.1087 -25.13748 43.16478 807.1087 -25.13748 40.07063 791.3596 -36.79175 36.10726 799.898 -36.79175 33.34222 796.9572 -40.62983 40.07063 791.3596 -36.79175 36.07163 789.5033 -41.17658 30.03554 793.9196 -43.6488 31.32197 787.2986 -44.51765 26.13886 790.8208 -45.88045 26.0382 784.846 -46.66667 22.00404 787.9903 -47.15288 20.45846 782.2559 -47.52681 17.58523 785.4104 -47.53919 13.16656 783.2394 -47.05585 14.83479 779.6455 -47.05585 85.81986 825.9322 -34.4591 64.5676 820.1878 -13.51989 66.07361 820.6832 -15.4402 80.65918 824.7162 -30.24904 75.61484 823.4539 -25.65611 70.75191 822.1224 -20.72462 50.93492 813.2986 -13.21573 63.31803 819.7802 -11.64482 67.42974 822.5675 -10.46173 64.5676 820.1878 -13.51989 63.31803 819.7802 -11.64482 67.73902 821.89 -13.9669 66.07361 820.6832 -15.4402 69.2611 823.3291 -12.54675 53.06249 814.8139 -9.178676 62.21976 819.4243 -9.661641 65.83658 821.91 -8.149031 62.21976 819.4243 -9.661641 61.32498 819.1346 -7.663414 61.32498 819.1346 -7.663414 54.36064 815.7691 -4.699023 60.65583 818.9195 -5.691586 64.57337 821.3919 -5.605688 60.65583 818.9195 -5.691586 60.19192 818.7705 -3.748839 60.19192 818.7705 -3.748839 54.79643 816.0949 -10e-7 59.83893 818.6575 -10e-7 63.74985 821.0556 -2.862322 59.83893 818.6575 -10e-7 54.36068 815.7691 4.698818 60.18076 818.7669 3.690529 63.46183 820.9382 4.72e-4 60.18076 818.7669 3.690529 60.63559 818.913 5.620534 63.74975 821.0555 2.86306 60.63559 818.913 5.620534 53.06254 814.8139 9.178548 61.29675 819.1256 7.589931 64.57326 821.3918 5.604653 61.29675 819.1256 7.589931 62.18728 819.4139 9.596158 62.18728 819.4139 9.596158 50.93521 813.2979 13.21573 63.28733 819.77 11.59542 65.83665 821.91 8.148368 63.28733 819.77 11.59542 64.56336 820.1865 13.51319 67.42871 822.567 10.46172 64.56336 820.1865 13.51319 43.16464 807.1086 25.13764 65.51155 818.5325 25.15887 66.0736 820.6831 15.44022 66.0736 820.6831 15.44022 38.00347 802.0104 33.56941 75.62987 823.4579 25.67016 70.76074 822.1251 20.73339 80.6781 824.7209 30.26508 85.83842 825.9365 34.47356 36.10755 799.8973 36.79175 26.18297 790.8534 45.86138 30.0183 793.9048 43.66143 33.30578 796.9213 40.67073 40.07063 791.3596 36.79175 38.00347 802.0104 33.56941 43.16464 807.1086 25.13764 36.10755 799.8973 36.79175 50.93521 813.2979 13.21573 57.38745 799.3978 13.21573 50.93521 813.2979 13.21573 53.06254 814.8139 9.178548 57.38745 799.3978 13.21573 61.14601 801.1425 4.713194 54.36068 815.7691 4.698818 59.70998 800.4758 9.193468 54.79643 816.0949 -10e-7 61.6318 801.3679 0 54.36064 815.7691 -4.699023 61.14601 801.1425 -4.713194 53.06249 814.8139 -9.178676 59.70998 800.4758 -9.193468 50.93492 813.2986 -13.21573 50.93492 813.2986 -13.21573 57.38745 799.3978 -13.21573 87.49483 827.6888 -32.40904 85.81986 825.9322 -34.4591 80.65918 824.7162 -30.24904 80.59275 825.8308 -26.89463 75.61484 823.4539 -25.65611 73.98327 823.9259 -20.71995 70.75191 822.1224 -20.72462 66.07361 820.6832 -15.4402 67.73902 821.89 -13.9669 67.73899 821.89 13.96695 66.0736 820.6831 15.44022 70.76074 822.1251 20.73339 67.73899 821.89 13.96695 73.97792 823.9241 20.71463 75.62987 823.4579 25.67016 80.58841 825.8295 26.89146 80.6781 824.7209 30.26508 85.83842 825.9365 34.47356 87.49193 827.688 32.40707 -8.166404 768.9687 42.35595 12.09747 782.76 46.83872 13.16653 783.2395 47.05585 1.646165 778.0004 44.71033 14.83479 779.6455 47.05585 13.16653 783.2395 47.05585 17.69994 785.472 47.54053 14.83479 779.6455 47.05585 20.45866 782.256 47.5268 22.10997 788.0576 47.13203 26.03849 784.8461 46.66659 26.18297 790.8534 45.86138 31.32223 787.2987 44.51751 30.0183 793.9048 43.66143 36.07178 789.5034 41.17645 33.30578 796.9213 40.67073 36.10755 799.8973 36.79175 40.07063 791.3596 36.79175 -9.856452 772.6096 42.35595 -9.856452 772.6096 42.35595 -8.166404 768.9687 42.35595 101.6193 831.5657 -41.0689 102.0141 830.6948 -42.29737 101.6193 831.5657 -41.0689 100.0996 833.4182 -37.29118 103.9626 833.2241 -40.9021 104.4114 832.3521 -42.00422 103.9626 833.2241 -40.9021 92.09827 830.7786 -32.65124 84.13774 828.3091 -26.87197 76.4802 825.875 -20.12901 69.2611 823.3291 -12.54675 106.0813 834.8596 -40.78866 106.7203 834.1181 -41.75991 106.0813 834.8596 -40.78866 107.929 836.4 -40.71681 107.929 836.4 -40.71681 108.2696 839.868 -38.44953 109.7853 838.061 -40.67174 108.9287 835.9775 -41.55963 109.7853 838.061 -40.67174 100.847 836.3924 -35.19598 93.09534 833.2975 -30.7703 85.30567 830.4746 -25.18763 77.7676 827.761 -18.62415 70.62313 824.9868 -11.19487 70.62313 824.9868 -11.19487 111.3603 839.5775 -40.64797 111.0321 837.9229 -41.39665 111.3603 839.5775 -40.64797 112.7879 841.0394 -40.64314 113.0142 839.9398 -41.26535 112.7879 841.0394 -40.64314 114.0583 842.4263 -40.64778 114.0583 842.4263 -40.64778 115.2108 843.7691 -40.65768 114.8768 842.0329 -41.15988 115.2108 843.7691 -40.65768 111.7129 846.0933 -38.06155 115.3054 848.8642 -39.26224 116.2978 845.128 -40.67052 116.5995 844.1932 -41.07419 116.2978 845.128 -40.67052 114.9427 848.5682 -39.14949 108.2357 843.7103 -36.7276 109.3787 844.4639 -37.18505 100.7015 839.3574 -33.21243 104.5687 841.469 -35.12798 102.6978 840.4185 -34.23185 93.18474 835.7913 -28.75852 94.81628 836.5195 -29.81083 86.03099 832.7854 -23.53708 86.38545 832.9296 -23.81959 78.85509 829.8578 -17.26306 77.17443 829.1606 -15.62349 71.80097 826.8314 -9.935744 71.80097 826.8314 -9.935744 117.8847 851.0693 -40.01062 117.2993 846.4812 -40.68528 117.2993 846.4812 -40.68528 118.1663 847.7633 -40.69887 118.1597 846.4248 -41.00202 118.1663 847.7633 -40.69887 118.918 849.0035 -40.7096 119.5149 848.7375 -40.93814 118.918 849.0035 -40.7096 120.6761 853.66 -40.71397 120.0759 851.3817 -40.72269 120.5755 851.1471 -40.87802 120.0759 851.3817 -40.72269 120.6761 853.66 -40.71397 120.6761 853.66 -40.71397 117.8847 851.0693 -40.01062 121.1348 853.6541 -40.81576 115.3054 848.8642 -39.26224 110.4905 850.2702 -36.19815 114.9427 848.5682 -39.14949 111.7129 846.0933 -38.06155 109.3787 844.4639 -37.18505 104.6943 846.5588 -32.99619 108.2357 843.7103 -36.7276 104.5687 841.469 -35.12798 102.6978 840.4185 -34.23185 98.01207 842.9514 -28.64151 100.7015 839.3574 -33.21243 94.81628 836.5195 -29.81083 90.45103 839.4813 -22.6402 93.18474 835.7913 -28.75852 86.38545 832.9296 -23.81959 82.47856 836.0665 -14.81699 86.03099 832.7854 -23.53708 78.85509 829.8578 -17.26306 77.17443 829.1606 -15.62349 77.2143 833.2915 -9.398168 71.80097 826.8314 -9.935744 74.52854 832.0998 -4.864228 77.2143 833.2915 -9.398168 71.80097 826.8314 -9.935744 70.49073 826.0778 -8.636091 70.49073 826.0778 -8.636091 102.8974 829.7525 -43.15467 105.3022 831.4541 -42.76187 107.6107 833.2744 -42.42128 109.8104 835.197 -42.12897 111.8964 837.2136 -41.87889 113.8525 839.3085 -41.6663 115.6793 841.4859 -41.48489 117.3562 843.7362 -41.32944 118.8603 846.0638 -41.19447 120.149 848.4804 -41.07565 121.132 851.0054 -40.96987 121.6031 853.6467 -40.87426 121.6945 850.8593 -40.99446 121.8396 853.6424 -40.88691 103.8455 828.6033 -43.58316 106.2561 830.3893 -43.12305 108.5598 832.2992 -42.72199 110.7444 834.3153 -42.37579 112.8057 836.4284 -42.07801 114.7279 838.622 -41.82374 116.5109 840.9005 -41.60575 118.1344 843.2536 -41.41873 119.576 845.687 -41.25713 120.7929 848.2144 -41.11667 122.0749 853.6376 -40.88835 80.53759 837.3906 -9.061828 87.32508 842.7849 -13.97991 88.21717 847.6184 -7.972946 91.67277 849.2988 -13.14507 94.13928 845.8997 -21.46435 84.30211 842.2455 -8.59624 91.42646 852.3741 -7.299854 95.44178 855.5661 -12.31241 97.38691 852.1566 -20.29222 96.03496 860.1156 -5.898525 98.55286 861.551 -11.48188 100.1256 858.2161 -19.12374 93.9878 856.5017 -6.603752 98.92422 866.0561 -4.4443 100.9263 867.2121 -10.65343 102.2877 864.0497 -17.95883 102.3887 872.5633 -9.489856 102.492 872.6718 -9.812292 103.8041 869.6124 -16.79735 102.2562 872.4262 -9.067708 100.8417 871.0832 -3.450073 102.3292 873.6525 -8.780432 102.492 872.6718 -9.812292 102.3887 872.5633 -9.489856 104.1053 874.5335 -14.30589 104.1053 874.5335 -14.30589 102.2562 872.4262 -9.067708 101.0593 872.6113 -3.271138 100.8417 871.0832 -3.450073 100.6052 870.8923 -1.74866 100.8417 871.0832 -3.450073 98.92422 866.0561 -4.4443 101.0593 872.6113 -3.271138 100.8417 871.0832 -3.450073 100.6052 870.8923 -1.74866 98.27259 865.3334 -2.358345 96.03496 860.1156 -5.898525 95.08197 859.455 -3.071128 93.9878 856.5017 -6.603752 91.04655 853.1495 -3.663745 91.42646 852.3741 -7.299854 88.21717 847.6184 -7.972946 86.22846 846.4586 -4.152169 84.30211 842.2455 -8.59624 80.69532 839.4254 -4.545564 80.53759 837.3906 -9.061828 100.636 849.1614 -27.33614 102.8789 855.254 -26.03603 104.6841 861.2001 -24.74106 105.9958 866.9776 -23.45112 104.6395 875.2005 -15.63908 106.7564 872.5474 -22.16598 104.0461 875.6522 -13.9724 104.6395 875.2005 -15.63908 106.1451 877.202 -19.12842 106.1451 877.202 -19.12842 106.3985 852.6306 -31.76168 107.7869 858.6328 -30.53399 108.8152 864.5436 -29.31297 109.4393 870.3441 -28.09843 106.9483 878.3591 -20.86245 109.6175 876.0408 -26.89006 105.9782 878.2154 -18.76292 106.9483 878.3591 -20.86245 107.3776 879.0051 -21.75894 107.3776 879.0051 -21.75894 111.3965 856.0602 -35.2181 112.0779 861.8353 -34.24591 112.5062 867.5823 -33.28142 112.6529 873.2865 -32.32437 108.269 880.4045 -23.56097 109.3526 882.1942 -25.65165 112.4946 878.9895 -31.37441 108.0234 881.2661 -23.18125 109.3526 882.1942 -25.65165 108.269 880.4045 -23.56097 112.045 885.3143 -30.41329 110.4696 884.1159 -27.70077 110.4696 884.1159 -27.70077 111.4323 886.291 -29.45036 112.045 885.3143 -30.41329 110.4696 884.1159 -27.70077 113.8016 886.4208 -33.15812 112.1883 888.4014 -30.955 113.8016 886.4208 -33.15812 112.1449 888.2636 -30.86196 110.1839 884.7295 -27.29811 111.4323 886.291 -29.45036 110.4696 884.1159 -27.70077 110.1839 884.7295 -27.29811 112.2044 888.4533 -30.98984 113.078 892.5701 -33.51186 111.5526 888.9963 -30.32037 112.1883 888.4014 -30.955 112.1449 888.2636 -30.86196 112.2044 888.4533 -30.98984 113.078 892.5701 -33.51186 113.078 892.5701 -33.51186 112.6942 896.6884 -35.13051 113.078 892.5701 -33.51186 112.2792 893.158 -32.93191 112.2792 893.158 -32.93191 111.7566 897.1758 -34.76956 111.9757 893.3336 -32.77871 110.7934 889.6719 -29.93601 111.9757 893.3336 -32.77871 110.4871 901.7097 -36.66869 110.7328 897.8379 -34.76167 111.3171 893.6512 -32.53575 111.3171 893.6512 -32.53575 110.6107 893.9127 -32.38658 109.9019 890.256 -29.72426 110.6107 893.9127 -32.38658 107.5741 907.6395 -38.57983 106.5568 909.8268 -39.07302 108.4068 905.507 -37.97211 109.4356 901.5075 -36.47487 110.2431 894.0213 -32.34754 109.6397 897.7233 -34.58345 108.9202 890.7208 -29.69511 110.2431 894.0213 -32.34754 109.12 894.2491 -32.37482 107.9171 891.0914 -29.88982 109.12 894.2491 -32.37482 107.8945 891.0466 -29.85086 104.0454 914.2536 -39.68529 88 914.234 -39.95563 104.0454 914.2536 -39.68529 105.3821 912.0302 -39.44074 88 917.4 -40.05699 102.3078 917.065 -39.8171 104.0454 914.2536 -39.68529 88 914.234 -39.95563 106.5568 909.8268 -39.07302 107.5741 907.6395 -38.57983 88 907.0598 -38.80419 108.4068 905.507 -37.97211 109.4356 901.5075 -36.47487 88 900.1444 -36.30818 109.6397 897.7233 -34.58345 109.12 894.2491 -32.37482 88 893.7796 -32.53591 107.9171 891.0914 -29.88982 123.3564 920.5202 -39.35414 99.99839 920.5518 -39.75283 99.99839 920.5518 -39.75283 88 927.7753 -38.79496 123.3564 920.5202 -39.35414 99.99839 920.5518 -39.75283 88 920.566 -39.95563 88 920.566 -39.95563 123.3564 920.5202 -39.35414 123.1448 927.5142 -38.19469 124.5188 920.5902 -39.19145 123.3564 920.5202 -39.35414 123.1448 927.5142 -38.19469 126.3806 927.1442 -36.98249 127.1848 920.6505 -37.44117 126.5789 920.6547 -38.08487 125.413 927.3125 -37.63735 126.1147 920.6488 -38.45192 125.6137 920.6359 -38.75999 124.3138 927.4187 -38.0545 124.7983 920.6039 -39.10908 126.6079 933.3074 34.73292 127.1617 938.9638 31.42482 127.9158 943.9548 27.16798 128.7338 948.1489 22.0847 129.483 951.4255 16.31074 130.0561 953.6834 10.01193 130.3664 954.8373 3.376805 130.3663 954.8372 -3.377282 130.0561 953.6834 -10.01261 129.4832 951.4253 -16.31177 128.7335 948.1484 -22.08446 127.915 943.9544 -27.16615 127.1617 938.9644 -31.42447 126.6082 933.3074 -34.73271 125.6304 933.6533 35.3484 126.1693 939.473 31.9827 126.9056 944.609 27.65158 127.7051 948.9259 22.47903 128.4378 952.2993 16.60282 128.9983 954.6245 10.19164 129.3018 955.8129 3.4375 129.3017 955.8129 -3.437985 128.9983 954.6244 -10.19233 128.4379 952.2991 -16.60387 127.7048 948.9254 -22.47878 126.9047 944.6086 -27.64971 126.1693 939.4736 -31.98235 125.6308 933.6533 -35.34819 124.5132 933.8991 35.72942 125.0232 939.8392 32.31107 125.7237 945.0728 27.91734 126.4848 949.463 22.67896 127.1817 952.8868 16.73946 127.7142 955.2425 10.27007 128.0023 956.445 3.462848 128.0022 956.445 -3.46334 127.7142 955.2424 -10.27075 127.1819 952.8867 -16.74048 126.4844 949.4623 -22.67877 125.7227 945.0719 -27.91563 125.0233 939.8399 -32.31071 124.5135 933.8992 -35.72917 123.3376 934.3372 35.7102 123.8546 940.616 31.97614 124.5683 946.1221 27.11155 125.3324 950.6657 21.24789 124.9585 948.5332 24.28488 125.9952 954.0308 14.64854 125.6865 952.5026 18.02704 126.4471 956.1097 7.532721 126.255 955.2361 11.14106 126.6112 956.8305 0.141691 126.5692 956.6429 3.855474 126.5751 956.6691 -3.576383 126.2706 955.307 -10.89528 126.4585 956.1602 -7.266433 125.7054 952.597 -17.84074 126.0134 954.1166 -14.43042 124.9733 948.6238 -24.16752 125.3499 950.7614 -21.09611 124.2067 943.5357 -29.62595 124.579 946.2009 -27.02729 123.3379 934.337 -35.7103 123.859 940.6572 -31.94607 88 927.7403 38.80418 123.3376 934.3372 35.7102 88 934.6558 36.30812 123.8546 940.616 31.97614 88 941.0206 32.53579 124.5683 946.1221 27.11155 88 946.5869 27.63153 124.9585 948.5332 24.28488 88 951.1737 21.73178 125.3324 950.6657 21.24789 88 953.0635 18.43839 125.6865 952.5026 18.02704 88 954.6275 14.99287 125.9952 954.0308 14.64854 88 955.8662 11.40541 126.255 955.2361 11.14106 88 956.7595 7.729559 126.4471 956.1097 7.532721 88 957.3077 3.984749 126.5692 956.6429 3.855474 88 957.5037 0.218952 126.6112 956.8305 0.141691 88 957.3482 -3.551093 126.5751 956.6691 -3.576383 88 956.839 -7.308726 126.4585 956.1602 -7.266433 88 955.981 -11.00572 126.2706 955.307 -10.89528 88 954.773 -14.62296 126.0134 954.1166 -14.43042 88 953.2324 -18.10463 125.7054 952.597 -17.84074 88 951.3579 -21.44032 125.3499 950.7614 -21.09611 88 949.2025 -24.55331 124.9733 948.6238 -24.16752 88 946.7727 -27.43265 124.579 946.2009 -27.02729 124.2067 943.5357 -29.62595 88 941.1729 -32.4244 123.859 940.6572 -31.94607 88 934.7509 -36.26299 123.3379 934.337 -35.7103 88 924.6329 36.28598 88 920.566 39.95563 88 927.7403 38.80418 88 917.4362 36.99993 88 917.4 40.05699 88 931.5532 34.18553 88 934.6558 36.30812 88 937.9393 30.77456 88 941.0206 32.53579 88 943.5462 26.17773 88 946.5869 27.63153 88 948.135 20.60119 88 951.1737 21.73178 88 951.5598 14.21501 88 953.0635 18.43839 88 953.6827 7.249401 88 954.6275 14.99287 88 954.773 -14.62296 88 955.8662 11.40541 88 954.4 0 88 954.2182 3.655726 88 955.981 -11.00572 88 956.7595 7.729559 88 956.839 -7.308726 88 957.3077 3.984749 88 957.3482 -3.551093 88 957.5037 0.218952 88 953.2324 -18.10463 88 951.5842 -14.15581 88 951.3579 -21.44032 88 953.6906 -7.209047 88 949.2025 -24.55331 88 948.1718 -20.54592 88 946.7727 -27.43265 88 943.5797 -26.14408 88 941.1729 -32.4244 88 937.9476 -30.76877 88 934.7509 -36.26299 88 931.5239 -34.19749 88 927.7753 -38.79496 88 924.5722 -36.29792 88 920.566 -39.95563 88 917.4 -40.05699 88 910.2279 36.29792 88 914.234 39.95563 104.0454 914.2536 39.68529 88 914.234 39.95563 88 907.0247 38.79496 104.0454 914.2536 39.68529 88 914.234 39.95563 88 907.0247 38.79496 88 903.2761 34.19749 88 900.0492 36.26301 108.3545 905.6569 38.01901 88 900.0492 36.26301 105.3521 912.084 39.44811 106.5077 909.9235 39.09187 107.5186 907.7692 38.61272 88 896.8524 30.76877 88 893.6273 32.4245 109.6442 897.8207 34.63853 88 893.6273 32.4245 109.4121 901.6524 36.53771 88 891.2203 26.14408 88 888.0274 27.43276 107.9203 891.098 29.89556 88 888.0274 27.43276 109.1199 894.2499 32.37365 88 886.6282 20.54592 88 885.5976 24.55344 105.9922 887.8729 26.75869 88 885.5976 24.55344 107.8944 891.0465 29.85075 88 883.2158 14.15581 88 883.4422 21.44041 103.654 884.7097 22.83897 88 883.4422 21.44041 88 881.5676 18.10463 102.6456 883.4823 20.99572 88 881.5676 18.10463 88 880.4 0 88 880.027 14.62284 99.77521 880.4518 15.12369 88 880.027 14.62284 88 881.1094 7.209047 101.4003 882.0893 18.58894 88 878.934 -11.40598 88 878.8189 11.00547 99.30154 880.0165 14.02792 88 878.8189 11.00547 88 880.1727 -14.99338 88 878.0407 -7.730095 88 877.9609 7.308418 97.5194 878.5509 9.303995 88 877.9609 7.308418 88 877.4924 -3.985209 88 877.4517 3.550745 96.03976 877.6006 3.638149 88 877.4517 3.550745 97.43226 878.4871 9.037449 88 877.2964 -0.219355 95.70199 877.4297 -4.89e-4 88 877.2964 -0.219355 96.03975 877.6006 -3.638136 88 877.4924 -3.985209 88 878.0407 -7.730095 97.43238 878.4873 -9.038298 88 878.934 -11.40598 99.30181 880.0167 -14.02849 88 880.1727 -14.99338 97.51562 878.5482 -9.292932 88 881.1173 -7.249401 88 881.7367 -18.43882 99.76918 880.4461 -15.11001 88 881.7367 -18.43882 88 880.5818 -3.655726 88 883.2402 -14.21501 88 883.6265 -21.73214 101.3999 882.0889 -18.58828 88 883.6265 -21.73214 88 886.6651 -20.60119 88 888.2135 -27.63179 103.6535 884.7092 -22.8383 88 888.2135 -27.63179 102.6405 883.4763 -20.98622 88 891.2538 -26.17773 88 893.7796 -32.53591 107.8945 891.0466 -29.85086 105.9922 887.8729 -26.75868 88 896.8607 -30.77456 88 900.1444 -36.30818 88 903.2468 -34.18553 88 907.0598 -38.80419 88 910.1671 -36.28598 88 914.234 -39.95563 88 917.3638 -36.99993 113.5 954.4 0 88 954.4 0 88 953.6906 -7.209047 113.5 953.6906 7.209047 88 954.2182 3.655726 88 954.4 0 113.5 954.4 0 113.5 953.6827 -7.249401 88 951.5842 -14.15581 113.5 954.2182 -3.655726 113.5 951.5598 -14.21501 88 948.1718 -20.54592 113.5 948.135 -20.60119 88 943.5797 -26.14408 113.5 943.5462 -26.17773 88 937.9476 -30.76877 113.5 937.9393 -30.77456 88 931.5239 -34.19749 113.5 924.6329 -36.28598 88 924.5722 -36.29792 113.5 931.5532 -34.18553 113.5 917.4362 -36.99993 88 917.3638 -36.99993 113.5 910.2279 -36.29792 88 910.1671 -36.28598 113.5 903.2761 -34.19749 88 903.2468 -34.18553 88 896.8607 -30.77456 113.5 896.8524 -30.76877 88 891.2538 -26.17773 113.5 891.2203 -26.14408 88 886.6651 -20.60119 113.5 886.6282 -20.54592 88 883.2402 -14.21501 113.5 883.2158 -14.15581 88 881.1173 -7.249401 113.5 881.1094 -7.209047 88 880.5818 -3.655726 88 880.4 0 113.5 880.4 0 88 880.4 0 88 881.1094 7.209047 113.5 880.4 0 113.5 881.1173 7.249401 88 883.2158 14.15581 113.5 880.5818 3.655726 113.5 883.2402 14.21501 88 886.6282 20.54592 113.5 886.6651 20.60119 88 891.2203 26.14408 113.5 891.2538 26.17773 88 896.8524 30.76877 113.5 896.8607 30.77456 88 903.2761 34.19749 113.5 910.1671 36.28598 88 910.2279 36.29792 113.5 903.2468 34.18553 113.5 917.3638 36.99993 88 917.4362 36.99993 113.5 924.5722 36.29792 88 924.6329 36.28598 113.5 931.5239 34.19749 88 931.5532 34.18553 88 937.9393 30.77456 113.5 937.9476 30.76877 88 943.5462 26.17773 113.5 943.5797 26.14408 88 948.135 20.60119 113.5 948.1718 20.54592 88 951.5598 14.21501 113.5 951.5842 14.15581 88 953.6827 7.249401 104.0454 914.2536 39.68529 106.5077 909.9235 39.09187 108.2138 909.1374 39.0626 107.5186 907.7692 38.61272 108.3545 905.6569 38.01901 109.5875 905.4813 38.07835 109.4121 901.6524 36.53771 110.4867 901.7111 36.66928 109.6442 897.8207 34.63853 110.7325 897.8375 34.76134 109.1199 894.2499 32.37365 108.92 890.7199 29.69451 109.1199 894.2499 32.37365 107.9203 891.098 29.89556 110.2434 894.0215 32.34703 110.2434 894.0215 32.34703 107.8944 891.0465 29.85075 106.7197 887.6365 26.56901 105.9922 887.8729 26.75869 104.5927 884.4688 22.63325 105.9922 887.8729 26.75869 103.654 884.7097 22.83897 106.7197 887.6365 26.56901 102.4367 881.8693 18.37834 102.6456 883.4823 20.99572 101.4003 882.0893 18.58894 100.4164 879.7918 13.75799 99.77521 880.4518 15.12369 99.30154 880.0165 14.02792 98.6483 878.2791 8.754967 97.5194 878.5509 9.303995 97.43226 878.4871 9.037449 97.55833 877.3627 3.408288 96.03976 877.6006 3.638149 97.27339 877.2043 -4.86e-4 96.03976 877.6006 3.638149 95.70199 877.4297 -4.89e-4 97.55833 877.3627 3.408288 97.55834 877.3627 -3.408287 96.03975 877.6006 -3.638136 98.64846 878.2792 -8.755381 96.03975 877.6006 -3.638136 97.43238 878.4873 -9.038298 97.55834 877.3627 -3.408287 100.4167 879.7919 -13.75876 97.51562 878.5482 -9.292932 99.30181 880.0167 -14.02849 102.4371 881.8697 -18.37843 99.76918 880.4461 -15.11001 101.3999 882.0889 -18.58828 104.5925 884.4688 -22.63338 102.6405 883.4763 -20.98622 103.6535 884.7092 -22.8383 106.7192 887.6366 -26.56913 105.9922 887.8729 -26.75868 105.9922 887.8729 -26.75868 106.7192 887.6366 -26.56913 106.8839 912.1497 39.63427 109.9508 907.6934 39.11383 108.6615 909.6772 39.3784 110.9923 904.2905 38.04304 111.6361 900.7733 36.61067 111.7561 897.1754 34.76902 110.6113 893.9127 32.38625 109.9017 890.2551 29.72365 110.6113 893.9127 32.38625 108.6615 909.6772 39.3784 109.4861 909.9299 39.69956 109.9508 907.6934 39.11383 110.2154 907.2576 39.04971 110.2154 907.2576 39.04971 112.0246 903.8109 38.45888 111.519 904.8784 38.65748 112.5987 900.3513 37.01211 111.317 893.6512 32.53569 112.695 896.7192 35.14743 111.317 893.6512 32.53569 111.9755 893.334 32.77811 110.7932 889.671 29.93539 111.9755 893.334 32.77811 111.4314 907.1287 39.52038 111.519 904.8784 38.65748 112.0246 903.8109 38.45888 113.3759 900.298 37.79 113.1306 904.0905 39.28195 113.3759 900.298 37.79 113.5037 896.4784 35.86691 112.2793 893.1583 32.9313 111.5524 888.9952 30.31974 112.2793 893.1583 32.9313 113.0778 892.5703 33.51158 112.2025 888.447 30.9856 113.0778 892.5703 33.51158 112.1883 888.4014 30.95501 112.1458 888.2664 30.86387 114.7938 897.336 37.92744 113.3759 900.298 37.79 113.5037 896.4784 35.86691 114.4642 900.7904 38.99851 117.1597 894.9561 39.10882 114.4642 900.7904 38.99851 113.3759 900.298 37.79 114.7938 897.336 37.92744 114.5383 893.6802 35.84999 113.0778 892.5703 33.51158 116.0405 894.5249 38.02727 114.4817 890.0892 34.56788 113.0778 892.5703 33.51158 112.2025 888.447 30.9856 114.5383 893.6802 35.84999 116.0405 894.5249 38.02727 118.2263 891.7055 39.14393 117.1597 894.9561 39.10882 116.0405 894.5249 38.02727 117.047 891.4428 38.09558 117.047 891.4428 38.09558 116.0405 894.5249 38.02727 118.733 888.2786 39.19237 117.5169 888.1917 38.14723 115.1117 887.1223 35.03686 117.5169 888.1917 38.14723 119.3378 876.4132 39.4775 118.733 888.2786 39.19237 117.5169 888.1917 38.14723 117.9536 882.6248 38.41403 115.6422 880.3132 35.70993 117.9536 882.6248 38.41403 117.5169 888.1917 38.14723 115.1117 887.1223 35.03686 120.3389 876.4494 39.92034 120.293 864.858 40.18021 118.9434 870.7203 39.29234 119.517 864.8443 39.8225 116.0766 867.6139 37.0975 119.517 864.8443 39.8225 118.9434 870.7203 39.29234 115.9881 861.3197 37.80705 118.458 876.3988 38.82935 115.968 873.9439 36.39864 118.458 876.3988 38.82935 118.4157 876.9213 38.7909 118.4157 876.9213 38.7909 121.1195 864.8674 40.40108 110.4945 850.2931 36.19426 109.3784 844.4636 37.18497 114.5769 848.2745 39.03366 111.3991 856.0792 35.21489 112.0794 861.8504 34.24337 112.5068 867.5935 33.27953 112.6529 873.2938 32.32313 112.4944 878.9932 31.3738 113.8022 886.4208 33.15901 113.8022 886.4208 33.15901 104.7039 846.5903 32.9898 102.5874 840.3643 34.1744 107.571 843.283 36.45324 107.571 843.283 36.45324 106.4052 852.6566 31.75639 107.7911 858.6533 30.52978 108.8173 864.5587 29.30983 109.44 870.354 28.09634 109.6175 876.0458 26.88902 112.0408 885.3116 30.40624 109.3525 882.194 25.65145 112.1458 888.2664 30.86387 112.0408 885.3116 30.40624 110.4696 884.1159 27.70077 110.4696 884.1159 27.70077 112.1883 888.4014 30.95501 102.5874 840.3643 34.1744 98.01316 842.9539 28.641 94.91403 836.5607 29.87435 99.68231 838.837 32.66625 99.68231 838.837 32.66625 100.6368 849.1633 27.33573 102.8794 855.2555 26.0357 104.6844 861.2012 24.74083 105.996 866.9783 23.45096 106.7564 872.5477 22.16591 107.3771 879.0043 21.75802 106.9483 878.359 20.8624 110.1837 884.7299 27.29786 109.3525 882.194 25.65145 110.4696 884.1159 27.70077 108.2686 880.4038 23.56022 108.2686 880.4038 23.56022 110.1837 884.7299 27.29786 110.4696 884.1159 27.70077 94.91403 836.5607 29.87435 90.45492 839.4878 22.63902 86.36159 832.9214 23.79931 92.4546 835.4714 28.27164 93.09426 833.2969 30.76972 92.4546 835.4714 28.27164 94.14219 845.905 21.46337 97.38893 852.1607 20.29144 100.1268 858.219 19.12316 102.2883 864.0516 17.95844 103.8043 869.6134 16.79716 104.6395 875.2005 15.63907 108.0235 881.2662 23.18103 106.9483 878.359 20.8624 107.3771 879.0043 21.75802 106.1449 877.2017 19.12797 106.1449 877.2017 19.12797 86.36159 832.9214 23.79931 82.47654 836.0637 14.81732 77.17958 829.16 15.63231 85.41413 832.5347 23.03966 85.30255 830.4732 25.18547 85.41413 832.5347 23.03966 87.32357 842.7827 13.98019 91.6717 849.2971 13.14529 95.4411 855.5649 12.31257 98.55252 861.5502 11.48199 100.9262 867.2117 10.65348 102.492 872.6718 9.812276 105.9774 878.2146 18.76206 104.6395 875.2005 15.63907 104.1054 874.5336 14.30616 104.1054 874.5336 14.30616 78.489 829.7063 16.91217 77.76358 827.7597 18.61957 78.489 829.7063 16.91217 77.17958 829.16 15.63231 77.21061 833.2871 9.398514 71.80095 826.8313 9.935777 71.80095 826.8313 9.935777 80.52293 837.3721 9.063443 84.27124 842.2046 8.600518 91.41178 852.3514 7.303383 88.19352 847.5847 7.977268 93.97883 856.4866 6.606506 98.9223 866.0517 4.445541 96.02964 860.1058 5.900594 102.3887 872.5633 9.489767 100.8417 871.0832 3.450076 102.2562 872.4262 9.06752 104.0461 875.6523 13.97244 102.492 872.6718 9.812276 102.3887 872.5633 9.489767 74.53226 832.1068 4.85441 71.80095 826.8313 9.935777 77.21061 833.2871 9.398514 70.6231 824.9868 11.19491 70.28833 825.9641 8.409552 70.6231 824.9868 11.19491 71.80095 826.8313 9.935777 70.28833 825.9641 8.409552 68.00643 824.6503 5.248205 80.52293 837.3721 9.063443 80.69789 839.431 4.536361 84.27124 842.2046 8.600518 86.23005 846.4628 4.143736 88.19352 847.5847 7.977268 91.41178 852.3514 7.303383 91.04735 853.1524 3.656289 93.97883 856.4866 6.606506 95.08218 859.4567 3.064887 96.02964 860.1058 5.900594 98.27246 865.3341 2.353588 98.9223 866.0517 4.445541 100.6049 870.892 1.745184 100.8417 871.0832 3.450076 102.3291 873.6525 8.780452 100.8417 871.0832 3.450076 102.2562 872.4262 9.06752 101.0593 872.6114 3.271139 100.6049 870.892 1.745184 100.8417 871.0832 3.450076 101.0593 872.6114 3.271139 92.04181 830.7607 32.61454 84.09829 828.2968 26.84037 76.4592 825.8682 20.10792 69.2611 823.3291 12.54675 69.2611 823.3291 12.54675 69.10845 825.2784 6.984041 67.63621 824.4355 4.525741 68.00643 824.6503 5.248205 68.26712 824.7983 5.710631 66.83929 823.9902 2.145108 66.62866 823.8676 0.756924 66.62174 823.8656 -0.606883 66.60063 823.8524 -0.005285978 67.08998 824.1286 -3.109051 68.61457 824.9974 -6.266973 68.01292 824.6517 -5.267594 67.97708 824.631 -5.20226 69.42745 825.462 -7.402983 69.42745 825.462 -7.402983 68.61457 824.9974 -6.266973 68.01292 824.6517 -5.267594 73.30205 831.3743 -0.004397988 67.97708 824.631 -5.20226 67.08998 824.1286 -3.109051 66.60063 823.8524 -0.005285978 66.62174 823.8656 -0.606883 66.83929 823.9902 2.145108 66.62866 823.8676 0.756924 67.63621 824.4355 4.525741 69.10845 825.2784 6.984041 68.26712 824.7983 5.710631 100.5243 870.8299 -4.62e-4 100.5243 870.8299 -4.62e-4 98.05286 865.127 -8.82e-4 94.69636 859.1605 -0.001473963 90.4718 852.7641 -0.002147853 85.44482 845.9691 -0.00287497 79.69321 838.8229 -0.003627896 100.7872 872.395 -4.67e-4 98.95037 876.6594 3.242929 99.78448 877.7719 8.545634 98.95037 876.6594 3.242929 99.82497 875.3803 -4.52e-4 100.0697 875.5527 3.160537 100.777 876.9995 8.44043 100.0697 875.5527 3.160537 98.69551 876.4974 -4.63e-4 100.546 873.9647 -4.53e-4 100.7964 874.1541 3.170622 101.5625 876.0121 8.445867 100.7964 874.1541 3.170622 102.0914 874.8721 8.561601 100.7964 874.1541 -3.17062 100.0697 875.5527 -3.160535 98.95037 876.6595 -3.242928 102.0915 874.8722 -8.561612 100.7964 874.1541 -3.17062 101.5625 876.0122 -8.44594 100.0697 875.5527 -3.160535 100.777 876.9995 -8.440592 98.95037 876.6595 -3.242928 99.78457 877.7719 -8.54591 107.4335 887.3129 26.46688 107.4335 887.3129 26.46688 105.468 884.044 22.49522 108.1155 886.9091 26.456 108.1155 886.9091 26.456 106.2781 883.4877 22.48302 108.7472 886.4359 26.5368 108.7472 886.4359 26.5368 106.9916 882.8217 22.59695 109.3118 885.9053 26.70771 109.3118 885.9053 26.70771 107.5811 882.0715 22.83261 109.7949 885.3314 26.96374 109.7949 885.3314 26.96374 105.5788 879.1519 18.43754 104.995 880.0233 18.23044 104.2533 880.7889 18.15005 103.3873 881.4139 18.20005 103.7155 876.7313 13.68568 103.151 877.7355 13.5151 102.3839 878.6103 13.46978 101.4556 879.3086 13.55216 103.7155 876.7312 -13.68572 103.1511 877.7354 -13.51526 102.384 878.6103 -13.47011 101.4558 879.3087 -13.5527 105.5795 879.1527 -18.43838 104.9957 880.0241 -18.23118 104.2539 880.7896 -18.15064 103.3878 881.4144 -18.20041 107.581 882.0714 -22.83279 106.9915 882.8216 -22.5971 106.2779 883.4877 -22.48316 105.4679 884.044 -22.49535 109.7952 885.3309 -26.9641 109.3119 885.9049 -26.70808 108.747 886.4357 -26.53711 108.1149 886.9092 -26.45622 107.4329 887.3131 -26.46705 109.7952 885.3309 -26.9641 109.3119 885.9049 -26.70808 108.747 886.4357 -26.53711 108.1149 886.9092 -26.45622 107.4329 887.3131 -26.46705 113.5 953.6906 7.209047 113.5 954.4 0 113.5 954.2182 -3.655726 113.5 953.6827 -7.249401 113.5 951.5842 14.15581 113.5 951.5598 -14.21501 113.5 948.1718 20.54592 113.5 948.135 -20.60119 113.5 943.5797 26.14408 113.5 943.5462 -26.17773 113.5 937.9476 30.76877 113.5 937.9393 -30.77456 113.5 931.5532 -34.18553 113.5 931.5239 34.19749 113.5 924.6329 -36.28598 113.5 924.5722 36.29792 113.5 917.4362 -36.99993 113.5 917.3638 36.99993 113.5 910.2279 -36.29792 113.5 910.1671 36.28598 113.5 903.2761 -34.19749 113.5 903.2468 34.18553 113.5 896.8524 -30.76877 113.5 891.2538 26.17773 113.5 891.2203 -26.14408 113.5 896.8607 30.77456 113.5 886.6651 20.60119 113.5 886.6282 -20.54592 113.5 883.2402 14.21501 113.5 883.2158 -14.15581 113.5 881.1173 7.249401 113.5 881.1094 -7.209047 113.5 880.5818 3.655726 113.5 880.4 0 57.38745 799.3978 13.21573 57.38745 799.3978 -13.21573 40.07063 791.3596 -36.79175 59.70998 800.4758 9.193468 59.70998 800.4758 -9.193468 40.07063 791.3596 36.79175 36.07163 789.5033 -41.17658 31.32223 787.2987 44.51751 31.32197 787.2986 -44.51765 36.07178 789.5034 41.17645 26.03849 784.8461 46.66659 26.0382 784.846 -46.66667 20.45866 782.256 47.5268 20.45846 782.2559 -47.52681 14.83479 779.6455 -47.05585 14.83479 779.6455 47.05585 -8.166404 768.9687 -42.35595 61.14601 801.1425 4.713194 61.14601 801.1425 -4.713194 61.6318 801.3679 0 -8.166404 768.9687 42.35595 -15.13636 765.7333 -40.17865 -15.10909 765.746 40.19025 -18.46122 764.19 -38.56038 -21.58094 762.7419 36.64815 -21.62717 762.7204 -36.61668 -27.34307 760.0672 31.8611 -27.39353 760.0438 -31.81053 -32.19611 757.8145 26.00253 -32.23561 757.7962 -25.94529 -36.01155 756.0434 19.2237 -36.03159 756.0341 -19.17983 -38.62562 754.83 11.79207 -38.63088 754.8276 -11.77211 -39.95166 754.2145 3.972513 -39.95194 754.2144 -3.969198 45.42438 770.7373 49.62154 51.61288 770.7397 47.44138 57.65616 770.7393 44.80319 63.47176 770.7366 41.72792 84.09385 793.6874 40.5233 68.97576 770.7321 38.24304 90.44699 793.6814 36.49505 74.08457 770.7263 34.37895 96.26206 793.6743 32.07794 78.71775 770.7197 30.17115 101.4233 793.6668 27.3146 82.79743 770.7127 25.65736 105.8247 793.6594 22.25154 86.25354 770.7059 20.879 109.3676 793.6526 16.93737 89.02076 770.6998 15.87892 111.9705 793.647 11.42291 91.04574 770.6948 10.70202 -47 750.4 0 47 750.4 0 46.81725 750.4 4.129784 -46.81725 750.4 -4.129784 46.28787 750.4 -8.149951 -46.28787 750.4 8.149951 46.27937 750.4 8.198644 -44.16648 750.4 16.07183 44.1421 750.4 16.13909 -40.70402 750.4 23.49939 40.6702 750.4 23.5582 -36.0195 750.4 30.1906 35.99309 750.4 30.22239 -33.23096 750.4 33.23587 30.19856 750.4 36.01375 -30.19496 750.4 36.01652 23.49571 750.4 40.70508 -23.44416 750.4 40.73464 16.09428 750.4 44.15781 -26.91589 750.4 38.52895 -15.9915 750.4 44.19508 8.211176 750.4 46.27641 -8.070898 750.4 46.30111 0.07673799 750.4 46.99917 -46.27937 750.4 -8.198644 44.16648 750.4 -16.07183 -44.1421 750.4 -16.13909 40.70402 750.4 -23.49939 -40.6702 750.4 -23.5582 36.0195 750.4 -30.1906 -35.99309 750.4 -30.22239 33.23096 750.4 -33.23587 -30.19856 750.4 -36.01375 30.19496 750.4 -36.01652 -23.49571 750.4 -40.70508 23.44416 750.4 -40.73464 -16.09428 750.4 -44.15781 26.91589 750.4 -38.52895 15.9915 750.4 -44.19508 -8.211176 750.4 -46.27641 8.070898 750.4 -46.30111 -0.07673799 750.4 -46.99917 129.3591 870.941 9.639678 129.3591 870.941 -9.639678 128.4948 881.9233 -24.8023 129.5146 868.9653 6.033399 129.5146 868.9654 -6.033578 128.4948 881.9233 24.8023 128.2443 885.1062 -28.39206 128.2443 885.1062 28.39206 127.9435 888.9289 -31.28688 127.9435 888.9289 31.28688 127.6039 893.2432 -33.37425 127.6039 893.2432 33.37425 127.2389 897.8814 -34.57314 127.2389 897.8814 34.57314 126.8625 902.6635 -34.83712 126.8625 902.6635 34.83712 125.7858 916.3447 -34.23794 129.5947 867.9478 2.053213 129.5947 867.9478 -2.0535 125.7858 916.3447 34.23794 125.243 923.2413 -33.22167 125.2457 923.207 33.23033 124.7319 929.7355 30.84803 124.7276 929.7897 -30.82175 124.2675 935.6369 27.20138 124.2632 935.6913 -27.15947 123.8705 940.6809 22.4328 123.8676 940.718 -22.3899 123.5555 944.6834 16.70721 123.3385 947.4402 -10.29736 123.3384 947.4419 10.29131 123.5545 944.6964 -16.68411 123.2282 948.8416 -3.490015 123.228 948.8441 3.464874 -42.89738 756.9 17.64657 -40.97083 756.9224 21.14017 -41.0405 756.9 21.01015 -41.0405 756.9 21.01015 -40.97083 756.9224 21.14017 -41.28938 757.1459 20.53412 -41.0405 756.9 21.01015 -41.06112 757.0635 20.95128 -40.95819 756.9003 21.16058 -41.58155 757.197 19.9889 -41.94689 757.2196 19.28848 -42.39703 757.2106 18.3952 -42.78251 756.9 17.60024 -42.89738 756.9 17.64657 -41.0405 756.9 21.01015 -40.8898 756.9448 21.26379 -40.8898 756.9448 21.26379 -41.06112 757.0635 20.95128 -40.8898 756.9448 21.26379 -40.87191 756.9262 21.29193 -40.86539 756.9 21.30298 -41.28938 757.1459 20.53412 -41.58155 757.197 19.9889 -41.94689 757.2196 19.28848 -42.79073 757.1798 17.58454 -42.39703 757.2106 18.3952 -42.79073 757.1798 17.58454 -44.39982 756.9 13.93945 31.48102 799.5927 -29.08545 44.53815 808.09 -22.45329 37.78889 801.6061 -33.3843 41.03539 794.5636 -33.19347 37.78889 801.6061 -33.3843 44.53815 808.09 -22.45329 36.85235 800.5808 -34.9665 39.38906 791.815 -36.44732 36.85235 800.5808 -34.9665 37.78889 801.6061 -33.3843 41.03539 794.5636 -33.19347 30.40827 801.6179 -17.5638 50.77352 812.9079 -12.96402 51.14352 797.2712 -20.31834 50.77352 812.9079 -12.96402 42.88395 795.4217 -30.65461 44.72676 796.2774 -28.12517 45.46254 794.6342 -28.10537 29.86931 802.6354 -5.872993 52.85843 814.386 -9.014695 56.63496 799.8202 -12.80564 50.77352 812.9079 -12.96402 52.85843 814.386 -9.014695 56.63496 799.8202 -12.80564 54.13798 815.3225 -4.606662 59.22314 801.0216 -8.073531 54.13798 815.3225 -4.606662 29.86935 802.6354 5.874382 54.56629 815.6407 0 60.56382 801.6439 -2.759381 54.56629 815.6407 0 54.138 815.3225 4.606548 60.56385 801.6439 2.759177 54.138 815.3225 4.606548 60.73397 801.7229 -1.07e-4 52.85852 814.3861 9.01449 59.22319 801.0216 8.073405 52.85852 814.3861 9.01449 30.40836 801.6177 17.56518 50.77356 812.9078 12.96405 50.77356 812.9078 12.96405 46.0414 809.3446 20.11712 56.63496 799.8202 12.80564 50.77356 812.9078 12.96405 46.0414 809.3446 20.11712 56.63496 799.8202 12.80564 31.48118 799.5924 29.0868 40.99219 804.8685 28.10014 51.14158 797.2703 20.32099 40.99219 804.8685 28.10014 38.40623 802.2627 32.35152 44.72673 796.2774 28.12514 40.99219 804.8685 28.10014 38.40623 802.2627 32.35152 44.72673 796.2774 28.12514 33.13495 796.5799 40.40057 35.93107 799.5392 36.54001 41.03554 794.5634 33.19351 35.93107 799.5392 36.54001 42.87622 795.4181 30.66521 39.38906 791.815 36.44732 35.93107 799.5392 36.54001 33.13495 796.5799 40.40057 41.77116 792.9207 33.17374 39.38906 791.815 36.44732 7.704969 784.9572 34.83233 9.617717 781.4716 45.91453 32.57117 796.0337 41.00528 35.47215 789.9968 40.78309 32.57117 796.0337 41.00528 37.53174 790.9528 38.7372 6.323956 787.4714 23.41057 5.489964 788.9897 11.7622 5.211067 789.4974 -4.00001e-6 5.489965 788.9897 -11.76221 6.323956 787.4714 -23.41057 35.93106 799.5392 -36.54003 33.13368 796.5786 -40.4023 7.704971 784.9572 -34.83234 37.53174 790.9528 -38.7372 33.13368 796.5786 -40.4023 35.93106 799.5392 -36.54003 32.56385 796.0266 -41.01319 35.47215 789.9968 -40.78309 32.56385 796.0266 -41.01319 35.93106 799.5392 -36.54003 39.38906 791.815 -36.44732 30.59902 794.2283 42.79674 33.22443 788.9534 42.5735 30.59902 794.2283 42.79674 28.43647 792.4105 44.29981 30.81453 787.8348 44.08666 28.43647 792.4105 44.29981 23.702 788.919 46.35472 25.63339 785.4298 46.21215 23.702 788.919 46.35472 13.29794 783.1301 46.66258 18.57328 785.774 47.13228 20.1499 782.8844 47.06884 18.57328 785.774 47.13228 13.29794 783.1301 46.66258 14.6151 780.3153 46.60961 13.29794 783.1301 46.66258 9.617717 781.4716 45.91453 14.6151 780.3153 46.60961 1.752901 777.8725 44.3115 3.141953 774.9896 44.26323 1.752901 777.8725 44.3115 -17.41696 772.7709 28.95494 -15.28066 770.0112 40.3613 -9.7199 772.4884 41.96263 -15.75463 769.8154 40.18149 -18.54039 774.7445 17.48425 -19.1048 775.7361 5.846706 -19.1048 775.7361 -5.846629 -18.54039 774.7446 -17.48417 -17.41696 772.7709 -28.95486 28.44293 792.4157 -44.29595 9.617804 781.4716 -45.91455 -15.75464 769.8154 -40.18149 30.59641 794.226 -42.7989 23.73148 788.9389 -46.34629 13.29764 783.13 -46.66255 3.141956 774.9896 -44.26323 9.617804 781.4716 -45.91455 13.29764 783.13 -46.66255 -15.27973 770.0116 -40.36164 1.752893 777.8725 -44.31147 1.752893 777.8725 -44.31147 18.61113 785.7949 -47.13139 14.6151 780.3153 -46.60961 13.29764 783.13 -46.66255 18.61113 785.7949 -47.13139 14.6151 780.3153 -46.60961 20.1499 782.8844 -47.06884 23.73148 788.9389 -46.34629 25.63339 785.4298 -46.21215 28.44293 792.4157 -44.29595 30.81453 787.8348 -44.08667 30.59641 794.226 -42.7989 33.22443 788.9534 -42.5735 -8.38594 769.6385 41.90864 -9.7199 772.4884 41.96263 -15.28066 770.0112 40.3613 -9.7199 772.4884 41.96263 -8.38594 769.6385 41.90864 -13.90236 767.0779 40.30782 -15.75463 769.8154 40.18149 -20.74854 767.8887 37.85063 -19.91469 766.2717 37.85287 -20.74854 767.8887 37.85063 -36.69028 763.2447 22.71041 -25.99024 766.1235 34.43253 -29.02804 765.2124 31.89563 -31.84337 764.436 29.08086 -40.30181 762.4692 15.57123 -43.28004 761.8969 0 -42.53479 762.0349 7.876314 -42.53423 762.035 -7.879176 -36.68834 763.2451 -22.71351 -40.30046 762.4695 -15.57466 -31.84158 764.4365 -29.08282 -13.90236 767.0779 -40.30782 -15.75464 769.8154 -40.18149 -15.27973 770.0116 -40.36164 -25.99024 766.1235 -34.43252 -20.74764 767.889 -37.85113 -19.91469 766.2717 -37.85287 -20.74764 767.889 -37.85113 -19.14559 764.6441 -37.82394 -9.719532 772.4885 -41.96273 -9.719532 772.4885 -41.96273 -8.385946 769.6385 -41.90866 -9.719532 772.4885 -41.96273 -8.385946 769.6385 -41.90866 -22.67596 764.9895 36.10401 -25.99024 766.1235 34.43253 -24.15538 762.3186 34.38758 -25.99024 766.1235 34.43253 -29.02804 765.2124 31.89563 -25.45957 765.0406 34.42577 -24.92052 763.9479 34.41909 -25.45957 765.0406 34.42577 -29.54388 759.8173 29.10018 -31.84337 764.436 29.08086 -33.96741 757.764 22.76786 -36.69028 763.2447 22.71041 -35.7573 756.9332 19.28325 -40.30181 762.4692 15.57123 -39.24954 755.3121 7.967524 -42.53479 762.0349 7.876314 -37.24722 756.2416 15.61862 -39.75849 755.0759 4.009252 -43.28004 761.8969 0 -39.76028 755.075 -3.985903 -42.53423 762.035 -7.879176 -39.92901 754.9967 0.01457285 -39.25046 755.3117 -7.962072 -40.30046 762.4695 -15.57466 -37.23548 756.247 -15.65263 -36.68834 763.2451 -22.71351 -38.40585 755.7037 -11.86088 -33.96634 757.7645 -22.76986 -31.84158 764.4365 -29.08282 -29.55285 759.8132 -29.08981 -25.99024 766.1235 -34.43252 -25.45889 765.0408 -34.42483 -25.99024 766.1235 -34.43252 -25.45889 765.0408 -34.42483 -24.92052 763.9479 -34.41909 -23.89927 764.4634 -35.23015 -22.01105 765.2838 -36.55213 41.77116 792.9207 -33.17374 42.88395 795.4217 -30.65461 41.77116 792.9207 -33.17374 41.03539 794.5636 -33.19347 39.38906 791.815 36.44732 39.38906 791.815 -36.44732 41.77116 792.9207 -33.17374 37.53174 790.9528 38.7372 37.53174 790.9528 -38.7372 44.72676 796.2774 -28.12517 45.46254 794.6342 -28.10537 41.77116 792.9207 33.17374 45.46254 794.6342 -28.10537 45.46254 794.6342 28.10537 51.14352 797.2712 -20.31834 51.14158 797.2703 20.32099 56.63496 799.8202 -12.80564 56.63496 799.8202 12.80564 59.22314 801.0216 -8.073531 -21.70319 763.4569 36.2155 -21.70319 763.4569 -36.2155 -19.14559 764.6441 -37.82394 -22.01105 765.2838 -36.55213 -19.14559 764.6441 -37.82394 -21.70319 763.4569 -36.2155 -19.14558 764.6441 37.82392 -13.90236 767.0779 -40.30782 -19.91469 766.2717 -37.85287 -24.15538 762.3186 34.38758 -24.15538 762.3186 -34.38758 -23.89927 764.4634 -35.23015 -24.15538 762.3186 -34.38758 -29.54388 759.8173 29.10018 -29.55285 759.8132 -29.08981 -24.92052 763.9479 -34.41909 -24.15538 762.3186 -34.38758 -24.92052 763.9479 -34.41909 -33.96741 757.764 22.76786 -33.96634 757.7645 -22.76986 -35.7573 756.9332 19.28325 -37.23548 756.247 -15.65263 -37.24722 756.2416 15.61862 -38.40585 755.7037 -11.86088 -39.24954 755.3121 7.967524 -39.25046 755.3117 -7.962072 -39.75849 755.0759 4.009252 -39.76028 755.075 -3.985903 -39.92901 754.9967 0.01457285 -22.67596 764.9895 36.10401 -24.15538 762.3186 34.38758 -21.70319 763.4569 36.2155 -24.92052 763.9479 34.41909 -24.92052 763.9479 34.41909 -19.14558 764.6441 37.82392 -13.90236 767.0779 40.30782 -19.14558 764.6441 37.82392 -19.91469 766.2717 37.85287 -8.385946 769.6385 -41.90866 -8.38594 769.6385 41.90864 3.141956 774.9896 -44.26323 3.141953 774.9896 44.26323 14.6151 780.3153 -46.60961 14.6151 780.3153 46.60961 20.1499 782.8844 -47.06884 20.1499 782.8844 47.06884 25.63339 785.4298 -46.21215 25.63339 785.4298 46.21215 30.81453 787.8348 -44.08667 30.81453 787.8348 44.08666 33.22443 788.9534 -42.5735 33.22443 788.9534 42.5735 35.47215 789.9968 -40.78309 35.47215 789.9968 40.78309 41.03554 794.5634 33.19351 41.77116 792.9207 33.17374 45.46254 794.6342 28.10537 45.46254 794.6342 28.10537 42.87622 795.4181 30.66521 44.72673 796.2774 28.12514 59.22319 801.0216 8.073405 60.56382 801.6439 -2.759381 60.56385 801.6439 2.759177 60.73397 801.7229 -1.07e-4 129.5225 908.555 34.19205 133.2455 887.0908 29.22579 134.8339 883.0313 24.9576 130.9351 882.7795 24.91705 134.8339 883.0313 24.9576 133.2455 887.0908 29.22579 132.4382 908.8385 24.6671 137.0248 877.561 17.21489 130.9607 882.455 24.46547 137.0248 877.561 17.21489 134.8339 883.0313 24.9576 130.9479 882.6173 24.69136 130.9351 882.7795 24.91705 131.8178 891.8647 32.23703 128.464 891.237 31.99841 131.8178 891.8647 32.23703 129.0062 884.3472 26.89677 128.8368 886.4996 28.92773 130.6748 897.2774 34.01597 128.2532 893.9151 33.11112 130.6748 897.2774 34.01597 129.9804 902.8915 34.43898 127.7966 899.7173 34.33748 129.9804 902.8915 34.43898 128.0279 896.7782 33.90766 127.5619 902.6992 34.39526 129.9804 902.8915 34.43898 129.5225 908.555 34.19205 127.5619 902.6992 34.39526 129.427 909.7293 34.14068 129.427 909.7293 34.14068 134.3982 909.0289 14.89846 129.8298 940.5786 22.47744 128.5646 922.5021 33.05109 128.8677 916.5698 33.84029 128.5497 925.3995 32.26696 128.6178 928.2351 31.22531 128.9633 933.5783 28.422 129.511 938.3998 24.689 138.8933 870.6928 7.24944 135.383 909.1245 4.982569 130.8626 946.2828 13.77843 138.5967 871.9926 9.404567 130.1594 942.5803 20.04078 130.533 944.6217 16.96953 139.1229 869.7482 -4.925337 135.383 909.1245 -4.982569 131.5155 949.2716 -0.001697957 139.2664 869.1759 -2.491409 139.3153 868.9838 0.001924932 139.2662 869.1765 2.495124 139.1226 869.7492 4.928397 131.344 948.5177 7.030491 138.597 871.9926 -9.404582 134.3982 909.0289 -14.89846 131.3437 948.5166 -7.035818 138.8934 870.6921 -7.248075 137.0242 877.5613 -17.21537 132.4382 908.8385 -24.6671 130.5319 944.6163 -16.97867 130.8618 946.2789 -13.78698 130.6754 897.2741 -34.0153 129.5225 908.555 -34.19205 129.5098 938.3914 -24.69671 131.8188 891.8608 -32.23521 133.2462 887.0888 -29.22415 134.8339 883.0325 -24.95916 130.1581 942.5731 -20.05053 129.8285 940.5707 -22.48623 129.9804 902.8915 -34.43898 126.4852 916.3804 -33.79704 129.5225 908.555 -34.19205 129.9804 902.8915 -34.43898 128.9626 933.57 -28.42729 128.6176 928.2281 -31.22821 128.5496 925.3937 -32.26878 128.5647 922.498 -33.05202 129.427 909.7293 -34.14068 128.8677 916.5698 -33.84029 129.427 909.7293 -34.14068 127.5619 902.6992 -34.39526 129.9804 902.8915 -34.43898 130.6754 897.2741 -34.0153 127.5619 902.6992 -34.39526 128.0281 896.776 -33.90715 131.8188 891.8608 -32.23521 127.7967 899.7162 -34.33739 128.4641 891.2354 -31.99762 133.2462 887.0888 -29.22415 128.2534 893.9126 -33.1103 128.8368 886.4993 -28.92748 134.8339 883.0325 -24.95916 130.9351 882.7806 -24.91856 134.8339 883.0325 -24.95916 137.0242 877.5613 -17.21537 129.0062 884.3471 -26.89663 130.9351 882.7806 -24.91856 129.5896 876.9345 -16.93554 138.597 871.9926 -9.404582 129.1644 882.3372 -24.44795 130.9608 882.4547 -24.465 130.9479 882.6176 -24.69167 130.1239 870.1461 -7.192123 138.597 871.9926 -9.404582 138.8934 870.6921 -7.248075 130.0221 871.4396 -9.316603 130.0221 871.4396 -9.316603 130.1983 869.2001 -4.893514 139.1229 869.7482 -4.925337 130.2437 868.6237 -2.476687 139.2664 869.1759 -2.491409 130.2589 868.4301 -6.6e-5 139.3153 868.9838 0.001924932 139.2662 869.1765 2.495124 130.2437 868.6237 2.476565 139.1226 869.7492 4.928397 130.1983 869.2001 4.89342 138.8933 870.6928 7.24944 130.1239 870.1461 7.192072 138.5967 871.9926 9.404567 130.0221 871.4396 9.316603 138.5967 871.9926 9.404567 130.0221 871.4396 9.316603 129.5896 876.9346 16.93576 126.4852 916.3804 33.79696 128.8677 916.5698 33.84029 128.5646 922.5021 33.05109 128.8677 916.5698 33.84029 126.4852 916.3804 33.79696 126.0141 922.3656 32.98859 128.5497 925.3995 32.26696 126.2481 919.3926 33.52805 125.7847 925.281 32.18224 128.6178 928.2351 31.22531 125.5616 928.1154 31.11446 128.9633 933.5783 28.422 125.1424 933.4423 28.23228 129.511 938.3998 24.689 125.3469 930.8438 29.79392 126.5639 938.3319 24.4605 129.8298 940.5786 22.47744 124.9497 935.8904 26.44224 126.426 940.0753 22.65181 130.1594 942.5803 20.04078 126.2572 942.218 19.99868 130.1594 942.5803 20.04078 130.533 944.6217 16.96953 126.2572 942.218 19.99868 124.4387 942.383 19.51665 130.8626 946.2828 13.77843 126.2307 942.5535 19.52923 126.2441 942.3865 19.76503 124.174 945.7467 13.50592 131.344 948.5177 7.030491 124.0096 947.8353 6.904347 131.5155 949.2716 -0.001697957 124.0096 947.8348 -6.906694 131.3437 948.5166 -7.035818 123.9539 948.5432 -0.001346886 124.174 945.7461 -13.50729 130.8618 946.2789 -13.78698 130.5319 944.6163 -16.97867 126.2307 942.5535 -19.52923 130.1581 942.5731 -20.05053 126.3847 940.9583 -21.62769 130.1581 942.5731 -20.05053 129.8285 940.5707 -22.48623 126.2577 942.2113 -20.00864 126.2436 942.3893 -19.7612 126.2577 942.2113 -20.00864 126.421 939.7194 -23.03985 129.5098 938.3914 -24.69671 124.9497 935.8904 -26.44225 128.9626 933.57 -28.42729 124.7701 938.1724 -24.43412 126.5639 938.3319 -24.4605 126.4641 938.8951 -23.89959 125.3469 930.8437 -29.79393 128.6176 928.2281 -31.22821 125.1424 933.4422 -28.23229 125.7847 925.281 -32.18225 128.5496 925.3937 -32.26878 125.5616 928.1154 -31.11447 126.0141 922.3656 -32.9886 128.5647 922.498 -33.05202 126.2481 919.3926 -33.52807 128.8677 916.5698 -33.84029 128.8677 916.5698 -33.84029 126.4852 916.3804 -33.79704 130.9479 882.6173 24.69136 129.1644 882.3375 24.44831 130.9607 882.455 24.46547 129.1644 882.3375 24.44831 129.1644 882.3372 -24.44795 129.5896 876.9346 16.93576 129.1644 882.3375 24.44831 129.0062 884.3471 -26.89663 129.0062 884.3472 26.89677 130.0221 871.4396 -9.316603 130.0221 871.4396 9.316603 130.1239 870.1461 -7.192123 130.1239 870.1461 7.192072 129.5896 876.9345 -16.93554 128.8368 886.4993 -28.92748 128.8368 886.4996 28.92773 128.4641 891.2354 -31.99762 128.464 891.237 31.99841 128.2534 893.9126 -33.1103 128.2532 893.9151 33.11112 128.0281 896.776 -33.90715 128.0279 896.7782 33.90766 127.7967 899.7162 -34.33739 127.7966 899.7173 34.33748 127.5619 902.6992 34.39526 127.5619 902.6992 -34.39526 126.4852 916.3804 33.79696 124.6007 940.3251 22.159 124.6002 940.3315 -22.1516 124.7701 938.1724 -24.43412 125.6737 938.2549 -24.44556 124.7701 938.1724 -24.43412 124.6002 940.3315 -22.1516 124.7701 938.1724 24.43411 124.9497 935.8904 -26.44225 125.6737 938.2549 -24.44556 124.4947 941.6719 20.49196 124.4945 941.6737 -20.48963 126.3847 940.9583 -21.62769 124.4945 941.6737 -20.48963 126.421 939.7194 -23.03985 126.4641 938.8951 -23.89959 124.4387 942.383 19.51665 124.4387 942.383 -19.51665 126.2577 942.2113 -20.00864 124.4387 942.383 -19.51665 124.174 945.7467 13.50592 124.174 945.7461 -13.50729 124.4387 942.383 -19.51665 126.2436 942.3893 -19.7612 125.3432 942.4669 -19.52603 125.3432 942.4669 -19.52603 124.0096 947.8348 -6.906694 124.0096 947.8353 6.904347 123.9539 948.5432 -0.001346886 125.3433 942.4669 19.52602 124.4387 942.383 19.51665 124.4947 941.6719 20.49196 125.3433 942.4669 19.52602 126.2572 942.218 19.99868 124.6007 940.3251 22.159 126.2441 942.3865 19.76503 126.426 940.0753 22.65181 124.7701 938.1724 24.43411 124.9497 935.8904 26.44224 124.7701 938.1724 24.43411 125.6736 938.2549 24.44556 125.6736 938.2549 24.44556 125.1424 933.4422 -28.23229 125.1424 933.4423 28.23228 125.3469 930.8437 -29.79393 125.3469 930.8438 29.79392 125.5616 928.1154 -31.11447 125.5616 928.1154 31.11446 125.7847 925.281 -32.18225 125.7847 925.281 32.18224 126.0141 922.3656 -32.9886 126.0141 922.3656 32.98859 126.2481 919.3926 -33.52807 126.2481 919.3926 33.52805 126.4852 916.3804 -33.79704 130.1983 869.2001 -4.893514 130.1983 869.2001 4.89342 130.2437 868.6237 -2.476687 130.2437 868.6237 2.476565 130.2589 868.4301 -6.6e-5 130.9479 882.6176 -24.69167 129.1644 882.3372 -24.44795 130.9608 882.4547 -24.465 126.5639 938.3319 -24.4605 126.2307 942.5535 19.52923 126.2307 942.5535 -19.52923 126.5639 938.3319 24.4605 + + + + + + + + + + 0.2495893 -0.02411049 -0.9680516 0.2496176 -0.02157717 -0.9681041 0.3258497 -0.1670296 -0.9305499 0.2470508 -0.03909474 -0.9682136 0.3253685 -0.1688644 -0.9303871 0.2459835 -0.02841323 -0.9688576 0.3253955 -0.1666653 -0.9307742 0.5357152 -0.7905971 -0.2965897 0.4091377 -0.3202969 -0.8544099 0.4074681 -0.3440177 -0.8459442 0.4042566 -0.3344593 -0.8513011 0.4062696 -0.3183137 -0.8565171 0.3259488 -0.1700854 -0.9299615 0.07944035 0.2648724 -0.9610057 0.07855635 0.2683857 -0.9601031 0.06814879 0.2308757 -0.9705937 0.06451731 0.2563298 -0.9644339 -0.1002259 0.5241718 -0.8456943 -0.101293 0.5279504 -0.843213 -0.1184152 0.4772013 -0.8707795 -0.1247321 0.511716 -0.8500522 -0.2685385 0.7241903 -0.6351658 -0.2692403 0.7275774 -0.6309842 -0.2870646 0.6773456 -0.6773456 -0.3011058 0.7069243 -0.6399949 -0.3427556 0.7970572 -0.4972108 -0.3420938 0.7984529 -0.4954241 -0.3657124 0.7446703 -0.5583196 -0.3829913 0.7733684 -0.5051921 -0.3429453 0.7952108 -0.5000282 -0.4298971 0.8501806 -0.3039433 -0.4173819 0.844713 -0.3350408 -0.4173219 0.849934 -0.3216437 -0.4180555 0.842154 -0.3405972 -0.4753346 0.7652353 -0.4341338 -0.427511 0.8151031 -0.3909492 -0.4498228 0.8151378 -0.3649793 -0.4475904 0.7893718 -0.4201844 -0.4175039 0.8481922 -0.3259766 -0.2826987 0.7109738 -0.6438927 -0.3497748 0.7896409 -0.5041079 -0.2779417 0.718522 -0.6375536 -0.3430939 0.7829328 -0.518944 -0.4188745 0.8422046 -0.3394638 -0.1261657 0.5169622 -0.8466595 -0.111946 0.5173079 -0.848446 0.04266601 0.269913 -0.961939 0.06674623 0.257768 -0.9638987 0.2074667 -0.006744623 -0.9782189 0.2389006 -0.02877914 -0.9706175 0.3239934 -0.171183 -0.9304433 0.2871533 -0.1324524 -0.948683 0.318739 -0.1742932 -0.9316799 0.2871251 -0.141945 -0.9473177 0.4126224 -0.3371479 -0.8462116 0.3955903 -0.3230766 -0.8597267 0.4204008 -0.3410511 -0.8408017 0.3845741 -0.3097102 -0.8695874 0.3289639 -0.1298276 -0.9353756 0.4052633 0.04953247 -0.9128572 0.2881303 -0.0263074 -0.9572298 0.08996891 0.1035802 -0.9905436 0.1146589 0.06857562 -0.9910352 0.1579048 0.03247207 -0.9869204 0.2430253 -0.05536198 -0.9684389 0.1897671 0.0310378 -0.9813385 0.1950796 0.03509724 -0.9801594 0.1969699 0.03750789 -0.9796919 -0.03527998 0.03497475 -0.9987654 0.09576952 0.03357118 -0.9948374 0.08166909 0.03650081 -0.9959909 0.009186267 0.06891226 -0.9975804 -0.02298057 0.0620141 -0.9978108 0.009277641 0.2483301 -0.968631 0.3884207 0.03772199 -0.9207098 0.1591858 0.02996939 -0.9867937 0.3412035 0.001525938 -0.9399883 0.1142021 0.0207529 -0.9932408 0.1588211 0.01651078 -0.9871693 0.1626383 0.01275712 -0.9866034 0.3089134 -0.03561568 -0.9504231 0.1394715 0.004089534 -0.9902178 0.1904091 -0.01867771 -0.9815272 0.298658 -0.06387603 -0.9522202 0.2074702 -0.02807772 -0.9778383 0.3009752 -0.08838206 -0.9495276 0.1578739 -0.01687687 -0.9873151 0.2240068 -0.0512408 -0.9732397 0.3579913 -0.1633087 -0.9193326 0.1712104 -0.03369271 -0.9846583 0.238719 -0.07388627 -0.9682738 0.4163691 -0.269146 -0.8684453 0.3987065 -0.1667584 -0.9017897 0.2503215 -0.08331841 -0.9645711 0.2899014 -0.1303473 -0.9481387 0.3437936 -0.2573951 -0.9030802 0.3967508 -0.2933209 -0.8697998 0.1746 -0.1524431 -0.9727672 0.6203113 -0.1247336 -0.7743743 0.5673437 -0.05386555 -0.8217176 0.4588214 -0.08420169 -0.8845299 0.5248077 -0.1875403 -0.8303046 0.2207447 -0.06500571 -0.973163 0.5667414 -0.04193335 -0.8228279 0.4838186 0.02325552 -0.8748593 0.2273036 -0.01895213 -0.9736396 0.3945517 -0.02258414 -0.9185962 0.1926351 0.0187996 -0.9810904 0.1825962 0.01629722 -0.9830529 0.342945 0.02017319 -0.9391389 0.3600034 0.02548342 -0.932603 0.258099 0.019288 -0.9659259 0.4894967 0.0352801 -0.8712912 0.5116615 0.04092681 -0.8582119 0.5089345 -0.01162773 -0.8607268 0.3877176 -0.1820783 -0.9036164 0.1832677 -0.04602289 -0.9819852 0.2624967 -0.1008358 -0.9596498 0.3836831 -0.1984336 -0.9018933 0.1929739 -0.05643028 -0.9795799 0.2688409 -0.1183827 -0.955882 0.3848506 -0.2156811 -0.8974251 0.2822431 -0.1290969 -0.9506172 0.3894544 -0.2324946 -0.8912191 0.2034122 -0.06274801 -0.9770805 0.2927727 -0.1419762 -0.9455828 0.4320939 -0.2971675 -0.8514613 0.2113155 -0.06695926 -0.9751216 0.2922784 -0.1492368 -0.9446173 0.4421973 -0.3252465 -0.8358685 0.4364593 -0.3016546 -0.8476484 0.4400613 -0.3023266 -0.845544 0.3028769 -0.1568404 -0.9400355 0.4626785 -0.3538148 -0.8128615 0.6767133 -0.2085105 -0.7061038 0.5898196 -0.1926084 -0.7842288 0.4428004 -0.3569199 -0.8225181 0.5861237 -0.2965258 -0.7540104 0.4261719 -0.3142271 -0.8483153 0.4486662 -0.3157846 -0.8360494 0.2200414 -0.06787407 -0.9731264 0.3094014 -0.1630934 -0.9368411 0.4302256 -0.312514 -0.8469008 0.2264183 -0.06576782 -0.9718073 0.3157531 -0.1696264 -0.9335561 0.4200055 -0.3192005 -0.8495331 0.2334374 -0.06039649 -0.9704944 0.3210594 -0.1729509 -0.9311332 0.4167993 -0.3209694 -0.8504452 0.2405824 -0.05157732 -0.9692574 0.3236519 -0.1722481 -0.9303656 0.442281 -0.3629927 -0.8201366 0.4581863 -0.3797212 -0.8036649 0.4647102 -0.3838964 -0.7979148 0.4863595 -0.4072833 -0.7730296 0.5040518 -0.4261368 -0.7512252 0.5069258 -0.4277587 -0.7483641 0.4971828 -0.3924115 -0.7738363 0.5307635 -0.4537324 -0.7158332 0.7022508 -0.2439413 -0.6688321 0.6084998 -0.3178921 -0.7270989 0.5498984 -0.4749428 -0.6870526 0.5479471 -0.4743646 -0.6890082 0.7573693 -0.3180121 -0.5703159 0.6800622 -0.3553671 -0.6412721 0.6464925 -0.3895801 -0.6559535 0.731037 -0.3141997 -0.6056928 0.1785969 0.02652096 -0.9835649 0.08215659 0.0347914 -0.996012 0.174172 0.009888112 -0.9846656 0.1645871 0.02795505 -0.9859665 0.158485 0.02377426 -0.9870752 0.1671854 0.02987849 -0.9854727 -0.0032655 0.03628677 -0.9993361 0.02310317 0.02618569 -0.9993901 0.0810886 0.02780264 -0.9963191 -0.00350964 0.02670377 -0.9996373 0.2567896 0.01941025 -0.9662725 0.1376087 0.0175482 -0.9903313 0.1266235 0.01495432 -0.9918382 0.3093147 0.02963435 -0.9504979 0.2569125 0.02200448 -0.9661841 0.2749476 0.02349978 -0.9611721 0.3379094 0.03015303 -0.9406956 -0.3401331 0.03549343 -0.9397073 -0.3633012 0.03228932 -0.9311121 -0.4188456 0.03381526 -0.9074276 -0.5779337 0.1055033 -0.8092353 -0.5639443 0.05032706 -0.8242779 -0.4630987 0.05878001 -0.8843556 -0.5013043 0.006988823 -0.8652428 -0.3398582 0.0217294 -0.9402257 -0.4297399 0.02026468 -0.9027254 -0.5924319 0.01483213 -0.805484 -0.663978 0.07779371 -0.7436945 -0.6539111 0.034487 -0.7557852 -0.1683402 0.03323465 -0.9851686 -0.4834212 0.1265623 -0.8661906 -0.397448 0.02526962 -0.9172768 -0.1742933 0.03723299 -0.9839897 -0.1537528 0.05047774 -0.9868193 -0.1539089 0.05133348 -0.9867507 -0.3976023 0.02490353 -0.9172198 -0.1938252 0.1940693 -0.9616491 -0.1657196 0.0860033 -0.9824157 -0.09744632 0.05871802 -0.9935072 -0.08578866 0.02172946 -0.9960764 -0.1742013 0.02414035 -0.9844142 -0.3016809 0.01486277 -0.9532932 -0.5216319 -0.004181087 -0.8531605 -0.6788474 -0.007568836 -0.7342404 -0.6513212 -0.014741 -0.758659 -0.7976511 -0.01202458 -0.6029993 -0.785364 -0.03198462 -0.6182075 -0.764137 -0.01101738 -0.6449599 -0.5085991 -0.1102041 -0.8539217 -0.511466 -0.06491363 -0.8568482 -0.647741 -0.08401954 -0.7572137 -0.642275 -0.1401743 -0.7535477 -0.794415 -0.08069276 -0.6019914 -0.7618553 -0.1662696 -0.626044 -0.7699083 -0.1012628 -0.6300692 -0.7059971 -0.005340814 -0.7081946 -0.7771928 0.01211595 -0.6291459 -0.7504676 -0.01339793 -0.6607716 -0.5988171 0.001434385 -0.8008846 -0.718424 0.01355051 -0.6954736 -0.7317272 0.04623651 -0.6800277 -0.2226067 0.01367253 -0.9748125 0.02295053 0.01980704 -0.9995405 -0.05899298 0.02142423 -0.9980286 0.1013856 0.01382529 -0.9947511 -0.07126182 -0.01153618 -0.997391 -0.0627163 -0.002349913 -0.9980287 -0.2137865 -0.02288931 -0.9766122 0.08734637 0.01532071 -0.9960603 0.08890271 0.02261477 -0.9957836 -0.217847 -0.04443615 -0.9749708 0.83737 -0.02167779 -0.5462065 -0.5130823 -0.1559206 -0.8440589 -0.6422852 -0.1933112 -0.7416876 -0.7921566 -0.138252 -0.5944531 -0.7526359 -0.2196167 -0.6207316 -0.5344482 -0.2267559 -0.8142156 -0.4929435 -0.2168682 -0.8426001 -0.6235476 -0.2704654 -0.73351 -0.2959464 -0.09744834 -0.9502208 -0.7380449 -0.2945709 -0.6070566 -0.7377691 -0.3159949 -0.5965266 -0.7441114 -0.3009467 -0.5964305 -0.673382 -0.2766286 -0.6855898 -0.7727072 -0.2025232 -0.6015879 -0.7436577 -0.2785779 -0.6077563 -0.2245 -0.07095736 -0.9718874 -0.07876861 -0.02923685 -0.9964641 0.09290075 0.03064137 -0.9952039 -0.9016965 -0.01626682 0.4320635 -0.9079789 -0.01791477 0.4186329 -0.901228 -0.1693503 0.3988842 -0.07693803 -0.03860634 -0.9962881 -0.07501673 -0.03875964 -0.9964287 -0.2195219 -0.1000102 -0.9704681 0.1020852 0.04162758 -0.9939044 -0.2505594 -0.1062054 -0.9622581 -0.09558498 -0.04168874 -0.994548 -0.6535068 -0.2801659 -0.7031615 -0.6358583 -0.3910063 -0.665431 -0.499041 -0.2975263 -0.8139019 -0.6176534 -0.3553689 -0.701582 -0.5918017 -0.3826827 -0.7094539 -0.6108152 -0.3874437 -0.6905014 -0.6731324 -0.3573803 -0.6474351 -0.6796416 -0.3372113 -0.6514415 0.1248224 0.06283849 -0.9901872 -0.1682801 -0.1220443 -0.978155 -0.08325487 -0.05838215 -0.9948167 -0.2242254 -0.1436544 -0.9638913 -0.0623508 -0.03778284 -0.9973389 0.05685633 0.02441495 -0.9980839 -0.3868935 -0.2729954 -0.8807877 -0.5307614 -0.3344001 -0.7787613 -0.1658722 -0.1817117 -0.9692612 -0.1899199 -0.2071326 -0.9597013 -0.1246381 -0.1345567 -0.9830361 -0.06344836 -0.09250217 -0.993689 -0.1062681 -0.1400223 -0.9844292 -0.1080692 -0.1936762 -0.9750952 -0.09744805 -0.102148 -0.9899847 -0.05621677 -0.04287976 -0.9974974 -0.09991836 -0.09430295 -0.9905168 -0.1185965 -0.1270198 -0.9847847 -0.04278802 -0.0350666 -0.9984686 -0.07132267 -0.08823019 -0.9935435 -0.106817 -0.1272343 -0.9861043 -0.07687717 -0.1035202 -0.9916519 -0.2015819 -0.2327424 -0.9514178 -0.1933976 -0.2856865 -0.9386057 -0.3072048 -0.306625 -0.900892 -0.09628766 -0.1916293 -0.9767328 -0.05758941 -0.09518891 -0.993792 -0.2822407 -0.2738785 -0.9194187 -0.2813833 -0.2998777 -0.9115355 -0.2638988 -0.2411621 -0.9339156 -0.3598777 -0.3129702 -0.8789414 -0.3254912 -0.3564381 -0.8757896 -0.4715833 -0.4003209 -0.7857179 -0.4041926 -0.3937856 -0.8255674 -0.4509213 -0.3903407 -0.8026857 -0.1999304 -0.3586296 -0.9118184 -0.458063 -0.3767598 -0.8051276 -0.4838576 -0.3868663 -0.7849945 -0.5071015 -0.3960434 -0.7655048 -0.4081018 -0.4189971 -0.8111069 -0.1116078 -0.1031236 -0.9883872 -0.06732398 -0.06689673 -0.995486 -0.06103801 -0.05908483 -0.9963852 -0.07513886 -0.0408045 -0.9963379 -0.02456754 -0.01727354 -0.9995489 -0.0590232 0.02661234 -0.9979019 -0.05881023 -0.05157721 -0.9969359 -0.0295729 -0.03323519 -0.99901 -0.03903329 -0.0348522 -0.99863 -0.01702958 -0.01281797 -0.9997729 -0.002990841 0.008514821 -0.9999594 -0.05191284 0.008728444 -0.9986135 0.04385524 0.01193279 -0.9989666 0.08032584 0.1044053 -0.9912857 0.09283816 0.1278737 -0.9874358 -0.03665381 -0.03125184 -0.9988393 0.0994001 0.139563 -0.9852116 0.05212599 0.03677505 -0.9979633 0.05594158 0.05057024 -0.9971526 0.0644859 0.07174938 -0.9953359 -0.01773154 0.004303157 -0.9998336 -0.0183112 0.004119992 -0.9998239 -0.007599174 0.0100407 -0.9999207 0.01710534 0.05452305 -0.9983661 -0.02603274 -0.01181083 -0.9995914 0.1067242 0.1523192 -0.9825522 0.04110914 0.04110914 -0.9983087 0.01709043 5.18818e-4 -0.9998539 -0.04306185 -0.01980662 -0.9988762 -0.02710115 -0.07156789 0.9970675 0.01712858 0.05593562 -0.9982875 0.01712691 0.05459004 -0.998362 -0.03082442 -0.07632863 0.9966062 0.01715767 0.05796909 -0.998171 0.01712107 0.05832159 -0.9981511 0.01718229 0.06021428 -0.9980376 0.01712131 0.06357181 -0.9978304 -0.09753996 -0.05215764 -0.9938639 -0.0863986 -0.04284828 -0.9953389 -0.06387621 -0.02768069 -0.9975739 0.01712453 0.05835479 -0.998149 0.01712149 0.06447225 -0.9977726 -0.02978616 -0.02505582 -0.9992423 -0.03891217 -0.0443446 -0.9982582 -0.08166891 -0.03817927 -0.995928 0.2168353 0.01925724 -0.9760183 0.181098 0.01730406 -0.9833129 0.1675507 0.01733493 -0.985711 0.312123 0.05218833 -0.9486072 0.295977 0.0686686 -0.9527237 0.1638275 0.06274765 -0.9844914 0.2369477 0.01242113 -0.971443 0.1401752 0.06711196 -0.9878497 0.8533784 0.07809865 -0.5154086 0.7796835 0.07434564 -0.6217447 0.8607022 0.08270698 -0.5023459 0.8594574 0.09555631 -0.5021971 0.8601272 0.09384703 -0.5013722 0.7831511 0.08066201 -0.6165778 0.8126292 0.07931882 -0.5773583 0.9307554 0.09105503 -0.3541234 0.7545086 0.07144665 -0.6523897 0.5699346 0.05356007 -0.8199428 0.6730518 0.08676761 -0.734488 0.5676533 0.06778264 -0.8204726 0.8683258 0.08206552 -0.489158 0.8439093 0.08185172 -0.5302053 0.7641159 0.09564799 -0.6379485 0.4921875 0.04516881 -0.8693166 0.4555551 0.07968473 -0.8866341 0.633156 0.05936026 -0.7717447 0.5691863 0.09128344 -0.8171256 0.6376317 0.04818934 -0.7688326 0.7527239 0.06082463 -0.6555205 0.762282 0.06692892 -0.6437754 0.8580464 0.0697363 -0.5088155 0.8923636 0.08160948 -0.4438775 0.895735 0.07602298 -0.4380404 0.8920537 0.06766164 -0.4468356 0.8566178 0.08215814 -0.5093683 0.963121 0.08716249 -0.2545596 0.9479116 0.08487254 -0.3070183 0.9476786 0.08267617 -0.3083343 0.9475743 0.08771061 -0.307262 0.8575194 0.07779258 -0.5085361 0.9283996 0.09106981 -0.3602508 0.9371922 0.08829283 -0.3374539 0.9556124 0.07925796 -0.2837661 0.9520332 0.07638847 -0.2963068 0.9470306 0.08188205 -0.3105294 0.9419164 0.0854845 -0.3247861 0.9357443 0.08746755 -0.3416607 0.9227061 0.088413 -0.3752289 0.9341899 0.09048914 -0.3451101 0.9338923 0.09052038 -0.3459064 0.9453217 0.08746701 -0.3141917 0.9324205 0.09116059 -0.3496882 0.9369788 0.09210777 -0.3370267 0.9317816 0.09114164 -0.3513922 0.9950357 0.07800608 0.06180059 0.9945302 0.09189337 0.04965478 0.9960432 0.08887082 -3.05188e-4 0.9793164 -0.1949233 0.05426234 0.9981818 -0.04535108 0.03970503 0.99654 -0.0490747 0.06708097 0.995878 0.08951336 0.01464927 0.9958855 0.0893892 -0.01489311 0.9947223 0.0899077 -0.04944008 0.9751703 -0.1941612 -0.1065109 0.9964912 -0.04815971 -0.06845515 0.9979813 -0.0468471 -0.04287958 0.9793483 -0.1942521 -0.05606299 0.9849391 0.08710116 0.1493599 0.9921855 0.09448802 0.08148676 0.975108 -0.194222 0.1069686 0.988329 -0.07443594 0.1329104 0.9895269 0.09064227 0.1123415 0.9606755 -0.1817708 0.2099093 0.9859921 -0.03869867 0.1622414 0.9851268 0.09244239 0.1448438 0.9750515 -0.05996978 0.2137246 0.9635523 0.08789527 0.2526685 0.9812554 0.09973692 0.1648955 0.9409747 -0.1625464 0.2968929 0.9666169 -0.03271597 0.2541287 0.9756811 0.09277957 0.198591 0.9582333 -0.03558504 0.283765 0.9688341 0.08856689 0.231336 0.9177376 -0.1427375 0.3706535 0.9423698 -0.03183144 0.3330553 0.9608128 0.08978813 0.2622535 0.8940168 -0.1241198 0.4304977 0.9304481 -0.01583957 0.3660814 0.9465707 0.08703953 0.3105286 0.9571295 0.1020242 0.2710982 0.9241126 -0.02035611 0.3815779 0.9487065 0.09350949 0.3020137 0.8556409 -0.08472174 0.510589 0.9147743 0.003692746 0.4039486 0.9023787 0.006531 0.4308944 0.8746702 -0.1225026 0.4689831 0.9410418 0.08853739 0.3264988 0.8372054 -0.07141512 0.5422058 0.8848695 0.02493405 0.4651714 0.9362936 0.08670455 0.3403483 0.8076517 -0.02624619 0.5890755 0.8711116 0.04129254 0.489346 0.9340399 0.08609461 0.346637 0.8680106 0.04956221 0.4940659 0.932787 0.08585029 0.3500545 0.78083 0.02011203 0.6244198 0.8556081 0.06836318 0.5130902 0.8952252 0.08078879 0.4382294 0.8574263 0.06915563 0.509939 0.9212977 0.08473634 0.3795133 0.8548482 0.07727509 0.513092 0.8607676 0.07053017 0.504088 0.8951924 0.08182227 0.4381047 0.7596551 0.04657238 0.6486565 0.762695 0.06024408 0.6439465 -0.1872885 -0.02449858 0.9819995 0.8951902 0.08185255 0.4381036 0.7799443 0.07501578 0.6213369 0.8916059 0.08649015 0.4444754 0.6629397 0.05282884 0.7468067 0.8546006 0.0819137 0.5127847 0.9360169 0.08584982 0.3413242 0.9338887 0.09079474 0.345844 0.8468216 0.08319586 -0.5253303 0.8336287 0.07742691 0.5468714 0.9304888 0.08856564 0.3554529 0.9227166 0.08841401 0.3752027 0.9661436 0.08774244 0.2426269 0.9244311 0.05719321 0.377036 0.9441396 0.07663351 0.3205118 0.9524474 0.08432489 0.2928025 0.9592126 0.08932912 0.2682011 0.9951934 -0.03466951 0.09158742 0.9754525 0.07321536 0.2076827 0.9916197 0.06994926 0.1086167 -0.072483 0.9899194 -0.1216799 -0.07486408 0.971311 -0.2257216 -0.0781297 0.9935597 -0.08206671 -0.06818026 0.9260191 -0.3712683 -0.0724225 0.921075 -0.382591 -0.07629817 0.9892216 0.1249765 -0.07812851 0.9934839 0.08298105 0.9950336 0.07812798 -0.0616784 -0.06732511 0.9706292 0.2309685 0.9893652 0.09250307 -0.1122489 0.9852494 0.08639967 -0.1477126 0.9952042 -0.03427314 -0.09161895 0.9919677 0.09283959 -0.08591169 -0.06595236 0.9234857 0.3779214 0.9695792 0.09323459 -0.2263267 0.9778224 0.08716166 -0.1904373 0.9748162 0.09329742 -0.2025564 0.9805099 0.08996957 -0.1746594 0.9854325 0.0890243 -0.1449049 0.9916174 0.06988805 -0.1086775 0.9467765 0.08994102 -0.3090711 0.9459059 0.0920453 -0.3111107 0.9447773 0.09418165 -0.3138881 0.9439716 0.09549582 -0.3159085 0.944353 0.09506702 -0.3148962 0.9476474 0.09222859 -0.3057094 0.9537365 0.088934 -0.2871891 0.9611055 0.08734548 -0.2620059 0.9655856 0.08996951 -0.2440286 0.7570871 0.04126179 -0.6520098 0.8580862 0.07162922 -0.5084854 0.858472 0.06689786 -0.5084788 0.7785165 0.01941025 -0.6273239 0.867994 0.04947143 -0.4941044 0.8711451 0.04129266 -0.4892866 0.8058046 -0.02716225 -0.5915582 0.8848701 0.02490353 -0.4651718 0.836714 -0.07092654 -0.5430279 0.9021388 5.18821e-4 -0.4314457 0.9111378 0.005554378 -0.4120644 0.8748813 -0.126195 -0.4676085 0.9240962 -0.02206546 -0.3815227 0.9291607 -0.01702976 -0.3692837 0.8557955 -0.08066284 -0.510987 0.8931984 -0.1256465 -0.4317517 0.9420929 -0.032045 -0.3338175 0.9171782 -0.1446328 -0.3713027 0.9580358 -0.03647071 -0.2843191 0.9644238 -0.03656148 -0.2618206 0.9406538 -0.1637949 -0.2972236 0.9720194 -0.09482145 -0.2149124 0.9834585 -0.04126226 -0.1763718 0.9604331 -0.1802452 -0.2123207 0.9881917 -0.07455915 -0.1338586 0.8565899 0.08224993 0.5094004 0.9342032 0.08791309 0.3457396 0.9338473 0.09132277 0.3458173 0.9341595 0.08963459 0.3454153 0.9315609 0.09110999 0.351985 0.8608862 0.08411097 0.5017971 0.00341022 -0.04349273 -0.9990479 0.9332854 0.0909565 0.347427 0.9358485 0.09271806 0.3399867 0.9331882 0.09088641 0.3477062 0.9340218 0.08963602 0.3457871 0.9348305 0.09124052 0.3431721 0.003421187 -0.04348391 -0.9990484 0.00342226 -0.04348528 -0.9990482 -0.003173947 0.05374383 -0.9985498 -0.004150569 0.0529204 -0.9985901 -0.01251274 0.152442 -0.9882333 0.003423571 -0.04348474 -0.9990483 -0.0107733 0.1528716 -0.9881873 -0.0283221 0.3443515 -0.9384135 -0.02551424 0.3431605 -0.9389303 -0.04001063 0.5002705 -0.8649443 -0.03500539 0.5189165 -0.8541079 -0.01702982 0.6189645 -0.7852343 -0.04297095 0.6722763 -0.7390522 -0.04907476 0.6759988 -0.7352669 -0.03256386 0.7611157 -0.6477982 -0.038271 0.7666419 -0.6409334 -0.06347584 0.8065233 -0.5877848 -0.058627 0.7449389 -0.6645518 -0.06347751 0.8065119 -0.5878004 -0.0689122 0.8737325 -0.4815005 -0.06876063 0.8739591 -0.4811109 -0.06347137 0.8065261 -0.5877814 0.8395489 0.09009224 0.5357621 0.8661912 0.08234035 0.4928824 0.8736088 0.09427344 0.47741 0.7814441 0.07577913 0.6193566 0.8739557 0.09564805 0.4765006 0.8354364 0.1190865 0.53653 0.8728439 0.110723 0.4752726 0.8777124 0.1229938 0.4631345 0.9359943 0.09192389 0.3398011 0.9433128 0.09564661 0.3178252 0.8149214 0.1493605 0.5599952 0.8877141 0.1506431 0.4350522 0.9354554 0.09148818 0.3413991 0.9450059 0.09561759 0.3127639 0.9533466 0.09851473 0.2853509 0.8262428 0.1966954 0.5278578 0.9029452 0.1743875 0.3927839 0.9408618 0.09360092 0.3256043 0.9561683 0.09836351 0.2758025 0.9639523 0.098028 0.2473589 0.8607828 0.2826651 0.4232652 0.9189859 0.2020658 0.338577 0.9508886 0.09497588 0.2946024 0.8419317 0.2402467 0.4831486 0.9633207 0.09561485 0.2507411 0.9706094 0.0979368 0.2198314 0.9183714 0.2248014 0.325666 0.9708572 0.09445798 0.2202595 0.9777899 0.09134256 0.1886363 0.8791705 0.3253971 0.3481035 0.9335005 0.2390593 0.2672594 0.9818787 0.09149509 0.1659607 0.9815615 0.0979669 0.1641327 0.9367876 0.2450083 0.2497998 0.9874665 0.08996939 0.1296744 0.8968279 0.3578949 0.2600209 0.9429065 0.2765607 0.1855843 0.9905819 0.09073263 0.1025434 0.9899511 0.09848541 0.1014763 0.9532008 0.2555663 0.1615372 0.9939678 0.08746695 0.06616479 0.9103935 0.3810346 0.1612339 0.9456983 0.312425 0.08969587 0.9953764 0.08948159 0.03491365 0.9945376 0.09805899 0.0357688 0.9639415 0.2581904 0.06445604 0.9962812 0.0861541 0.001220703 0.9178366 0.3929356 0.05636906 0.9575271 0.2883415 0.00100708 0.9951362 0.09357154 -0.03079372 0.9947115 0.09793603 -0.03094643 0.9173567 0.3943126 -0.05453842 0.9672695 0.2495539 -0.04596161 0.9931262 0.09772253 -0.06442606 0.9540929 0.2839207 -0.09537267 0.9928036 0.09735459 -0.06973522 0.9904428 0.09827214 -0.09677666 0.9102336 0.3815199 -0.1609885 0.9582719 0.245832 -0.1458817 0.98973 0.09793531 -0.1041307 0.9867733 0.09784412 -0.1292483 0.9452399 0.2679889 -0.186289 0.9857026 0.09744715 -0.1374576 0.9823273 0.09775352 -0.1596163 0.8970575 0.3573825 -0.259934 0.9407526 0.2388123 -0.2407349 0.9806849 0.0974459 -0.1695919 0.9771029 0.09723418 -0.1892496 0.9327203 0.2425951 -0.2667967 0.9749884 0.0968976 -0.2000211 0.9714489 0.09695869 -0.2165319 0.8796105 0.324475 -0.3478524 0.9189155 0.2241972 -0.3245458 0.9687055 0.0968064 -0.2285572 0.9653117 0.0966227 -0.2425639 0.9171423 0.2140029 -0.3362336 0.9544313 0.09497618 -0.2829143 0.9593166 0.09512895 -0.265824 0.8597307 0.2864243 -0.4228764 0.8954731 0.2036872 -0.3957771 0.962081 0.09637898 -0.2551693 0.9451242 0.09393864 -0.3129152 0.9549463 0.09155762 -0.2823027 0.9017304 0.1794244 -0.3933054 0.9434848 0.09527927 -0.3174247 0.8421157 0.2407658 -0.4825692 0.8891299 0.1493023 -0.4326165 0.9348723 0.09131419 -0.3430388 0.8259386 0.1960852 -0.5285604 0.8784584 0.1222895 -0.4619048 0.9309835 0.09335774 -0.3529222 0.8148124 0.148661 -0.5603399 0.8734378 0.1091377 -0.4745478 0.8320795 0.1257092 -0.5402231 0.003416955 -0.04348331 0.9990484 0.003493309 -0.04350358 0.9990472 0.01351976 -0.1419425 0.9897826 0.01107853 -0.1409084 0.9899607 0.01788425 -0.238538 0.9709685 0.003423511 -0.04348522 0.9990482 0.02200448 -0.2461088 0.9689925 0.03158694 -0.4308039 0.9018927 0.0372641 -0.4371592 0.8986119 0.04501545 -0.5846518 0.8100345 0.05731576 -0.6058136 0.7935395 0.09589314 -0.6944472 0.7131252 0.07004207 -0.744979 0.6634007 0.06653231 -0.7536157 0.6539394 0.1017209 -0.8253651 0.5553604 0.07974773 -0.865994 0.4936547 0.07706034 -0.8667991 0.4926673 0.07825094 -0.9164277 0.3924757 0.09112954 -0.9495665 0.3000317 0.07495558 -0.9518694 0.2971978 0.08209592 -0.9765146 0.1991971 0.08642923 -0.9916473 0.09573745 0.07806849 -0.9942288 0.07358211 0.07846552 -0.9917605 -0.1012635 0.07806849 -0.9918788 -0.1004086 0.07510781 -0.9532376 -0.2927405 0.07587188 -0.9509627 -0.2998558 0.0683636 -0.8775877 -0.4745169 0.07022339 -0.8700865 -0.4878711 0.06079399 -0.7789389 -0.6241461 0.06848609 -0.7549953 -0.652144 0.08533209 -0.67991 -0.7283137 0.0629611 -0.6259796 -0.7772938 0.06088542 -0.6128523 -0.7878484 0.05652141 -0.5273097 -0.8477911 0.05761975 -0.4336435 -0.8992404 0.03460913 -0.4376805 -0.8984643 0.04864794 -0.3402306 -0.9390829 0.03189247 -0.2316402 -0.9722786 0.01818948 -0.2171143 -0.9759768 0.0125432 -0.1437128 -0.98954 0.01135301 -0.1443853 -0.9894564 -0.07291013 0.9269874 0.3679383 -0.06878972 0.873727 0.481528 -0.06347954 0.8065271 0.5877792 -0.06875997 0.8736758 0.481625 -0.06348198 0.8065198 0.587789 -0.04480129 0.7535653 0.6558448 -0.06106787 0.7758767 0.6279221 -0.05469018 0.7482978 0.6611047 -0.06348693 0.8065258 0.5877803 -0.037813 0.677918 0.7341645 -0.0533787 0.6773511 0.7337208 -0.04120016 0.6024991 0.7970556 -0.03085494 0.5151347 0.8565537 -0.04001033 0.5001755 0.8649993 -0.02548372 0.3431607 0.9389309 -0.02832156 0.3443148 0.938427 -0.01120048 0.1522907 0.9882723 -0.01199418 0.1519567 0.9883143 -0.003234982 0.0541411 0.998528 0.003423154 -0.04348427 0.9990483 -0.004303157 0.05475109 0.9984909 0.8860023 -0.4574214 0.07593172 0.8769875 -0.4551265 -0.1541198 0.8903245 -0.4506098 -0.06537121 0.8849133 -0.4423498 0.1457917 0.8620885 -0.4180886 0.2863659 0.8294874 -0.3879019 0.4018492 0.7915155 -0.3558234 0.4968832 0.7560606 -0.3221337 0.5697388 0.73045 -0.3063226 0.6104174 0.6770116 -0.2120792 0.7047537 0.7022457 -0.24397 0.6688271 0.6637051 -0.3880845 0.6394421 0.6352494 -0.3886573 0.6673858 0.58618 -0.2965844 0.7539435 0.6085324 -0.3178933 0.7270709 0.8199301 -0.5665288 0.08221882 0.8403472 -0.533049 -0.09836345 0.8179056 -0.5723202 -0.05899292 0.8327544 -0.5047311 0.2275227 0.8277305 -0.5497654 0.1123396 0.7969238 -0.4779651 0.3694074 0.7928335 -0.5340898 0.2935358 0.7471496 -0.4790046 0.4607844 0.7076334 -0.4120181 0.5740175 0.7435654 -0.4478666 0.4965139 0.5499879 -0.4737812 0.6877824 0.5532003 -0.4782133 0.6821155 0.531921 -0.4561721 0.7134194 0.4203464 -0.2650322 0.8677942 0.4628217 -0.3861578 0.7979212 0.449632 -0.3756241 0.8103935 0.4707639 -0.3295195 0.8184121 0.5113208 -0.4384712 0.7391171 0.7302352 -0.6791154 0.07455861 0.7290065 -0.6798099 0.08005124 0.7241908 -0.674536 0.1433488 0.7239453 -0.6745653 -0.1444472 0.7271419 -0.6832558 -0.06653106 0.7296648 -0.6798872 -0.07309466 0.7256392 -0.6761054 -0.1277865 0.7240695 -0.6747503 0.1429522 0.7114884 -0.6591789 0.2434497 0.703369 -0.6519141 0.2833374 0.6908929 -0.6411467 0.3340628 0.6721926 -0.6173185 0.408748 0.6739539 -0.6168527 0.4065453 0.6488393 -0.5839859 0.4878197 0.6364108 -0.5716802 0.5178448 0.6141057 -0.5514499 0.5646037 0.584237 -0.5171244 0.6254995 0.595005 -0.5240475 0.6093796 0.622102 -0.1240298 0.7730497 0.5672999 -0.03747814 0.8226581 0.5161353 0.01214647 0.8564209 0.6337015 0.05459886 0.7716485 0.5119004 0.03515821 0.8583251 0.755002 0.06714111 0.6522761 0.4272032 -0.01980674 0.9039387 0.3646152 0.008850574 0.9311163 0.3389399 0.02551352 0.940462 0.3570111 0.02023404 0.933881 0.4921766 0.04074257 0.8695415 0.572794 -0.2183075 0.7900943 0.509305 -0.1188418 0.8523411 0.5146095 -0.1857074 0.8370722 0.4762833 -0.1026667 0.8732777 0.435786 -0.06793606 0.8974828 0.2421662 -0.06500494 0.9680548 0.2207438 -0.06506645 0.9731591 0.2273393 -0.01895254 0.9736312 0.2580705 0.01928812 0.9659336 0.1871112 0.02887082 0.9819145 0.1933975 0.01910471 0.9809345 0.1919336 0.01181077 0.9813368 0.1954467 0.03549414 0.9800719 0.383539 -0.285205 0.8783827 0.3973618 -0.2844707 0.8724564 0.3284808 -0.1406031 0.9339867 0.3430935 -0.2633782 0.9016201 0.368732 -0.1654746 0.9146884 0.3429114 -0.1814659 0.9216735 0.2790016 -0.1158183 0.9532808 0.1746304 -0.1524125 0.9727666 0.2795541 -0.001983702 0.9601279 0.2912474 0.04077398 0.9557784 0.2977439 0.01391667 0.9545444 0.2567611 0.01941043 0.9662801 0.1814969 0.02078348 0.9831719 0.2874854 0.02716153 0.9573998 0.2565721 0.02139371 0.9662883 0.3380658 0.02997022 0.9406452 0.1597665 0.01678538 0.9870122 0.1734717 0.01193302 0.9847666 0.1296134 0.02096641 0.991343 0.1657183 0.03415077 0.9855817 0.3084902 0.02633821 0.9508628 0.4930697 0.04733538 0.8687012 0.1713628 0.01351976 0.9851153 0.3811203 0.04080379 0.9236246 0.3406904 0.0352196 0.9395156 0.6319685 0.06122219 0.7725721 0.5694203 0.0523703 0.8203766 0.7545218 0.07144498 0.6523746 0.1663292 0.07352054 0.9833257 0.1637058 0.06851595 0.9841271 0.3031737 0.0740996 0.95005 0.04016339 0.01696872 0.9990491 0.05578857 0.01236015 0.9983662 0.03341835 0.01767051 0.9992853 0.01739591 0.05591124 0.9982842 0.01730412 0.05832141 0.9981479 0.01730418 0.06231951 0.9979063 0.01728552 0.05455893 0.9983609 0.01733571 0.0547226 0.9983512 0.01733487 0.04898327 0.9986491 0.01730442 0.05014324 0.9985921 0.01754826 0.04461848 0.9988501 0.0177924 0.04171913 0.9989711 0.01831144 0.03817933 0.9991032 0.01971548 0.03189277 0.9992969 0.02569663 0.02081364 0.9994532 0.02240061 0.02551352 0.9994235 0.3466388 0.06702047 0.9356013 0.5616355 0.07266497 0.8241878 0.1483241 0.05844455 0.9872103 0.1995625 0.05966424 0.978067 0.6734691 0.08594226 0.7342025 0.4441527 0.05749905 0.8941042 0.56918 0.09112983 0.8171472 0.7641005 0.09442532 0.6381492 0.1013855 0.01385581 0.9947507 0.09253454 0.009735643 0.9956619 0.1260144 0.02792519 0.9916353 0.1272954 0.02548348 0.9915375 0.08374434 0.01416081 0.9963867 -0.9003417 -0.1764304 0.3978154 0.05963444 0.01556473 0.998099 0.05569732 0.01831144 0.9982798 0.05255323 0.02273643 0.9983593 0.05142438 0.02835208 0.9982744 0.01734364 0.06670773 0.9976218 0.01733481 0.05765044 0.9981864 0.01734584 0.05805015 0.998163 0.0173062 0.06068742 0.9980068 0.01730173 0.06452101 0.9977664 0.2479407 0.2421725 0.9380182 0.1254646 0.1665434 0.9780194 0.2004529 0.1739009 0.9641459 0.01730394 0.06886136 0.9974762 0.01794517 0.2535824 0.9671474 0.01672458 0.1655983 0.9860514 0.01721262 0.1640084 0.9863088 0.1339169 0.2532764 0.9580801 0.4673963 0.2237642 0.8552604 0.319567 0.1749973 0.9312642 0.4492756 0.166361 0.8777675 0.6608684 0.1911433 0.7257528 0.5579745 0.1613221 0.8140269 0.6667932 0.1475625 0.7304877 0.7575147 0.1364509 0.6383986 -0.01644963 0.003448605 0.9998589 -0.008697867 0.008758902 0.9999238 -0.01055961 0.005005121 0.9999318 0.01730668 0.05015343 0.9985916 -0.02539193 -0.01028496 0.9996247 -0.02368289 0.00137335 0.9997187 -0.04645049 -0.01278758 0.9988388 -0.04904341 -0.0144658 0.998692 -0.03598153 -0.02536106 0.9990307 -0.06503701 -0.02148568 0.9976516 -0.07220834 -0.02557504 0.9970617 -0.04077374 -0.01327586 0.9990803 -0.07272607 -0.02591037 0.9970154 0.01800632 0.1593716 0.9870545 0.01678538 -3.05189e-5 0.9998592 0.01638865 0.03326565 0.9993123 0.01672446 0.03198403 0.9993485 0.01678544 -0.01071214 0.9998018 -0.02893191 -0.02191251 0.9993413 -0.03592061 -0.02975583 0.9989116 -0.03671377 -0.04675441 0.9982315 -0.05368363 -0.03640967 0.9978941 -0.04718184 -0.009033501 0.9988455 -0.006134271 0.01135295 0.9999168 -0.1059938 -0.03161805 0.9938641 -0.1840304 -0.04626697 0.9818311 -0.1179858 -0.05435401 0.9915266 -0.0599097 -0.06247329 0.9962469 -0.001739561 0.004059016 0.9999904 -0.0203253 -0.02615433 0.9994513 -0.0145272 -0.01260447 0.9998151 -0.1469504 -0.1628815 0.975641 -0.0484941 -0.06634753 0.9966174 -0.09042781 -0.1112418 0.9896708 -0.0137335 -0.08877974 0.9959567 -0.1048949 -0.1388934 0.9847364 -0.179026 -0.2068901 0.9618452 -0.06192249 -0.1056864 0.9924697 -0.1143856 -0.1227173 0.9858278 -0.09113073 -0.09561711 0.9912379 -0.05896317 -0.1319957 0.9894951 -0.09686672 -0.1762768 0.9795629 -0.1061756 -0.1478646 0.9832919 -0.1162798 -0.1899237 0.9748888 -0.04110866 -0.09033536 0.9950626 -0.06018352 -0.07318466 0.9955009 -0.08478152 0.02148526 0.996168 0.07748794 0.03296059 0.9964483 0.01898276 0.02777218 0.9994341 -0.002716124 0.03558468 0.9993631 0.1008965 0.03656202 0.994225 0.08105736 0.03317368 0.9961573 -0.004944086 0.03396779 0.9994108 -0.2200396 0.01022374 0.9754375 -0.03515797 0.01931858 0.9991951 -0.06393808 0.01355057 0.9978619 -0.2150656 -0.0218209 0.9763559 -0.06299179 -0.00238049 0.9980112 -0.0712921 -0.01159715 0.997388 0.5439409 0.7839426 -0.2992697 0.5812408 0.749677 -0.316455 0.9025626 -0.1962053 -0.3832549 -0.2194297 -0.04443526 0.9746159 -0.2254744 -0.0737949 0.9714503 -0.07876861 -0.02923685 0.9964641 -0.2478476 -0.1077027 0.9627937 -0.08084428 -0.03524917 0.9961032 -0.09698987 -0.04791504 0.9941314 -0.2187007 -0.09659332 0.9709994 -0.09640985 -0.04721307 0.9942214 -0.2388097 -0.1289114 0.9624718 -0.09375381 -0.05304169 0.9941815 -0.07733422 -0.05386537 0.9955491 -0.1883955 -0.1289134 0.9735957 -0.05914646 -0.05276793 0.9968538 -0.1379465 -0.1202454 0.9831134 -0.04324549 -0.04397797 0.9980961 -0.09601372 -0.09528124 0.9908093 -0.03100693 -0.02826023 0.9991196 0.08264607 0.03497505 0.9959651 -0.03613454 0.07403928 0.9966005 0.08124053 0.02655118 0.9963409 0.08160758 0.02841311 0.9962595 -0.04348939 0.04455757 0.9980598 0.09918808 0.07568812 0.9921861 0.3415663 0.001403808 0.9398567 0.1392563 0.006256282 0.9902367 0.165811 0.01266545 0.9860763 0.1590681 0.01675522 0.9871255 0.1449647 0.2225133 0.9640919 0.115363 0.02252322 0.993068 0.3009823 -0.08844518 0.9495195 0.2986915 -0.06402927 0.9521995 0.3090035 -0.03576809 0.9503881 0.1695921 -0.03024393 0.9850503 0.2400958 -0.07077437 0.9681658 0.2241607 -0.04986768 0.9732756 0.3986788 -0.1667901 0.9017962 0.1799685 -0.04370272 0.9827011 0.2514472 -0.08972626 0.963703 0.1559507 -0.01525932 0.987647 0.2143358 -0.03524959 0.9761238 0.1938862 -0.01522886 0.980906 0.3894627 -0.232408 0.8912382 0.4320978 -0.2971397 0.851469 0.4422017 -0.3252192 0.8358769 0.3848425 -0.2156461 0.8974369 0.3836936 -0.198439 0.9018875 0.3877435 -0.1820762 0.9036058 0.2137582 -0.06757003 0.974547 0.2976207 -0.1536323 0.9422416 0.293507 -0.143259 0.9451617 0.4377337 -0.3020768 0.8468406 0.4410063 -0.2985414 0.8463962 0.3042762 -0.1573263 0.9395023 0.2066417 -0.06491315 0.976261 0.2838594 -0.130073 0.9500027 0.1987119 -0.06018424 0.9782083 0.2734553 -0.115486 0.9549268 0.1901615 -0.05304133 0.980319 0.2624301 -0.1000402 0.9597513 0.5044831 -0.4246447 0.7517805 0.4857849 -0.4078371 0.773099 0.4690837 -0.3940058 0.7903923 0.4270889 -0.314045 0.8479214 0.4258346 -0.3147752 0.8482816 0.4582716 -0.3782817 0.8042949 0.4415531 -0.3637899 0.8201755 0.431263 -0.3133989 0.8460458 0.4349919 -0.3052238 0.8471249 0.4170095 -0.3211193 0.8502856 0.4092032 -0.3202699 0.8543887 0.4255596 -0.3510622 0.8340591 0.4196981 -0.3197787 0.8494676 0.4057881 -0.3438333 0.8468263 0.4059086 -0.3449002 0.8463346 0.4133599 -0.3370605 0.8458864 0.3956494 -0.3232582 0.8596311 0.404134 -0.3303083 0.8529785 0.4063057 -0.3183181 0.8564984 0.2488803 -0.02136307 0.9682987 0.3251199 -0.1684043 0.9305575 0.3224676 -0.1658422 0.9319394 0.2508023 -0.02377402 0.9677464 0.2096329 -0.006592035 0.977758 0.3088245 -0.173441 0.9351715 0.2346886 -0.03326535 0.9715012 0.2849858 -0.1076708 0.9524654 0.3846682 -0.3111162 0.8690438 0.3268235 -0.1672112 0.9301757 0.2481179 -0.02438449 0.968423 0.3257905 -0.1677935 0.9304332 0.3251215 -0.1697175 0.9303182 0.2458927 -0.03631776 0.9686164 0.323628 -0.1721906 0.9303846 0.2400947 -0.04855602 0.9695344 0.3212499 -0.173138 0.9310327 0.2336512 -0.05804651 0.9705863 0.31755 -0.1743243 0.93208 0.314102 -0.1693807 0.9341574 0.2273679 -0.06311368 0.9717615 0.3095523 -0.163886 0.936653 0.2210776 -0.06677496 0.9729676 -0.1812515 0.07852506 0.9802967 0.275951 -0.03860628 -0.9603962 -0.2157078 0.04443556 0.9754464 -0.4615764 0.1670024 0.8712391 -0.2912422 0.03671425 0.9559446 -0.2908464 0.0365923 0.9560698 -0.1399298 0.1404487 0.98015 -0.2484833 0.092197 0.9642384 -0.1666945 0.0564906 0.9843891 -0.2155572 0.06024491 0.974631 -0.3900685 0.219465 0.8942492 -0.342023 0.1068459 0.9335975 -0.3350735 0.0914669 0.9377418 -0.3600006 0.06250262 0.9308561 -0.113438 0.07831096 0.9904541 -0.1082515 0.0729103 0.9914463 -0.1539072 0.05761981 0.9864039 -0.4840331 0.1265017 0.8658577 -0.4631591 0.05877989 0.8843238 0.04391694 0.07184195 0.9964488 -0.02743631 0.03860616 0.9988778 -0.346823 0.01129215 0.9378626 -0.3976613 0.004669368 0.9175204 -0.1778977 0.03134346 0.9835497 0.02765011 0.03408956 0.9990363 0.03039693 0.03149563 0.9990416 -0.08447706 0.05945134 0.9946503 -0.025361 0.03766006 0.9989688 -0.08612531 0.04834246 0.9951108 -0.1955062 0.0832259 0.9771647 -0.2935962 0.6745083 0.6773772 -0.3704431 0.7494621 0.5487062 -0.3556977 0.7809481 0.5134194 -0.475125 0.7652419 0.4343512 -0.4220508 0.8184959 0.3897919 -0.4326983 0.8062204 0.4034611 -0.2840704 0.7203695 0.6327496 -0.2671049 0.724986 0.6348625 -0.2710394 0.7267798 0.6311331 -0.3433424 0.7963408 0.4979533 -0.3394031 0.7956944 0.5016733 -0.422533 0.8358798 0.3503865 -0.5151886 0.8557789 -0.04715156 -0.4231459 0.8417445 0.3352817 -0.4185638 0.8411866 0.3423587 -0.4497884 0.8151308 0.3650373 -0.3814923 0.7216614 0.5776404 -0.4572682 0.7748809 0.4364236 -0.3091578 0.6250298 0.71677 -0.3946218 0.684591 0.6128694 -0.4622147 0.7218423 0.5150741 -0.3214032 0.5711154 0.7553325 -0.3992512 0.6583281 0.6381244 -0.5132461 0.6401156 0.5716909 -0.4547355 0.7141788 0.532132 -0.4051487 0.6241884 0.6680147 -0.4811413 0.6819602 0.550848 -0.3281771 0.5193213 0.7890534 -0.4109113 0.5718088 0.710061 -0.4976471 0.6376694 0.587984 -0.3304023 0.4693568 0.8188642 -0.4127772 0.5268899 0.7429684 -0.4960992 0.541299 0.6788823 -0.3274462 0.4177541 0.8475025 -0.4099639 0.4971266 0.7647187 -0.5039916 0.4280296 0.7501887 -0.4351454 0.5220036 0.7335945 -0.5525245 0.5021368 0.6652634 -0.4072809 0.4683502 0.784073 -0.4598675 0.5089734 0.7276455 -0.3203576 0.3690658 0.8724457 -0.3987638 0.4193947 0.8155339 -0.4779919 0.479823 0.7357267 -0.3091228 0.3169966 0.8966361 -0.3896993 0.3712047 0.8428176 -0.4817498 0.4446076 0.7551433 -0.3765432 0.3468482 0.8590178 -0.4757627 0.4067285 0.7798859 -0.2917055 0.2713795 0.9172028 -0.3644351 0.3076685 0.8789352 -0.4348396 0.2922533 0.8517645 -0.2729032 0.2256593 0.9352015 -0.3497546 0.2798343 0.8940718 -0.4664903 0.2395779 0.851463 -0.3468143 0.2689001 0.8985615 -0.4829962 0.3162701 0.8165096 -0.3422079 0.259807 0.9029918 -0.3365698 0.2524273 0.9071941 -0.2488517 0.1778646 0.9520699 -0.3193491 0.2208343 0.9215468 -0.3550953 0.2419286 0.9029828 -0.3114143 0.1981283 0.9293904 -0.3670558 0.2238897 0.902853 -0.2230956 0.131599 0.9658728 -0.2845308 0.1567773 0.9457606 -0.3709571 0.1982812 0.9072351 -0.2808662 0.1394107 0.9495677 -0.3657057 0.1651672 0.9159581 -0.09839481 0.08563762 0.9914559 -0.1120653 0.1124621 0.9873164 -0.1246713 0.1404803 0.9822028 -0.1355369 0.170207 0.9760428 -0.1441418 0.2019146 0.9687381 -0.1499686 0.2354817 0.9602384 -0.1531764 0.2714388 0.9501884 -0.1535136 0.3096213 0.938386 -0.1505506 0.3499928 0.9245754 -0.1438983 0.392264 0.9085276 -0.1334005 0.4364282 0.8897948 -0.1186586 0.4820202 0.868088 -0.1131029 0.5213235 0.8458307 -0.09903621 0.5250294 0.8453024 -0.1026353 0.527307 0.8434532 0.06741726 0.2348465 0.9696918 0.07156628 0.2631322 0.9621018 0.08035629 0.2655756 0.9607354 0.07751762 0.267863 0.9603335 0.02896225 0.03665298 0.9989084 0.02877914 0.0421769 0.9986957 0.02807778 0.05011272 0.9983488 0.02758926 0.06039738 0.9977931 0.02777242 0.07309335 0.9969384 0.02899301 0.08819973 0.9956809 0.031282 0.1059012 0.9938845 0.03482228 0.126288 0.9913823 0.03994935 0.1494516 0.9879617 0.04699873 0.1752383 0.9834036 0.05606424 0.203748 0.9774168 -0.3415724 0.7954559 0.5005781 -0.5165446 0.8543968 -0.05646127 -0.3459646 0.7831814 0.516658 -0.2765947 0.718725 0.6379105 -0.3483806 0.7914328 0.5022601 -0.515524 0.8555036 -0.04846388 0.04290997 0.269454 0.9620568 0.06485378 0.2560886 0.9644754 -0.1259553 0.5165784 0.846925 -0.1124346 0.5165464 0.8488453 -0.2829485 0.7108353 0.643936 -0.4428322 0.8295702 0.3401659 -0.4402737 0.8246358 0.3551549 -0.4424354 0.8284105 0.3434925 -0.3495403 0.6785409 0.6460682 -0.3897882 0.724978 0.5678664 -0.3966869 0.7443296 0.5372272 -0.440173 0.8246796 0.3551781 -0.3714808 0.7080476 0.6005586 -0.4041686 0.7247751 0.5579865 -0.4058147 0.6861646 0.6037321 -0.4081605 0.7397183 0.5349972 -0.3789013 0.7415967 0.5535957 -0.3264355 0.6823223 0.6541224 -0.3750218 0.7347229 0.5652794 -0.4296481 0.8153792 0.38802 -0.4675567 0.8556409 0.2219673 -0.4594407 0.848656 0.2621015 -0.3756335 0.7514503 0.5424224 -0.4735639 0.8596602 0.191629 -0.4300163 0.8288115 0.3579909 -0.438104 0.8138877 0.3816434 -0.3673639 0.7518187 0.5475513 -0.3099547 0.6912942 0.6527177 -0.3570435 0.758584 0.5450415 -0.2941783 0.6992037 0.6515931 -0.3587588 0.7674174 0.5313782 -0.5059138 0.8623759 0.01895231 -0.3498403 0.7701187 0.5334126 -0.4291638 0.8500263 0.3054076 -0.1510394 0.5122643 0.8454422 -0.1792083 0.5099137 0.8413515 -0.2123828 0.5100057 0.8335393 -0.2529131 0.5132728 0.8201134 -0.3320237 0.6360304 0.6965815 -0.3738036 0.6191504 0.6905966 -0.2839241 0.5438902 0.7896648 -0.3821268 0.6441009 0.6626563 -0.3280565 0.5188354 0.7894232 0.006988704 0.2772005 0.9607867 -0.03360116 0.2867853 0.9574055 -0.08160781 0.2989947 0.9507588 -0.1402655 0.3148955 0.9387047 -0.2327099 0.4493056 0.8625374 -0.2837972 0.4260772 0.8590212 -0.1748471 0.3381274 0.9247153 -0.300794 0.4436528 0.8442128 -0.2287721 0.3081527 0.9234205 0.1632462 0.01718217 0.9864357 0.1178955 0.03875929 0.9922693 0.05450695 0.07052946 0.9960194 -0.01886075 0.1015979 0.9946467 -0.1167057 0.2302069 0.9661184 -0.1760981 0.202345 0.9633514 -0.06412023 0.1129506 0.9915296 -0.1954432 0.2085052 0.9582942 -0.1149662 0.07892286 0.9902293 0.2546502 -0.1188713 0.9596995 0.2887098 -0.1332154 0.9481036 0.2335627 -0.1133174 0.9657162 0.1522914 -0.05960416 0.9865368 0.1865037 -0.03564655 0.9818074 0.08862632 -0.03003036 0.9956122 0.1321769 -0.0260325 0.9908843 -0.04126119 0.0784024 0.9960677 0.02514743 0.1120344 0.9933862 0.05298167 -0.007904469 0.9985643 -0.03415066 0.04165828 0.9985482 -0.09061223 0.02490383 0.9955748 0.07809752 -0.1146284 0.9903339 0.07062 -0.1091039 0.9915186 0.03341853 -0.09488427 0.9949272 -0.1234493 0.09949195 0.9873509 -0.03439497 -0.0609771 0.9975464 -0.05005097 -0.05435413 0.9972665 0.04025501 -0.09506779 0.9946566 0.4127725 -0.3303096 0.8488312 0.367603 -0.2986603 0.8807213 0.3584495 -0.2851421 0.8889365 0.3446845 -0.2749785 0.8975408 0.3205157 -0.2593852 0.9110375 0.3013773 -0.2429025 0.9220467 0.2836115 -0.2316074 0.9305496 0.2597492 -0.2175716 0.9408469 0.2451281 -0.2060639 0.9473384 0.2136616 -0.2050553 0.9551445 0.2022799 -0.1831445 0.9620504 0.2233683 -0.193948 0.9552438 0.1667269 -0.1626373 0.9724975 0.1536307 -0.1542411 0.9760161 0.12406 -0.1356572 0.982958 -0.4240916 0.7288846 0.5374696 -0.4048057 0.6481959 0.6449608 -0.4178723 0.711103 0.5654338 -0.4155805 0.7220852 0.5530696 -0.4320368 0.7276811 0.5327518 -0.4300096 0.6529188 0.6235293 -0.3433137 0.4546793 0.8218287 -0.4503734 0.735271 0.5064983 -0.4560183 0.6582693 0.5989399 -0.386375 0.4651455 0.7964636 -0.4482662 0.7244651 0.5236486 -0.4708802 0.7435385 0.4747867 -0.481903 0.665081 0.5704706 -0.4306245 0.4747856 0.7675554 -0.4719552 0.7152881 0.5153846 -0.4847978 0.7398775 0.4664252 -0.5125749 0.6702996 0.5366243 -0.4767781 0.4834314 0.7341504 -0.4911715 0.7219861 0.4873261 -0.5049131 0.7516626 0.4243419 -0.543309 0.6770762 0.49637 -0.5254145 0.4902566 0.6954051 -0.5008267 0.7462655 0.4384752 -0.5284444 0.745926 0.4053899 -0.5755625 0.6810676 0.4526309 -0.576938 0.4949325 0.6497572 -0.5488812 0.7603767 0.3472128 -0.6092244 0.6854614 0.3987334 -0.6307037 0.4976413 0.5954544 -0.5468752 0.7537655 0.3643698 -0.5700023 0.7702065 0.2861456 -0.6423082 0.6880871 0.3376039 -0.6858966 0.4979267 0.5306742 -0.5977511 0.7324022 0.3260072 -0.6007134 0.757339 0.2560883 -0.673869 0.6894339 0.2656716 -0.7412496 0.4956008 0.4526908 -0.6164207 0.7662073 0.1815264 -0.6997236 0.6902626 0.1841859 -0.792955 0.4918811 0.359549 -0.5982968 0.7760096 0.1996255 -0.6259496 0.7704277 0.1209477 -0.7120403 0.6955599 0.09589087 -0.836142 0.4876402 0.2511447 -0.6229329 0.7814205 0.03656232 -0.7198156 0.6925013 0.04803651 -0.8653441 0.4841276 0.1296154 -0.6397713 0.7672189 0.04547339 -0.6530231 0.7560565 -0.04403942 -0.7241583 0.6882067 -0.0443443 -0.6190578 0.785084 -0.02026492 -0.8737128 0.4819337 0.06607472 -0.7176927 0.688913 -0.1015684 -0.8736526 0.4814154 -0.07050013 -0.5069472 0.861972 -0.003021299 -0.5050612 0.8630812 -0.002044737 -0.5071708 0.8609818 0.03857642 -0.5025577 0.8623166 -0.06201475 -0.4933202 0.8695974 -0.02087545 -0.5045197 0.8610498 0.06366389 -0.4986919 0.8624867 0.08615708 -0.5006115 0.8591548 0.1060248 -0.4999334 0.8572205 0.1234498 -0.4938628 0.8575915 0.1436542 -0.4960952 0.8531434 0.1613568 -0.4940774 0.8505737 0.1800335 -0.488764 0.8501716 0.1957497 -0.489003 0.8469583 0.2086572 -0.4864199 0.8423079 0.2321924 -0.4824516 0.8416656 0.2425686 -0.4829648 0.8370475 0.2570929 -0.4804075 0.8322669 0.2766593 -0.47561 0.831646 0.2866356 -0.4718949 0.8242443 0.3129485 -0.4739682 0.822379 0.3147173 -0.4670404 0.8166416 0.339072 -0.4685928 0.8183131 0.3328431 -0.4640475 0.8159973 0.3446861 -0.4568978 0.8124119 0.3622588 -0.4617298 0.8141693 0.3520426 -0.4657763 0.8153374 0.3439151 -0.4582723 0.8117731 0.3619545 -0.4469581 0.8025408 0.3951665 -0.4541273 0.8108981 0.36907 -0.4409418 0.8017094 0.4035251 -0.4499119 0.811868 0.3720883 -0.4467094 0.8067443 0.3868002 -0.4431061 0.8033224 0.3979073 -0.4394792 0.8020191 0.404504 -0.4362981 0.8025859 0.4068168 -0.3533813 0.7605374 0.5447059 -0.4413698 0.8001691 0.4061061 -0.4318755 0.8004546 0.4156394 -0.4396355 0.800866 0.4066132 -0.2555693 0.2251414 0.9402105 -0.3135213 0.2435108 0.9178273 -0.3792564 0.2623086 0.8873324 -0.4406028 0.2714055 0.8556917 -0.5085126 0.2837074 0.8129731 -0.5762442 0.285299 0.7658637 -0.6493501 0.2891663 0.7033686 -0.72093 0.2555392 0.6441736 -0.7956727 0.2474212 0.5528904 -0.8637332 0.2420504 0.4420143 -0.9194449 0.2394518 0.3119038 -0.9566748 0.2410075 0.1633675 -0.967235 0.2427167 0.07446604 -0.8638845 0.4841611 -0.1388942 -0.9673265 0.2388408 -0.08505612 -0.1901927 0.1213425 0.9742191 -0.2534347 0.1483862 0.955904 -0.311567 0.1587591 0.936868 -0.3528322 0.1523212 0.9232052 -0.4576081 0.2046326 0.8652864 -0.390854 0.2185144 0.8941391 -0.5040844 0.1803375 0.8446167 -0.6020539 0.2124752 0.7696658 -0.5257268 0.299975 0.7960065 -0.5408983 0.2156207 0.8129802 -0.6844829 0.2165942 0.6961107 -0.6206953 0.2034091 0.7572067 -0.7604114 0.2055454 0.6160565 -0.835125 0.1945898 0.5144912 -0.900398 0.1797561 0.3961959 -0.951524 0.1582414 0.2637459 -0.9831088 0.1337953 0.1248838 -0.9907416 0.1143856 0.07312375 -0.9568327 0.2337147 -0.1727682 -0.988021 0.127264 -0.0872842 -0.09030449 -0.03976571 0.99512 -0.117896 -0.02539205 0.9927014 -0.04498571 -0.05829221 0.9972855 -0.1785683 -0.005676567 0.9839112 -0.1806434 -0.002990841 0.9835441 -0.2353664 0.01199412 0.9718328 -0.2616712 0.0197764 0.9649545 -0.2967064 0.02945089 0.9545146 -0.3437086 0.03851538 0.9382862 -0.3553656 0.04171973 0.933796 -0.3986072 0.04294008 0.916116 -0.4221768 0.05136436 0.9050571 -0.4592232 -0.01016288 0.8882628 -0.4811962 0.05288976 0.875016 -0.5072256 0.06705021 0.8592011 -0.525089 0.06082546 0.848871 -0.5993466 0.0668382 0.7976944 -0.5619438 0.0597254 0.8250164 -0.615182 0.05969613 0.7861218 -0.6864054 0.06219792 0.7245544 -0.6706904 0.05206578 0.739908 -0.7685158 0.05093729 0.6378001 -0.7481049 0.04043722 0.6623473 -0.8413887 0.03286933 0.53943 -0.8307692 0.02548366 0.5560334 -0.9062163 0.01751816 0.4224513 -0.90096 0.009369373 0.4338012 -0.95689 0.001159667 0.2904485 -0.9545859 -0.00463891 0.2978999 -0.9887416 -0.01046782 0.1492664 -0.9883465 -0.01388597 0.1515861 -0.9969773 -0.0169993 0.07581019 -0.9972385 -0.01428288 0.07287931 -0.989474 -0.01379477 -0.1440522 -0.9970524 -0.01785355 -0.07461869 -0.9972224 -0.01739603 -0.07242256 -0.9774916 0.1872643 -0.09717231 -0.996038 -0.01590019 0.08749699 -0.9988992 -0.01742655 0.04355114 -0.9889962 -0.01257377 -0.1474063 -0.9987087 -0.009064137 -0.04999035 -0.9841189 -0.00689727 0.177377 -0.9965953 -0.04413032 0.06964415 -0.9998366 -0.01214659 0.01339787 -0.9963868 -0.01110893 -0.08420211 -0.9999684 -0.006927847 0.003906428 -0.9935732 -0.04416084 -0.104222 -0.984071 -0.008819818 0.1775569 -0.93826 0.007629811 0.3458466 -0.9657912 -0.001556396 0.2593165 -0.9032825 0.02407979 0.4283702 -0.8611974 0.04486352 0.5062869 -0.7613074 0.06033688 0.6455777 -0.8192902 0.05588078 0.5706496 -0.7018017 0.07431554 0.7084855 -0.5718291 0.07345849 0.8170774 -0.6434922 0.07849472 0.7614175 -0.4997504 0.07126212 0.863233 -0.4132952 0.0555455 0.9089015 -0.4244655 0.06421303 0.9031643 -0.3162959 0.03613412 0.9479722 -0.2660971 0.02285885 0.9636752 -0.213786 0.007232964 0.9768538 -0.3493856 0.04907512 0.935693 -0.1823496 -0.00451672 0.9832234 -0.1076113 -0.03192323 0.9936805 -0.04525983 -0.05279809 0.9975791 -0.05386531 -0.0536822 0.9971043 -0.09601193 -0.03518807 0.994758 0.07394665 -0.1110268 0.9910625 0.0433374 -0.09595274 0.994442 -0.04614436 -0.05563569 0.9973844 0.04355031 -0.09604257 0.9944241 0.001709043 -0.01910513 0.9998161 -3.96753e-4 -1.52597e-4 1 -0.08658176 -0.0127263 0.9961634 0.0874378 -0.01266551 0.9960895 -0.1716394 -0.01916599 0.9849734 -0.1738985 -1.22077e-4 0.9847636 -0.25816 -0.01281791 0.9660171 -0.3401651 -0.01922696 0.9401692 -0.3422747 -1.22077e-4 0.9395999 -0.4221115 -0.0129401 0.9064517 -0.487142 -0.00991857 0.8732665 -0.5000254 1.52596e-4 0.8660107 -0.572655 -3.66226e-4 0.8197965 -0.573661 6.10375e-5 0.8190928 -0.6424002 -3.05193e-4 0.7663694 -0.6428492 -6.10377e-5 0.7659928 -0.7070915 -3.05189e-4 0.707122 -0.7071373 -1.52598e-4 0.7070763 -0.7659928 -1.83113e-4 0.6428492 -0.7745849 -0.009766221 0.6323946 -0.8190751 -0.01260441 0.5735479 -0.8659244 -0.018983 0.4998148 -0.8660449 6.10385e-5 0.4999665 -0.9062877 -0.01263475 0.4224724 -0.9412208 -0.01641947 0.3373928 -0.9397453 -3.05191e-5 0.3418754 -0.9693774 -0.04440522 0.2415279 -0.9823386 -0.0122075 0.1867139 0.08612531 -0.1168887 0.9894037 0.04358059 -0.09607273 0.9944199 -0.9840953 -0.009094715 -0.1774088 -0.987025 -0.01217716 -0.1601043 -0.9567462 -0.002960324 -0.2909089 -0.9641628 0.006042778 -0.2652425 -0.985399 -0.007110893 -0.1701132 -0.9604325 -0.04367262 -0.2750676 -0.9083984 0.0132147 -0.4178968 -0.9404599 0.01529026 -0.3395605 -0.9441906 -0.01214647 -0.3291758 -0.9035732 0.02127164 -0.4279055 -0.9408121 -0.007141411 -0.3388535 -0.8980379 -0.04370397 -0.4377419 -0.8437548 0.03070193 -0.5358501 -0.8617394 0.04010218 -0.5057638 -0.8726042 -0.0121771 -0.4882762 -0.7699936 0.0421772 -0.6366562 -0.8135456 0.06088542 -0.578305 -0.8677402 -0.007080316 -0.4969677 -0.8083004 -0.04394757 -0.5871279 -0.6912295 0.0559417 -0.7204669 -0.7681211 0.0700733 -0.6364589 -0.7745099 -0.01220756 -0.6324442 -0.7028883 0.06369358 -0.7084428 -0.7714625 -0.009644031 -0.6362017 -0.7070498 -0.01269614 -0.7070498 -0.6034835 0.06003093 -0.7951126 -0.6390513 0.07315564 -0.7656774 -0.6427862 -0.01910471 -0.7658073 -0.6427654 -9.15577e-5 -0.7660631 -0.5117384 0.05429279 -0.8574241 -0.5781244 0.07211673 -0.8127556 -0.5735824 -0.01266556 -0.8190501 -0.500511 0.05578863 -0.8639308 -0.5002629 -0.0190742 -0.8656635 -0.4998713 -6.10381e-5 -0.8660997 -0.4123757 0.0418418 -0.9100526 -0.4247328 0.04821997 -0.9040336 -0.4226326 -0.01266551 -0.9062126 -0.3094933 0.01815879 -0.9507282 -0.3459011 0.03701937 -0.9375405 -0.3424525 -0.01910477 -0.939341 -0.341721 -3.0519e-5 -0.9398014 -0.2033157 -0.009064018 -0.9790713 -0.2699075 0.01828068 -0.9627128 -0.2588042 -0.01272654 -0.9658461 -0.180918 -0.01648038 -0.9833602 -0.1693482 -0.01648008 -0.9854185 -0.1733152 0 -0.9848664 -0.08780419 -0.04580956 -0.995084 -0.09494435 -0.04236024 -0.994581 -0.06955301 -0.04483252 -0.9965704 -0.0318005 -0.06302118 -0.9975055 -0.04345965 -0.05685764 -0.9974361 -0.07055985 -0.02447617 -0.9972073 0.09134256 -0.1199997 -0.988563 0.0441001 -0.09567743 -0.994435 0.0466023 -0.09741622 -0.9941521 -0.08737629 0 -0.9961755 0.08746802 -0.01272648 -0.996086 0.0698893 -0.01907455 -0.9973724 0.04379481 0 -0.9990407 0.07403999 -0.1107548 -0.9910861 -0.03112894 -0.0624715 -0.9975613 0.04635912 -0.09763187 -0.9941423 -0.1596449 -0.01773154 -0.9870153 -0.01168876 -0.07330679 -0.997241 -0.0587182 -0.05740588 -0.9966226 -0.2502533 0.008301079 -0.9681448 -0.3411465 0.03155708 -0.9394804 -0.4205514 0.04339796 -0.9062302 -0.4930686 0.04449701 -0.8688519 -0.5540783 0.04071277 -0.8314684 -0.6637419 0.0445587 -0.7466333 -0.5946411 0.02850514 -0.8034858 -0.7438172 0.03515821 -0.6674578 -0.8311944 0.02356088 -0.5554825 -0.9044075 0.009338855 -0.4265676 -0.9577007 -0.004059076 -0.2877375 0.08334827 -0.1170721 -0.9896197 0.04278749 -0.09570729 -0.9944896 -0.01001012 -0.07199388 -0.9973549 0.04196363 -0.09634858 -0.9944627 -0.08014351 -0.04397821 -0.9958127 0.005523979 -0.08429437 -0.9964256 -0.001800596 -0.08231031 -0.9966052 -0.1464934 -0.02261489 -0.9889531 -0.2734175 0.01742619 -0.9617377 -0.1998069 -0.01318413 -0.9797466 -0.3316476 0.02758896 -0.9429998 -0.45486 0.01696872 -0.8904013 -0.3623554 -0.004669427 -0.9320283 -0.5409541 0.283524 -0.7918226 -0.5210916 0.1753656 -0.8352908 -0.5795235 0.2314248 -0.781406 -0.4689345 0.2708009 -0.8406945 -0.5068923 0.2453128 -0.8263666 -0.6195684 0.2860556 -0.7309632 -0.6315006 0.1767969 -0.7549503 -0.6661111 0.2254145 -0.7109743 -0.7046942 0.2507174 -0.6637371 -0.7466903 0.2159866 -0.6291292 -0.784034 0.2415887 -0.5717742 -0.8253416 0.207045 -0.5253034 -0.857123 0.234324 -0.4587294 -0.8940266 0.2002968 -0.4007463 -0.9168856 0.2304803 -0.325883 -0.9463127 0.191875 -0.2601467 0.08041644 -0.1127967 -0.9903587 0.03219765 -0.08975678 -0.9954431 -0.1443567 0.08847564 -0.9855625 -0.08383589 0.01565629 -0.9963567 -0.09467107 0.08633929 -0.9917575 0.02755886 -0.08063191 -0.9963629 -0.2013326 -0.03842318 -0.9787691 -0.1729499 0.1971207 -0.9650036 -0.1717002 0.1213437 -0.9776476 -0.2441533 0.2222405 -0.9439271 -0.2299297 0.1222589 -0.9654974 -0.2642664 0.1395035 -0.9543071 -0.3220972 0.2444874 -0.9145924 -0.3369595 0.1823811 -0.9236859 -0.3914062 0.2598693 -0.8827622 -0.3906688 0.1644037 -0.9057314 -0.4224163 0.1913554 -0.8859726 0 -1 4.67458e-6 0 -1 -4.68701e-6 0 -1 0 0 -1 -9.37528e-6 0 -1 9.99518e-6 0 -1 9.95948e-6 0 -1 -1.87893e-5 0 -1 1.99955e-5 0 -1 -1.99363e-5 0 -1 5.00105e-6 0.1740217 -0.01910513 -0.9845564 0.1748121 -0.01907426 0.9844172 0.1731324 -1.22075e-4 0.9848986 0.1581789 -0.1536621 0.9753807 0.25889 -0.01260417 0.9658247 0.1690781 -0.1592203 0.9726569 0.2396997 -0.1990478 0.9502231 0.3425166 -0.01904392 0.9393188 0.3416941 -9.15579e-5 0.9398113 0.247968 -0.2037458 0.9471006 0.3172476 -0.2469007 0.9156386 0.4225964 -0.01257377 0.9062308 0.3222263 -0.2504441 0.9129338 0.3895116 -0.2966123 0.871953 0.4999911 -0.01904374 0.8658211 0.4999303 -6.10378e-5 0.8660657 0.3913509 -0.2989685 0.8703231 0.455255 -0.347217 0.8198679 0.5735127 -0.01266533 0.8190988 0.4548581 -0.3487429 0.8194405 0.5134888 -0.3975456 0.7604517 0.6492944 -0.009674549 0.7604756 0.6530191 -0.01226866 0.7572422 0.5127284 -0.4042314 0.7574342 0.5688831 -0.4422273 0.6934026 0.7682694 -0.007111012 0.6400873 0.6940041 -0.0443747 0.7186025 0.6105962 -0.4763121 0.632692 0.7743746 -0.01214677 0.6326109 0.5611352 -0.4546214 0.6916984 0.6448485 -0.5199623 0.5601872 0.8673182 -0.007141411 0.4977031 0.8083954 -0.04297113 0.5870694 0.6048276 -0.5013373 0.6187443 0.6714164 -0.5591373 0.4863802 0.8726274 -0.01190233 0.4882416 0.6416435 -0.5446828 0.5400133 0.6912941 -0.5931744 0.4126218 0.9405452 -0.007385671 0.3395887 0.8981237 -0.0428797 0.4376476 0.6716946 -0.583464 0.4565045 0.7056105 -0.6217429 0.339926 0.9442231 -0.01208543 0.3290849 0.6952111 -0.6167447 0.3691983 0.7156273 -0.6446689 0.2688485 0.9813944 -0.007110834 0.191872 0.9604637 -0.0433675 0.2750068 0.7126037 -0.6436598 0.2791023 0.7224526 -0.6619939 0.1995656 0.9848551 1.22077e-4 0.1733796 0.7242893 -0.663647 0.1870236 0.7270562 -0.6738004 0.1318424 0.9961432 -3.05191e-4 0.08774238 0.9962101 -3.05193e-5 0.08697992 0.7303462 -0.6766635 0.0933876 0.7309349 -0.6793879 0.06454807 0.9990339 -2.74669e-4 0.0439471 0.9990513 0 0.04355108 0.7324544 -0.6799924 0.03347927 0.9854185 -0.01648008 -0.1693482 0.9972065 -0.02450668 -0.07055979 0.9961755 0 -0.08737629 0.9965718 -0.04489362 -0.06949204 0.7312319 -0.680357 -0.04913532 0.7309922 -0.681643 -0.03183132 0.7301684 -0.6801476 -0.06521916 0.7310726 -0.6806559 0.04733431 0 -1 -1.62091e-5 0 -1 -4.6723e-6 0 -1 -1.40037e-5 0 -1 -1.8792e-5 0 -1 9.9469e-6 0 -1 -9.98229e-6 0 -1 9.89063e-6 0 -1 -3.74814e-5 0 -1 1.97833e-5 0 -1 1.99256e-5 0 -1 -2.53052e-5 0 -1 -1.50069e-5 0 -1 8.27596e-5 0 -1 -1.49134e-4 0 -1 5.00266e-5 0 -1 2.75666e-5 0 -1 -3.31767e-5 0 -1 3.99282e-5 0 -1 -3.30751e-5 0 -1 -1.87765e-5 0 -1 -1.87068e-5 0 -1 -9.34411e-6 0 -1 1.99016e-5 0.9658883 -0.0127263 -0.2586465 0.939341 -0.01910477 -0.3424525 0 -1 1.98796e-5 0.9848925 0 -0.1731672 0.9063159 -0.01269578 -0.4224103 0.865663 -0.01910465 -0.5002626 0.9399138 -3.05187e-5 -0.3414123 0.819239 -0.01269614 -0.5733117 0.7658224 -0.01910507 -0.6427683 0.8663457 -6.10382e-5 -0.499445 0 -1 3.75363e-5 0.707355 -0.01269614 -0.7067446 0.6428012 -0.01910519 -0.7657947 0.7664673 -9.15586e-5 -0.6422834 0.5740674 -0.01269596 -0.8187097 0.5002758 -0.01910519 -0.8656554 0.6433789 -9.15581e-5 -0.765548 0 -1 2.54544e-5 0.4233008 -0.01269596 -0.9059002 0.3424525 -0.01910477 -0.939341 0 -1 -4.00397e-5 0.5007956 -6.10391e-5 -0.8655655 0.2595334 -0.01269584 -0.9656507 0.3429092 -3.05188e-5 -0.9393686 0.1743233 0 -0.9846885 -0.9986489 0.009338855 -0.05111962 -0.9962048 0 -0.08704048 -0.9848281 4.88309e-4 -0.1735329 -0.9848281 -4.88309e-4 0.1735329 -0.9964335 -0.005981624 0.0841704 -0.9986489 -0.009338855 0.05111962 -0.9962048 0 0.08704048 -0.98063 -9.15564e-5 -0.1958696 -0.9397453 1.22077e-4 -0.3418754 -0.9964335 0.005981624 -0.0841704 -0.9392657 -1.52597e-4 -0.3431909 -0.8660789 1.52597e-4 -0.4999074 -0.8654083 -9.15582e-5 -0.5010676 -0.7799838 9.15581e-5 -0.6257998 -0.7667431 -0.002655148 -0.6419486 -0.7071373 -4.27273e-4 -0.7070763 -0.6425892 -0.005188286 -0.7661934 -0.6424181 0 -0.7663544 -0.5727944 -3.96757e-4 -0.8196991 -0.4984722 -0.002655148 -0.8669016 -0.4797863 1.52594e-4 -0.8773854 -0.342483 -1.83113e-4 -0.9395241 -0.3403508 2.74673e-4 -0.9402986 -0.1746888 -2.74668e-4 -0.9846237 -0.1718229 3.35711e-4 -0.9851279 -0.001586973 -3.35713e-4 -0.9999987 0.001586973 3.35713e-4 -0.9999987 0.1718229 -3.35711e-4 -0.9851279 0.1746888 2.74668e-4 -0.9846237 0.3403508 -2.74673e-4 -0.9402986 0.342483 1.83113e-4 -0.9395241 0.4797863 -1.52594e-4 -0.8773854 0.4984722 0.002655148 -0.8669016 0.5727944 3.96757e-4 -0.8196991 0.6425892 0.005188286 -0.7661934 0.7071373 4.27273e-4 -0.7070763 0.7667431 0.002655148 -0.6419486 0.6424181 0 -0.7663544 0.7799838 -9.15581e-5 -0.6257998 0.8654083 9.15582e-5 -0.5010676 0.8660789 -1.52597e-4 -0.4999074 0.9392657 1.52597e-4 -0.3431909 0.9397453 -1.22077e-4 -0.3418754 0.98063 9.15564e-5 -0.1958696 0.9848281 -4.88309e-4 -0.1735329 0.9964335 -0.005981624 -0.0841704 0.9986489 -0.009338855 -0.05111962 0.9986489 0.009338855 0.05111962 0.9962048 0 0.08704048 0.9848281 4.88309e-4 0.1735329 0.9962048 0 -0.08704048 0.98063 -9.15564e-5 0.1958696 0.9397453 1.22077e-4 0.3418754 0.9964335 0.005981624 0.0841704 0.9392657 -1.52597e-4 0.3431909 0.8660789 1.52597e-4 0.4999074 0.8654083 -9.15582e-5 0.5010676 0.7799838 9.15581e-5 0.6257998 0.7667431 -0.002655148 0.6419486 0.7071373 -4.27273e-4 0.7070763 0.6425892 -0.005188286 0.7661934 0.6424181 0 0.7663544 0.5727944 -3.96757e-4 0.8196991 0.4984722 -0.002655148 0.8669016 0.4797863 1.52594e-4 0.8773854 0.342483 -1.83113e-4 0.9395241 0.3403508 2.74673e-4 0.9402986 0.1746888 -2.74668e-4 0.9846237 0.1718229 3.35711e-4 0.9851279 0.001586973 -3.35713e-4 0.9999987 -0.001586973 3.35713e-4 0.9999987 -0.1718229 -3.35711e-4 0.9851279 -0.1746888 2.74668e-4 0.9846237 -0.3403508 -2.74673e-4 0.9402986 -0.342483 1.83113e-4 0.9395241 -0.4797863 -1.52594e-4 0.8773854 -0.4984722 0.002655148 0.8669016 -0.5727944 3.96757e-4 0.8196991 -0.6425892 0.005188286 0.7661934 -0.7071373 4.27273e-4 0.7070763 -0.7667431 0.002655148 0.6419486 -0.6424181 0 0.7663544 -0.7799838 -9.15581e-5 0.6257998 -0.8654083 9.15582e-5 0.5010676 -0.8660789 -1.52597e-4 0.4999074 -0.9392657 1.52597e-4 0.3431909 -0.9397453 -1.22077e-4 0.3418754 -0.98063 9.15564e-5 0.1958696 0.7293429 -0.6769113 -0.09924775 0.7273032 -0.6734978 -0.132026 0.7208582 -0.6641234 -0.1982513 0.7232775 -0.6609265 -0.2001152 0.706389 -0.6431845 -0.2955139 0.7172668 -0.6423722 -0.2699745 0.6871453 -0.6134103 -0.389306 0.705023 -0.6249712 -0.3351919 0.6873198 -0.6003099 -0.4089249 0.6609785 -0.5743048 -0.4829923 0.667365 -0.5675669 -0.482174 0.6265199 -0.5311183 -0.5704264 0.6411783 -0.5291117 -0.5558161 0.5842936 -0.4831523 -0.6520466 0.6076083 -0.4856532 -0.628453 0.5342716 -0.4318181 -0.726696 0.5658584 -0.438074 -0.6984952 0.4779902 -0.3776434 -0.793039 0.5168121 -0.3985502 -0.7576696 0.4554392 -0.3504834 -0.8183744 0.4124968 -0.3197186 -0.8530102 0.3900038 -0.299423 -0.8707715 0.340689 -0.2665266 -0.9016066 0.3179492 -0.2491589 -0.9147832 0.2628308 -0.2151904 -0.9405388 0.2404635 -0.2007271 -0.9496768 0.1793936 -0.1662092 -0.9696352 0.1587925 -0.1546419 -0.975126 0.1404783 -0.1435301 -0.9796249 0.1626372 -0.157571 -0.9740229 0.2004495 -0.1836945 -0.9623286 0.2369205 -0.1993514 -0.9508563 0.2432042 -0.2063986 -0.9477612 0.3066016 -0.2438224 -0.9200795 0.3026329 -0.2460189 -0.9208084 0.3719042 -0.2908153 -0.8815406 0.3589065 -0.2878882 -0.8878663 0.4330369 -0.340228 -0.8347001 0.4128955 -0.333118 -0.8476732 0.4899593 -0.3915035 -0.7788869 0.4647766 -0.3811846 -0.7991753 0.5423957 -0.4436035 -0.7134585 0.5146118 -0.4311728 -0.741124 0.5899116 -0.495118 -0.6378578 0.5621638 -0.4820204 -0.672033 0.6318105 -0.5441896 -0.5519721 0.6067261 -0.5321366 -0.5905202 0.667336 -0.5887486 -0.4561116 0.6471315 -0.5792565 -0.4956641 0.6957451 -0.6266192 -0.3511228 0.6817043 -0.6206967 -0.3873174 0.7163116 -0.6557313 -0.2385671 0.7085604 -0.653382 -0.2665227 0.7282281 -0.6746051 -0.1207966 0.7300799 -0.6799674 -0.06802725 0.7305938 -0.6801764 -0.05993926 0.7257776 -0.6742611 -0.1364514 0.7264249 -0.6737482 0.135537 0.7308159 -0.6801538 0.05743736 0.7298988 -0.6800913 0.0687294 0.727392 -0.676944 0.1124628 0.7039273 -0.6514953 -0.2829138 0.6735306 -0.617253 -0.4066392 0.6358934 -0.5733295 -0.5166557 0.5941735 -0.5240409 -0.6101959 0.3305257 -0.264207 -0.9060616 0.3559757 -0.2835842 -0.8904277 0.2880061 -0.231821 -0.9291456 0.2100647 -0.219129 -0.9528145 0.2414993 -0.2008171 -0.949395 0.05984771 0.06698918 -0.9959572 0.1004062 -0.04071182 -0.9941133 0.05459892 0.01190251 -0.9984374 0.1259515 -0.05197364 -0.9906741 -0.01535117 0.09110015 -0.9957235 -0.04861754 0.08444744 -0.9952412 0.0237134 -0.07281887 -0.9970633 -0.02935904 0.04974561 -0.9983304 -0.8871744 -0.4272745 -0.1742364 -0.3640347 -0.1344987 -0.921623 -0.05618578 0.1081599 -0.9925445 0.7098742 -0.6514912 -0.2676525 0.6815469 -0.6203566 -0.3881387 0.6553862 -0.5924234 -0.4685122 0.6050742 -0.5353988 -0.5892652 0.6307141 -0.5649142 -0.5320448 0.574351 -0.5043082 -0.6448211 0.2454912 -0.1089512 -0.9632568 0.1661141 0.01199388 -0.9860336 0.196358 -0.07446587 -0.9777005 0.11991 0.03378474 -0.9922099 0.1425837 -0.04525935 -0.9887475 0.8249424 -0.513094 -0.2370755 0.8511087 -0.4376703 -0.2899287 0.8164873 -0.4443024 -0.3687057 0.7661216 -0.4928534 -0.4124965 0.8312032 -0.3877829 -0.3984038 0.7552941 -0.4440878 -0.4819929 0.7959735 -0.3502088 -0.493741 0.7061932 -0.4426869 -0.5525575 0.7006319 -0.4105763 -0.5835598 -0.1408172 0.3155112 -0.9384154 -0.08966463 0.1770099 -0.9801162 -0.2855975 0.4380097 -0.8523976 -0.1696237 0.2018822 -0.9646095 -0.1222306 0.2312768 -0.9651792 -0.3376972 0.4504054 -0.826496 -0.3895453 0.4618755 -0.7968222 -0.4419506 0.4723783 -0.7625867 -0.4957488 0.4814354 -0.7228093 -0.5513949 0.4884333 -0.676311 -0.609371 0.4930939 -0.6209071 -0.6687429 0.4951786 -0.5546001 -0.7276132 0.4947196 -0.4752177 -0.7834961 0.4917604 -0.379876 -0.8311519 0.4876921 -0.2671014 -0.2091189 0.3141667 -0.9260501 -0.1779595 0.3358372 -0.9249562 -0.2597164 0.4026062 -0.877756 -0.2532461 0.5137558 -0.8197082 -0.2186397 0.4151836 -0.8830738 -0.3745059 0.6416133 -0.6693862 -0.2891688 0.4398113 -0.8502632 -0.2477868 0.4649322 -0.8499646 -0.4024301 0.6454264 -0.6492108 -0.4325166 0.6507282 -0.6240851 -0.4616321 0.6573208 -0.5956721 -0.493961 0.6625213 -0.5630881 -0.5266401 0.6701111 -0.5230693 -0.5621411 0.6768339 -0.4752823 -0.5999804 0.682749 -0.4169862 -0.6342209 0.6874465 -0.3538098 -0.6678901 0.6884908 -0.2826722 -0.6979749 0.6885445 -0.1968185 -0.31542 0.5249675 -0.7905185 -0.2895984 0.5435195 -0.7878575 -0.3616544 0.610845 -0.7043257 -0.3497772 0.6789542 -0.6455054 -0.3297609 0.619633 -0.712259 -0.3998907 0.7242774 -0.5617026 -0.3891178 0.635315 -0.6670548 -0.3511571 0.6573591 -0.6667591 -0.4122208 0.7211042 -0.5568507 -0.4285782 0.7251008 -0.5390264 -0.4146014 0.7224166 -0.5533715 -0.4500036 0.7263537 -0.519526 -0.4360968 0.7299411 -0.5263132 -0.4681717 0.7310681 -0.4963414 -0.4920688 0.7325639 -0.4703388 -0.4739023 0.7402435 -0.4769237 -0.5096473 0.7462659 -0.4281904 -0.4944058 0.7286076 -0.4740191 -0.5444647 0.742535 -0.3901284 -0.5165451 0.7507835 -0.4117102 -0.5641496 0.7699413 -0.2982043 -0.544281 0.7650269 -0.344227 -0.5847702 0.7721554 -0.2486364 -0.6231369 0.7538498 -0.2083532 -0.6426391 0.7551627 -0.1294006 -0.6027636 0.7815478 -0.1608082 -0.6147426 0.7844278 -0.08224844 -0.3985853 0.6920612 -0.6018149 -0.3792323 0.7070091 -0.5969262 -0.4053602 0.7412274 -0.5350376 -0.3912004 0.7344239 -0.5546024 -0.4005382 0.7438219 -0.5350683 -0.4456413 0.8330827 -0.3276847 -0.451231 0.8437119 -0.2907594 -0.4434461 0.8292412 -0.3401686 -0.4422212 0.8280432 -0.3446518 -0.428367 0.8140072 -0.3922933 -0.4385576 0.8012755 -0.4069705 -0.4420095 0.8266734 -0.3481935 -0.4416698 0.8217829 -0.3600012 -0.4423201 0.8323296 -0.3340366 -0.4488806 0.8094988 -0.3784416 -0.441977 0.7998129 -0.4061476 -0.4305381 0.7998847 -0.4181167 -0.4412971 0.799472 -0.4075554 -0.4395958 0.8001779 -0.4080086 -0.4541258 0.8099798 -0.371083 -0.4471115 0.8027254 -0.3946179 -0.4576092 0.8159387 -0.3533242 -0.4619357 0.81559 -0.348466 -0.466979 0.8157866 -0.3412081 -0.4639858 0.8163929 -0.3438311 -0.4656637 0.8143775 -0.3463332 -0.4561041 0.8067961 -0.3755649 -0.470794 0.8206697 -0.323812 -0.4726588 0.8227809 -0.3156349 -0.4754545 0.8285891 -0.2956064 -0.4809222 0.8307642 -0.2802582 -0.4784168 0.8328042 -0.2784864 -0.4851332 0.8377825 -0.2505321 -0.4904688 0.838567 -0.2371621 -0.4927979 0.8451452 -0.2070746 -0.4961812 0.8483118 -0.1848548 -0.4970626 0.8523952 -0.1623305 -0.4995677 0.8549935 -0.1393503 -0.4983769 0.857892 -0.1250672 -0.5028343 0.8577727 -0.1066951 -0.5027192 0.8603481 -0.08411204 -0.5075682 0.8599146 -0.05404984 0.006653249 0.2776362 -0.9606633 -0.03390693 0.2873086 -0.9572378 -0.08188229 0.2996045 -0.9505432 -0.1512823 0.5126569 -0.8451607 -0.1794248 0.5103186 -0.8410599 -0.2125966 0.5104639 -0.8332043 -0.2945095 0.6991016 -0.6515528 -0.3101366 0.6914745 -0.6524404 -0.3272538 0.6825848 -0.6534394 -0.3498479 0.7700438 -0.5335158 -0.3594207 0.7643755 -0.5353009 -0.3673653 0.7516385 -0.5477976 -0.3475252 0.7525796 -0.5593303 -0.3771261 0.749888 -0.5435475 -0.367056 0.7318537 -0.5741603 -0.3821666 0.7434579 -0.5488343 -0.4238212 0.8354043 -0.3499646 -0.4249457 0.8333806 -0.3534092 -0.4298374 0.8297045 -0.3561326 -0.4236651 0.8264858 -0.3707146 -0.4245181 0.8209587 -0.3818526 -0.427208 0.8159618 -0.3894863 -0.4281609 0.817989 -0.3841514 -0.4278511 0.8099536 -0.4011466 -0.4283937 0.7989236 -0.4221373 0.4047798 0.1803701 0.8964486 0.356006 0.1574178 0.9211295 0.467373 0.2008171 0.8609502 0.3077852 0.1514968 0.9393173 0.2775744 0.1352317 0.9511387 0.4934626 0.2311818 0.8384806 0.5852096 0.2668921 0.7657012 0.6091977 0.2924979 0.7371045 0.6979756 0.3178276 0.6417286 0.7207885 0.3454548 0.6009368 0.7890263 0.3588508 0.4986617 0.8082153 0.3864674 0.4443322 0.8561386 0.3890651 0.340081 0.8681653 0.414627 0.272715 0.8967576 0.4077114 0.172039 0.898581 0.4290714 0.09192425 0.910153 0.4142719 6.1039e-4 0.8984187 0.429372 -0.09210634 0.8969789 0.408464 -0.1690743 0.8679788 0.4146705 -0.2732424 0.8574488 0.390285 -0.3353496 0.8078189 0.3861013 -0.4453701 0.7915462 0.3605234 -0.4934346 0.7201314 0.3445619 -0.6022357 0.7013719 0.3196627 -0.6370975 0.6083723 0.2912154 -0.7382932 0.588879 0.268574 -0.7622923 0.4746652 0.2257506 -0.850723 0.4532986 0.2144265 -0.8651831 0.3625962 0.1742634 -0.9155088 0.3240512 0.1578139 -0.9327839 0.2755007 0.1362091 -0.9516021 0.1652941 0.07672834 0.9832552 0.165294 0.07672756 0.9832553 0.1652984 0.07672876 0.9832544 0.239943 0.1170111 0.9637094 0.2395452 0.1111814 0.9644982 0.1652982 0.07672947 0.9832544 -0.4207667 0.8483392 -0.321366 -0.4323053 0.8513653 -0.2971355 -0.4371567 0.8308541 -0.3443479 -0.7049179 -0.327221 0.629299 -0.4441698 0.8702726 -0.2129293 -0.4433559 0.8673319 -0.22621 -0.7048996 -0.3272018 0.6293295 -0.6458451 -0.2928918 0.7050521 -0.6491225 -0.30129 0.6984729 -0.6000392 -0.2795869 0.7495226 -0.7049021 -0.3272036 0.6293258 -0.5727531 -0.2553538 0.7789406 -0.4630282 -0.2189099 0.858885 -0.410212 -0.1753038 0.8949831 -0.3102265 -0.1478039 0.9391025 -0.2287443 -0.08850681 0.9694548 -0.1492707 -0.07025575 0.9862974 -0.02877926 -0.001525938 0.9995847 0.01788383 0.02020329 0.9996359 0.07059115 0.04641985 0.9964247 0.06869906 0.03186219 0.9971286 -0.4250995 0.8537697 -0.3006124 -0.4577562 0.8769974 -0.1460645 -0.4796712 0.8621692 -0.1630339 -0.4442971 0.8461726 -0.2942652 -0.4353862 0.8708029 -0.2283443 -0.4464991 0.8761514 -0.1816515 -0.4493405 0.881834 -0.1430454 -0.45086 0.8867657 -0.1018425 -0.5878114 0.7819173 -0.2075651 -0.5092961 0.8422551 -0.1767032 -0.5229389 0.8396931 -0.1464595 -0.4844949 0.8304624 -0.274949 -0.4841642 0.860655 -0.1576646 -0.5732422 0.7819936 -0.2447029 -0.4528436 0.8878641 -0.08142518 -0.4516192 0.888162 -0.08490365 -0.5971373 0.7856235 -0.1619345 -0.5257493 0.8413454 -0.1254022 -0.4526604 0.8892066 -0.0664097 -0.5297523 0.8424826 -0.09790557 -0.4544324 0.8898208 -0.04135364 -0.4533287 0.8899026 -0.05066144 -0.6014766 0.7915515 -0.1080387 -0.53116 0.8441366 -0.07281929 -0.453026 0.8910366 -0.02865743 -0.5334137 0.84477 -0.04281836 -0.4537327 0.8911375 7.32467e-4 -0.4538543 0.8910756 7.62986e-4 -0.6041928 0.7949696 -0.05453819 -0.5337437 0.845646 7.93489e-4 -0.4539153 0.8900989 0.04104858 -0.4539403 0.8906069 0.02752816 -0.6063824 0.7951731 6.40899e-4 -0.5314956 0.8460286 0.04181158 -0.4536032 0.88978 0.05035626 -0.6038414 0.7951627 0.05560493 -0.5301427 0.8449752 0.070468 -0.4524465 0.8880161 0.08197444 -0.4529 0.8891367 0.06570708 -0.5992698 0.793065 0.1091967 -0.5249041 0.8454195 0.09869992 -0.4522874 0.8877896 0.08523875 -0.5239142 0.8434143 0.1190229 -0.4492471 0.8818916 0.1429839 -0.4512595 0.8866184 0.1013548 -0.5969233 0.7865996 0.1579363 -0.5231291 0.8396435 0.1460647 -0.4577521 0.87702 0.1459411 -0.5872143 0.7801853 0.2156161 -0.5138532 0.8402569 0.1729833 -0.4433528 0.867326 0.226239 -0.4440177 0.8703651 0.2128685 -0.4796712 0.8621692 0.1630339 -0.487276 0.8523514 0.189893 -0.4323661 0.8513343 0.2971354 -0.4388948 0.8663145 0.238476 -0.4464333 0.8761727 0.1817107 -0.4334086 0.8607132 0.2670768 -0.4228138 0.8545698 0.3015608 -0.4209223 0.8482842 0.3213073 -0.3573534 0.7651862 0.5355265 -0.4296842 0.8185334 0.3812803 -0.4371532 0.8307559 0.3445893 -0.7049034 -0.3272114 -0.6293202 -0.7049055 -0.3272082 -0.6293195 -0.704904 -0.3272095 -0.6293206 -0.7651509 -0.3552758 -0.5369576 -0.7653604 -0.3552435 -0.5366801 -0.8180611 -0.3797476 -0.431935 -0.7049043 -0.3272075 -0.6293213 -0.8839291 -0.4102398 -0.2244386 -0.8846903 -0.4106357 -0.2206842 -0.8154178 -0.3785018 -0.4379842 -0.9070848 -0.4209481 0 -0.8846666 -0.4106694 0.2207165 -0.883952 -0.4101752 0.2244671 -0.8180321 -0.3798093 0.4319358 -0.8154484 -0.3784714 0.4379537 -0.7652683 -0.3553043 0.5367712 -0.7049098 -0.3272088 0.6293145 -0.7651758 -0.3551817 0.5369842 -0.4876086 0.7882248 -0.3754192 -0.452967 0.8253327 -0.3371158 -0.4617286 0.8370873 -0.2934139 -0.5001792 0.8071109 -0.3136764 -0.4679253 0.8492057 -0.244736 -0.5092769 0.8213987 -0.2567901 -0.4770511 0.8552799 -0.2022836 -0.472653 0.863087 -0.1779888 -0.5041067 0.8381025 -0.2084727 -0.50009 0.8395872 0.2121399 -0.4684689 0.8651261 0.1791473 -0.4763425 0.8567939 0.1974892 -0.4825459 0.85104 0.2070757 -0.5096729 0.8223741 0.2528527 -0.4679542 0.8491724 0.2447962 -0.4991753 0.806994 0.3155706 -0.4476267 0.8459342 0.2898724 -0.4556812 0.8274042 0.3282638 -0.4907144 0.7864432 0.3751086 0.1652874 0.07674598 -0.9832549 0.1653037 0.0767306 -0.9832534 0.07440632 0.04626744 -0.9961542 0.08661228 0.0401932 -0.995431 0.01147502 0.006286799 -0.9999144 0.1652933 0.07672601 -0.9832555 -0.03402918 -7.93506e-4 -0.9994207 -0.1525043 -0.07156741 -0.9857082 -0.2287714 -0.0882613 -0.9694708 -0.3118717 -0.1480772 -0.9385144 -0.4104275 -0.1750909 -0.894926 -0.4627918 -0.2183947 -0.8591435 -0.5734809 -0.2589225 -0.7772252 -0.6044983 -0.2763229 -0.7471462 -0.6481449 -0.2940869 -0.7024393 -0.6396304 -0.296895 -0.7090321 0.2431475 0.1176825 -0.962824 0.1652916 0.0767253 -0.9832558 0.2469292 0.1145988 -0.9622335 -0.470768 0.7170323 -0.5140451 -0.3137989 0.6216161 -0.7177212 -0.3925076 0.6785031 -0.6209439 -0.5143717 0.6324203 -0.5791947 -0.4801275 0.6830494 -0.5503826 -0.3261291 0.5654308 -0.7575803 -0.4050828 0.6220445 -0.6700513 -0.540776 0.6761607 -0.5003681 -0.5590574 0.7136695 -0.4220551 -0.5726647 0.7456178 -0.3407483 -0.5692756 0.7754026 -0.2732694 -0.4975811 0.6373884 -0.5883445 -0.3337941 0.5052539 -0.7958015 -0.4210768 0.565739 -0.7089667 -0.4862334 0.5325617 -0.692788 -0.4131962 0.5287715 -0.7413972 -0.4938566 0.4256469 -0.7582417 -0.4585534 0.5101617 -0.7276427 -0.3301249 0.4507057 -0.8293865 -0.4071573 0.478084 -0.7782408 -0.5562086 0.504723 -0.6602172 -0.5889637 0.5681495 -0.5747416 -0.6130384 0.6209123 -0.4885202 -0.6310806 0.6643467 -0.4004758 -0.6302853 0.7019446 -0.3316841 -0.6118247 0.6908702 -0.3851867 -0.4775993 0.4812311 -0.7350616 -0.3259788 0.3969671 -0.8579947 -0.4007235 0.4313347 -0.8083139 -0.4818462 0.4463517 -0.7540521 -0.3175519 0.3420893 -0.8843843 -0.4108861 0.3834795 -0.8271132 -0.4761542 0.4080973 -0.7789312 -0.3789566 0.3497802 -0.8567647 -0.4291965 0.2850527 -0.8570503 -0.2979021 0.2917981 -0.908905 -0.3636298 0.3127552 -0.8774724 -0.4658743 0.2836751 -0.8381465 -0.4355937 0.2263574 -0.8712179 -0.3389802 0.2375639 -0.9103055 -0.2812017 0.2394213 -0.9293025 -0.3646139 0.2674405 -0.8919262 -0.4653922 0.2415925 -0.8514946 -0.5302165 0.3520432 -0.7713211 -0.5312807 0.3415114 -0.7753134 -0.5798574 0.4414546 -0.6847506 -0.5689409 0.4265073 -0.7031343 -0.5769372 0.4313296 -0.6936126 -0.6167577 0.5139393 -0.5962184 -0.6058596 0.5063377 -0.6136419 -0.6442615 0.5725108 -0.507108 -0.6325357 0.570277 -0.5241019 -0.6556133 0.6185019 -0.4331589 -0.6738672 0.5991559 -0.4323371 -0.6606471 0.6626613 -0.3527398 -0.6424551 0.6977249 -0.3169091 -0.3569207 0.159981 -0.9203335 -0.2501354 0.1720062 -0.9528097 -0.3278039 0.2400619 -0.9137368 -0.2768691 0.1731652 -0.9451758 -0.254863 0.1913533 -0.9478549 -0.3144993 0.2049663 -0.9268652 -0.3054957 0.1558912 -0.9393458 -0.2297755 0.1413322 -0.962927 -0.2870017 0.1570819 -0.9449632 -0.3052226 0.1143249 -0.9453936 -0.04171991 0.01480185 -0.9990198 -0.1976433 0.08768206 -0.9763448 -0.2555658 0.09283864 -0.9623239 -0.2213875 0.07233089 -0.9724998 -0.3836584 0.07892292 -0.9200965 -0.3733431 0.1383441 -0.9173199 -0.1651691 0.06412053 -0.9841787 -0.460048 0.1694737 -0.8715702 -0.5634434 0.2321892 -0.7928555 -0.468189 0.2466225 -0.8485143 -0.4767082 0.2379879 -0.8462334 -0.5413731 0.2721056 -0.7955337 -0.6183166 0.3313151 -0.7126816 -0.5376845 0.341386 -0.7709416 -0.5484303 0.3345211 -0.766368 -0.5974232 0.3681592 -0.7124214 -0.6558596 0.4228448 -0.6253403 -0.5877656 0.4309589 -0.6846941 -0.6368088 0.4587611 -0.6196876 -0.6844732 0.5048401 -0.5259591 -0.6214957 0.5164176 -0.5891147 -0.6656467 0.5376507 -0.5175387 -0.699451 0.5719091 -0.4285885 -0.6390734 0.5970484 -0.4848901 -0.6724313 0.5757157 -0.4651749 -0.6923947 0.5925046 -0.4117379 -0.7000281 0.5994966 -0.3880262 -0.6861333 0.6081872 -0.399161 -0.7416396 0.646146 -0.1801835 -0.7318465 0.6279902 -0.2646305 -0.6993427 0.6494441 -0.2985673 -0.6642183 0.7063957 -0.2445802 -0.6977317 0.6527158 -0.2951824 -0.133612 0.4282726 -0.8937173 -0.1440193 0.3810911 -0.9132513 -0.1499431 0.3360214 -0.9298424 -0.1518322 0.2933794 -0.943862 -0.1500303 0.253367 -0.9556652 -0.1451178 0.2159523 -0.9655597 -0.1369991 0.1810379 -0.9738873 -0.1260762 0.1485385 -0.9808369 -0.1129528 0.1182022 -0.9865444 -0.09842407 0.08954304 -0.991108 -0.08356028 0.061953 -0.994575 -0.08298188 0.04880028 -0.9953555 0.02963387 0.03418117 -0.9989763 -0.02850455 0.04007118 -0.9987902 0.05636924 0.1977348 -0.9786335 0.04709112 0.167581 -0.984733 0.04016363 0.1405424 -0.9892597 0.03527987 0.1167349 -0.9925363 0.03213638 0.0960735 -0.9948554 0.03024458 0.07849568 -0.9964556 0.02963411 0.06384611 -0.9975197 0.02993941 0.0520659 -0.9981948 0.03064072 0.04309231 -0.9986011 0.03094661 0.03695893 -0.9988375 0.03366279 0.0318011 -0.9989273 -0.716038 0.5914897 -0.3707149 -0.7266653 0.5565201 -0.4027941 -0.7555601 0.5621914 -0.3362588 -0.7620081 0.5297555 -0.3724281 -0.720779 0.4847716 -0.4954535 -0.7290999 0.5878578 -0.3504807 -0.783135 0.5398321 -0.3086761 -0.8004272 0.4952351 -0.3377255 -0.7621904 0.4560508 -0.4594384 -0.8334513 0.484036 -0.266586 -0.8470284 0.4396893 -0.2986909 -0.8078944 0.4133775 -0.4200306 -0.7999124 0.5254823 -0.2898423 -0.8815372 0.4139273 -0.2270603 -0.8983671 0.3547262 -0.2590481 -0.8560916 0.3514581 -0.3789253 -0.933826 0.2981724 -0.1976422 -0.9284238 0.2747031 -0.2501351 -0.9029399 0.2606642 -0.3416925 -0.9380273 0.29469 -0.1823806 -0.9184771 0.3437689 -0.1955063 -0.9624382 -0.001922667 -0.2714945 -0.9516387 0.1332758 -0.2768059 -0.9569869 0.1198179 -0.2642343 -0.9433333 0.1940379 -0.2692055 -0.9455009 0.05340778 -0.3212097 -0.9656221 0.1167048 -0.2322803 -0.9735198 0.01269578 -0.2282502 -0.9654649 0.1614143 -0.204507 -0.9213753 0.3831993 -0.06500589 -0.9249404 0.3700128 -0.08704024 -0.8982173 0.4205577 -0.1278154 -0.9957496 0.00814861 -0.09174066 -0.98093 0.1536051 -0.1190874 -0.9765365 0.2077776 -0.05661386 -0.8942497 0.4383505 -0.09036797 -0.8538592 0.4939187 -0.1642224 -0.8509122 0.5119634 -0.1176524 -0.8229835 0.5345151 -0.1923326 -0.8157283 0.5618051 -0.1377045 -0.805931 0.5561892 -0.2028027 -0.7818083 0.5818776 -0.2240408 -0.7854396 0.599151 -0.1552506 -0.7589806 0.6040349 -0.2430849 -0.7615775 0.6255226 -0.1694734 -0.7457709 0.6167656 -0.2518457 -0.7040879 0.4008448 -0.5861601 -0.7553175 0.3687929 -0.5417447 -0.8071827 0.3217988 -0.4948755 -0.8557071 0.2565779 -0.4493699 -0.9271854 0.1777156 -0.3297643 -0.8949978 0.1690443 -0.412799 -0.9297024 -0.05578881 -0.364062 -0.9325468 0.07672542 -0.3528028 -0.930759 0.1061134 -0.3498967 -0.9179267 -4.88308e-4 -0.3967499 -0.6793944 0.3082774 -0.6658742 -0.7403308 0.2747018 -0.6135547 -0.7962685 0.2274878 -0.5605406 -0.8422062 0.165902 -0.5129963 -0.9108998 0.09332698 -0.4019349 -0.8731956 0.09247428 -0.4785164 -0.8914273 -0.09720277 -0.442616 -0.9081312 0.02005112 -0.4182054 -0.9088813 0.03286874 -0.415758 -0.9096823 0.0460838 -0.4127401 -0.6385807 0.2113444 -0.739965 -0.7094511 0.1818643 -0.6808851 -0.7696986 0.142678 -0.6222596 -0.8145304 0.09512871 -0.572268 -0.9051598 0.04290956 -0.4229003 -0.8795361 0.03579914 -0.4744837 -0.8422319 0.04474079 -0.5372558 -0.8512432 -0.1227179 -0.510221 -0.8815416 0.006042718 -0.472068 -0.8853395 -0.03924804 -0.4632856 -0.8521583 0.009857714 -0.5231913 -0.8511195 -0.06122148 -0.52139 -0.8621279 -0.05810791 -0.5033479 -0.8608525 -0.03988844 -0.5072886 -0.8508506 -0.04614531 -0.5233774 -0.8579168 -0.03268569 -0.5127481 -0.385123 -0.7438469 -0.5462344 -0.8342615 -0.07055944 -0.5468356 -0.8229854 -0.06418222 -0.5644253 -0.8774286 -0.04297107 -0.4777789 -0.8172176 -0.1123113 -0.56528 -0.8321607 -0.08911538 -0.5473272 -0.8481929 -0.04880034 -0.5274348 -0.8294593 -0.1286397 -0.5435525 -0.8029777 -0.1479547 -0.5773529 -0.7862268 -0.195107 -0.5863282 -0.7174667 -0.2567548 -0.6475481 -0.7717717 -0.1712742 -0.6124 -0.7771952 -0.1705398 -0.6057093 -0.7752804 -0.1861979 -0.6035486 -0.748659 -0.2804076 -0.6007339 -0.7054819 -0.2802273 -0.6509746 -0.6011579 -0.3719317 -0.7073019 -0.6959331 -0.3179202 -0.6438976 -0.6421953 -0.3578739 -0.6778728 -0.6410238 -0.3319566 -0.6920212 -0.4143658 -0.4389953 -0.7972354 -0.5458655 -0.4098112 -0.7308117 -0.5668379 -0.3916562 -0.724776 -0.5378978 -0.4016914 -0.7411545 -0.2002987 -0.4116456 -0.8890604 -0.2038064 -0.471184 -0.8581659 -0.4196092 -0.4507389 -0.787885 -0.4269615 -0.4665753 -0.7746041 -0.2978379 -0.4873934 -0.8208168 -0.3885069 -0.5068291 -0.7695367 -0.3017445 -0.5249934 -0.7958218 -0.07706141 -0.2801985 -0.9568439 -0.08505576 -0.2192163 -0.9719619 -0.09225821 -0.3317391 -0.9388491 -0.08984971 -0.4107331 -0.9073178 -0.1647433 -0.5123585 -0.8428218 -0.08978694 -0.4923329 -0.8657636 -0.1883023 -0.6004616 -0.7771667 -0.177744 -0.5694281 -0.8025951 -0.0859729 -0.525329 -0.8465448 0.06366294 -0.6699263 -0.7396931 -0.1005008 -0.5913465 -0.8001306 -0.07742643 -0.6412327 -0.7634304 -0.03289937 -0.06708049 -0.997205 0.01422202 -0.1576329 -0.9873954 0.01687693 -0.09927803 -0.9949167 0.01126152 -0.1422498 -0.9897668 0.01687687 0 -0.9998577 0.01635801 -0.01626646 -0.9997339 0.01605296 -0.03604286 -0.9992213 0.01684647 -0.03198397 -0.9993465 -0.002288937 -0.2056084 -0.9786317 0.01187205 -0.242935 -0.9699699 0.01519858 -0.2494956 -0.9682567 0.01443529 -0.3180345 -0.9479693 0.01715195 -0.3993169 -0.9166526 0.0157786 -0.427457 -0.903898 0.01379454 -0.4953225 -0.8685997 0.0137642 -0.5715057 -0.8204827 0.01477098 -0.5860806 -0.8101182 0.01574784 -0.6396186 -0.7685312 0.01712173 0.06882363 -0.997482 0.01715892 0.06668859 -0.9976263 0.01736503 0.03021341 -0.9993926 0.01794523 0.2516917 -0.9676412 0.01791453 0.1633976 -0.9863977 0.01702958 0.1591566 -0.9871066 0.01684665 0.1589143 -0.9871487 0.01690751 0.03198391 -0.9993454 0.1338251 0.07409971 -0.9882308 0.1337035 0.2525748 -0.9582951 0.1970939 0.1664525 -0.9661509 0.1268664 0.1659304 -0.9779428 0.01840305 0.253645 -0.9671224 0.6607419 0.19102 -0.7259005 0.7615445 0.1390147 -0.6330283 0.6629114 0.1490261 -0.7337164 0.4672482 0.2240411 -0.8552688 0.5636898 0.1584252 -0.8106512 0.4453126 0.1630666 -0.880401 0.2477847 0.2432069 -0.9377917 0.3264353 0.1671546 -0.9303222 0.6721522 0.2784256 0.6860689 0.6887977 0.3619629 0.6281247 0.708851 0.4397587 0.5514913 0.7298865 0.5094801 0.4557365 0.7492151 0.5671987 0.3419978 0.7641154 0.6089546 0.2128426 0.7722597 0.6311691 0.07239168 0.7722057 0.6312664 -0.07211768 0.7639001 0.6092889 -0.212659 0.7488519 0.5676589 -0.3420298 0.7295051 0.5098266 -0.4559598 0.7084487 0.4401825 -0.5516701 0.6884214 0.3623238 -0.6283292 0.6718776 0.2784866 -0.6863132 0.476764 0.3462048 0.8079841 0.4904812 0.4621895 0.738789 0.507131 0.56884 0.647487 0.5246499 0.6630224 0.5339887 0.5408616 0.739969 0.3998933 0.553347 0.7950605 0.2483667 0.5602126 0.824052 0.0842638 0.5601186 0.8241096 -0.08432447 0.5530462 0.79525 -0.2484298 0.540469 0.7401883 -0.4000185 0.5240761 0.6632744 -0.5342391 0.5065253 0.569303 -0.647554 0.4900829 0.4626153 -0.7387868 0.4764357 0.3464848 -0.8080578 0.2521185 0.3883864 0.8863365 0.2543165 0.526853 0.8110173 0.2566382 0.6550392 0.7106762 0.2885329 0.7668066 0.573373 0.2996025 0.8536093 0.4261332 0.3082747 0.9143559 0.2625263 0.3134957 0.9454618 0.0884453 0.3089166 0.9462211 -0.09610533 0.3071117 0.9141939 -0.2644463 0.2996102 0.8538448 -0.4256559 0.2888044 0.7673475 -0.5725121 0.2796478 0.6579034 -0.6992569 0.2541959 0.5246893 -0.8124566 0.2520592 0.3884806 -0.886312 0.1387401 0.4253455 0.8943335 0.1494814 0.5838564 0.7979768 0.1801558 0.7143056 0.676248 0.2111925 0.826367 0.5220301 0.2202895 0.7386628 0.6370635 0.2268195 0.9048365 0.360311 0.1957192 0.8539863 0.4820802 0.2352722 0.9542123 0.1847324 0.1767348 0.9364718 0.3029609 0.2389936 0.9710203 0.001342773 0.164864 0.9804251 0.1076408 0.1751178 0.9780717 -0.112737 0.1832367 0.9339762 -0.306778 0.3188681 0.9354542 -0.1524755 0.1952956 0.854216 -0.4818451 0.2759575 0.8993188 -0.3392245 0.2076524 0.7462242 -0.6324793 0.2315481 0.8267616 -0.5126898 0.2182138 0.6181402 -0.7551724 0.1924555 0.7197702 -0.6670021 0.1386182 0.4252545 -0.8943957 0.1506445 0.5737676 -0.8050448 0.01861655 0.2502556 0.9680009 0.01889145 0.4301092 0.9025793 0.01913577 0.426542 0.9042654 0.01922738 0.5917769 0.8058725 0.01919674 0.5878981 0.8087071 0.01904398 0.7149747 0.6988911 0.01675516 0.7272784 0.6861382 0.01843351 0.7911157 0.6113888 0.01629704 0.831089 0.5559006 0.01846414 0.8449574 0.534515 0.01815885 0.8897857 0.4560171 0.01818913 0.8912376 0.4531722 0.01794499 0.9287455 0.3702836 0.01794505 0.9296661 0.3679661 0.01773172 0.9593763 0.2815717 0.0177316 0.9599482 0.2796161 0.01754838 0.9814891 0.1907128 0.01757866 0.9818136 0.1890321 0.01742637 0.9949829 0.09851557 0.01751768 0.9951522 0.09677463 0.01736533 0.9998348 0.005371332 0.01751798 0.9998404 0.003540217 0.01736521 0.9959839 -0.08783334 0.01757895 0.9958059 -0.089787 0.01739591 0.9834509 -0.180338 0.01770091 0.9830743 -0.1823503 0.01754868 0.9622179 -0.2717148 0.01788407 0.9617115 -0.2734798 0.01773136 0.9323475 -0.3611283 0.01809793 0.9318166 -0.3624782 0.01800596 0.8939524 -0.4478002 0.01831132 0.8935927 -0.4485054 0.01825058 0.8477061 -0.530152 0.01858615 0.8473954 -0.5306369 0.0185554 0.7938866 -0.6077827 0.01892185 0.7934058 -0.6083989 0.01666343 0.7175045 -0.6963548 0.01898294 0.7319741 -0.681068 0.01879972 0.6643695 -0.7471678 0.01675486 0.5906322 -0.806767 0.01941001 0.572627 -0.8195863 0.01886075 0.4290372 -0.90309 0.01910507 0.4302306 -0.9025168 -1 0 0 -1 2.65316e-6 0 -1 -1.26947e-6 0 -1 5.28138e-6 0 -1 -2.58319e-6 0 -1 2.62204e-6 0 -1 1.35021e-5 0 -1 -6.8624e-5 0 -1 1.6185e-5 0 -1 1.55717e-5 0 -1 -8.88168e-6 0 -1 1.5363e-5 0 -1 -1.85008e-5 0 -1 -5.12328e-6 0 -1 4.73142e-6 0 -1 5.51564e-5 0 -1 -6.17535e-6 0 -1 2.40203e-6 0 -1 -2.63602e-6 0 -1 -2.65218e-6 0 0.01693826 -0.03155702 0.9993584 0.01684647 -0.03198397 0.9993465 -4.57786e-4 -0.1211607 0.9926329 0.01681613 -0.1589143 0.9871492 0.01379454 -0.2502244 0.9680896 0.01559531 -0.3136154 0.9494221 0.0129401 -0.4286723 0.9033675 0.003021299 -0.1382497 0.9903928 0.0137946 -0.1887909 0.9819204 0.01831161 -0.2429042 0.9698775 0.01895272 -0.4909106 0.8710039 0.01196348 -0.5914908 0.8062232 -1 2.50838e-6 0 0.01788425 -0.3964147 0.9178974 0.01516801 -0.6401408 0.7681079 0.01461857 -0.7181431 0.6957421 0.01889133 -0.5742487 0.818463 -1 2.40204e-6 0 0.02124148 -0.7341449 0.6786605 0.01727366 -0.7936117 0.6081793 0.01229929 -0.6735951 0.7389982 0.02130204 -0.8052964 0.5924897 0.01663279 -0.8480302 0.5296869 -1 -4.73127e-6 0 0.01788425 -0.8495029 0.5272808 0.01684659 -0.8938176 0.4481143 -1 -2.56154e-6 0 0.0190134 -0.9173738 0.3975724 0.01586985 -0.9324156 0.3610394 -1 -5.51702e-5 0 -1 6.17528e-6 0 0.01745682 -0.8833413 0.4684053 -1 6.66057e-6 0 0.01983761 -0.9417988 0.3355916 0.01580893 -0.9619982 0.2725982 -1 -4.62434e-6 0 0.01904368 -0.9652179 0.2607526 0.01709085 -0.9837014 0.1789963 -1 -1.24579e-5 0 -1 1.52981e-5 0 0.02151596 -0.9943755 0.1037041 0.01675474 -0.9959782 0.08801597 -1 1.53601e-5 0 0.01739597 -0.9790908 0.2026789 0.01803678 -0.9998373 2.13634e-4 0.01629692 -0.999853 -0.005340754 0.02102762 -0.9943125 -0.1044058 0.01767045 -0.9948571 -0.09973591 0.01779264 -0.9818913 -0.1886081 0.01669383 -0.9791099 -0.202646 0.01562595 -0.9592873 -0.2819997 0.01986783 -0.9417561 -0.3357093 0.01602256 -0.9285469 -0.3708694 0.01867759 -0.9654385 -0.259961 0.01855564 -0.9172239 -0.3979398 0.01736539 -0.8898171 -0.455987 -1 -1.61863e-5 0 -1 3.43264e-5 0 0.01742655 -0.8835973 -0.4679232 0.01446604 -0.8314041 -0.55548 -1 6.27959e-6 0 0.01608347 -0.8024347 -0.5965233 0.01205503 -0.7286137 -0.6848188 -1 -3.93296e-6 0 0.01812833 -0.849651 -0.5270339 -1 -2.65332e-6 0 0.01410007 -0.6740569 -0.7385449 -1 2.58334e-6 0 0.01895225 -0.7352318 -0.677551 -1 1.2695e-6 0 0.01129198 -0.9982447 0.0581386 0 -0.9951928 0.09793531 6.71425e-4 -0.9807994 0.1950184 -6.71425e-4 -0.9807994 -0.1950184 -0.007446527 -0.9955187 -0.09427213 -0.01129198 -0.9982447 -0.0581386 0 -0.9951928 -0.09793531 -9.15559e-5 -0.9754979 0.2200089 1.52595e-4 -0.9239954 0.382404 0.007446527 -0.9955187 0.09427213 -1.83118e-4 -0.923372 0.3839067 1.83116e-4 -0.831651 0.5552987 -1.52597e-4 -0.8307098 0.5567058 1.83113e-4 -0.7072746 0.7069389 -6.1039e-5 -0.706435 0.7077779 9.15579e-5 -0.5553902 0.83159 3.05193e-5 -0.5552072 0.8317121 9.15577e-5 -0.3819484 0.9241837 -1.22076e-4 -0.195535 0.9806967 2.13632e-4 -0.1940087 0.9809998 0 -0.3826816 0.9238803 -1.83117e-4 -9.15583e-4 0.9999997 1.83117e-4 9.15583e-4 0.9999997 -2.13632e-4 0.1940087 0.9809998 1.22076e-4 0.195535 0.9806967 -9.15577e-5 0.3819484 0.9241837 0 0.3826816 0.9238803 -3.05193e-5 0.5552072 0.8317121 -9.15579e-5 0.5553902 0.83159 6.1039e-5 0.706435 0.7077779 -1.83113e-4 0.7072746 0.7069389 1.52597e-4 0.8307098 0.5567058 -1.83116e-4 0.831651 0.5552987 1.83118e-4 0.923372 0.3839067 -1.52595e-4 0.9239954 0.382404 9.15559e-5 0.9754979 0.2200089 -6.71425e-4 0.9807994 0.1950184 -0.007446527 0.9955158 0.09430235 -0.01132249 0.9982426 0.058169 0.01132249 0.9982426 -0.058169 0 0.9951958 -0.09790509 6.71425e-4 0.9807994 -0.1950184 0 0.9951958 0.09790509 -9.15559e-5 0.9754979 -0.2200089 1.52595e-4 0.9239954 -0.382404 0.007446527 0.9955158 -0.09430235 -1.83118e-4 0.923372 -0.3839067 1.83116e-4 0.831651 -0.5552987 -1.52597e-4 0.8307098 -0.5567058 1.83113e-4 0.7072746 -0.7069389 -6.1039e-5 0.706435 -0.7077779 9.15579e-5 0.5553902 -0.83159 3.05193e-5 0.5552072 -0.8317121 9.15577e-5 0.3819484 -0.9241837 -1.22076e-4 0.195535 -0.9806967 2.13632e-4 0.1940087 -0.9809998 0 0.3826816 -0.9238803 -1.83117e-4 9.15583e-4 -0.9999997 1.83117e-4 -9.15583e-4 -0.9999997 -2.13632e-4 -0.1940087 -0.9809998 1.22076e-4 -0.195535 -0.9806967 -9.15577e-5 -0.3819484 -0.9241837 0 -0.3826816 -0.9238803 -3.05193e-5 -0.5552072 -0.8317121 -9.15579e-5 -0.5553902 -0.83159 6.1039e-5 -0.706435 -0.7077779 -1.83113e-4 -0.7072746 -0.7069389 1.52597e-4 -0.8307098 -0.5567058 -1.83116e-4 -0.831651 -0.5552987 1.83118e-4 -0.923372 -0.3839067 -1.52595e-4 -0.9239954 -0.382404 9.15559e-5 -0.9754979 -0.2200089 -0.008087396 -0.1134989 0.9935052 -0.08633881 -0.2204096 0.9715787 -0.1930941 -0.2866656 0.9383697 -0.06537175 -0.281538 0.9573207 -0.08713161 -0.3186484 0.9438598 -0.2023106 -0.3583849 0.9113895 -0.08942085 -0.4064531 0.9092854 -0.200511 -0.4131993 0.8882914 -0.089787 -0.4876332 0.8684194 -0.2042983 -0.4708873 0.8582118 -0.0867058 -0.5246602 0.8468848 -0.1918402 -0.5992338 0.7772491 -0.09744745 -0.5981743 0.7954192 -0.07468068 -0.6149945 0.784987 -0.1743274 -0.5188927 0.8368754 -0.1828697 -0.5671647 0.803046 -0.08938962 -0.652706 0.7523194 -0.108801 -0.6624198 0.7411899 -0.03396791 -0.6868965 0.7259611 -0.1629117 -0.7636831 0.6246984 -0.07382482 -0.756743 0.6495307 -0.06247347 -0.8010156 0.595375 -0.1490229 -0.7294282 0.6676278 -0.1778041 -0.8349711 0.5207774 0.07208549 -0.8516898 0.5190648 -0.08075362 -0.8726335 0.4816529 -0.1965474 -0.8922765 0.4064625 -0.02957254 -0.905367 0.4235992 -0.09680813 -0.9279481 0.3599175 -0.2195525 -0.9346087 0.2798272 -0.08575886 -0.9516793 0.2948762 -0.1128306 -0.9672856 0.2272177 -0.2665567 -0.9381061 0.2211437 -0.123511 -0.9736528 0.1916908 -0.2909102 -0.9567503 3.66232e-4 -0.1447504 -0.987739 0.05847388 -0.1425236 -0.9897913 5.7986e-4 -0.291705 -0.9540382 0.0686993 -0.2910339 -0.9541922 -0.06940132 -0.145635 -0.9875229 -0.05990809 -0.2218135 -0.9339181 -0.2803494 -0.1232677 -0.9736292 -0.1919668 -0.0895133 -0.9654802 -0.2446127 -0.2666178 -0.9380455 -0.221327 -0.199136 -0.8887726 -0.4128297 0.1029421 -0.9735707 -0.2038699 -0.0819143 -0.9231535 -0.3756033 -0.177164 -0.8311907 -0.5270057 0.07971554 -0.9361693 -0.3423923 -0.07574903 -0.8647665 -0.4964281 -0.1563786 -0.7623003 -0.6280478 0.01828104 -0.8658335 -0.4999983 -0.06930893 -0.7880042 -0.6117562 -0.1471623 -0.728823 -0.6687006 -0.07477134 -0.7537258 -0.6529218 -0.04806709 -0.6926247 -0.7196949 -0.1071229 -0.6689844 -0.7355166 -0.3071717 -0.3065918 0.9009147 -0.3254517 -0.3564587 0.8757959 -0.2813833 -0.2998777 0.9115355 -0.4040146 -0.3938822 0.8256083 -0.4080105 -0.4189669 0.8111685 -0.4135109 -0.4396358 0.7973263 -0.290484 -0.4957577 0.8184397 -0.3873521 -0.5070492 0.7699738 -0.2993901 -0.5228799 0.7980991 -0.2666769 -0.2758021 0.9234808 -0.2171145 -0.2221807 0.9505246 -0.2642065 -0.2953972 0.9181151 -0.4506775 -0.3904325 0.8027779 -0.3614684 -0.3229228 0.8746779 -0.5127017 -0.3953226 0.7621398 -0.4837646 -0.3869873 0.7849922 -0.5926443 -0.3855744 0.7071813 -0.4234572 -0.4491546 0.7867301 -0.6007406 -0.3747762 0.7061541 -0.4268975 -0.4665415 0.7746596 -0.535562 -0.4048761 0.7411131 -0.5687359 -0.3896764 0.7243562 -0.5405645 -0.3923305 0.7442224 -0.3023577 -0.2643609 0.9158019 -0.3856126 -0.3434042 0.8563742 -0.4929226 -0.3442004 0.7990955 -0.6710623 -0.3648298 0.6454259 -0.4094141 -0.2740312 0.8702225 -0.6047762 -0.3251252 0.7270072 -0.6807324 -0.3386723 0.6495417 -0.6442643 -0.3459678 0.6820778 -0.7240124 -0.2551119 0.6408775 -0.6397132 -0.3134628 0.7017893 -0.698138 -0.3122165 0.6443013 -0.6344951 -0.2863315 0.7179347 -0.6875689 -0.2675625 0.6750255 -0.63179 -0.2870691 0.7200227 -0.7656403 -0.1963008 0.6125855 -0.7390533 -0.3167284 0.5945448 -0.7351738 -0.3242956 0.5952745 -0.7410265 -0.299084 0.6011894 -0.5169031 -0.2669206 0.8133662 -0.5006691 -0.211987 0.8392807 -0.5347542 -0.2316698 0.8126298 -0.6480408 -0.2846203 0.7064236 -0.6316186 -0.2665213 0.7280278 -0.7436377 -0.2786123 0.607765 -0.7486663 -0.2804409 0.6007093 -0.7402733 -0.2910309 0.6060499 -0.7915712 -0.1371523 0.5954867 -0.7861753 -0.195201 0.5863659 -0.8029913 -0.1466448 0.577668 -0.7628564 -0.2138781 0.6101691 -0.6215851 -0.2492811 0.7426244 -0.5089979 -0.1088007 0.853864 -0.5115356 -0.1614781 0.8439528 -0.6364183 -0.198131 0.7454636 -0.6400487 -0.1373364 0.7559606 -0.7666414 -0.1622093 0.6212481 -0.7557668 -0.2332244 0.6119013 -0.5113542 -0.06229025 0.8571096 -0.6462519 -0.08133465 0.7587775 -0.7943612 -0.080724 0.6020579 -0.7698389 -0.1012616 0.630154 -0.5043031 0.004120111 0.8635169 -0.5215947 -0.004760861 0.8531801 -0.6509755 -0.01489335 0.7589527 -0.6463942 -0.01342839 0.7628856 -0.7784173 0.00891149 0.6276839 -0.7498614 -0.02365249 0.661172 -0.777322 -0.009613513 0.6290296 -0.802254 2.74671e-4 0.5969829 -0.3021044 0.01019322 0.9532205 -0.3415392 0.03790467 0.939103 -0.4339794 0.03640908 0.9001868 -0.4188755 0.04092615 0.907121 -0.6640609 0.07776212 0.7436237 -0.5639868 0.05029487 0.8242508 -0.6539117 0.03445655 0.7557859 -0.5780596 0.1054735 0.8091492 -0.5894111 0.006836175 0.8078043 -0.7321364 0.04541325 0.6796426 -0.6971158 -0.002807736 0.7169531 -0.5947233 0.006958305 0.8039004 -0.7222304 0.01138353 0.6915589 -0.1756368 0.03561568 0.9838107 -0.5631715 0.2310611 0.7933781 -0.5425754 0.2715318 0.7949104 -0.5568839 0.4098118 0.7224506 -0.6387917 0.211252 0.7398093 -0.7096124 0.181775 0.6807408 -0.7697752 0.1425837 0.6221864 -0.8145597 0.09506756 0.5722366 -0.8423522 0.04394721 0.5371327 -0.8292365 0.01168882 0.5587756 -0.823378 -0.06399875 0.5638731 -0.618082 0.3302826 0.713364 -0.5988743 0.3685474 0.7110011 -0.5843647 0.4973829 0.6411928 -0.5411715 0.3390104 0.7695488 -0.6796039 0.3081535 0.6657177 -0.74048 0.2745785 0.6134298 -0.7963732 0.2274 0.5604277 -0.8422632 0.1658096 0.5129327 -0.8733019 0.09277784 0.4782637 -0.8575366 0.01321488 0.5142534 -0.8801537 0.03384619 0.4734805 -0.8401585 -0.07297098 0.5374097 -0.8460537 -0.05209624 0.5305461 -0.8512156 -0.0611608 0.5212402 -0.8539386 -0.049869 0.5179788 -0.8322181 -0.09027469 0.5470501 -0.5454658 0.4084966 0.7318453 -0.6559746 0.421772 0.6259438 -0.6398019 0.4582133 0.6170041 -0.589999 0.6525635 0.4754601 -0.5931382 0.4250086 0.6837798 -0.704144 0.400842 0.5860949 -0.7553811 0.3687942 0.541655 -0.8072283 0.3217927 0.494805 -0.855727 0.2565747 0.4493337 -0.8950887 0.1695324 0.4124018 -0.9077951 0.03338801 0.4180831 -0.9122089 0.08978646 0.3997666 -0.8291721 -0.1205807 0.5458332 -0.8793492 -0.02056992 0.475733 -0.8531507 -0.0569784 0.5185435 0.9293291 -0.2765312 -0.2447 -0.8781098 -0.03860723 0.4768992 -0.831991 -0.1171947 0.5422698 -0.8521599 -0.0877735 0.5158677 -0.5900332 0.4904176 0.641367 -0.684293 0.5037437 0.5272432 -0.6699826 0.5379881 0.5115587 -0.5207136 0.8185476 0.2425643 -0.5871526 0.566003 0.5786989 -0.6306512 0.4981363 0.5950962 -0.7207936 0.484761 0.4954426 -0.7621904 0.4560508 0.4594384 -0.807915 0.4133575 0.4200108 -0.8561008 0.3514314 0.3789294 -0.9029329 0.2612115 0.3412931 -0.9289408 0.1729518 0.327348 -0.849036 -0.1179251 0.5150066 -0.9064852 -0.00149542 0.422235 -0.8930029 -0.02737605 0.4492177 0.9240476 -0.3130922 -0.2193384 -0.9126717 -0.003296017 0.4086803 -0.6247282 0.5636593 0.5403731 -0.7001154 0.5698586 0.4302322 -0.685291 0.5979434 0.4157403 -0.3663472 0.9303339 -0.01638853 -0.6084372 0.6200652 0.4953014 -0.6457592 0.5723602 0.5053702 -0.7270034 0.551242 0.4093877 -0.7595978 0.5321366 0.3739544 -0.8009926 0.491369 0.342005 -0.8444439 0.44296 0.3011664 -0.8983671 0.3547262 0.2590481 -0.9280899 0.2748562 0.2512038 -0.8896917 -0.09549415 0.4464634 -0.9348192 0.05084586 0.3514652 0.8908805 -0.4316609 -0.1414251 -0.9414471 0.04968476 0.33348 -0.3072926 0.9474219 -0.08923661 -0.6324816 0.660956 0.4038617 -0.6558264 0.6209735 0.4292826 -0.6853817 0.5986446 0.4145801 -0.6999961 0.5994952 0.3880864 -0.6861293 0.6081531 0.3992197 -0.6530793 0.6560397 0.3782849 -0.7159594 0.5915615 0.3707522 -0.7355579 0.58244 0.3460031 -0.7830258 0.539942 0.3087607 -0.7542466 0.5749474 0.3170924 -0.8119664 0.5137621 0.2770543 -0.8814891 0.4139944 0.2271246 -0.8321432 0.4961546 0.2477263 -0.9338411 0.2981675 0.1975779 -0.918462 0.3437938 0.1955336 -0.9380236 0.2946984 0.1823858 -0.928244 -0.05502623 0.3678795 -0.9556587 0.1277853 0.2653065 -0.9563245 0.1457605 0.2533718 -0.7432696 0.6442952 0.180095 -0.7118275 0.6506062 0.2646006 -0.7332963 0.6239444 0.2701297 -0.6198459 0.7058187 0.3429448 -0.6620882 0.6966362 0.2762923 -0.6101453 0.7218466 0.3265889 -0.6896136 0.6534484 0.3121512 -0.4938275 0.8695465 -0.004821956 -0.7120481 0.6881819 0.13926 -0.7416138 0.6197205 0.2568181 -0.7610935 0.6263502 0.1685893 -0.7589297 0.6041345 0.2429966 -0.7866571 0.5978362 0.1541513 -0.7837557 0.5757389 0.2329202 -0.8000571 0.5622526 0.2092386 -0.8147009 0.5638054 0.1355953 -0.8229613 0.5345816 0.192243 -0.8509492 0.5119368 0.1175007 -0.8538336 0.4940131 0.1640708 -0.8942777 0.4383187 0.09024566 -0.8982003 0.4206413 0.1276603 -0.9213682 0.3832269 0.06494438 -0.9249373 0.370042 0.08694839 -0.962909 -0.001953184 0.2698196 -0.9685042 0.1528719 0.1965452 -0.9633504 0.1163979 0.2416768 -0.9957525 0.00814861 0.09171038 -0.9765167 0.2078955 0.05652117 -0.9809383 0.1536016 0.1190237 -0.9748898 0.01596128 0.2221152 -0.5387917 0.6818977 0.494691 -0.5568499 0.7179903 0.4176222 -0.5713521 0.7483946 0.3368417 -0.562435 0.7779298 0.2801646 -0.5959783 0.7596831 0.2601759 -0.671395 0.7109481 0.2092406 -0.6842095 0.7176585 0.1297065 -0.6903165 0.7073768 0.1519252 -0.6801697 0.7136791 0.1674254 -0.6818279 0.7280034 0.07156735 -0.682215 0.7306482 0.02713108 -0.6802134 0.7324014 -0.02996987 -0.6804038 0.7328365 0.001190245 -0.678218 0.7294895 -0.08868741 -0.6712408 0.7195527 -0.1779883 -0.6724358 0.7249599 -0.1492097 -0.6753914 0.7258703 -0.1302257 -0.6687914 0.7107244 -0.2181491 -0.7141184 0.649082 -0.2621598 -0.7259615 0.6492666 -0.2267885 -0.7213322 0.6709443 -0.1717951 -0.752486 0.6586083 9.15582e-5 -0.7128801 0.6835506 -0.1567189 -0.731161 0.6748522 -0.09989106 -0.7180966 0.6957867 0.01477146 -0.4800369 0.8772447 0.002563595 -0.4821444 0.8760879 -0.002655148 -0.5112014 0.8594592 0.001770079 -0.5097939 0.8602772 0.00576812 -0.5256021 0.8503265 0.02621597 -0.5074102 0.8616451 0.01013231 -0.92019 0.3914722 -3.05194e-5 -0.982944 0.1839053 0 -0.8959237 0.444208 -3.05193e-5 -0.8538961 0.5204436 -6.10384e-5 -0.8198108 0.5726346 -9.15581e-5 -0.7919155 0.6106308 -1.22077e-4 -0.7692984 0.6388897 -1.52596e-4 -0.9999248 0.0122686 0 -0.5736379 -0.8145559 0.08624708 -0.4521728 -0.8325643 0.3199635 -0.5445212 -0.7955405 0.2657295 -0.8071137 -0.5903961 -4.2727e-4 -0.7994402 -0.5931025 0.09552383 -0.6533263 -0.6773145 0.3382452 -0.7700244 -0.5726276 0.2813544 -0.5783331 -0.8158007 -4.27265e-4 -0.9524763 -0.3046129 0 -0.94532 -0.3119632 0.0951271 -0.8116304 -0.4781154 0.3356513 -0.9185699 -0.2921307 0.2662504 -0.917092 -0.2478132 0.3122996 -0.9453173 -0.3119623 -0.09515732 -0.7999649 -0.5925269 -0.09470051 -0.5731495 -0.8149832 -0.08545356 -0.9154483 -0.2472955 -0.3174893 -0.9185623 -0.2921283 -0.2662787 -0.8102779 -0.4779571 -0.3391265 -0.7700378 -0.5726071 -0.2813593 -0.6523606 -0.6773868 -0.33996 -0.5445212 -0.7955405 -0.2657295 -0.4516225 -0.8328983 -0.3198713 -0.2903013 -0.6640734 0.6890078 -0.2584055 -0.6025697 0.7550739 -0.3383063 -0.6788406 0.6517089 -0.4263869 -0.5817613 0.6926384 -0.3932673 -0.5287105 0.7522009 -0.5005779 -0.5663471 0.654731 -0.5514618 -0.4839216 0.6794923 -0.5220633 -0.4356936 0.7332264 -0.6433887 -0.4321303 0.6319133 -0.6621451 -0.3731281 0.6498764 -0.6447912 -0.3351376 0.6869696 -0.7613227 -0.2812615 0.5841915 -0.7555375 -0.2523341 0.6045582 -0.740247 -0.2316419 0.6311708 -0.8106258 -0.2854785 0.5112611 -0.693999 -0.4607433 0.553246 -0.5454772 -0.6146957 0.5697403 -0.3715701 -0.7404546 0.5600562 -0.8631061 -0.2727478 0.4250373 -0.7504132 -0.4748832 0.4597456 -0.5967146 -0.6509169 0.4692962 -0.4100841 -0.7915108 0.4531465 -0.8629976 -0.274217 -0.4243115 -0.7499791 -0.4761913 -0.4591005 -0.595978 -0.6520112 -0.4687131 -0.4090805 -0.7923418 -0.452601 -0.8106311 -0.2870368 -0.5103793 -0.693731 -0.4620906 -0.5524579 -0.5448907 -0.6157869 -0.5691229 -0.3707429 -0.7412416 -0.5595629 -0.7623768 -0.2834955 -0.581732 -0.6438136 -0.4335937 -0.6304765 -0.5003989 -0.5669926 -0.6543091 -0.3375112 -0.6786236 -0.6523467 -0.7555046 -0.2523639 -0.6045868 -0.6621054 -0.3732144 -0.6498674 -0.5514489 -0.4840018 -0.6794458 -0.4264459 -0.5817584 -0.6926045 -0.2903569 -0.6640306 -0.6890256 -0.7405824 -0.2248054 -0.6332458 -0.6385489 -0.333481 -0.6935746 -0.5219956 -0.435688 -0.733278 -0.3939194 -0.5257956 -0.7539008 -0.255324 -0.6013512 -0.7570908 -1 -1.56332e-5 0 -1 -1.58239e-5 0 -1 1.21954e-5 0 -1 3.47072e-6 0 -1 -5.03544e-6 0 -1 -1.52647e-6 0 -1 2.83036e-6 0 -1 -3.31219e-6 0 -1 7.76548e-7 0 -1 1.28958e-7 0 -1 -4.44733e-6 0 -1 -2.80404e-6 0 -1 3.87175e-6 0 -1 -1.97399e-6 0 -1 3.66184e-6 0 -1 -3.20626e-6 0 -1 3.73872e-6 0 -1 4.03036e-6 0 -1 2.89817e-6 0 -1 -2.83036e-6 0 -1 3.77666e-6 0 -1 -3.47062e-6 0 -1 8.00171e-6 0 -1 -1.62604e-5 0 -1 3.16478e-5 0 -0.421036 0.9070439 0 -0.4210109 0.9070557 0 -0.4210112 0.9070555 0 -0.4210446 0.9070399 0 -0.4210361 0.9070439 0 -0.4210346 0.9070447 -1.04731e-6 -0.421036 0.907044 0 -0.4210432 0.9070406 -6.34539e-7 -0.4210264 0.9070484 0 -0.4210283 0.9070476 4.75264e-7 -0.4210436 0.9070404 0 -0.4210461 0.9070392 1.70486e-6 -0.4210347 0.9070445 0 -0.4210305 0.9070465 0 -0.4210365 0.9070438 0 -0.4210903 0.9070187 0 -0.4210901 0.9070189 0 -0.4208847 0.9071142 0 -0.4210364 0.9070437 0 -0.4210391 0.9070426 0 -0.4210429 0.9070408 0 -0.4210308 0.9070464 0 -0.4210195 0.9070517 0 -0.4210345 0.9070447 0 -0.4210405 0.9070419 -5.66634e-7 -0.4210336 0.9070451 1.43468e-6 -0.421025 0.9070491 0 -0.4210456 0.9070396 2.23754e-6 -0.4210353 0.9070444 8.10851e-7 -0.4210274 0.907048 0 -0.421046 0.9070393 -7.35107e-7 -0.4210426 0.907041 3.54813e-6 -0.4210339 0.907045 -2.94274e-6 -0.420968 0.9070755 9.45958e-6 0.2896921 -0.2372594 0.9272468 0.3517374 -0.2821224 0.8925737 0.4099081 -0.3290618 0.850702 0.464221 -0.3776393 0.8011788 0.4649336 -0.3779532 0.8006173 0.5145965 -0.4270348 0.7435265 0.5151314 -0.4275416 0.7428647 0.5607926 -0.4761015 0.6773765 0.5631371 -0.4782332 0.6739212 0.6024248 -0.5234708 0.6025469 0.6081216 -0.5284366 0.5924044 0.6391282 -0.5674697 0.5191276 0.6488362 -0.5759566 0.4972783 0.6704235 -0.6064544 0.4274876 0.6835397 -0.6179843 0.3884185 0.6958179 -0.6387461 0.3283916 0.7101578 -0.6514689 0.2669539 0.7148608 -0.6627638 0.2229762 0 -1 -2.31909e-5 0 -1 4.02499e-5 0 -1 -2.05143e-5 0 -1 6.48156e-7 0 -1 2.05143e-5 0 -1 3.82909e-6 0 -1 -2.13106e-5 0 -1 6.46807e-6 0 -1 1.1915e-5 0 -1 1.42399e-5 0 -1 -1.43555e-5 0 -1 -1.27342e-5 0 -1 -1.0341e-5 0 -1 4.65191e-5 0 -1 -4.82694e-5 0 -1 1.50766e-4 0 -1 -6.53657e-5 0 -1 -8.65707e-5 0 -1 3.50938e-5 0 -1 -8.44259e-5 0 -1 1.1327e-4 0 -1 -6.48156e-7 0 -1 -3.82909e-6 0 -1 2.13106e-5 0 -1 -6.46807e-6 0 -1 -1.1915e-5 0 -1 -1.42399e-5 0 -1 1.43555e-5 0 -1 1.27342e-5 0 -1 1.0341e-5 0 -1 -4.65191e-5 0 -1 4.82694e-5 0 -1 -1.50766e-4 0 -1 6.53657e-5 0 -1 8.65707e-5 0 -1 -3.50938e-5 0 -1 8.44259e-5 0 -1 -1.1327e-4 0.9969176 0.07845646 0 0.9969168 0.07846653 1.27621e-6 0.9969168 0.07846605 0 0.9969166 0.07846826 0 0.9969176 0.0784564 0 0.9969187 0.07844144 0 0.9969177 0.07845431 0 0.9969168 0.07846629 0 0.9969182 0.07844984 0 0.9969182 0.07845026 0 0.9969158 0.07847899 0 0.9969171 0.07846295 0 0.996918 0.07845169 0 0.9969165 0.07847088 0 0.9969174 0.07845991 0 0.996918 0.07845216 0 0.9969142 0.07849854 0 0.9969177 0.07845449 0 0.9969167 0.0784679 -1.33444e-7 0.9969168 0.07846593 0 0.9969181 0.07845085 1.40281e-7 0.996918 0.07845044 -6.69123e-7 0.996917 0.07846373 -6.80157e-7 0.9969171 0.07846307 -4.44241e-7 0.996918 0.0784505 -3.08011e-7 0.9969173 0.07846081 3.39566e-7 0.9969175 0.07845795 4.19525e-7 0.9969181 0.07845008 -2.14233e-6 0.9969164 0.07847219 9.95301e-7 0.9969168 0.07846683 6.42857e-7 0.996915 0.0784893 1.55708e-6 0.9969171 0.07846289 -1.58225e-6 0.8413653 -0.38705 -0.3772227 0.7879748 -0.4404529 -0.430229 0.8718725 0.08185249 -0.4828442 0.8739233 0.05831682 -0.482553 -0.8791916 0.03058004 0.4754862 -0.8758689 0.05151629 0.4797914 -0.8692612 0.07077509 0.4892607 -0.8754522 0.06202572 0.4793084 -0.8864305 -0.02505624 0.4621829 -0.8880534 -0.09906595 0.4489403 -0.8901324 -0.05508768 0.4523603 0 1 0 0.8637539 -0.163064 -0.4768012 0.8397062 -0.02411133 -0.5425055 0.874374 -0.0162667 -0.48498 -0.850916 0.1200899 0.5113906 -0.8367838 0.02216893 0.5470845 -0.8368828 0.02108812 0.5469757 0.8360631 -0.02060317 -0.5482463 0.8743473 -0.03372377 -0.4841276 0.872501 -0.1077618 -0.476581 0.8619176 -0.2244977 -0.4546416 0.8420354 -0.3879345 -0.3748111 0.7688429 0.5040572 -0.3934552 -0.9015943 -0.002197325 0.4325773 0 0.9999999 -4.92762e-4 -0.4575771 0.8560382 -0.2404622 -0.4541933 0.8738994 -0.1732295 -0.44888 0.8555516 -0.2579503 0.7143002 0.3123127 -0.6262875 -0.4617281 0.8415727 -0.2802903 0.7147792 0.3125346 -0.62563 0.7147563 0.3125419 -0.6256526 -0.4647708 0.873326 -0.1459103 -0.4612663 0.8813623 -0.1021475 0.7136128 0.3119068 -0.6272726 0.7148541 0.3118519 -0.625885 0.71454 0.3120509 -0.6261444 0.7141391 0.3122243 -0.6265153 0.7140069 0.3122721 -0.6266422 -0.467675 0.8825826 -0.04825073 -0.4613278 0.8847203 -0.06668436 0.7841836 0.3386379 -0.5199813 0.7732316 0.3397995 -0.5353963 0.8241421 0.3655291 -0.432641 0.7135003 0.3119552 -0.6273766 -0.4648306 0.8848903 -0.03003036 0.842825 0.3636392 -0.3967528 0.8897604 0.3991928 -0.2212956 -0.4674375 0.8826866 0.04864811 -0.4663365 0.8846049 -0.002105832 0.9035129 0.3954032 -0.1652905 0.9112924 0.4117601 0 -0.4616684 0.8864389 0.03299152 0.9035174 0.3954052 0.1652608 0.8897663 0.3991954 0.2212666 0.9142553 0.4051387 0 -0.4629485 0.8838106 0.06750881 0.841018 0.3656507 0.3987335 0.8246256 0.3621089 0.4345917 -0.4641039 0.8736396 0.1461559 -0.4663965 0.8795672 0.0939995 0.7785739 0.3351307 0.5305753 -0.4580267 0.8752496 0.1554019 0.7134847 0.3119468 0.6273986 0.783918 0.3448372 0.5162945 -0.4580067 0.8555847 0.2412569 -0.4576609 0.8641417 0.2092984 0.7140275 0.3121863 0.6266613 0.7134928 0.3119726 0.6273765 -0.4572308 0.8486938 0.2658177 0.7144589 0.3123956 0.6260651 0.714031 0.3122102 0.6266455 -0.4570948 0.8374018 0.2997043 -0.6539963 0.7497351 0.100927 0.7147957 0.3125207 0.6256181 0.7144371 0.3123112 0.626132 0.7145839 0.3124754 0.6258826 0.6653467 0.3097687 0.6792328 0.6582364 0.2863304 0.6962327 0.6264607 0.2747308 0.7294313 0.7147654 0.3124814 0.6256723 0.7148289 0.3125778 0.6255515 -0.459957 0.8392513 0.2899947 -0.4491154 0.8260232 0.3405598 -0.4562633 0.8285986 0.32442 0.5778204 0.2458018 0.7782706 0.5625331 0.242568 0.7903907 0.649695 0.3013476 0.6979155 -0.4721326 0.8595744 0.1955062 -0.4790953 0.8722477 0.09824228 -0.4814395 0.8764794 0 -0.4790968 0.8722504 -0.09821206 -0.4721326 0.8595744 -0.1955062 -0.4722587 0.8331212 -0.2878904 -0.45705 0.8365517 -0.3021364 -0.4605948 0.8385744 -0.2909389 0.649999 0.2843784 -0.7047201 0.6201478 0.2768386 -0.7340144 0.6580235 0.2994539 -0.6908926 -0.4512959 0.8287949 -0.3308038 0.5778588 0.2457746 -0.7782507 0.5623431 0.2424429 -0.7905642 0.7149222 0.3125522 -0.6254578 0.6833959 0.2979328 -0.666488 -0.4522117 0.8260181 0.3364502 0.4986883 0.2108286 0.8407505 0.4963107 0.2131187 0.8415796 -0.4476856 0.8220947 0.3517639 0.3934592 0.160045 0.9053041 0.3906475 0.1634921 0.9059056 -0.4437208 0.8174914 0.3671783 0.2332254 0.08569705 0.9686392 0.227003 0.08871978 0.9698446 -0.443085 0.8160968 0.371028 -0.4413714 0.8134333 0.3788372 0.03775185 -0.003540158 0.9992809 0.03134298 -0.004821956 0.9994971 -0.06088566 -0.04968512 0.9969074 -0.1581259 -0.09249174 0.9830776 -0.06079429 -0.04721325 0.9970332 -0.452937 0.8267984 0.3335455 -0.1580047 -0.09259104 0.9830877 -0.1581288 -0.09246408 0.9830797 -0.4769847 0.8454737 0.2401251 -0.4621254 0.8281145 0.3172801 -0.4600074 0.8272687 0.3225209 -0.4653555 0.8348199 0.2941432 -0.4887442 0.8602313 0.1453658 -0.4940432 0.8680548 0.04901367 -0.4941364 0.8679966 -0.04910534 -0.4888586 0.8601874 -0.1452414 -0.4792354 0.8434763 -0.2426543 -0.4516295 0.8228703 -0.3448413 -0.4520865 0.825402 -0.3381264 -0.4681068 0.8348281 -0.2897208 -0.4518952 0.8255091 -0.3381203 -0.4437158 0.8174822 -0.3672047 -0.4431146 0.816095 -0.3709967 -0.1581836 -0.09240931 -0.983076 -0.4506458 0.8543836 -0.2587413 -0.391989 0.911579 0.1239691 -0.1580047 -0.09258252 -0.9830886 -0.4413996 0.81349 -0.3786826 -0.06192302 -0.04971539 -0.996842 -0.06360244 -0.04852586 -0.9967948 0.03366219 -0.002685606 -0.9994297 -0.1581131 -0.09249716 -0.9830791 0.03878915 -0.003753781 -0.9992404 0.2283455 0.0889638 -0.969507 0.2328935 0.085729 -0.9687163 0.3909513 0.163461 -0.9057801 0.3933967 0.1600444 -0.9053313 0.4961774 0.2130224 -0.8416826 0.4987176 0.210767 -0.8407486 -0.2236118 -0.1228995 0.9668989 -0.2236158 -0.1229933 0.9668861 -0.2594721 -0.13938 0.9556398 -0.1578602 -0.09252333 0.9831173 -0.1578664 -0.09251743 0.9831169 -0.2841957 -0.1555263 0.9460678 -0.3258492 -0.1759713 0.9289007 -0.4632214 0.8385779 0.2867285 -0.3829859 -0.1986192 0.9021487 -0.4131361 -0.1994418 0.8885616 -0.492003 0.8525284 0.1764325 -0.4731733 0.8369345 0.2750412 -0.4807028 0.8384146 0.2568774 -0.4862034 0.8449276 0.2229437 -0.4961743 0.8602024 0.1177414 -0.501883 0.8649356 0 -0.4998496 0.8639176 0.06161898 -0.4995111 0.8640959 -0.06186282 -0.4920004 0.8525238 -0.1764621 -0.4957291 0.8605294 -0.1172256 -0.4824135 0.8459862 -0.2271223 -0.2828868 -0.1558029 -0.9464147 -0.3254836 -0.1745373 -0.9292992 -0.2595016 -0.139349 -0.9556363 -0.4230589 0.8873494 -0.1833906 -0.4417638 0.8672305 -0.2296866 -0.382613 -0.1969066 -0.9026822 -0.4151194 -0.1985871 -0.8878283 -0.3525863 -0.1868069 -0.916944 -0.4526 0.8573764 -0.2450693 -0.2235836 -0.1228703 -0.9669092 -0.1578482 -0.0925104 -0.9831205 -0.2235239 -0.122932 -0.9669151 -0.1578673 -0.09251779 -0.9831167 -0.4873933 -0.2062799 0.8484671 -0.498809 -0.2256909 0.8368113 -0.571406 -0.3082107 0.7605928 -0.5639979 -0.2811444 0.7764433 -0.5910393 -0.3128241 0.7435144 -0.5572044 -0.2780001 0.7824572 -0.03826522 -0.02617359 0.9989248 -0.5029004 -0.2523658 0.8266819 -0.6571692 -0.3373283 0.6740463 -0.6752662 -0.3324143 0.6584196 -0.7482073 -0.3667485 0.5528848 -0.7648087 -0.3622007 0.5328025 -0.8063528 -0.3825606 0.4510461 -0.8451666 -0.4018761 0.3524045 -0.8793981 -0.4276289 0.2092671 -0.8873541 -0.4208027 0.1884883 -0.8438959 -0.4113119 0.3444741 -0.8987022 -0.4284607 0.09357219 -0.9067166 -0.4217407 0 -0.8987296 -0.4284897 -0.09317511 -0.8873095 -0.4208571 -0.1885769 -0.8995373 -0.4368439 3.35705e-4 -0.8866397 -0.4176228 -0.1986485 -0.8412752 -0.402341 -0.3610785 -0.8284189 -0.404077 -0.3878712 -0.764884 -0.3734387 -0.5248773 -0.8819428 -0.3912556 -0.2628615 -0.7593299 -0.3724012 -0.5336062 -0.6622799 -0.3258906 -0.6746709 -0.6557983 -0.3239622 -0.6818923 -0.5954322 -0.2961291 -0.7468386 -0.4731137 -0.2378386 -0.8482902 -0.4729609 -0.2381438 -0.8482899 -0.5945388 -0.2969489 -0.7472249 -0.4965229 -0.2081129 -0.8427064 -0.5955787 -0.06457823 -0.8006971 -0.4997245 -0.1801254 -0.8472487 0.7147127 0.3125728 -0.6256869 0.7145606 0.3124981 -0.6258978 0.4210301 -0.9070467 0 0.4210532 -0.907036 0 0.4210515 -0.9070367 0 0.7141458 0.3129562 -0.6261423 0.7145016 0.3123913 -0.6260186 0.4210394 -0.9070423 0 0.4210291 -0.9070472 0 0.4210277 -0.9070479 0 0.4210398 -0.9070422 0 0.4210302 -0.9070466 3.96888e-6 0.4210358 -0.9070441 0 0.4210245 -0.9070493 0 0.4210423 -0.907041 0 0.421035 -0.9070445 0 -0.456987 -0.2328271 -0.8584605 -0.4369204 -0.2262732 -0.8705752 -0.4688642 -0.2430843 -0.8491622 0.4210324 -0.9070456 0 0.4210292 -0.9070472 9.70241e-7 -0.4365404 -0.2217798 -0.8719211 0.4210472 -0.9070388 0 -0.4985993 -0.2569448 -0.8278757 -0.5034193 -0.2631697 -0.822989 0.4210472 -0.9070388 0 0.4210371 -0.9070435 0 -0.5953652 -0.295821 -0.7470143 -0.5963399 -0.2944772 -0.7467677 0.4210391 -0.9070426 0 -0.5172756 -0.2586836 -0.8157872 0.4210305 -0.9070465 2.20375e-6 0.4210375 -0.9070433 0 0.4210441 -0.9070401 3.55076e-6 0.4210001 -0.9070606 0 0.4210798 -0.9070236 3.02892e-6 0.4210641 -0.9070309 1.85488e-6 0.4209433 -0.907087 -8.22771e-6 0.4210522 -0.9070364 4.79755e-6 0.4211653 -0.906984 1.35576e-5 0.4209074 -0.9071037 -6.83204e-6 0.4211649 -0.9069842 1.02048e-5 -0.4751197 -0.2397572 0.8466274 -0.5016143 -0.2536454 0.8270715 -0.4694156 -0.2360354 0.8508445 -0.4728532 -0.2384808 0.8482552 -0.5032895 -0.2523314 0.8264555 -0.4444534 -0.2234627 0.8674823 0.4210294 -0.907047 0 -0.3506683 -0.1820484 0.918635 -0.4443861 -0.2254128 0.8670122 0.421032 -0.9070459 0 0.4210321 -0.9070457 0 0.4210401 -0.9070421 0 0.4210398 -0.9070422 0 0.4210376 -0.9070433 0 0.4210376 -0.9070432 1.74422e-6 0.4210253 -0.907049 0 0.4210255 -0.9070489 0 0.4210439 -0.9070402 0 0.4210436 -0.9070404 0 0.4210308 -0.9070464 0 0.4210305 -0.9070466 0 0.4210391 -0.9070426 0 0.4210404 -0.907042 0 0.4210486 -0.9070381 0 0.4210495 -0.9070377 0 0.4210244 -0.9070494 0 0.4210211 -0.9070509 0 0.7144822 0.312423 0.6260249 0.7140343 0.3122002 0.6266468 0.7143811 0.3123612 0.6261711 0.7143843 0.3130355 0.6258305 0.4210331 -0.9070453 0 0.4210283 -0.9070475 0 0.4210377 -0.9070432 -1.02297e-5 0.4210583 -0.9070337 -2.94817e-5 0.9512044 0.09165036 0.2946363 0.9596697 0.1062061 0.2602965 0.9692121 0.09488254 0.2272115 0.05084437 -0.7610789 0.6466637 0.0390343 -0.7167481 0.696239 0.04272741 -0.6337093 0.7723904 0.9647808 0.09280961 0.2461393 0.9832628 0.09271687 0.1568374 0.04612779 -0.8096629 0.5850797 0.04623878 -0.809899 0.584744 0.04623019 -0.8098697 0.5847854 0.9489501 0.09524899 0.3007013 0.01840317 -0.4655129 0.8848499 0.03634804 -0.4366344 0.8989046 0.06909608 -0.7255092 0.6847352 0.03009188 -0.6197525 0.7842203 0.9404112 0.09094649 0.3276516 0.03363215 -0.3182545 0.9474086 0.02664345 -0.196698 0.9801022 0.936984 0.09047102 0.3374552 0.021577 -0.07754909 0.9967551 0.01489311 -0.04217684 0.9989992 -1.22076e-4 -0.2112524 0.9774315 -0.02138197 0.0418238 0.9988962 -0.01641923 -0.02066135 0.9996518 0.9515473 0.09045785 0.2938966 -0.02171361 0.04193097 0.9988846 0.9843107 0.09580028 0.1481715 0.9727641 0.09265583 0.2124736 0.9505224 0.08633899 0.2984173 0.9512423 0.08877933 0.295392 0.9506128 0.08639991 0.2981117 0.9525387 0.08917742 0.2910628 0.9585314 0.09378397 0.2691139 0.9659538 0.09546309 0.2404584 0.9930509 0.09637832 0.06753808 0.9941204 0.09625637 0.04959309 0.9880037 0.09689897 0.1202463 0.990979 0.0989117 0.09042745 0.9770609 0.0941506 0.1910175 0.9818297 0.09711176 0.163033 0.9942275 0.09891307 -0.04156726 0.9941354 0.0962578 -0.04928863 0.9950049 0.09982705 0 0.9946083 0.1010478 -0.02331638 0.9952255 0.0975998 -8.24014e-4 0.9951921 0.09531062 0.02255344 0.994489 0.0943644 0.04568678 0.993007 0.09842479 0.06518924 0.9909854 0.09467017 -0.0947923 0.9842249 0.09607255 -0.1485645 0.9929851 0.09872776 -0.06506574 0.9932717 0.09463942 -0.06674504 0.9832561 0.09268569 -0.1568973 0.9645441 0.09469956 -0.246347 0.9818503 0.09576791 -0.1637027 0.9878894 0.09738504 -0.1207929 0.9483853 0.09830242 -0.3014996 0.951383 0.0924434 -0.2938108 0.9659624 0.09326654 -0.2412846 0.9495159 0.09818053 -0.2979598 0.9564194 0.09348112 -0.2766285 0.9696719 0.09256333 -0.2262049 0.978062 0.09168088 -0.1870546 0.9719398 0.09473109 -0.2153118 0.9369654 0.09045845 -0.3375102 -0.02234995 0.04174357 -0.9988784 0.9662129 0.07822114 -0.2455894 0.9547818 0.08673453 -0.2843745 0.9474762 0.08978819 -0.3069646 0.9438639 0.09079426 -0.3176122 0.9450765 0.09061038 -0.3140387 0.9416344 0.09119087 -0.3240512 -0.0219109 0.04191792 -0.9988809 0.02011203 -0.05832189 -0.9980953 -0.01190227 -0.07666301 -0.996986 0.01535099 -0.2040801 -0.9788339 -0.0213983 0.04199326 -0.9988887 0.01614481 -0.2254475 -0.9741216 0.033724 -0.4334679 -0.9005378 0.07318502 -0.04507684 -0.9962992 0.01840317 -0.4655733 -0.884818 0.03726351 -0.636227 -0.7706016 0.0621373 -0.2982043 -0.9524774 0.04358148 -0.6281166 -0.7768979 0.05685669 -0.7218334 -0.6897274 0.04621624 -0.8096419 -0.5851019 0.06900483 -0.7139151 -0.696824 -0.01541197 -0.7910185 -0.6115981 0.04614102 -0.8089627 -0.5860464 0.04624807 -0.8097476 -0.584953 0.04736053 -0.8091074 -0.5857494 0.04539293 -0.8099535 -0.5847349 0.04492062 -0.8100743 -0.584604 0.05246245 -0.8900918 -0.4527519 0.04968523 -0.8521881 -0.5208715 0.05279755 -0.8919741 -0.4489932 0.04959404 -0.8520417 -0.5211195 0.04616034 -0.8089507 -0.5860615 0.05710166 -0.9496709 -0.3080013 0.05740612 -0.9507262 -0.3046706 0.05997067 -0.9859614 -0.1558323 0.06012225 -0.9862498 -0.1539375 0.06097602 -0.9981393 0 0.06100827 -0.9981374 1.52597e-4 0.06009143 -0.9862136 0.1541807 0.05999958 -0.9859651 0.1557976 0.05737584 -0.9506691 0.304855 0.0571022 -0.9496798 0.3079737 0.05276709 -0.8919448 0.4490548 0.05246245 -0.8900918 0.4527519 0.04968523 -0.8521881 0.5208715 0.04616385 -0.8089621 0.5860456 0.04959404 -0.8520417 0.5211195 0.04624086 -0.8096082 0.5851464 0.04615235 -0.8089556 0.5860555 -0.001220762 0.1213447 0.9926097 -0.02838307 0.130379 0.9910579 -0.02420186 0.206067 0.9782386 -0.0221616 0.04205119 0.9988697 -0.02150809 0.04199063 0.9988865 -0.03640973 0.2199846 0.9748237 -0.04153615 0.3051582 0.9513955 0.05218684 0.1132851 0.992191 -0.04330664 0.3066871 0.9508247 -0.04815942 0.4100573 0.9107874 -0.03769141 0.4048699 0.9135972 -0.05133306 0.5528838 0.8316757 -0.05066227 0.5605207 0.8265894 -0.0630533 0.6743289 0.7357342 -0.01019328 0.4591259 0.8883128 -0.07141488 0.6780754 0.7315146 -0.07745647 0.7508827 0.6558779 -0.03296047 0.6125163 0.7897706 -0.07504701 0.7440307 0.6639175 -0.08054071 0.7743082 0.6276624 -0.05905336 0.8208573 0.5680722 -0.08334839 0.8345522 0.5445877 -0.1205198 0.8700075 0.4780815 -0.07855546 0.7731337 0.6293594 -0.0979349 0.8633473 0.4950155 -0.09982728 0.9168488 0.3865524 -0.06656366 0.8278498 0.5569865 -0.04193335 0.8106811 0.5839846 -0.09070283 0.9133157 0.3970234 -0.0929917 0.9749027 0.2022807 -0.09454804 0.9746261 0.2028907 -0.09509712 0.9954681 -3.0519e-5 -0.09457707 0.9746113 -0.2029486 -0.09296137 0.9748738 -0.2024336 -0.09585893 0.995395 -3.05186e-5 -0.09744882 0.9145177 -0.3926337 -0.08920776 0.921468 -0.3780726 -0.096807 0.8641521 -0.4938317 -0.09137511 0.8443804 -0.5278942 -0.07696974 0.8323231 -0.5489206 -0.07712173 0.768013 -0.6357738 -0.07275754 0.7786951 -0.6231697 -0.06976675 0.7486045 -0.659336 -0.07944041 0.78534 -0.6139465 -0.08099895 0.8092265 -0.5818862 -0.0811209 0.8069672 -0.5849986 -0.07065099 0.7304067 -0.6793487 -0.05841469 0.6753402 -0.7351894 -0.05435538 0.6207073 -0.7821559 -0.04120081 0.5488864 -0.8348811 -0.07190293 0.6569536 -0.7504945 -0.0715689 0.6914259 -0.7188938 -0.06570786 0.7108842 -0.7002329 -0.0376299 0.4710611 -0.8812977 -0.03836208 0.4011081 -0.9152271 -0.06091582 0.5504403 -0.8326493 -0.04333716 0.3066867 -0.9508234 -0.04147511 0.3049752 -0.9514567 -0.04864734 0.3922002 -0.9185927 -0.03643995 0.2200134 -0.974816 -0.02291953 0.2099075 -0.9774526 0.001220762 0.1330631 -0.9911069 -0.003112912 0.1070304 -0.994251 -0.02148431 0.0421077 -0.9988821 -0.02499514 0.08694887 -0.9958993 0.04736614 -0.8098942 0.5846607 0.02887094 -0.7794554 0.6257922 0.04736572 -0.8097654 0.584839 0.0473712 -0.8096638 0.5849791 -0.9969175 -0.07845747 6.90967e-7 -0.9969155 -0.07848286 2.81416e-7 -0.9969168 -0.07846719 3.0957e-7 -0.9969167 -0.07846742 0 -0.9969173 -0.07846027 0 -0.9969169 -0.07846575 0 -0.996917 -0.07846379 3.26922e-7 -0.9969177 -0.07845455 0 -0.9969171 -0.07846295 2.44319e-7 -0.9969176 -0.07845556 2.6278e-7 -0.9969183 -0.07844787 4.01403e-7 -0.9969181 -0.07845044 4.44126e-7 -0.996917 -0.07846403 -1.7155e-7 -0.9969163 -0.07847231 7.84331e-7 -0.9969179 -0.07845371 -6.26776e-7 -0.9969189 -0.07844054 0 -0.9969173 -0.07846039 -1.5073e-7 -0.9969177 -0.07845485 -6.28812e-7 -0.9969169 -0.0784657 -1.48564e-7 -0.9969174 -0.07845807 0 -0.9969164 -0.0784707 0 -0.9969179 -0.07845318 3.17959e-7 -0.08273607 0.7132211 -0.6960391 -0.07455921 0.721665 -0.6882156 -0.08301216 0.7482998 -0.6581462 -0.9969173 -0.07846081 0 -0.9969183 -0.0784468 0 -0.07096064 0.6694565 -0.7394543 -0.9969131 -0.07851356 1.38264e-6 -0.07605338 0.767767 -0.6361995 -0.08093732 0.7889252 -0.6091357 -0.9969181 -0.07844954 -2.54945e-7 -0.08789467 0.7269316 -0.6810616 -0.09155809 0.7099722 -0.6982527 -0.9969211 -0.07841199 0 -0.07849669 0.7979379 -0.5976064 -0.08337777 0.804144 -0.5885581 -0.9969108 -0.07854229 1.566e-6 -0.9969168 -0.07846623 1.33959e-6 -0.08600229 0.8676527 -0.4896759 -0.9969181 -0.07844972 0 -0.08169919 0.8088133 -0.5823627 -0.08103209 0.8091136 -0.5820388 -0.08124214 0.8111096 -0.5792245 -0.9969164 -0.07847177 2.157e-6 -0.996921 -0.07841354 3.11066e-6 -0.9969174 -0.07845866 3.16366e-6 -0.08285957 0.8047299 0.5878301 -0.0806322 0.8032094 0.5902146 -0.07107961 0.7861793 0.6138974 -0.08103489 0.8081775 0.5833376 -0.07718265 0.7937702 0.6033008 -0.07312327 0.7537557 0.6530738 -0.08353084 0.8075667 0.583831 -0.07547444 0.7412242 0.6670011 -0.07925897 0.7173292 0.6922117 -0.9969167 -0.07846772 0 -0.06937086 0.6559562 0.7516044 -0.07087403 0.6682409 0.7405613 -0.07385665 0.7152803 0.6949239 -0.9969164 -0.0784713 4.4019e-7 -0.9969169 -0.07846564 0 -0.9969173 -0.07845985 0 -0.9969172 -0.07846212 2.07352e-7 -0.996919 -0.07843804 0 -0.9969183 -0.07844871 1.87139e-7 -0.996917 -0.07846331 0 -0.9969164 -0.07847142 0 -0.9969192 -0.07843565 0 -0.9969185 -0.07844513 0 -0.9969173 -0.07846057 0 -0.9969158 -0.07847893 0 -0.9969175 -0.07845771 0 -0.9969167 -0.07846754 0 -0.9969176 -0.07845568 0 -0.9969235 -0.07838165 0 -0.9969226 -0.07839268 0 -0.996916 -0.0784769 0 -0.9969086 -0.07857209 0 -0.99693 -0.07829898 0 0.02252286 -0.7971525 -0.6033578 0.03570759 -0.7753436 -0.6305294 0.04742711 -0.8100454 -0.5844461 -0.07229894 0.6973231 -0.7131013 -0.08124274 0.8110849 0.5792592 -0.08124041 0.8111417 -0.5791797 -0.07352125 0.7152227 0.6950188 + + + + + + + + + + 0.05477386 0.01459586 0.05148983 0.01559686 0.05042797 0.01612287 0.04856598 0.01647984 0.05042797 0.01612287 0.05148983 0.01559686 0.05208384 0.01561486 0.05477386 0.01459586 0.05042797 0.01612287 0.05208384 0.01561486 0.05042797 0.01612287 0.05371499 0.01512485 0.04715389 0.01756197 0.05371499 0.01512485 0.05042797 0.01612287 0.04715389 0.01756197 0.05042797 0.01612287 0.04802387 0.016846 0.04856598 0.01647984 0.04802387 0.016846 0.05042797 0.01612287 0.05599999 0.01472598 0.05272185 0.01573199 0.05148983 0.01559686 0.04983294 0.01655 0.05148983 0.01559686 0.05272185 0.01573199 0.05477386 0.01459586 0.05599999 0.01472598 0.05148983 0.01559686 0.04856598 0.01647984 0.05148983 0.01559686 0.04983294 0.01655 0.057253 0.01549887 0.05398386 0.01650798 0.05272185 0.01573199 0.05111998 0.01722186 0.05272185 0.01573199 0.05398386 0.01650798 0.05599999 0.01472598 0.057253 0.01549887 0.05272185 0.01573199 0.04983294 0.01655 0.05272185 0.01573199 0.05111998 0.01722186 0.05839186 0.01682382 0.05513298 0.01783597 0.05398386 0.01650798 0.052293 0.01842099 0.05398386 0.01650798 0.05513298 0.01783597 0.057253 0.01549887 0.05839186 0.01682382 0.05398386 0.01650798 0.05111998 0.01722186 0.05398386 0.01650798 0.052293 0.01842099 0.05765998 0.01904797 0.05603796 0.01955896 0.05513298 0.01783597 0.05294096 0.02005195 0.05513298 0.01783597 0.05603796 0.01955896 0.05928796 0.01854497 0.05765998 0.01904797 0.05513298 0.01783597 0.05839186 0.01682382 0.05928796 0.01854497 0.05513298 0.01783597 0.052293 0.01842099 0.05513298 0.01783597 0.05294096 0.02005195 0.08996796 0.024782 0.05603796 0.01955896 0.05765998 0.01904797 0.06214886 0.02351099 0.05603796 0.01955896 0.08996796 0.024782 0.05826985 0.02496784 0.05603796 0.01955896 0.06214886 0.02351099 0.05826985 0.02496784 0.05294096 0.02005195 0.05603796 0.01955896 0.08996796 0.024782 0.05765998 0.01904797 0.05928796 0.01854497 0.07152897 0.01310884 0.05928796 0.01854497 0.05839186 0.01682382 0.070719 0.01522582 0.05928796 0.01854497 0.07152897 0.01310884 0.08996796 0.024782 0.05928796 0.01854497 0.070719 0.01522582 0.070463 0.01182097 0.05839186 0.01682382 0.057253 0.01549887 0.07152897 0.01310884 0.05839186 0.01682382 0.070463 0.01182097 0.069283 0.01104086 0.057253 0.01549887 0.05599999 0.01472598 0.070463 0.01182097 0.057253 0.01549887 0.069283 0.01104086 0.06810897 0.01085084 0.05599999 0.01472598 0.05477386 0.01459586 0.069283 0.01104086 0.05599999 0.01472598 0.06810897 0.01085084 0.05208384 0.01561486 0.05371499 0.01512485 0.05477386 0.01459586 0.06225585 0.01261287 0.05477386 0.01459586 0.05371499 0.01512485 0.06595498 0.01157999 0.05477386 0.01459586 0.06225585 0.01261287 0.06810897 0.01085084 0.05477386 0.01459586 0.06595498 0.01157999 0.05326396 0.01670295 0.05371499 0.01512485 0.04715389 0.01756197 0.06225585 0.01261287 0.05371499 0.01512485 0.05326396 0.01670295 0.02385985 0.02330183 0.02869486 0.02220398 0.02874886 0.02222198 0.02917885 0.022098 0.02874886 0.02222198 0.02869486 0.02220398 0.02496695 0.0233289 0.02385985 0.02330183 0.02874886 0.02222198 0.02971899 0.022731 0.02496695 0.0233289 0.02874886 0.02222198 0.03009796 0.02210187 0.02971899 0.022731 0.02874886 0.02222198 0.02999287 0.02205985 0.03009796 0.02210187 0.02874886 0.02222198 0.02972197 0.02205985 0.02999287 0.02205985 0.02874886 0.02222198 0.02917885 0.022098 0.02972197 0.02205985 0.02874886 0.02222198 0.02385985 0.02330183 0.02864295 0.02218699 0.02869486 0.02220398 0.02917885 0.022098 0.02869486 0.02220398 0.02864295 0.02218699 0.02385985 0.02330183 0.02840799 0.02205795 0.02864295 0.02218699 0.02917885 0.022098 0.02864295 0.02218699 0.02840799 0.02205795 0.02385985 0.02330183 0.02838397 0.02192986 0.02840799 0.02205795 0.02903199 0.02182799 0.02840799 0.02205795 0.02838397 0.02192986 0.02903199 0.02182799 0.02917885 0.022098 0.02840799 0.02205795 0.02385985 0.02330183 0.02857995 0.02178984 0.02838397 0.02192986 0.02903199 0.02182799 0.02838397 0.02192986 0.02857995 0.02178984 0.02385985 0.02330183 0.02895295 0.02163797 0.02857995 0.02178984 0.02952086 0.02154296 0.02857995 0.02178984 0.02895295 0.02163797 0.02903199 0.02182799 0.02857995 0.02178984 0.02952086 0.02154296 0.02385985 0.02330183 0.02955085 0.02145385 0.02895295 0.02163797 0.03041183 0.02123785 0.02895295 0.02163797 0.02955085 0.02145385 0.02952086 0.02154296 0.02895295 0.02163797 0.03041183 0.02123785 0.02536797 0.02381891 0.02955085 0.02145385 0.02385985 0.02330183 0.02536797 0.02381891 0.03021496 0.021281 0.02955085 0.02145385 0.03041183 0.02123785 0.02955085 0.02145385 0.03021496 0.021281 0.02496695 0.0233289 0.01834297 0.02508497 0.02385985 0.02330183 0.01665097 0.02618283 0.02385985 0.02330183 0.01834297 0.02508497 0.01512783 0.02756196 0.02536797 0.02381891 0.02385985 0.02330183 0.01665097 0.02618283 0.01512783 0.02756196 0.02385985 0.02330183 0.02496695 0.0233289 0.01904886 0.02476799 0.01834297 0.02508497 0.01557284 0.02677083 0.01834297 0.02508497 0.01904886 0.02476799 0.01557284 0.02677083 0.01665097 0.02618283 0.01834297 0.02508497 0.02496695 0.0233289 0.02020382 0.02444297 0.01904886 0.02476799 0.01771098 0.02546799 0.01904886 0.02476799 0.02020382 0.02444297 0.01557284 0.02677083 0.01904886 0.02476799 0.01771098 0.02546799 0.02496695 0.0233289 0.02132797 0.024378 0.02020382 0.02444297 0.01771098 0.02546799 0.02020382 0.02444297 0.02132797 0.024378 0.02971899 0.022731 0.02132797 0.024378 0.02496695 0.0233289 0.022578 0.02453899 0.02132797 0.024378 0.02971899 0.022731 0.02291285 0.02495998 0.02132797 0.024378 0.022578 0.02453899 0.02205383 0.02537697 0.02132797 0.024378 0.02291285 0.02495998 0.01960796 0.02508985 0.02132797 0.024378 0.02205383 0.02537697 0.01771098 0.02546799 0.02132797 0.024378 0.01960796 0.02508985 0.02536797 0.02381891 0.03110986 0.02106899 0.03021496 0.021281 0.031596 0.02090787 0.03021496 0.021281 0.03110986 0.02106899 0.03041183 0.02123785 0.03021496 0.021281 0.031596 0.02090787 0.02536797 0.02381891 0.032175 0.02082896 0.03110986 0.02106899 0.03302484 0.02054697 0.03110986 0.02106899 0.032175 0.02082896 0.031596 0.02090787 0.03110986 0.02106899 0.03302484 0.02054697 0.02536797 0.02381891 0.033445 0.02054995 0.032175 0.02082896 0.03302484 0.02054697 0.032175 0.02082896 0.033445 0.02054995 0.02536797 0.02381891 0.03495287 0.02021795 0.033445 0.02054995 0.03467297 0.02014595 0.033445 0.02054995 0.03495287 0.02021795 0.03302484 0.02054697 0.033445 0.02054995 0.03467297 0.02014595 0.02536797 0.02381891 0.03615099 0.019948 0.03495287 0.02021795 0.03652 0.01969999 0.03495287 0.02021795 0.03615099 0.019948 0.03467297 0.02014595 0.03495287 0.02021795 0.03652 0.01969999 0.02645999 0.02570599 0.03615099 0.019948 0.02536797 0.02381891 0.03351783 0.022861 0.03740698 0.01965999 0.03615099 0.019948 0.03652 0.01969999 0.03615099 0.019948 0.03740698 0.01965999 0.02645999 0.02570599 0.03351783 0.022861 0.03615099 0.019948 0.01924598 0.028665 0.02536797 0.02381891 0.01512783 0.02756196 0.01924598 0.028665 0.02645999 0.02570599 0.02536797 0.02381891 0.01325899 0.02906197 0.01512783 0.02756196 0.01665097 0.02618283 0.01421684 0.02856296 0.01924598 0.028665 0.01512783 0.02756196 0.01325899 0.02906197 0.01421684 0.02856296 0.01512783 0.02756196 0.01325899 0.02906197 0.01665097 0.02618283 0.01557284 0.02677083 0.040416 0.02014297 0.03878599 0.01933383 0.03740698 0.01965999 0.03856682 0.01919597 0.03740698 0.01965999 0.03878599 0.01933383 0.03351783 0.022861 0.040416 0.02014297 0.03740698 0.01965999 0.03652 0.01969999 0.03740698 0.01965999 0.03856682 0.01919597 0.040416 0.02014297 0.04113495 0.01875185 0.03878599 0.01933383 0.04079896 0.01862984 0.03878599 0.01933383 0.04113495 0.01875185 0.03856682 0.01919597 0.03878599 0.01933383 0.04079896 0.01862984 0.040416 0.02014297 0.04379987 0.01805299 0.04113495 0.01875185 0.04321485 0.01799297 0.04113495 0.01875185 0.04379987 0.01805299 0.04079896 0.01862984 0.04113495 0.01875185 0.04321485 0.01799297 0.04715389 0.01756197 0.045816 0.01748895 0.04379987 0.01805299 0.04580599 0.01727795 0.04379987 0.01805299 0.045816 0.01748895 0.040416 0.02014297 0.04715389 0.01756197 0.04379987 0.01805299 0.04321485 0.01799297 0.04379987 0.01805299 0.04580599 0.01727795 0.04715389 0.01756197 0.04802387 0.016846 0.045816 0.01748895 0.04856598 0.01647984 0.045816 0.01748895 0.04802387 0.016846 0.04580599 0.01727795 0.045816 0.01748895 0.04856598 0.01647984 0.05326396 0.01670295 0.04715389 0.01756197 0.040416 0.02014297 0.04471898 0.02126795 0.040416 0.02014297 0.03351783 0.022861 0.05326396 0.01670295 0.040416 0.02014297 0.04471898 0.02126795 0.04471898 0.02126795 0.03351783 0.022861 0.02645999 0.02570599 0.03673595 0.02626997 0.02645999 0.02570599 0.01924598 0.028665 0.04471898 0.02126795 0.02645999 0.02570599 0.03673595 0.02626997 0.01421684 0.02856296 0.01189899 0.03172791 0.01924598 0.028665 0.03673595 0.02626997 0.01924598 0.028665 0.01189899 0.03172791 0.01087695 0.03235197 0.01189899 0.03172791 0.01421684 0.02856296 0.03673595 0.02626997 0.01189899 0.03172791 0.02945798 0.031663 0.01009386 0.03472495 0.02945798 0.031663 0.01189899 0.03172791 0.008298993 0.03681695 0.01009386 0.03472495 0.01189899 0.03172791 0.008298993 0.03681695 0.01189899 0.03172791 0.01087695 0.03235197 0.01325899 0.02906197 0.01087695 0.03235197 0.01421684 0.02856296 0.022578 0.02453899 0.02971899 0.022731 0.03069382 0.02321583 0.03009796 0.02210187 0.03069382 0.02321583 0.02971899 0.022731 0.02382493 0.02469998 0.022578 0.02453899 0.03069382 0.02321583 0.03290086 0.02415382 0.02382493 0.02469998 0.03069382 0.02321583 0.03165996 0.02313095 0.03069382 0.02321583 0.03009796 0.02210187 0.03290086 0.02415382 0.03069382 0.02321583 0.03165996 0.02313095 0.02291285 0.02495998 0.022578 0.02453899 0.02382493 0.02469998 0.03300487 0.02419096 0.02382493 0.02469998 0.03290086 0.02415382 0.027417 0.02519899 0.02382493 0.02469998 0.03300487 0.02419096 0.03661698 0.02716797 0.02382493 0.02469998 0.027417 0.02519899 0.02291285 0.02495998 0.02382493 0.02469998 0.03661698 0.02716797 0.03356099 0.023458 0.03291589 0.02303797 0.03443884 0.02385985 0.03790485 0.02596497 0.03443884 0.02385985 0.03291589 0.02303797 0.03643 0.02483797 0.03356099 0.023458 0.03443884 0.02385985 0.03600084 0.02475982 0.03643 0.02483797 0.03443884 0.02385985 0.03876495 0.027085 0.03600084 0.02475982 0.03443884 0.02385985 0.03876495 0.027085 0.03443884 0.02385985 0.03790485 0.02596497 0.03356099 0.023458 0.03143388 0.02230197 0.03291589 0.02303797 0.03724282 0.024818 0.03291589 0.02303797 0.03143388 0.02230197 0.03790485 0.02596497 0.03291589 0.02303797 0.03724282 0.024818 0.0326249 0.02321195 0.03009796 0.02210187 0.03143388 0.02230197 0.03138095 0.02227687 0.03143388 0.02230197 0.03009796 0.02210187 0.03356099 0.023458 0.0326249 0.02321195 0.03143388 0.02230197 0.03724282 0.024818 0.03143388 0.02230197 0.03138095 0.02227687 0.0326249 0.02321195 0.03165996 0.02313095 0.03009796 0.02210187 0.03080385 0.02213698 0.03133183 0.02225196 0.03009796 0.02210187 0.03138095 0.02227687 0.03009796 0.02210187 0.03133183 0.02225196 0.03026497 0.02207297 0.03080385 0.02213698 0.03009796 0.02210187 0.02999287 0.02205985 0.03026497 0.02207297 0.03009796 0.02210187 0.03411698 0.02411592 0.03165996 0.02313095 0.0326249 0.02321195 0.03290086 0.02415382 0.03165996 0.02313095 0.03411698 0.02411592 0.03531485 0.02434682 0.0326249 0.02321195 0.03356099 0.023458 0.03411698 0.02411592 0.0326249 0.02321195 0.03531485 0.02434682 0.03531485 0.02434682 0.03356099 0.023458 0.03643 0.02483797 0.03888487 0.02573496 0.03891187 0.02632898 0.04021787 0.02688795 0.042732 0.03030186 0.04021787 0.02688795 0.03891187 0.02632898 0.03994786 0.02595084 0.03888487 0.02573496 0.04021787 0.02688795 0.03994786 0.02595084 0.04021787 0.02688795 0.04120987 0.02709496 0.042732 0.03030186 0.04120987 0.02709496 0.04021787 0.02688795 0.03888487 0.02573496 0.03754097 0.02563196 0.03891187 0.02632898 0.04114699 0.02924299 0.03891187 0.02632898 0.03754097 0.02563196 0.042732 0.03030186 0.03891187 0.02632898 0.04114699 0.02924299 0.03888487 0.02573496 0.03741395 0.025563 0.03754097 0.02563196 0.04114699 0.02924299 0.03754097 0.02563196 0.03741395 0.025563 0.03888487 0.02573496 0.03643 0.02483797 0.03741395 0.025563 0.03600084 0.02475982 0.03741395 0.025563 0.03643 0.02483797 0.03983891 0.02817696 0.03741395 0.025563 0.03600084 0.02475982 0.04114699 0.02924299 0.03741395 0.025563 0.03983891 0.02817696 0.03888487 0.02573496 0.03531485 0.02434682 0.03643 0.02483797 0.03725183 0.025074 0.03411698 0.02411592 0.03531485 0.02434682 0.03888487 0.02573496 0.03725183 0.025074 0.03531485 0.02434682 0.03300487 0.02419096 0.03290086 0.02415382 0.03411698 0.02411592 0.03549796 0.02497684 0.03300487 0.02419096 0.03411698 0.02411592 0.03725183 0.025074 0.03549796 0.02497684 0.03411698 0.02411592 0.027417 0.02519899 0.03300487 0.02419096 0.03549796 0.02497684 0.03672498 0.02519297 0.03549796 0.02497684 0.03725183 0.025074 0.03100699 0.02573299 0.03549796 0.02497684 0.03672498 0.02519297 0.03100699 0.02573299 0.027417 0.02519899 0.03549796 0.02497684 0.03840595 0.02529597 0.03725183 0.025074 0.03888487 0.02573496 0.03672498 0.02519297 0.03725183 0.025074 0.03840595 0.02529597 0.2258239 0.09735 0.225709 0.09752196 0.225702 0.09753799 0.03840595 0.02529597 0.03888487 0.02573496 0.03994786 0.02595084 0.03983891 0.02817696 0.03600084 0.02475982 0.03876495 0.027085 0.04159283 0.02613782 0.04120987 0.02709496 0.04276084 0.02730786 0.04385387 0.03094995 0.04276084 0.02730786 0.04120987 0.02709496 0.04536998 0.026519 0.04159283 0.02613782 0.04276084 0.02730786 0.04452782 0.02753984 0.04276084 0.02730786 0.04649198 0.02781885 0.04582285 0.02977287 0.04649198 0.02781885 0.04276084 0.02730786 0.04536998 0.026519 0.04276084 0.02730786 0.04452782 0.02753984 0.04429584 0.02967482 0.04276084 0.02730786 0.04385387 0.03094995 0.04582285 0.02977287 0.04276084 0.02730786 0.04429584 0.02967482 0.04159283 0.02613782 0.03994786 0.02595084 0.04120987 0.02709496 0.04385387 0.03094995 0.04120987 0.02709496 0.042732 0.03030186 0.04014986 0.02546083 0.03840595 0.02529597 0.03994786 0.02595084 0.04159283 0.02613782 0.04014986 0.02546083 0.03994786 0.02595084 0.04014986 0.02546083 0.03672498 0.02519297 0.03840595 0.02529597 0.04014986 0.02546083 0.03859299 0.02534896 0.03672498 0.02519297 0.03100699 0.02573299 0.03672498 0.02519297 0.03859299 0.02534896 0.228227 0.09265297 0.2284229 0.09219199 0.229303 0.09027796 0.04037797 0.02546 0.03859299 0.02534896 0.04014986 0.02546083 0.03100699 0.02573299 0.03859299 0.02534896 0.04037797 0.02546 0.04393386 0.02574497 0.04014986 0.02546083 0.04159283 0.02613782 0.04235297 0.02558696 0.04037797 0.02546 0.04014986 0.02546083 0.04393386 0.02574497 0.04235297 0.02558696 0.04014986 0.02546083 0.04536998 0.026519 0.04393386 0.02574497 0.04159283 0.02613782 0.04536998 0.026519 0.04452782 0.02753984 0.04649198 0.02781885 0.04768699 0.02744698 0.04536998 0.026519 0.04649198 0.02781885 0.04733383 0.02870082 0.04768699 0.02744698 0.04649198 0.02781885 0.04733383 0.02870082 0.04649198 0.02781885 0.04582285 0.02977287 0.03100699 0.02573299 0.04037797 0.02546 0.04235297 0.02558696 0.04677498 0.02583783 0.04235297 0.02558696 0.04393386 0.02574497 0.04405587 0.02568387 0.04235297 0.02558696 0.04677498 0.02583783 0.03100699 0.02573299 0.04235297 0.02558696 0.04405587 0.02568387 0.04781585 0.02631795 0.04393386 0.02574497 0.04536998 0.026519 0.04677498 0.02583783 0.04393386 0.02574497 0.04781585 0.02631795 0.04768699 0.02744698 0.04842787 0.027242 0.04536998 0.026519 0.04781585 0.02631795 0.04536998 0.026519 0.04842787 0.027242 0.05397486 0.026133 0.05559682 0.02628898 0.05760395 0.02625 0.058025 0.02631998 0.05760395 0.02625 0.05559682 0.02628898 0.05733686 0.02618283 0.05397486 0.026133 0.05760395 0.02625 0.05852997 0.02625596 0.05733686 0.02618283 0.05760395 0.02625 0.06066387 0.026317 0.05852997 0.02625596 0.05760395 0.02625 0.06066387 0.026317 0.05760395 0.02625 0.058025 0.02631998 0.05397486 0.026133 0.05511695 0.02631199 0.05559682 0.02628898 0.05329185 0.026802 0.05559682 0.02628898 0.05511695 0.02631199 0.056728 0.02650797 0.05559682 0.02628898 0.05329185 0.026802 0.05844783 0.02633899 0.058025 0.02631998 0.05559682 0.02628898 0.056728 0.02650797 0.05844783 0.02633899 0.05559682 0.02628898 0.05397486 0.026133 0.05287587 0.02648496 0.05511695 0.02631199 0.05329185 0.026802 0.05511695 0.02631199 0.05287587 0.02648496 0.05075883 0.02618098 0.05121994 0.02668792 0.05287587 0.02648496 0.05329185 0.026802 0.05287587 0.02648496 0.05121994 0.02668792 0.05397486 0.026133 0.05075883 0.02618098 0.05287587 0.02648496 0.04781585 0.02631795 0.05087095 0.02673995 0.05121994 0.02668792 0.04963582 0.02770799 0.05121994 0.02668792 0.05087095 0.02673995 0.05075883 0.02618098 0.04781585 0.02631795 0.05121994 0.02668792 0.05132198 0.02771699 0.05121994 0.02668792 0.04963582 0.02770799 0.05132198 0.02771699 0.05329185 0.026802 0.05121994 0.02668792 0.04781585 0.02631795 0.04913687 0.027067 0.05087095 0.02673995 0.04963582 0.02770799 0.05087095 0.02673995 0.04913687 0.027067 0.04781585 0.02631795 0.04842787 0.027242 0.04913687 0.027067 0.04963582 0.02770799 0.04913687 0.027067 0.04842787 0.027242 0.04733383 0.02870082 0.04842787 0.027242 0.04768699 0.02744698 0.04845899 0.029127 0.04842787 0.027242 0.04733383 0.02870082 0.04845899 0.029127 0.04963582 0.02770799 0.04842787 0.027242 0.04677498 0.02583783 0.04781585 0.02631795 0.05075883 0.02618098 0.05004698 0.02592384 0.05075883 0.02618098 0.05397486 0.026133 0.05004698 0.02592384 0.04677498 0.02583783 0.05075883 0.02618098 0.05351787 0.02602487 0.05397486 0.026133 0.05733686 0.02618283 0.05351787 0.02602487 0.05004698 0.02592384 0.05397486 0.026133 0.05351787 0.02602487 0.05733686 0.02618283 0.05720198 0.02616482 0.05852997 0.02625596 0.05720198 0.02616482 0.05733686 0.02618283 0.05706685 0.02615886 0.05351787 0.02602487 0.05720198 0.02616482 0.05852997 0.02625596 0.05706685 0.02615886 0.05720198 0.02616482 0.04600983 0.025774 0.04677498 0.02583783 0.05004698 0.02592384 0.04600983 0.025774 0.04405587 0.02568387 0.04677498 0.02583783 0.05084395 0.02595496 0.05004698 0.02592384 0.05351787 0.02602487 0.04823899 0.02586096 0.04600983 0.025774 0.05004698 0.02592384 0.05084395 0.02595496 0.04823899 0.02586096 0.05004698 0.02592384 0.05370485 0.02605897 0.05351787 0.02602487 0.05706685 0.02615886 0.05370485 0.02605897 0.05084395 0.02595496 0.05351787 0.02602487 0.05370485 0.02605897 0.05706685 0.02615886 0.05679595 0.026178 0.05852997 0.02625596 0.05679595 0.026178 0.05706685 0.02615886 0.03458899 0.02629697 0.05370485 0.02605897 0.05679595 0.026178 0.05863696 0.02626097 0.05679595 0.026178 0.05852997 0.02625596 0.03458899 0.02629697 0.05679595 0.026178 0.05863696 0.02626097 0.03458899 0.02629697 0.04405587 0.02568387 0.04600983 0.025774 0.03458899 0.02629697 0.03100699 0.02573299 0.04405587 0.02568387 0.03458899 0.02629697 0.04600983 0.025774 0.04823899 0.02586096 0.03458899 0.02629697 0.04823899 0.02586096 0.05084395 0.02595496 0.03458899 0.02629697 0.05084395 0.02595496 0.05370485 0.02605897 0.0609079 0.02634096 0.06111097 0.02638 0.06080389 0.02637583 0.05761384 0.02644598 0.06080389 0.02637583 0.06111097 0.02638 0.05968087 0.02631199 0.0609079 0.02634096 0.06080389 0.02637583 0.03458899 0.02629697 0.05968087 0.02631199 0.06080389 0.02637583 0.05761384 0.02644598 0.03458899 0.02629697 0.06080389 0.02637583 0.06234598 0.02644383 0.06146287 0.02639389 0.06111097 0.02638 0.03815895 0.0268839 0.06111097 0.02638 0.06146287 0.02639389 0.0609079 0.02634096 0.06234598 0.02644383 0.06111097 0.02638 0.05761384 0.02644598 0.06111097 0.02638 0.03815895 0.0268839 0.06234598 0.02644383 0.06187283 0.02641385 0.06146287 0.02639389 0.03815895 0.0268839 0.06146287 0.02639389 0.06187283 0.02641385 0.03815895 0.0268839 0.06187283 0.02641385 0.06234598 0.02644383 0.06295597 0.02648997 0.06234598 0.02644383 0.0609079 0.02634096 0.03834682 0.02698493 0.03815895 0.0268839 0.06234598 0.02644383 0.03834682 0.02698493 0.06234598 0.02644383 0.06295597 0.02648997 0.05968087 0.02631199 0.05962491 0.02628386 0.0609079 0.02634096 0.06066387 0.026317 0.0609079 0.02634096 0.05962491 0.02628386 0.06356 0.02653586 0.06295597 0.02648997 0.0609079 0.02634096 0.06066387 0.026317 0.06356 0.02653586 0.0609079 0.02634096 0.05863696 0.02626097 0.05852997 0.02625596 0.05962491 0.02628386 0.06066387 0.026317 0.05962491 0.02628386 0.05852997 0.02625596 0.05968087 0.02631199 0.05863696 0.02626097 0.05962491 0.02628386 0.03458899 0.02629697 0.05863696 0.02626097 0.05968087 0.02631199 0.03661698 0.02716797 0.027417 0.02519899 0.03100699 0.02573299 0.03661698 0.02716797 0.03100699 0.02573299 0.03458899 0.02629697 0.05761384 0.02644598 0.03815895 0.0268839 0.03458899 0.02629697 0.03661698 0.02716797 0.03458899 0.02629697 0.03815895 0.0268839 0.03702396 0.02736896 0.03661698 0.02716797 0.03815895 0.0268839 0.03731983 0.027278 0.03815895 0.0268839 0.03834682 0.02698493 0.03731983 0.027278 0.03702396 0.02736896 0.03815895 0.0268839 0.02004498 0.02742499 0.03410089 0.02898997 0.03331995 0.03036195 0.033508 0.03044492 0.03331995 0.03036195 0.03410089 0.02898997 0.03104794 0.02999997 0.02004498 0.02742499 0.03331995 0.03036195 0.033508 0.03044492 0.03104794 0.02999997 0.03331995 0.03036195 0.02059584 0.02662897 0.03522884 0.02788895 0.03410089 0.02898997 0.035133 0.02848196 0.03410089 0.02898997 0.03522884 0.02788895 0.02004498 0.02742499 0.02059584 0.02662897 0.03410089 0.02898997 0.033508 0.03044492 0.03410089 0.02898997 0.03369086 0.03053987 0.034298 0.02943295 0.03369086 0.03053987 0.03410089 0.02898997 0.03448587 0.02917695 0.034298 0.02943295 0.03410089 0.02898997 0.035133 0.02848196 0.03448587 0.02917695 0.03410089 0.02898997 0.02205383 0.02537697 0.03661698 0.02716797 0.03522884 0.02788895 0.03615885 0.02774995 0.03522884 0.02788895 0.03661698 0.02716797 0.02127283 0.02593886 0.02205383 0.02537697 0.03522884 0.02788895 0.02059584 0.02662897 0.02127283 0.02593886 0.03522884 0.02788895 0.03562682 0.02808499 0.035133 0.02848196 0.03522884 0.02788895 0.03615885 0.02774995 0.03562682 0.02808499 0.03522884 0.02788895 0.02205383 0.02537697 0.02291285 0.02495998 0.03661698 0.02716797 0.03702396 0.02736896 0.03615885 0.02774995 0.03661698 0.02716797 0.01960796 0.02508985 0.02205383 0.02537697 0.02127283 0.02593886 0.01960796 0.02508985 0.02127283 0.02593886 0.02059584 0.02662897 0.01820397 0.02633798 0.02059584 0.02662897 0.02004498 0.02742499 0.01960796 0.02508985 0.02059584 0.02662897 0.01820397 0.02633798 0.019885 0.02833497 0.01963299 0.028301 0.02004498 0.02742499 0.01820397 0.02633798 0.02004498 0.02742499 0.01963299 0.028301 0.02663499 0.02931886 0.019885 0.02833497 0.02004498 0.02742499 0.03104794 0.02999997 0.02663499 0.02931886 0.02004498 0.02742499 0.01609599 0.04047298 0.01963299 0.028301 0.019885 0.02833497 0.01845699 0.02814197 0.01963299 0.028301 0.01609599 0.04047298 0.01820397 0.02633798 0.01963299 0.028301 0.01845699 0.02814197 0.02860999 0.03127098 0.019885 0.02833497 0.02663499 0.02931886 0.020675 0.03956395 0.01609599 0.04047298 0.019885 0.02833497 0.02167296 0.03767287 0.020675 0.03956395 0.019885 0.02833497 0.02268898 0.03600895 0.02167296 0.03767287 0.019885 0.02833497 0.023696 0.03457999 0.02268898 0.03600895 0.019885 0.02833497 0.02560496 0.03246086 0.023696 0.03457999 0.019885 0.02833497 0.02727288 0.03135496 0.02560496 0.03246086 0.019885 0.02833497 0.02860999 0.03127098 0.02727288 0.03135496 0.019885 0.02833497 0.030366 0.03191 0.02663499 0.02931886 0.03104794 0.02999997 0.03027182 0.03187495 0.02663499 0.02931886 0.030366 0.03191 0.03027182 0.03187495 0.02860999 0.03127098 0.02663499 0.02931886 0.03369086 0.03053987 0.03477895 0.03187882 0.03104794 0.02999997 0.030366 0.03191 0.03104794 0.02999997 0.03477895 0.03187882 0.033508 0.03044492 0.03369086 0.03053987 0.03104794 0.02999997 0.01251 0.073291 5.48e-4 0.07626497 2.09e-4 0.06944096 0 0.06944096 2.09e-4 0.06944096 5.48e-4 0.07626497 0.01240599 0.07175797 0.01251 0.073291 2.09e-4 0.06944096 0.012407 0.06710195 0.01240599 0.07175797 2.09e-4 0.06944096 5.64e-4 0.06246298 0.012407 0.06710195 2.09e-4 0.06944096 4.02e-4 0.06195282 5.64e-4 0.06246298 2.09e-4 0.06944096 4.02e-4 0.06195282 2.09e-4 0.06944096 0 0.06944096 0.01364094 0.08593195 0.001003921 0.07985496 5.48e-4 0.07626497 4.03e-4 0.07692998 5.48e-4 0.07626497 0.001003921 0.07985496 0.01251 0.073291 0.01364094 0.08593195 5.48e-4 0.07626497 4.03e-4 0.07692998 0 0.06944096 5.48e-4 0.07626497 0.01364094 0.08593195 0.001663923 0.08350098 0.001003921 0.07985496 0.001537919 0.08401095 0.001003921 0.07985496 0.001663923 0.08350098 0.001537919 0.08401095 4.03e-4 0.07692998 0.001003921 0.07985496 0.01364094 0.08593195 0.002532899 0.08714395 0.001663923 0.08350098 0.001537919 0.08401095 0.001663923 0.08350098 0.002532899 0.08714395 0.01609599 0.09840798 0.003615975 0.09077996 0.002532899 0.08714395 0.003242969 0.090451 0.002532899 0.08714395 0.003615975 0.09077996 0.01364094 0.08593195 0.01609599 0.09840798 0.002532899 0.08714395 0.003242969 0.090451 0.001537919 0.08401095 0.002532899 0.08714395 0.01609599 0.09840798 0.0049299 0.09441298 0.003615975 0.09077996 0.003242969 0.090451 0.003615975 0.09077996 0.0049299 0.09441298 0.01609599 0.09840798 0.006437957 0.09795296 0.0049299 0.09441298 0.00534296 0.09617197 0.0049299 0.09441298 0.006437957 0.09795296 0.00534296 0.09617197 0.003242969 0.090451 0.0049299 0.09441298 0.01609599 0.09840798 0.008098959 0.101308 0.006437957 0.09795296 0.007693946 0.101206 0.006437957 0.09795296 0.008098959 0.101308 0.007693946 0.101206 0.00534296 0.09617197 0.006437957 0.09795296 0.019885 0.110547 0.009909987 0.104506 0.008098959 0.101308 0.007693946 0.101206 0.008098959 0.101308 0.009909987 0.104506 0.01609599 0.09840798 0.019885 0.110547 0.008098959 0.101308 0.019885 0.110547 0.01185786 0.107345 0.009909987 0.104506 0.01019597 0.105623 0.009909987 0.104506 0.01185786 0.107345 0.01019597 0.105623 0.007693946 0.101206 0.009909987 0.104506 0.019885 0.110547 0.01382082 0.109439 0.01185786 0.107345 0.01243084 0.108781 0.01185786 0.107345 0.01382082 0.109439 0.01243084 0.108781 0.01019597 0.105623 0.01185786 0.107345 0.019885 0.110547 0.01475197 0.110149 0.01382082 0.109439 0.01457285 0.110973 0.01382082 0.109439 0.01475197 0.110149 0.01457285 0.110973 0.01243084 0.108781 0.01382082 0.109439 0.019885 0.110547 0.01563996 0.110631 0.01475197 0.110149 0.01457285 0.110973 0.01475197 0.110149 0.01563996 0.110631 0.019885 0.110547 0.016478 0.11088 0.01563996 0.110631 0.01651698 0.112206 0.01563996 0.110631 0.016478 0.11088 0.01651698 0.112206 0.01457285 0.110973 0.01563996 0.110631 0.016478 0.11088 0.019885 0.110547 0.01845699 0.11074 0.01651698 0.112206 0.016478 0.11088 0.01726984 0.1109 0.01845699 0.11074 0.01726984 0.1109 0.016478 0.11088 0.02004384 0.111457 0.01726984 0.1109 0.01845699 0.11074 0.01820397 0.112544 0.01651698 0.112206 0.01726984 0.1109 0.02004384 0.111457 0.01820397 0.112544 0.01726984 0.1109 0.019885 0.110547 0.01963299 0.110581 0.01845699 0.11074 0.02004384 0.111457 0.01845699 0.11074 0.01963299 0.110581 0.034096 0.109883 0.01963299 0.110581 0.019885 0.110547 0.034096 0.109883 0.02004384 0.111457 0.01963299 0.110581 0.02560496 0.10642 0.019885 0.110547 0.01609599 0.09840798 0.03104895 0.108883 0.026636 0.109565 0.019885 0.110547 0.034096 0.109883 0.019885 0.110547 0.026636 0.109565 0.02860999 0.10761 0.03104895 0.108883 0.019885 0.110547 0.02727288 0.107526 0.02860999 0.10761 0.019885 0.110547 0.02560496 0.10642 0.02727288 0.107526 0.019885 0.110547 0.01969397 0.09721499 0.01609599 0.09840798 0.01364094 0.08593195 0.02369499 0.1043 0.02560496 0.10642 0.01609599 0.09840798 0.02268797 0.102871 0.02369499 0.1043 0.01609599 0.09840798 0.02167195 0.101207 0.02268797 0.102871 0.01609599 0.09840798 0.02067399 0.099316 0.02167195 0.101207 0.01609599 0.09840798 0.01969397 0.09721499 0.02067399 0.099316 0.01609599 0.09840798 0.012869 0.07626998 0.01364094 0.08593195 0.01251 0.073291 0.01642698 0.08890795 0.01969397 0.09721499 0.01364094 0.08593195 0.01374197 0.080361 0.01642698 0.08890795 0.01364094 0.08593195 0.012869 0.07626998 0.01374197 0.080361 0.01364094 0.08593195 0.02354699 0.07178097 0.01251 0.073291 0.01240599 0.07175797 0.02380895 0.07630795 0.012869 0.07626998 0.01251 0.073291 0.02380895 0.07630795 0.01251 0.073291 0.02354699 0.07178097 0.02354699 0.067101 0.01240599 0.07175797 0.012407 0.06710195 0.02354699 0.07178097 0.01240599 0.07175797 0.02354699 0.067101 5.64e-4 0.06246298 0.01251 0.06558597 0.012407 0.06710195 0.02354699 0.067101 0.012407 0.06710195 0.01251 0.06558597 0.001708984 0.0551669 0.01364094 0.05294698 0.01251 0.06558597 0.01287084 0.06259799 0.01251 0.06558597 0.01364094 0.05294698 0.001032948 0.05883193 0.001708984 0.0551669 0.01251 0.06558597 5.64e-4 0.06246298 0.001032948 0.05883193 0.01251 0.06558597 0.02354699 0.067101 0.01251 0.06558597 0.01287084 0.06259799 0.006490886 0.04081487 0.01609599 0.04047298 0.01364094 0.05294698 0.01642698 0.04997396 0.01364094 0.05294698 0.01609599 0.04047298 0.004993975 0.04430598 0.006490886 0.04081487 0.01364094 0.05294698 0.003681898 0.047903 0.004993975 0.04430598 0.01364094 0.05294698 0.002590954 0.05152183 0.003681898 0.047903 0.01364094 0.05294698 0.001708984 0.0551669 0.002590954 0.05152183 0.01364094 0.05294698 0.01374197 0.05851984 0.01287084 0.06259799 0.01364094 0.05294698 0.01642698 0.04997396 0.01374197 0.05851984 0.01364094 0.05294698 0.01726984 0.02798187 0.01845699 0.02814197 0.01609599 0.04047298 0.01647686 0.02800196 0.01726984 0.02798187 0.01609599 0.04047298 0.01563799 0.02825099 0.01647686 0.02800196 0.01609599 0.04047298 0.01475 0.02873384 0.01563799 0.02825099 0.01609599 0.04047298 0.01381886 0.02944499 0.01475 0.02873384 0.01609599 0.04047298 0.0118559 0.03153896 0.01381886 0.02944499 0.01609599 0.04047298 0.009909987 0.03437584 0.0118559 0.03153896 0.01609599 0.04047298 0.008130967 0.03751283 0.009909987 0.03437584 0.01609599 0.04047298 0.006490886 0.04081487 0.008130967 0.03751283 0.01609599 0.04047298 0.01969283 0.04166597 0.01642698 0.04997396 0.01609599 0.04047298 0.020675 0.03956395 0.01969283 0.04166597 0.01609599 0.04047298 0.01820397 0.02633798 0.01845699 0.02814197 0.01726984 0.02798187 0.01820397 0.02633798 0.01726984 0.02798187 0.01647686 0.02800196 0.01651698 0.02667587 0.01647686 0.02800196 0.01563799 0.02825099 0.01651698 0.02667587 0.01820397 0.02633798 0.01647686 0.02800196 0.01651698 0.02667587 0.01563799 0.02825099 0.01475 0.02873384 0.01457285 0.02790898 0.01475 0.02873384 0.01381886 0.02944499 0.01457285 0.02790898 0.01651698 0.02667587 0.01475 0.02873384 0.01243084 0.030101 0.01381886 0.02944499 0.0118559 0.03153896 0.01243084 0.030101 0.01457285 0.02790898 0.01381886 0.02944499 0.01243084 0.030101 0.0118559 0.03153896 0.009909987 0.03437584 0.01019597 0.03325897 0.009909987 0.03437584 0.008130967 0.03751283 0.01243084 0.030101 0.009909987 0.03437584 0.01019597 0.03325897 0.007694959 0.03767496 0.008130967 0.03751283 0.006490886 0.04081487 0.007694959 0.03767496 0.01019597 0.03325897 0.008130967 0.03751283 0.005343973 0.04270899 0.006490886 0.04081487 0.004993975 0.04430598 0.005343973 0.04270899 0.007694959 0.03767496 0.006490886 0.04081487 0.005343973 0.04270899 0.004993975 0.04430598 0.003681898 0.047903 0.003242969 0.04843199 0.003681898 0.047903 0.002590954 0.05152183 0.003242969 0.04843199 0.005343973 0.04270899 0.003681898 0.047903 0.003242969 0.04843199 0.002590954 0.05152183 0.001708984 0.0551669 0.001536965 0.05487185 0.001708984 0.0551669 0.001032948 0.05883193 0.001536965 0.05487185 0.003242969 0.04843199 0.001708984 0.0551669 4.02e-4 0.06195282 0.001032948 0.05883193 5.64e-4 0.06246298 4.02e-4 0.06195282 0.001536965 0.05487185 0.001032948 0.05883193 0.034096 0.109883 0.026636 0.109565 0.03104895 0.108883 0.03027182 0.107007 0.030366 0.106972 0.03104895 0.108883 0.033508 0.108437 0.03104895 0.108883 0.030366 0.106972 0.02860999 0.10761 0.03027182 0.107007 0.03104895 0.108883 0.033508 0.108437 0.03331995 0.108519 0.03104895 0.108883 0.034096 0.109883 0.03104895 0.108883 0.03331995 0.108519 0.03534787 0.10644 0.030366 0.106972 0.03027182 0.107007 0.03369086 0.108342 0.033508 0.108437 0.030366 0.106972 0.03477483 0.107011 0.03369086 0.108342 0.030366 0.106972 0.03190785 0.106412 0.03477483 0.107011 0.030366 0.106972 0.03534787 0.10644 0.03190785 0.106412 0.030366 0.106972 0.03534787 0.10644 0.03027182 0.107007 0.02860999 0.10761 0.03213596 0.10764 0.02860999 0.10761 0.02727288 0.107526 0.03534787 0.10644 0.02860999 0.10761 0.03213596 0.10764 0.03099083 0.107547 0.02727288 0.107526 0.02560496 0.10642 0.03213596 0.10764 0.02727288 0.107526 0.03099083 0.107547 0.02986997 0.106412 0.02560496 0.10642 0.02369499 0.1043 0.03099083 0.107547 0.02560496 0.10642 0.02986997 0.106412 0.02881598 0.104264 0.02369499 0.1043 0.02268797 0.102871 0.02986997 0.106412 0.02369499 0.1043 0.02881598 0.104264 0.02881598 0.104264 0.02268797 0.102871 0.02167195 0.101207 0.02787399 0.101176 0.02167195 0.101207 0.02067399 0.099316 0.02881598 0.104264 0.02167195 0.101207 0.02787399 0.101176 0.02787399 0.101176 0.02067399 0.099316 0.01969397 0.09721499 0.02708399 0.09726297 0.01969397 0.09721499 0.01642698 0.08890795 0.02787399 0.101176 0.01969397 0.09721499 0.02708399 0.09726297 0.02708399 0.09726297 0.01642698 0.08890795 0.01374197 0.080361 0.02431398 0.080388 0.01374197 0.080361 0.012869 0.07626998 0.02708399 0.09726297 0.01374197 0.080361 0.02431398 0.080388 0.02431398 0.080388 0.012869 0.07626998 0.02380895 0.07630795 0.034298 0.109449 0.03331995 0.108519 0.033508 0.108437 0.034298 0.109449 0.034096 0.109883 0.03331995 0.108519 0.034298 0.109449 0.033508 0.108437 0.03369086 0.108342 0.034298 0.109449 0.03369086 0.108342 0.03477483 0.107011 0.03323882 0.105107 0.03540086 0.104462 0.03477483 0.107011 0.03542697 0.108035 0.03477483 0.107011 0.03540086 0.104462 0.03190785 0.106412 0.03323882 0.105107 0.03477483 0.107011 0.03542697 0.108035 0.034298 0.109449 0.03477483 0.107011 0.03406995 0.102288 0.03560882 0.100744 0.03540086 0.104462 0.03604996 0.10545 0.03540086 0.104462 0.03560882 0.100744 0.03371793 0.103883 0.03406995 0.102288 0.03540086 0.104462 0.03323882 0.105107 0.03371793 0.103883 0.03540086 0.104462 0.03604996 0.10545 0.03542697 0.108035 0.03540086 0.104462 0.03441184 0.098109 0.03550398 0.09598195 0.03560882 0.100744 0.03615885 0.09727197 0.03560882 0.100744 0.03550398 0.09598195 0.03429198 0.100339 0.03441184 0.098109 0.03560882 0.100744 0.03406995 0.102288 0.03429198 0.100339 0.03560882 0.100744 0.03625386 0.101817 0.03604996 0.10545 0.03560882 0.100744 0.03615885 0.09727197 0.03625386 0.101817 0.03560882 0.100744 0.03444099 0.095618 0.03537595 0.09323799 0.03550398 0.09598195 0.03615885 0.09727197 0.03550398 0.09598195 0.03537595 0.09323799 0.03441184 0.098109 0.03444099 0.095618 0.03550398 0.09598195 0.03440994 0.092848 0.03521895 0.09028798 0.03537595 0.09323799 0.03588998 0.09195196 0.03537595 0.09323799 0.03521895 0.09028798 0.03444099 0.095618 0.03440994 0.092848 0.03537595 0.09323799 0.03588998 0.09195196 0.03615885 0.09727197 0.03537595 0.09323799 0.03423684 0.08672899 0.035052 0.087134 0.03521895 0.09028798 0.03588998 0.09195196 0.03521895 0.09028798 0.035052 0.087134 0.03440994 0.092848 0.03423684 0.08672899 0.03521895 0.09028798 0.03423684 0.08672899 0.03489089 0.08382397 0.035052 0.087134 0.03556984 0.08600097 0.035052 0.087134 0.03489089 0.08382397 0.03556984 0.08600097 0.03588998 0.09195196 0.035052 0.087134 0.03403896 0.08015197 0.03474897 0.08037197 0.03489089 0.08382397 0.03556984 0.08600097 0.03489089 0.08382397 0.03474897 0.08037197 0.03423684 0.08672899 0.03403896 0.08015197 0.03489089 0.08382397 0.03403896 0.08015197 0.034639 0.07685196 0.03474897 0.08037197 0.03529298 0.07957696 0.03474897 0.08037197 0.034639 0.07685196 0.03529298 0.07957696 0.03556984 0.08600097 0.03474897 0.08037197 0.03391283 0.07310301 0.03456896 0.07326698 0.034639 0.07685196 0.03529298 0.07957696 0.034639 0.07685196 0.03456896 0.07326698 0.03403896 0.08015197 0.03391283 0.07310301 0.034639 0.07685196 0.03391283 0.07310301 0.03454285 0.06964397 0.03456896 0.07326698 0.03513383 0.07285398 0.03456896 0.07326698 0.03454285 0.06964397 0.03513383 0.07285398 0.03529298 0.07957696 0.03456896 0.07326698 0.033912 0.06587797 0.03456383 0.06601595 0.03454285 0.06964397 0.03513383 0.06602698 0.03454285 0.06964397 0.03456383 0.06601595 0.03391283 0.07310301 0.033912 0.06587797 0.03454285 0.06964397 0.03513383 0.06602698 0.03513383 0.07285398 0.03454285 0.06964397 0.033912 0.06587797 0.03463 0.06241887 0.03456383 0.06601595 0.03513383 0.06602698 0.03456383 0.06601595 0.03463 0.06241887 0.03396499 0.06224685 0.03473585 0.058878 0.03463 0.06241887 0.03529298 0.05930387 0.03463 0.06241887 0.03473585 0.058878 0.033912 0.06587797 0.03396499 0.06224685 0.03463 0.06241887 0.03529298 0.05930387 0.03513383 0.06602698 0.03463 0.06241887 0.03404086 0.05869096 0.03487485 0.05539697 0.03473585 0.058878 0.03529298 0.05930387 0.03473585 0.058878 0.03487485 0.05539697 0.03396499 0.06224685 0.03404086 0.05869096 0.03473585 0.058878 0.03413999 0.05525696 0.03503698 0.05205297 0.03487485 0.05539697 0.03556895 0.05287986 0.03487485 0.05539697 0.03503698 0.05205297 0.03404086 0.05869096 0.03413999 0.05525696 0.03487485 0.05539697 0.03556895 0.05287986 0.03529298 0.05930387 0.03487485 0.05539697 0.03424495 0.051907 0.03520482 0.04885995 0.03503698 0.05205297 0.03556895 0.05287986 0.03503698 0.05205297 0.03520482 0.04885995 0.03413999 0.05525696 0.03424495 0.051907 0.03503698 0.05205297 0.03434598 0.04868698 0.03536397 0.04586786 0.03520482 0.04885995 0.03588998 0.04692995 0.03520482 0.04885995 0.03536397 0.04586786 0.03424495 0.051907 0.03434598 0.04868698 0.03520482 0.04885995 0.03588998 0.04692995 0.03556895 0.05287986 0.03520482 0.04885995 0.03441596 0.04566997 0.03549587 0.04308187 0.03536397 0.04586786 0.03588998 0.04692995 0.03536397 0.04586786 0.03549587 0.04308187 0.03434598 0.04868698 0.03441596 0.04566997 0.03536397 0.04586786 0.03440195 0.04047387 0.03558397 0.04053884 0.03549587 0.04308187 0.03615999 0.04161083 0.03549587 0.04308187 0.03558397 0.04053884 0.03444099 0.04290884 0.03440195 0.04047387 0.03549587 0.04308187 0.03441596 0.04566997 0.03444099 0.04290884 0.03549587 0.04308187 0.03615999 0.04161083 0.03588998 0.04692995 0.03549587 0.04308187 0.03404682 0.03644984 0.03560996 0.03823983 0.03558397 0.04053884 0.03615999 0.04161083 0.03558397 0.04053884 0.03560996 0.03823983 0.03440195 0.04047387 0.03404682 0.03644984 0.03558397 0.04053884 0.03404682 0.03644984 0.03540599 0.03446286 0.03560996 0.03823983 0.03625386 0.03706485 0.03560996 0.03823983 0.03540599 0.03446286 0.03625386 0.03706485 0.03615999 0.04161083 0.03560996 0.03823983 0.03190785 0.03246897 0.03477895 0.03187882 0.03540599 0.03446286 0.03604882 0.03343182 0.03540599 0.03446286 0.03477895 0.03187882 0.03322494 0.033746 0.03190785 0.03246897 0.03540599 0.03446286 0.03404682 0.03644984 0.03322494 0.033746 0.03540599 0.03446286 0.03604882 0.03343182 0.03625386 0.03706485 0.03540599 0.03446286 0.03542697 0.03084695 0.03477895 0.03187882 0.03369086 0.03053987 0.03190785 0.03246897 0.030366 0.03191 0.03477895 0.03187882 0.03542697 0.03084695 0.03604882 0.03343182 0.03477895 0.03187882 0.03542697 0.03084695 0.03369086 0.03053987 0.034298 0.02943295 0.03213596 0.03124094 0.030366 0.03191 0.03190785 0.03246897 0.03213596 0.03124094 0.03027182 0.03187495 0.030366 0.03191 0.03534787 0.03244096 0.03190785 0.03246897 0.03322494 0.033746 0.03534787 0.03244096 0.03213596 0.03124094 0.03190785 0.03246897 0.03693085 0.03379899 0.03322494 0.033746 0.03404682 0.03644984 0.03534787 0.03244096 0.03322494 0.033746 0.03693085 0.03379899 0.038414 0.03659784 0.03404682 0.03644984 0.03440195 0.04047387 0.03693085 0.03379899 0.03404682 0.03644984 0.038414 0.03659784 0.03973299 0.04067498 0.03440195 0.04047387 0.03444099 0.04290884 0.038414 0.03659784 0.03440195 0.04047387 0.03973299 0.04067498 0.03973299 0.04067498 0.03444099 0.04290884 0.03441596 0.04566997 0.04084396 0.04584795 0.03441596 0.04566997 0.03434598 0.04868698 0.03973299 0.04067498 0.03441596 0.04566997 0.04084396 0.04584795 0.04084396 0.04584795 0.03434598 0.04868698 0.03424495 0.051907 0.04171484 0.05193096 0.03424495 0.051907 0.03413999 0.05525696 0.04084396 0.04584795 0.03424495 0.051907 0.04171484 0.05193096 0.04231095 0.05866396 0.03413999 0.05525696 0.03404086 0.05869096 0.04171484 0.05193096 0.03413999 0.05525696 0.04231095 0.05866396 0.04231095 0.05866396 0.03404086 0.05869096 0.03396499 0.06224685 0.04261487 0.06579297 0.03396499 0.06224685 0.033912 0.06587797 0.04231095 0.05866396 0.03396499 0.06224685 0.04261487 0.06579297 0.04261487 0.073062 0.033912 0.06587797 0.03391283 0.07310301 0.04261487 0.06579297 0.033912 0.06587797 0.04261487 0.073062 0.04261487 0.073062 0.03391283 0.07310301 0.03403896 0.08015197 0.04231184 0.08021199 0.03403896 0.08015197 0.03423684 0.08672899 0.04261487 0.073062 0.03403896 0.08015197 0.04231184 0.08021199 0.04171186 0.08697497 0.03423684 0.08672899 0.03440994 0.092848 0.04231184 0.08021199 0.03423684 0.08672899 0.04171186 0.08697497 0.04083585 0.09307998 0.03440994 0.092848 0.03444099 0.095618 0.04171186 0.08697497 0.03440994 0.092848 0.04083585 0.09307998 0.04083585 0.09307998 0.03444099 0.095618 0.03441184 0.098109 0.03972095 0.09825199 0.03441184 0.098109 0.03429198 0.100339 0.04083585 0.09307998 0.03441184 0.098109 0.03972095 0.09825199 0.03840196 0.102314 0.03429198 0.100339 0.03406995 0.102288 0.03972095 0.09825199 0.03429198 0.100339 0.03840196 0.102314 0.03840196 0.102314 0.03406995 0.102288 0.03371793 0.103883 0.036924 0.105093 0.03371793 0.103883 0.03323882 0.105107 0.03840196 0.102314 0.03371793 0.103883 0.036924 0.105093 0.036924 0.105093 0.03323882 0.105107 0.03190785 0.106412 0.036924 0.105093 0.03190785 0.106412 0.03534787 0.10644 0.02380895 0.06257295 0.01287084 0.06259799 0.01374197 0.05851984 0.02354699 0.067101 0.01287084 0.06259799 0.02380895 0.06257295 0.02431398 0.05849283 0.01374197 0.05851984 0.01642698 0.04997396 0.02380895 0.06257295 0.01374197 0.05851984 0.02431398 0.05849283 0.02431398 0.05849283 0.01642698 0.04997396 0.01969283 0.04166597 0.02708399 0.041619 0.01969283 0.04166597 0.020675 0.03956395 0.02708399 0.041619 0.02431398 0.05849283 0.01969283 0.04166597 0.02787399 0.037705 0.020675 0.03956395 0.02167296 0.03767287 0.02787399 0.037705 0.02708399 0.041619 0.020675 0.03956395 0.02787399 0.037705 0.02167296 0.03767287 0.02268898 0.03600895 0.02881598 0.03461796 0.02268898 0.03600895 0.023696 0.03457999 0.02881598 0.03461796 0.02787399 0.037705 0.02268898 0.03600895 0.02986997 0.03246986 0.023696 0.03457999 0.02560496 0.03246086 0.02986997 0.03246986 0.02881598 0.03461796 0.023696 0.03457999 0.03099083 0.03133487 0.02560496 0.03246086 0.02727288 0.03135496 0.03099083 0.03133487 0.02986997 0.03246986 0.02560496 0.03246086 0.03099083 0.03133487 0.02727288 0.03135496 0.02860999 0.03127098 0.03213596 0.03124094 0.02860999 0.03127098 0.03027182 0.03187495 0.03213596 0.03124094 0.03099083 0.03133487 0.02860999 0.03127098 2.64e-4 0.06944096 0 0.06944096 4.03e-4 0.07692998 6.89e-4 0.06169492 0 0.06944096 2.64e-4 0.06944096 6.89e-4 0.06169492 4.02e-4 0.06195282 0 0.06944096 6.9e-4 0.07718795 4.03e-4 0.07692998 0.001537919 0.08401095 6.9e-4 0.07718795 2.64e-4 0.06944096 4.03e-4 0.07692998 0.001885831 0.08449399 0.001537919 0.08401095 0.003242969 0.090451 0.001885831 0.08449399 6.9e-4 0.07718795 0.001537919 0.08401095 0.003672957 0.09110701 0.003242969 0.090451 0.00534296 0.09617197 0.003672957 0.09110701 0.001885831 0.08449399 0.003242969 0.090451 0.005861997 0.09694999 0.00534296 0.09617197 0.007693946 0.101206 0.005861997 0.09694999 0.003672957 0.09110701 0.00534296 0.09617197 0.008297979 0.102064 0.007693946 0.101206 0.01019597 0.105623 0.008297979 0.102064 0.005861997 0.09694999 0.007693946 0.101206 0.008297979 0.102064 0.01019597 0.105623 0.01087695 0.10653 0.01325899 0.109819 0.01087695 0.10653 0.01019597 0.105623 0.01325899 0.109819 0.01019597 0.105623 0.01243084 0.108781 0.009804964 0.103643 0.008297979 0.102064 0.01087695 0.10653 0.009804964 0.103643 0.01087695 0.10653 0.01189899 0.107154 0.01421582 0.110317 0.01189899 0.107154 0.01087695 0.10653 0.01421582 0.110317 0.01087695 0.10653 0.01325899 0.109819 9.73e-4 0.06944096 2.64e-4 0.06944096 6.9e-4 0.07718795 0.001185894 0.06392896 2.64e-4 0.06944096 9.73e-4 0.06944096 6.89e-4 0.06169492 2.64e-4 0.06944096 0.001185894 0.06392896 0.001792967 0.08020997 6.9e-4 0.07718795 0.001885831 0.08449399 0.001311898 0.07642096 9.73e-4 0.06944096 6.9e-4 0.07718795 0.001792967 0.08020997 0.001311898 0.07642096 6.9e-4 0.07718795 0.003441989 0.08801198 0.001885831 0.08449399 0.003672957 0.09110701 0.002492964 0.08407795 0.001792967 0.08020997 0.001885831 0.08449399 0.003441989 0.08801198 0.002492964 0.08407795 0.001885831 0.08449399 0.004654884 0.09200596 0.003672957 0.09110701 0.005861997 0.09694999 0.004654884 0.09200596 0.003441989 0.08801198 0.003672957 0.09110701 0.007871985 0.099922 0.005861997 0.09694999 0.008297979 0.102064 0.006127953 0.09598797 0.004654884 0.09200596 0.005861997 0.09694999 0.007871985 0.099922 0.006127953 0.09598797 0.005861997 0.09694999 0.009804964 0.103643 0.007871985 0.099922 0.008297979 0.102064 0.02943295 0.1071979 0.009804964 0.103643 0.01189899 0.107154 0.02536797 0.1150619 0.01189899 0.107154 0.01421582 0.110317 0.01924484 0.110216 0.01189899 0.107154 0.02536797 0.1150619 0.02943295 0.1071979 0.01189899 0.107154 0.01924484 0.110216 0.00733298 0.06944096 9.73e-4 0.06944096 0.001311898 0.07642096 0.007995963 0.062756 9.73e-4 0.06944096 0.00733298 0.06944096 0.001185894 0.06392896 9.73e-4 0.06944096 0.007995963 0.062756 0.007994949 0.07612097 0.001311898 0.07642096 0.001792967 0.08020997 0.007994949 0.07612097 0.00733298 0.06944096 0.001311898 0.07642096 0.009952962 0.08271497 0.001792967 0.08020997 0.002492964 0.08407795 0.007994949 0.07612097 0.001792967 0.08020997 0.009952962 0.08271497 0.009952962 0.08271497 0.002492964 0.08407795 0.003441989 0.08801198 0.01316183 0.08917099 0.003441989 0.08801198 0.004654884 0.09200596 0.009952962 0.08271497 0.003441989 0.08801198 0.01316183 0.08917099 0.01754283 0.095438 0.004654884 0.09200596 0.006127953 0.09598797 0.01316183 0.08917099 0.004654884 0.09200596 0.01754283 0.095438 0.01754283 0.095438 0.006127953 0.09598797 0.007871985 0.099922 0.02300482 0.101464 0.007871985 0.099922 0.009804964 0.103643 0.01754283 0.095438 0.007871985 0.099922 0.02300482 0.101464 0.02300482 0.101464 0.009804964 0.103643 0.02943295 0.1071979 0.01325899 0.109819 0.01243084 0.108781 0.01457285 0.110973 0.01557284 0.112111 0.01457285 0.110973 0.01651698 0.112206 0.01557284 0.112111 0.01325899 0.109819 0.01457285 0.110973 0.01771098 0.113413 0.01651698 0.112206 0.01820397 0.112544 0.01771098 0.113413 0.01557284 0.112111 0.01651698 0.112206 0.01771098 0.113413 0.01820397 0.112544 0.01960796 0.113792 0.02127283 0.112943 0.01960796 0.113792 0.01820397 0.112544 0.02059584 0.112253 0.02127283 0.112943 0.01820397 0.112544 0.02004384 0.111457 0.02059584 0.112253 0.01820397 0.112544 0.02020382 0.114439 0.01771098 0.113413 0.01960796 0.113792 0.02020382 0.114439 0.01960796 0.113792 0.02132797 0.114503 0.02291285 0.1139219 0.02132797 0.114503 0.01960796 0.113792 0.02205383 0.113505 0.02291285 0.1139219 0.01960796 0.113792 0.02127283 0.112943 0.02205383 0.113505 0.01960796 0.113792 0.01512783 0.111319 0.01325899 0.109819 0.01557284 0.112111 0.01512783 0.111319 0.01421582 0.110317 0.01325899 0.109819 0.01785784 0.11353 0.01557284 0.112111 0.01771098 0.113413 0.01664882 0.112697 0.01512783 0.111319 0.01557284 0.112111 0.01785784 0.11353 0.01664882 0.112697 0.01557284 0.112111 0.01834595 0.113798 0.01785784 0.11353 0.01771098 0.113413 0.01904797 0.114113 0.01834595 0.113798 0.01771098 0.113413 0.02020382 0.114439 0.01904797 0.114113 0.01771098 0.113413 0.02496695 0.115553 0.02020382 0.114439 0.02132797 0.114503 0.02291285 0.1139219 0.022578 0.114343 0.02132797 0.114503 0.02971982 0.11615 0.02132797 0.114503 0.022578 0.114343 0.02874886 0.1166599 0.02496695 0.115553 0.02132797 0.114503 0.02971982 0.11615 0.02874886 0.1166599 0.02132797 0.114503 0.02536797 0.1150619 0.01421582 0.110317 0.01512783 0.111319 0.02388083 0.115587 0.01512783 0.111319 0.01664882 0.112697 0.02955085 0.117427 0.01512783 0.111319 0.02388083 0.115587 0.02536797 0.1150619 0.01512783 0.111319 0.02955085 0.117427 0.02388083 0.115587 0.01664882 0.112697 0.01785784 0.11353 0.02388083 0.115587 0.01785784 0.11353 0.01834595 0.113798 0.02496695 0.115553 0.01834595 0.113798 0.01904797 0.114113 0.02874886 0.1166599 0.01834595 0.113798 0.02496695 0.115553 0.02869486 0.116677 0.01834595 0.113798 0.02874886 0.1166599 0.02869486 0.116677 0.02864295 0.116694 0.01834595 0.113798 0.02388083 0.115587 0.01834595 0.113798 0.02864295 0.116694 0.02496695 0.115553 0.01904797 0.114113 0.02020382 0.114439 0.02291285 0.1139219 0.02382493 0.114182 0.022578 0.114343 0.02971982 0.11615 0.022578 0.114343 0.02382493 0.114182 0.02741295 0.1136839 0.02382493 0.114182 0.02291285 0.1139219 0.03069382 0.115665 0.02382493 0.114182 0.02741295 0.1136839 0.02971982 0.11615 0.02382493 0.114182 0.03069382 0.115665 0.03662699 0.111715 0.02291285 0.1139219 0.02205383 0.113505 0.03662699 0.111715 0.03813797 0.111995 0.02291285 0.1139219 0.03458487 0.112586 0.02291285 0.1139219 0.03813797 0.111995 0.03100198 0.113151 0.02741295 0.1136839 0.02291285 0.1139219 0.03458487 0.112586 0.03100198 0.113151 0.02291285 0.1139219 0.03662699 0.111715 0.02205383 0.113505 0.02127283 0.112943 0.03522795 0.110992 0.02127283 0.112943 0.02059584 0.112253 0.03522795 0.110992 0.03662699 0.111715 0.02127283 0.112943 0.034096 0.109883 0.02059584 0.112253 0.02004384 0.111457 0.034096 0.109883 0.03522795 0.110992 0.02059584 0.112253 0.03834784 0.111895 0.03813797 0.111995 0.03662699 0.111715 0.04605185 0.113106 0.03458487 0.112586 0.03813797 0.111995 0.06111097 0.112503 0.03813797 0.111995 0.03834784 0.111895 0.06111097 0.112503 0.06080496 0.1125079 0.05761384 0.112437 0.05761384 0.112437 0.03813797 0.111995 0.06111097 0.112503 0.059744 0.112566 0.03813797 0.111995 0.05761384 0.112437 0.05872386 0.112617 0.03813797 0.111995 0.059744 0.112566 0.05774194 0.112662 0.03813797 0.111995 0.05872386 0.112617 0.05679595 0.112703 0.03813797 0.111995 0.05774194 0.112662 0.05367696 0.112822 0.03813797 0.111995 0.05679595 0.112703 0.04830998 0.113018 0.04605185 0.113106 0.03813797 0.111995 0.05084896 0.112926 0.04830998 0.113018 0.03813797 0.111995 0.05367696 0.112822 0.05084896 0.112926 0.03813797 0.111995 0.03702396 0.111513 0.03662699 0.111715 0.03522795 0.110992 0.0385499 0.111787 0.03834784 0.111895 0.03662699 0.111715 0.03731983 0.111604 0.0385499 0.111787 0.03662699 0.111715 0.03702396 0.111513 0.03731983 0.111604 0.03662699 0.111715 0.035133 0.1104 0.03522795 0.110992 0.034096 0.109883 0.03615885 0.111132 0.03702396 0.111513 0.03522795 0.110992 0.03562682 0.110797 0.03615885 0.111132 0.03522795 0.110992 0.035133 0.1104 0.03562682 0.110797 0.03522795 0.110992 0.03448683 0.109705 0.035133 0.1104 0.034096 0.109883 0.034298 0.109449 0.03448683 0.109705 0.034096 0.109883 0.03549796 0.1139039 0.02741295 0.1136839 0.03100198 0.113151 0.03290086 0.114728 0.03069382 0.115665 0.02741295 0.1136839 0.03300487 0.11469 0.03290086 0.114728 0.02741295 0.1136839 0.03549796 0.1139039 0.03300487 0.11469 0.02741295 0.1136839 0.03672498 0.113689 0.03100198 0.113151 0.03458487 0.112586 0.03672498 0.113689 0.03549796 0.1139039 0.03100198 0.113151 0.228227 0.09265297 0.229303 0.09027796 0.230357 0.08782398 0.03859299 0.113533 0.03672498 0.113689 0.03458487 0.112586 0.04038 0.113422 0.03859299 0.113533 0.03458487 0.112586 0.04235297 0.113295 0.04038 0.113422 0.03458487 0.112586 0.04406785 0.113197 0.04235297 0.113295 0.03458487 0.112586 0.04605185 0.113106 0.04406785 0.113197 0.03458487 0.112586 0.06295597 0.112394 0.03834784 0.111895 0.0385499 0.111787 0.06146287 0.1124899 0.06111097 0.112503 0.03834784 0.111895 0.061872 0.11247 0.06146287 0.1124899 0.03834784 0.111895 0.06234699 0.112439 0.061872 0.11247 0.03834784 0.111895 0.06295597 0.112394 0.06234699 0.112439 0.03834784 0.111895 0.03851598 0.110088 0.0385499 0.111787 0.03731983 0.111604 0.06356 0.112348 0.06295597 0.112394 0.0385499 0.111787 0.03977096 0.110232 0.06356 0.112348 0.0385499 0.111787 0.03977096 0.110232 0.0385499 0.111787 0.03851598 0.110088 0.03733599 0.109641 0.03731983 0.111604 0.03702396 0.111513 0.03851598 0.110088 0.03731983 0.111604 0.03733599 0.109641 0.03733599 0.109641 0.03702396 0.111513 0.03615885 0.111132 0.03628695 0.1089439 0.03615885 0.111132 0.03562682 0.110797 0.03733599 0.109641 0.03615885 0.111132 0.03628695 0.1089439 0.03628695 0.1089439 0.03562682 0.110797 0.035133 0.1104 0.03542697 0.108035 0.035133 0.1104 0.03448683 0.109705 0.03628695 0.1089439 0.035133 0.1104 0.03542697 0.108035 0.03542697 0.108035 0.03448683 0.109705 0.034298 0.109449 0.06102395 0.112534 0.06080496 0.1125079 0.06111097 0.112503 0.059744 0.112566 0.05761384 0.112437 0.06080496 0.1125079 0.06102395 0.112534 0.059744 0.112566 0.06080496 0.1125079 0.06102395 0.112534 0.06111097 0.112503 0.06146287 0.1124899 0.06102395 0.112534 0.06146287 0.1124899 0.061872 0.11247 0.06102395 0.112534 0.061872 0.11247 0.06234699 0.112439 0.06104195 0.112551 0.06234699 0.112439 0.06295597 0.112394 0.06104195 0.112551 0.06102395 0.112534 0.06234699 0.112439 0.06104195 0.112551 0.06295597 0.112394 0.06356 0.112348 0.07646 0.11262 0.06356 0.112348 0.03977096 0.110232 0.07613295 0.112878 0.06356 0.112348 0.07646 0.11262 0.06104195 0.112551 0.06356 0.112348 0.07613295 0.112878 0.05978983 0.112592 0.05872386 0.112617 0.059744 0.112566 0.06102395 0.112534 0.05978983 0.112592 0.059744 0.112566 0.05864685 0.112623 0.05774194 0.112662 0.05872386 0.112617 0.05978983 0.112592 0.05864685 0.112623 0.05872386 0.112617 0.05706685 0.112723 0.05679595 0.112703 0.05774194 0.112662 0.05720198 0.112717 0.05706685 0.112723 0.05774194 0.112662 0.05733686 0.112699 0.05720198 0.112717 0.05774194 0.112662 0.05760395 0.112632 0.05733686 0.112699 0.05774194 0.112662 0.05864685 0.112623 0.05760395 0.112632 0.05774194 0.112662 0.054223 0.112833 0.05679595 0.112703 0.05706685 0.112723 0.054223 0.112833 0.05367696 0.112822 0.05679595 0.112703 0.05463784 0.112746 0.05706685 0.112723 0.05720198 0.112717 0.054223 0.112833 0.05706685 0.112723 0.05463784 0.112746 0.05463784 0.112746 0.05720198 0.112717 0.05733686 0.112699 0.05559796 0.112593 0.05733686 0.112699 0.05760395 0.112632 0.05511796 0.11257 0.05733686 0.112699 0.05559796 0.112593 0.05463784 0.112746 0.05733686 0.112699 0.05511796 0.11257 0.05802798 0.112562 0.05760395 0.112632 0.05864685 0.112623 0.05802798 0.112562 0.05676686 0.112379 0.05760395 0.112632 0.05559796 0.112593 0.05760395 0.112632 0.05676686 0.112379 0.05844783 0.112543 0.05864685 0.112623 0.05978983 0.112592 0.05802798 0.112562 0.05864685 0.112623 0.05844783 0.112543 0.06104195 0.112551 0.05978983 0.112592 0.06102395 0.112534 0.06104195 0.112551 0.05844783 0.112543 0.05978983 0.112592 0.03411698 0.114766 0.03069382 0.115665 0.03290086 0.114728 0.03165996 0.115751 0.02971982 0.11615 0.03069382 0.115665 0.03165996 0.115751 0.03069382 0.115665 0.03411698 0.114766 0.03725087 0.113807 0.03290086 0.114728 0.03300487 0.11469 0.03411698 0.114766 0.03290086 0.114728 0.03725087 0.113807 0.03725087 0.113807 0.03300487 0.11469 0.03549796 0.1139039 0.03725087 0.113807 0.03549796 0.1139039 0.03672498 0.113689 0.229303 0.09027796 0.2284229 0.09219199 0.230357 0.08782398 0.03725087 0.113807 0.03672498 0.113689 0.03840595 0.113586 0.040151 0.113421 0.03672498 0.113689 0.03859299 0.113533 0.03840595 0.113586 0.03672498 0.113689 0.040151 0.113421 0.04393386 0.113137 0.03859299 0.113533 0.04038 0.113422 0.040151 0.113421 0.03859299 0.113533 0.04393386 0.113137 0.04393386 0.113137 0.04038 0.113422 0.04235297 0.113295 0.04393386 0.113137 0.04235297 0.113295 0.04406785 0.113197 0.04616385 0.1130599 0.04406785 0.113197 0.04605185 0.113106 0.04616385 0.1130599 0.04393386 0.113137 0.04406785 0.113197 0.048702 0.112993 0.04605185 0.113106 0.04830998 0.113018 0.04616385 0.1130599 0.04605185 0.113106 0.048702 0.112993 0.05141484 0.11292 0.04830998 0.113018 0.05084896 0.112926 0.048702 0.112993 0.04830998 0.113018 0.05141484 0.11292 0.05141484 0.11292 0.05084896 0.112926 0.05367696 0.112822 0.05141484 0.11292 0.05367696 0.112822 0.054223 0.112833 0.03165996 0.115751 0.02874886 0.1166599 0.02971982 0.11615 0.03009796 0.11678 0.02869486 0.116677 0.02874886 0.1166599 0.03165996 0.115751 0.03009796 0.11678 0.02874886 0.1166599 0.03009796 0.11678 0.02864295 0.116694 0.02869486 0.116677 0.02840799 0.116824 0.02388083 0.115587 0.02864295 0.116694 0.02901798 0.117034 0.02840799 0.116824 0.02864295 0.116694 0.02917885 0.116784 0.02864295 0.116694 0.03009796 0.11678 0.02901798 0.117034 0.02864295 0.116694 0.02917885 0.116784 0.02895498 0.117245 0.02955085 0.117427 0.02388083 0.115587 0.02858185 0.117093 0.02895498 0.117245 0.02388083 0.115587 0.02838397 0.116952 0.02858185 0.117093 0.02388083 0.115587 0.02840799 0.116824 0.02838397 0.116952 0.02388083 0.115587 0.03019696 0.117578 0.02955085 0.117427 0.02895498 0.117245 0.03021585 0.117601 0.02536797 0.1150619 0.02955085 0.117427 0.031237 0.117878 0.03021585 0.117601 0.02955085 0.117427 0.031237 0.117878 0.02955085 0.117427 0.03019696 0.117578 0.02942585 0.117298 0.02895498 0.117245 0.02858185 0.117093 0.03019696 0.117578 0.02895498 0.117245 0.02942585 0.117298 0.02942585 0.117298 0.02858185 0.117093 0.02838397 0.116952 0.02901798 0.117034 0.02838397 0.116952 0.02840799 0.116824 0.02942585 0.117298 0.02838397 0.116952 0.02901798 0.117034 0.03494495 0.1186619 0.03614687 0.118932 0.02536797 0.1150619 0.02645885 0.113176 0.02536797 0.1150619 0.03614687 0.118932 0.033445 0.118332 0.03494495 0.1186619 0.02536797 0.1150619 0.032175 0.118053 0.033445 0.118332 0.02536797 0.1150619 0.03110897 0.117813 0.032175 0.118053 0.02536797 0.1150619 0.03021585 0.117601 0.03110897 0.117813 0.02536797 0.1150619 0.02645885 0.113176 0.01924484 0.110216 0.02536797 0.1150619 0.03737282 0.11939 0.03614687 0.118932 0.03494495 0.1186619 0.033517 0.11602 0.02645885 0.113176 0.03614687 0.118932 0.03740096 0.119221 0.033517 0.11602 0.03614687 0.118932 0.03737282 0.11939 0.03740096 0.119221 0.03614687 0.118932 0.03557085 0.118952 0.03494495 0.1186619 0.033445 0.118332 0.03737282 0.11939 0.03494495 0.1186619 0.03557085 0.118952 0.03394997 0.118561 0.033445 0.118332 0.032175 0.118053 0.03557085 0.118952 0.033445 0.118332 0.03394997 0.118561 0.03249597 0.1182039 0.032175 0.118053 0.03110897 0.117813 0.03394997 0.118561 0.032175 0.118053 0.03249597 0.1182039 0.031237 0.117878 0.03110897 0.117813 0.03021585 0.117601 0.03249597 0.1182039 0.03110897 0.117813 0.031237 0.117878 0.03670299 0.112589 0.01924484 0.110216 0.02645885 0.113176 0.02943295 0.1071979 0.01924484 0.110216 0.03670299 0.112589 0.03670299 0.112589 0.02645885 0.113176 0.033517 0.11602 0.04197084 0.120344 0.04041486 0.118738 0.033517 0.11602 0.04467797 0.11759 0.033517 0.11602 0.04041486 0.118738 0.04031497 0.119923 0.04197084 0.120344 0.033517 0.11602 0.03877782 0.119546 0.04031497 0.119923 0.033517 0.11602 0.03740096 0.119221 0.03877782 0.119546 0.033517 0.11602 0.03670299 0.112589 0.033517 0.11602 0.04467797 0.11759 0.04580485 0.12139 0.04715287 0.12132 0.04041486 0.118738 0.04467797 0.11759 0.04041486 0.118738 0.04715287 0.12132 0.04378783 0.120826 0.04580485 0.12139 0.04041486 0.118738 0.04197084 0.120344 0.04378783 0.120826 0.04041486 0.118738 0.05208384 0.123267 0.053716 0.123757 0.04715287 0.12132 0.05321484 0.122155 0.04715287 0.12132 0.053716 0.123757 0.05042797 0.122759 0.05208384 0.123267 0.04715287 0.12132 0.04801785 0.122034 0.05042797 0.122759 0.04715287 0.12132 0.04580485 0.12139 0.04801785 0.122034 0.04715287 0.12132 0.04467797 0.11759 0.04715287 0.12132 0.05321484 0.122155 0.05148983 0.123284 0.053716 0.123757 0.05208384 0.123267 0.05477494 0.124286 0.053716 0.123757 0.05148983 0.123284 0.068089 0.1280249 0.053716 0.123757 0.05477494 0.124286 0.06216984 0.126241 0.053716 0.123757 0.068089 0.1280249 0.05321484 0.122155 0.053716 0.123757 0.06216984 0.126241 0.05148983 0.123284 0.05208384 0.123267 0.05042797 0.122759 0.05148983 0.123284 0.05042797 0.122759 0.04801785 0.122034 0.04876887 0.122462 0.04801785 0.122034 0.04580485 0.12139 0.04876887 0.122462 0.05148983 0.123284 0.04801785 0.122034 0.04618698 0.121712 0.04580485 0.12139 0.04378783 0.120826 0.04876887 0.122462 0.04580485 0.12139 0.04618698 0.121712 0.04374986 0.121034 0.04378783 0.120826 0.04197084 0.120344 0.04618698 0.121712 0.04378783 0.120826 0.04374986 0.121034 0.04374986 0.121034 0.04197084 0.120344 0.04031497 0.119923 0.04147297 0.120427 0.04031497 0.119923 0.03877782 0.119546 0.04374986 0.121034 0.04031497 0.119923 0.04147297 0.120427 0.03934288 0.11988 0.03877782 0.119546 0.03740096 0.119221 0.04147297 0.120427 0.03877782 0.119546 0.03934288 0.11988 0.03934288 0.11988 0.03740096 0.119221 0.03737282 0.11939 0.03143388 0.11658 0.03138095 0.116605 0.03133183 0.11663 0.03674799 0.115243 0.03133183 0.11663 0.03138095 0.116605 0.03080385 0.116744 0.03143388 0.11658 0.03133183 0.11663 0.03164494 0.116766 0.03080385 0.116744 0.03133183 0.11663 0.03674799 0.115243 0.03164494 0.116766 0.03133183 0.11663 0.03674799 0.115243 0.03138095 0.116605 0.03143388 0.11658 0.03026497 0.116809 0.03009796 0.11678 0.03143388 0.11658 0.03291589 0.115844 0.03143388 0.11658 0.03009796 0.11678 0.03080385 0.116744 0.03026497 0.116809 0.03143388 0.11658 0.03724396 0.114062 0.03143388 0.11658 0.03291589 0.115844 0.03724396 0.114062 0.03674799 0.115243 0.03143388 0.11658 0.02972197 0.116822 0.02917885 0.116784 0.03009796 0.11678 0.02999287 0.116822 0.02972197 0.116822 0.03009796 0.11678 0.03026497 0.116809 0.02999287 0.116822 0.03009796 0.11678 0.03356099 0.115424 0.03443884 0.115022 0.03009796 0.11678 0.03291589 0.115844 0.03009796 0.11678 0.03443884 0.115022 0.0326249 0.11567 0.03009796 0.11678 0.03165996 0.115751 0.03356099 0.115424 0.03009796 0.11678 0.0326249 0.11567 0.02967995 0.11708 0.02917885 0.116784 0.02972197 0.116822 0.02901798 0.117034 0.02917885 0.116784 0.02967995 0.11708 0.03034299 0.117049 0.02972197 0.116822 0.02999287 0.116822 0.02967995 0.11708 0.02972197 0.116822 0.03034299 0.117049 0.03034299 0.117049 0.02999287 0.116822 0.03026497 0.116809 0.030999 0.116943 0.03026497 0.116809 0.03080385 0.116744 0.03034299 0.117049 0.03026497 0.116809 0.030999 0.116943 0.030999 0.116943 0.03080385 0.116744 0.03164494 0.116766 0.05249089 0.1205 0.0539 0.118982 0.05603796 0.119323 0.05827283 0.113912 0.05603796 0.119323 0.0539 0.118982 0.05513298 0.121046 0.05249089 0.1205 0.05603796 0.119323 0.05839186 0.122058 0.05513298 0.121046 0.05603796 0.119323 0.05839186 0.122058 0.05603796 0.119323 0.05765998 0.119834 0.08736896 0.127887 0.05765998 0.119834 0.05603796 0.119323 0.06213498 0.115381 0.08736896 0.127887 0.05603796 0.119323 0.05827283 0.113912 0.06213498 0.115381 0.05603796 0.119323 0.05249089 0.1205 0.05191683 0.118673 0.0539 0.118982 0.05827283 0.113912 0.0539 0.118982 0.05191683 0.118673 0.04994785 0.120007 0.05017 0.1184239 0.05191683 0.118673 0.05827283 0.113912 0.05191683 0.118673 0.05017 0.1184239 0.05249089 0.1205 0.04994785 0.120007 0.05191683 0.118673 0.04751396 0.119565 0.05008095 0.118412 0.05017 0.1184239 0.05231183 0.113795 0.05017 0.1184239 0.05008095 0.118412 0.04994785 0.120007 0.04751396 0.119565 0.05017 0.1184239 0.05827283 0.113912 0.05017 0.1184239 0.05231183 0.113795 0.04751396 0.119565 0.04756587 0.118106 0.05008095 0.118412 0.05231183 0.113795 0.05008095 0.118412 0.04756587 0.118106 0.04520297 0.119173 0.04531997 0.117865 0.04756587 0.118106 0.05231183 0.113795 0.04756587 0.118106 0.04531997 0.117865 0.04751396 0.119565 0.04520297 0.119173 0.04756587 0.118106 0.04300493 0.118822 0.04355084 0.117695 0.04531997 0.117865 0.05231183 0.113795 0.04531997 0.117865 0.04355084 0.117695 0.04520297 0.119173 0.04300493 0.118822 0.04531997 0.117865 0.04093384 0.11851 0.04327899 0.117671 0.04355084 0.117695 0.04355299 0.114816 0.04355084 0.117695 0.04327899 0.117671 0.04300493 0.118822 0.04093384 0.11851 0.04355084 0.117695 0.05176997 0.111195 0.04355084 0.117695 0.04355299 0.114816 0.05231183 0.113795 0.04355084 0.117695 0.05176997 0.111195 0.04093384 0.11851 0.04143697 0.117518 0.04327899 0.117671 0.04355299 0.114816 0.04327899 0.117671 0.04143697 0.117518 0.03899896 0.1182309 0.03982585 0.1173959 0.04143697 0.117518 0.04355299 0.114816 0.04143697 0.117518 0.03982585 0.1173959 0.04093384 0.11851 0.03899896 0.1182309 0.04143697 0.117518 0.03721582 0.117981 0.038396 0.117297 0.03982585 0.1173959 0.04355299 0.114816 0.03982585 0.1173959 0.038396 0.117297 0.03899896 0.1182309 0.03721582 0.117981 0.03982585 0.1173959 0.03721582 0.117981 0.03712385 0.117215 0.038396 0.117297 0.04355299 0.114816 0.038396 0.117297 0.03712385 0.117215 0.03556686 0.117751 0.03605896 0.117147 0.03712385 0.117215 0.04355299 0.114816 0.03712385 0.117215 0.03605896 0.117147 0.03721582 0.117981 0.03556686 0.117751 0.03712385 0.117215 0.03408199 0.117538 0.0359869 0.117143 0.03605896 0.117147 0.03750598 0.115011 0.03605896 0.117147 0.0359869 0.117143 0.03556686 0.117751 0.03408199 0.117538 0.03605896 0.117147 0.04295682 0.113082 0.03605896 0.117147 0.03750598 0.115011 0.04355299 0.114816 0.03605896 0.117147 0.04295682 0.113082 0.03408199 0.117538 0.03495395 0.117075 0.0359869 0.117143 0.03674799 0.115243 0.0359869 0.117143 0.03495395 0.117075 0.03750598 0.115011 0.0359869 0.117143 0.03674799 0.115243 0.03278696 0.117335 0.03402584 0.117011 0.03495395 0.117075 0.03674799 0.115243 0.03495395 0.117075 0.03402584 0.117011 0.03408199 0.117538 0.03278696 0.117335 0.03495395 0.117075 0.03278696 0.117335 0.03323799 0.11695 0.03402584 0.117011 0.03674799 0.115243 0.03402584 0.117011 0.03323799 0.11695 0.03172791 0.117138 0.032579 0.1168889 0.03323799 0.11695 0.03674799 0.115243 0.03323799 0.11695 0.032579 0.1168889 0.03278696 0.117335 0.03172791 0.117138 0.03323799 0.11695 0.03172791 0.117138 0.03204596 0.116829 0.032579 0.1168889 0.03674799 0.115243 0.032579 0.1168889 0.03204596 0.116829 0.030999 0.116943 0.03164494 0.116766 0.03204596 0.116829 0.03674799 0.115243 0.03204596 0.116829 0.03164494 0.116766 0.03172791 0.117138 0.030999 0.116943 0.03204596 0.116829 0.03034299 0.117049 0.030999 0.116943 0.03172791 0.117138 0.03096795 0.117299 0.03172791 0.117138 0.03278696 0.117335 0.03096795 0.117299 0.03034299 0.117049 0.03172791 0.117138 0.03193593 0.117559 0.03278696 0.117335 0.03408199 0.117538 0.03193593 0.117559 0.03096795 0.117299 0.03278696 0.117335 0.03315097 0.117833 0.03408199 0.117538 0.03556686 0.117751 0.03315097 0.117833 0.03193593 0.117559 0.03408199 0.117538 0.03456687 0.118126 0.03556686 0.117751 0.03721582 0.117981 0.03456687 0.118126 0.03315097 0.117833 0.03556686 0.117751 0.03615784 0.118441 0.03721582 0.117981 0.03899896 0.1182309 0.03615784 0.118441 0.03456687 0.118126 0.03721582 0.117981 0.03789496 0.1187829 0.03899896 0.1182309 0.04093384 0.11851 0.03789496 0.1187829 0.03615784 0.118441 0.03899896 0.1182309 0.03979295 0.1191599 0.04093384 0.11851 0.04300493 0.118822 0.03979295 0.1191599 0.03789496 0.1187829 0.04093384 0.11851 0.04183799 0.119575 0.04300493 0.118822 0.04520297 0.119173 0.04183799 0.119575 0.03979295 0.1191599 0.04300493 0.118822 0.04402095 0.120034 0.04520297 0.119173 0.04751396 0.119565 0.04402095 0.120034 0.04183799 0.119575 0.04520297 0.119173 0.04632484 0.120539 0.04751396 0.119565 0.04994785 0.120007 0.04632484 0.120539 0.04402095 0.120034 0.04751396 0.119565 0.04876285 0.121097 0.04994785 0.120007 0.05249089 0.1205 0.04876285 0.121097 0.04632484 0.120539 0.04994785 0.120007 0.05131983 0.121709 0.05249089 0.1205 0.05513298 0.121046 0.05131983 0.121709 0.04876285 0.121097 0.05249089 0.1205 0.05131983 0.121709 0.05513298 0.121046 0.05398386 0.1223739 0.057253 0.123383 0.05398386 0.1223739 0.05513298 0.121046 0.05839186 0.122058 0.057253 0.123383 0.05513298 0.121046 0.05003386 0.122387 0.05131983 0.121709 0.05398386 0.1223739 0.05003386 0.122387 0.05398386 0.1223739 0.05272185 0.12315 0.05599999 0.124155 0.05272185 0.12315 0.05398386 0.1223739 0.057253 0.123383 0.05599999 0.124155 0.05398386 0.1223739 0.02967995 0.11708 0.03034299 0.117049 0.03096795 0.117299 0.03019595 0.117352 0.03096795 0.117299 0.03193593 0.117559 0.03019595 0.117352 0.02967995 0.11708 0.03096795 0.117299 0.03106486 0.11764 0.03193593 0.117559 0.03315097 0.117833 0.03106486 0.11764 0.03019595 0.117352 0.03193593 0.117559 0.03219199 0.117948 0.03315097 0.117833 0.03456687 0.118126 0.03219199 0.117948 0.03106486 0.11764 0.03315097 0.117833 0.03352898 0.118279 0.03456687 0.118126 0.03615784 0.118441 0.03352898 0.118279 0.03219199 0.117948 0.03456687 0.118126 0.035052 0.118638 0.03615784 0.118441 0.03789496 0.1187829 0.035052 0.118638 0.03352898 0.118279 0.03615784 0.118441 0.036731 0.119028 0.03789496 0.1187829 0.03979295 0.1191599 0.036731 0.119028 0.035052 0.118638 0.03789496 0.1187829 0.03858095 0.11946 0.03979295 0.1191599 0.04183799 0.119575 0.03858095 0.11946 0.036731 0.119028 0.03979295 0.1191599 0.04058796 0.119937 0.04183799 0.119575 0.04402095 0.120034 0.04058796 0.119937 0.03858095 0.11946 0.04183799 0.119575 0.04274284 0.120464 0.04402095 0.120034 0.04632484 0.120539 0.04274284 0.120464 0.04058796 0.119937 0.04402095 0.120034 0.04503196 0.121044 0.04632484 0.120539 0.04876285 0.121097 0.04503196 0.121044 0.04274284 0.120464 0.04632484 0.120539 0.04746782 0.121685 0.04876285 0.121097 0.05131983 0.121709 0.04746782 0.121685 0.04503196 0.121044 0.04876285 0.121097 0.05003386 0.122387 0.04746782 0.121685 0.05131983 0.121709 0.04876887 0.122462 0.05003386 0.122387 0.05272185 0.12315 0.04876887 0.122462 0.05272185 0.12315 0.05148983 0.123284 0.05477494 0.124286 0.05148983 0.123284 0.05272185 0.12315 0.05599999 0.124155 0.05477494 0.124286 0.05272185 0.12315 0.02901798 0.117034 0.02967995 0.11708 0.03019595 0.117352 0.02942585 0.117298 0.03019595 0.117352 0.03106486 0.11764 0.02942585 0.117298 0.02901798 0.117034 0.03019595 0.117352 0.03019696 0.117578 0.03106486 0.11764 0.03219199 0.117948 0.03019696 0.117578 0.02942585 0.117298 0.03106486 0.11764 0.031237 0.117878 0.03219199 0.117948 0.03352898 0.118279 0.031237 0.117878 0.03019696 0.117578 0.03219199 0.117948 0.03249597 0.1182039 0.03352898 0.118279 0.035052 0.118638 0.03249597 0.1182039 0.031237 0.117878 0.03352898 0.118279 0.03394997 0.118561 0.035052 0.118638 0.036731 0.119028 0.03394997 0.118561 0.03249597 0.1182039 0.035052 0.118638 0.03557085 0.118952 0.036731 0.119028 0.03858095 0.11946 0.03557085 0.118952 0.03394997 0.118561 0.036731 0.119028 0.03737282 0.11939 0.03858095 0.11946 0.04058796 0.119937 0.03737282 0.11939 0.03557085 0.118952 0.03858095 0.11946 0.03934288 0.11988 0.04058796 0.119937 0.04274284 0.120464 0.03934288 0.11988 0.03737282 0.11939 0.04058796 0.119937 0.04147297 0.120427 0.04274284 0.120464 0.04503196 0.121044 0.04147297 0.120427 0.03934288 0.11988 0.04274284 0.120464 0.04374986 0.121034 0.04503196 0.121044 0.04746782 0.121685 0.04374986 0.121034 0.04147297 0.120427 0.04503196 0.121044 0.04618698 0.121712 0.04746782 0.121685 0.05003386 0.122387 0.04618698 0.121712 0.04374986 0.121034 0.04746782 0.121685 0.04876887 0.122462 0.04618698 0.121712 0.05003386 0.122387 0.05839186 0.122058 0.05765998 0.119834 0.05928796 0.120337 0.08736896 0.127887 0.05928796 0.120337 0.05765998 0.119834 0.07063496 0.123632 0.05839186 0.122058 0.05928796 0.120337 0.07063496 0.123632 0.05928796 0.120337 0.08736896 0.127887 0.06926095 0.127834 0.05477494 0.124286 0.05599999 0.124155 0.068089 0.1280249 0.05477494 0.124286 0.06926095 0.127834 0.07043898 0.127053 0.05599999 0.124155 0.057253 0.123383 0.06926095 0.127834 0.05599999 0.124155 0.07043898 0.127053 0.07150197 0.125764 0.057253 0.123383 0.05839186 0.122058 0.07043898 0.127053 0.057253 0.123383 0.07150197 0.125764 0.07150197 0.125764 0.05839186 0.122058 0.07063496 0.123632 0.122922 0.133946 0.141405 0.134874 0.132374 0.134656 0.126545 0.1357139 0.132374 0.134656 0.141405 0.134874 0.147531 0.1347129 0.141405 0.134874 0.122922 0.133946 0.1410509 0.136189 0.126545 0.1357139 0.141405 0.134874 0.147531 0.1347129 0.1410509 0.136189 0.141405 0.134874 0.126545 0.1357139 0.122922 0.133946 0.132374 0.134656 0.112342 0.134196 0.120205 0.133659 0.122922 0.133946 0.147531 0.1347129 0.122922 0.133946 0.120205 0.133659 0.126545 0.1357139 0.112342 0.134196 0.122922 0.133946 0.102804 0.131076 0.120205 0.133659 0.113027 0.132737 0.112342 0.134196 0.113027 0.132737 0.120205 0.133659 0.09237897 0.1290079 0.120205 0.133659 0.102804 0.131076 0.08736896 0.127887 0.120205 0.133659 0.09237897 0.1290079 0.122503 0.122529 0.120205 0.133659 0.08736896 0.127887 0.147531 0.1347129 0.120205 0.133659 0.15375 0.13428 0.122503 0.122529 0.15375 0.13428 0.120205 0.133659 0.112342 0.134196 0.102804 0.131076 0.113027 0.132737 0.09845095 0.131925 0.09237897 0.1290079 0.102804 0.131076 0.112342 0.134196 0.09845095 0.131925 0.102804 0.131076 0.08484697 0.129072 0.08736896 0.127887 0.09237897 0.1290079 0.09845095 0.131925 0.08484697 0.129072 0.09237897 0.1290079 0.07063496 0.123632 0.08736896 0.127887 0.08167099 0.126524 0.08484697 0.129072 0.08167099 0.126524 0.08736896 0.127887 0.122503 0.122529 0.08736896 0.127887 0.08996897 0.114099 0.06213498 0.115381 0.08996897 0.114099 0.08736896 0.127887 0.07150197 0.125764 0.07063496 0.123632 0.08167099 0.126524 0.08484697 0.129072 0.07150197 0.125764 0.08167099 0.126524 0.07043898 0.127053 0.07150197 0.125764 0.08484697 0.129072 0.08386498 0.1303279 0.08484697 0.129072 0.09845095 0.131925 0.08386498 0.1303279 0.07043898 0.127053 0.08484697 0.129072 0.09755998 0.133149 0.09845095 0.131925 0.112342 0.134196 0.09755998 0.133149 0.08386498 0.1303279 0.09845095 0.131925 0.111558 0.135388 0.112342 0.134196 0.126545 0.1357139 0.111558 0.135388 0.09755998 0.133149 0.112342 0.134196 0.125889 0.136871 0.126545 0.1357139 0.1410509 0.136189 0.125889 0.136871 0.111558 0.135388 0.126545 0.1357139 0.125889 0.136871 0.1410509 0.136189 0.1409389 0.136492 0.147531 0.1347129 0.1409389 0.136492 0.1410509 0.136189 0.1405529 0.137305 0.125889 0.136871 0.1409389 0.136492 0.150231 0.136089 0.1405529 0.137305 0.1409389 0.136492 0.147531 0.1347129 0.150231 0.136089 0.1409389 0.136492 0.06926095 0.127834 0.07043898 0.127053 0.08386498 0.1303279 0.08276796 0.131119 0.08386498 0.1303279 0.09755998 0.133149 0.08276796 0.131119 0.06926095 0.127834 0.08386498 0.1303279 0.09655296 0.133952 0.09755998 0.133149 0.111558 0.135388 0.09655296 0.133952 0.08276796 0.131119 0.09755998 0.133149 0.110656 0.136205 0.111558 0.135388 0.125889 0.136871 0.110656 0.136205 0.09655296 0.133952 0.111558 0.135388 0.125116 0.137703 0.125889 0.136871 0.1405529 0.137305 0.125116 0.137703 0.110656 0.136205 0.125889 0.136871 0.125116 0.137703 0.1405529 0.137305 0.140258 0.137764 0.150231 0.136089 0.140258 0.137764 0.1405529 0.137305 0.1399379 0.1381469 0.125116 0.137703 0.140258 0.137764 0.149687 0.137337 0.1399379 0.1381469 0.140258 0.137764 0.149687 0.137337 0.140258 0.137764 0.150231 0.136089 0.068089 0.1280249 0.06926095 0.127834 0.08276796 0.131119 0.081658 0.13137 0.08276796 0.131119 0.09655296 0.133952 0.081658 0.13137 0.068089 0.1280249 0.08276796 0.131119 0.09551495 0.134266 0.09655296 0.133952 0.110656 0.136205 0.09551495 0.134266 0.081658 0.13137 0.09655296 0.133952 0.109706 0.136586 0.110656 0.136205 0.125116 0.137703 0.109706 0.136586 0.09551495 0.134266 0.110656 0.136205 0.124277 0.138154 0.125116 0.137703 0.1399379 0.1381469 0.124277 0.138154 0.109706 0.136586 0.125116 0.137703 0.124277 0.138154 0.1399379 0.1381469 0.139421 0.138568 0.149687 0.137337 0.139421 0.138568 0.1399379 0.1381469 0.139241 0.138667 0.124277 0.138154 0.139421 0.138568 0.14898 0.13817 0.139241 0.138667 0.139421 0.138568 0.14898 0.13817 0.139421 0.138568 0.149687 0.137337 0.07192498 0.128894 0.068089 0.1280249 0.081658 0.13137 0.06287997 0.126442 0.06216984 0.126241 0.068089 0.1280249 0.07192498 0.128894 0.06287997 0.126442 0.068089 0.1280249 0.08081001 0.131097 0.081658 0.13137 0.09551495 0.134266 0.08081001 0.131097 0.07192498 0.128894 0.081658 0.13137 0.09805595 0.134725 0.09551495 0.134266 0.109706 0.136586 0.08949899 0.133034 0.08081001 0.131097 0.09551495 0.134266 0.09805595 0.134725 0.08949899 0.133034 0.09551495 0.134266 0.110869 0.136795 0.109706 0.136586 0.124277 0.138154 0.106506 0.136158 0.09805595 0.134725 0.109706 0.136586 0.110869 0.136795 0.106506 0.136158 0.109706 0.136586 0.130809 0.138667 0.124277 0.138154 0.139241 0.138667 0.114799 0.137305 0.110869 0.136795 0.124277 0.138154 0.122904 0.138149 0.114799 0.137305 0.124277 0.138154 0.130809 0.138667 0.122904 0.138149 0.124277 0.138154 0.130809 0.138667 0.139241 0.138667 0.138502 0.1388379 0.14898 0.13817 0.138502 0.1388379 0.139241 0.138667 0.1370519 0.138414 0.130809 0.138667 0.138502 0.1388379 0.147149 0.138588 0.138502 0.1388379 0.14898 0.13817 0.1448619 0.138742 0.138502 0.1388379 0.147149 0.138588 0.1370519 0.138414 0.138502 0.1388379 0.1448619 0.138742 0.074651 0.124715 0.06216984 0.126241 0.06287997 0.126442 0.05321484 0.122155 0.06216984 0.126241 0.074651 0.124715 0.083485 0.128686 0.06287997 0.126442 0.07192498 0.128894 0.074651 0.124715 0.06287997 0.126442 0.083485 0.128686 0.083485 0.128686 0.07192498 0.128894 0.08081001 0.131097 0.09255999 0.132042 0.08081001 0.131097 0.08949899 0.133034 0.083485 0.128686 0.08081001 0.131097 0.09255999 0.132042 0.09255999 0.132042 0.08949899 0.133034 0.09805595 0.134725 0.101733 0.134754 0.09805595 0.134725 0.106506 0.136158 0.09255999 0.132042 0.09805595 0.134725 0.101733 0.134754 0.101733 0.134754 0.106506 0.136158 0.110869 0.136795 0.120984 0.135851 0.110869 0.136795 0.114799 0.137305 0.120984 0.135851 0.101733 0.134754 0.110869 0.136795 0.129067 0.1374509 0.114799 0.137305 0.122904 0.138149 0.129067 0.1374509 0.120984 0.135851 0.114799 0.137305 0.1370519 0.138414 0.122904 0.138149 0.130809 0.138667 0.1370519 0.138414 0.129067 0.1374509 0.122904 0.138149 0.159747 0.133608 0.159632 0.1350859 0.150231 0.136089 0.149687 0.137337 0.150231 0.136089 0.159632 0.1350859 0.155301 0.134131 0.159747 0.133608 0.150231 0.136089 0.15375 0.13428 0.155301 0.134131 0.150231 0.136089 0.147531 0.1347129 0.15375 0.13428 0.150231 0.136089 0.1656 0.132688 0.169061 0.133442 0.159632 0.1350859 0.159219 0.13631 0.159632 0.1350859 0.169061 0.133442 0.159747 0.133608 0.1656 0.132688 0.159632 0.1350859 0.159219 0.13631 0.149687 0.137337 0.159632 0.1350859 0.176847 0.130152 0.178416 0.131108 0.169061 0.133442 0.168779 0.13464 0.169061 0.133442 0.178416 0.131108 0.171394 0.131516 0.176847 0.130152 0.169061 0.133442 0.1656 0.132688 0.171394 0.131516 0.169061 0.133442 0.168779 0.13464 0.159219 0.13631 0.169061 0.133442 0.187195 0.126782 0.187582 0.128037 0.178416 0.131108 0.178265 0.132279 0.178416 0.131108 0.187582 0.128037 0.182299 0.128509 0.187195 0.126782 0.178416 0.131108 0.176847 0.130152 0.182299 0.128509 0.178416 0.131108 0.178265 0.132279 0.168779 0.13464 0.178416 0.131108 0.1933079 0.124249 0.196416 0.124202 0.187582 0.128037 0.187565 0.129179 0.187582 0.128037 0.196416 0.124202 0.191779 0.1249279 0.1933079 0.124249 0.187582 0.128037 0.187195 0.126782 0.191779 0.1249279 0.187582 0.128037 0.187565 0.129179 0.178265 0.132279 0.187582 0.128037 0.202718 0.119322 0.204759 0.119588 0.196416 0.124202 0.196537 0.12531 0.196416 0.124202 0.204759 0.119588 0.196875 0.122519 0.202718 0.119322 0.196416 0.124202 0.1933079 0.124249 0.196875 0.122519 0.196416 0.124202 0.196537 0.12531 0.187565 0.129179 0.196416 0.124202 0.208124 0.115811 0.212454 0.114187 0.204759 0.119588 0.205026 0.120652 0.204759 0.119588 0.212454 0.114187 0.202718 0.119322 0.208124 0.115811 0.204759 0.119588 0.205026 0.120652 0.196537 0.12531 0.204759 0.119588 0.217158 0.10835 0.219337 0.108049 0.212454 0.114187 0.2128739 0.115193 0.212454 0.114187 0.219337 0.108049 0.212795 0.112249 0.217158 0.10835 0.212454 0.114187 0.208124 0.115811 0.212795 0.112249 0.212454 0.114187 0.2128739 0.115193 0.205026 0.120652 0.212454 0.114187 0.223713 0.101046 0.225241 0.101242 0.219337 0.108049 0.219915 0.108974 0.219337 0.108049 0.225241 0.101242 0.220746 0.104639 0.223713 0.101046 0.219337 0.108049 0.217158 0.10835 0.220746 0.104639 0.219337 0.108049 0.219915 0.108974 0.2128739 0.115193 0.219337 0.108049 0.226473 0.09712499 0.2300119 0.093849 0.225241 0.101242 0.225976 0.102056 0.225241 0.101242 0.2300119 0.093849 0.223713 0.101046 0.226473 0.09712499 0.225241 0.101242 0.225976 0.102056 0.219915 0.108974 0.225241 0.101242 0.231348 0.08779895 0.233526 0.085994 0.2300119 0.093849 0.230895 0.09451395 0.2300119 0.093849 0.233526 0.085994 0.229155 0.09255099 0.231348 0.08779895 0.2300119 0.093849 0.226473 0.09712499 0.229155 0.09255099 0.2300119 0.093849 0.230895 0.09451395 0.225976 0.102056 0.2300119 0.093849 0.232831 0.083673 0.235678 0.07781195 0.233526 0.085994 0.234533 0.08647 0.233526 0.085994 0.235678 0.07781195 0.231348 0.08779895 0.232831 0.083673 0.233526 0.085994 0.234533 0.08647 0.230895 0.09451395 0.233526 0.085994 0.23499 0.06944096 0.236407 0.06944096 0.235678 0.07781195 0.23677 0.07805997 0.235678 0.07781195 0.236407 0.06944096 0.234566 0.075836 0.23499 0.06944096 0.235678 0.07781195 0.232831 0.083673 0.234566 0.075836 0.235678 0.07781195 0.23677 0.07805997 0.234533 0.08647 0.235678 0.07781195 0.234775 0.06492197 0.236407 0.06944096 0.23499 0.06944096 0.237529 0.06944096 0.23677 0.07805997 0.236407 0.06944096 0.235562 0.06039083 0.237529 0.06944096 0.236407 0.06944096 0.234775 0.06492197 0.235562 0.06039083 0.236407 0.06944096 0.2291229 0.06944096 0.23499 0.06944096 0.234566 0.075836 0.228248 0.05966883 0.234775 0.06492197 0.23499 0.06944096 0.2291229 0.06944096 0.228248 0.05966883 0.23499 0.06944096 0.228283 0.07901799 0.234566 0.075836 0.232831 0.083673 0.228283 0.07901799 0.2291229 0.06944096 0.234566 0.075836 0.228283 0.07901799 0.232831 0.083673 0.231348 0.08779895 0.225744 0.088458 0.231348 0.08779895 0.229155 0.09255099 0.225744 0.088458 0.228283 0.07901799 0.231348 0.08779895 0.225744 0.088458 0.229155 0.09255099 0.226473 0.09712499 0.221567 0.097382 0.226473 0.09712499 0.223713 0.101046 0.221567 0.097382 0.225744 0.088458 0.226473 0.09712499 0.221567 0.097382 0.223713 0.101046 0.220746 0.104639 0.21596 0.105401 0.220746 0.104639 0.217158 0.10835 0.21596 0.105401 0.221567 0.097382 0.220746 0.104639 0.21596 0.105401 0.217158 0.10835 0.212795 0.112249 0.209133 0.112302 0.212795 0.112249 0.208124 0.115811 0.209133 0.112302 0.21596 0.105401 0.212795 0.112249 0.2013069 0.11789 0.208124 0.115811 0.202718 0.119322 0.2013069 0.11789 0.209133 0.112302 0.208124 0.115811 0.193944 0.121505 0.202718 0.119322 0.196875 0.122519 0.193944 0.121505 0.2013069 0.11789 0.202718 0.119322 0.193944 0.121505 0.196875 0.122519 0.1933079 0.124249 0.184521 0.124204 0.1933079 0.124249 0.191779 0.1249279 0.1929489 0.121888 0.193944 0.121505 0.1933079 0.124249 0.184521 0.124204 0.1929489 0.121888 0.1933079 0.124249 0.184521 0.124204 0.191779 0.1249279 0.187195 0.126782 0.169648 0.126846 0.187195 0.126782 0.182299 0.128509 0.169648 0.126846 0.184521 0.124204 0.187195 0.126782 0.15631 0.1292 0.182299 0.128509 0.176847 0.130152 0.169648 0.126846 0.182299 0.128509 0.15631 0.1292 0.15631 0.1292 0.176847 0.130152 0.171394 0.131516 0.15631 0.1292 0.171394 0.131516 0.1656 0.132688 0.15631 0.1292 0.1656 0.132688 0.159747 0.133608 0.15631 0.1292 0.159747 0.133608 0.155301 0.134131 0.122503 0.122529 0.155301 0.134131 0.15375 0.13428 0.143715 0.129154 0.155301 0.134131 0.122503 0.122529 0.154955 0.1294389 0.15631 0.1292 0.155301 0.134131 0.1492339 0.129877 0.154955 0.1294389 0.155301 0.134131 0.143715 0.129154 0.1492339 0.129877 0.155301 0.134131 0.14898 0.13817 0.149687 0.137337 0.159219 0.13631 0.15864 0.1371639 0.159219 0.13631 0.168779 0.13464 0.15864 0.1371639 0.14898 0.13817 0.159219 0.13631 0.168325 0.135506 0.168779 0.13464 0.178265 0.132279 0.168325 0.135506 0.15864 0.1371639 0.168779 0.13464 0.177936 0.13315 0.178265 0.132279 0.187565 0.129179 0.177936 0.13315 0.168325 0.135506 0.178265 0.132279 0.187361 0.130047 0.187565 0.129179 0.196537 0.12531 0.187361 0.130047 0.177936 0.13315 0.187565 0.129179 0.196461 0.126165 0.196537 0.12531 0.205026 0.120652 0.196461 0.126165 0.187361 0.130047 0.196537 0.12531 0.20508 0.121481 0.205026 0.120652 0.2128739 0.115193 0.20508 0.121481 0.196461 0.126165 0.205026 0.120652 0.213061 0.115981 0.2128739 0.115193 0.219915 0.108974 0.213061 0.115981 0.20508 0.121481 0.2128739 0.115193 0.220232 0.1097 0.219915 0.108974 0.225976 0.102056 0.220232 0.1097 0.213061 0.115981 0.219915 0.108974 0.22642 0.102694 0.225976 0.102056 0.230895 0.09451395 0.22642 0.102694 0.220232 0.1097 0.225976 0.102056 0.231456 0.09503298 0.230895 0.09451395 0.234533 0.08647 0.231456 0.09503298 0.22642 0.102694 0.230895 0.09451395 0.23519 0.08683896 0.234533 0.08647 0.23677 0.07805997 0.23519 0.08683896 0.231456 0.09503298 0.234533 0.08647 0.237489 0.07825297 0.23677 0.07805997 0.237529 0.06944096 0.237489 0.07825297 0.23519 0.08683896 0.23677 0.07805997 0.2382709 0.06944096 0.237489 0.07825297 0.237529 0.06944096 0.23665 0.06012797 0.2382709 0.06944096 0.237529 0.06944096 0.235562 0.06039083 0.23665 0.06012797 0.237529 0.06944096 0.15545 0.137889 0.14898 0.13817 0.15864 0.1371639 0.15545 0.137889 0.147149 0.138588 0.14898 0.13817 0.163312 0.136795 0.15864 0.1371639 0.168325 0.135506 0.163312 0.136795 0.15545 0.137889 0.15864 0.1371639 0.170724 0.135352 0.168325 0.135506 0.177936 0.13315 0.170724 0.135352 0.163312 0.136795 0.168325 0.135506 0.17776 0.133581 0.177936 0.13315 0.187361 0.130047 0.17776 0.133581 0.170724 0.135352 0.177936 0.13315 0.190703 0.129144 0.187361 0.130047 0.196461 0.126165 0.184378 0.131519 0.17776 0.133581 0.187361 0.130047 0.190703 0.129144 0.184378 0.131519 0.187361 0.130047 0.196716 0.126467 0.196461 0.126165 0.20508 0.121481 0.196716 0.126467 0.190703 0.129144 0.196461 0.126165 0.207229 0.120582 0.20508 0.121481 0.213061 0.115981 0.200498 0.124545 0.196716 0.126467 0.20508 0.121481 0.2022359 0.123592 0.200498 0.124545 0.20508 0.121481 0.207229 0.120582 0.2022359 0.123592 0.20508 0.121481 0.2158139 0.114251 0.213061 0.115981 0.220232 0.1097 0.211758 0.1174499 0.207229 0.120582 0.213061 0.115981 0.2158139 0.114251 0.211758 0.1174499 0.213061 0.115981 0.222889 0.107473 0.220232 0.1097 0.22642 0.102694 0.222889 0.107473 0.2158139 0.114251 0.220232 0.1097 0.228664 0.10021 0.22642 0.102694 0.231456 0.09503298 0.228664 0.10021 0.222889 0.107473 0.22642 0.102694 0.233066 0.09268999 0.231456 0.09503298 0.23519 0.08683896 0.233066 0.09268999 0.228664 0.10021 0.231456 0.09503298 0.236147 0.08503395 0.23519 0.08683896 0.237489 0.07825297 0.236147 0.08503395 0.233066 0.09268999 0.23519 0.08683896 0.237984 0.07722198 0.237489 0.07825297 0.2382709 0.06944096 0.237984 0.07722198 0.236147 0.08503395 0.237489 0.07825297 0.238584 0.06944096 0.237984 0.07722198 0.2382709 0.06944096 0.237367 0.05992382 0.238584 0.06944096 0.2382709 0.06944096 0.23665 0.06012797 0.237367 0.05992382 0.2382709 0.06944096 0.157588 0.1382949 0.147149 0.138588 0.15545 0.137889 0.149043 0.138678 0.147149 0.138588 0.157588 0.1382949 0.1448619 0.138742 0.147149 0.138588 0.149043 0.138678 0.1663089 0.137111 0.15545 0.137889 0.163312 0.136795 0.157588 0.1382949 0.15545 0.137889 0.1663089 0.137111 0.1663089 0.137111 0.163312 0.136795 0.170724 0.135352 0.175085 0.135127 0.170724 0.135352 0.17776 0.133581 0.1663089 0.137111 0.170724 0.135352 0.175085 0.135127 0.183793 0.132355 0.17776 0.133581 0.184378 0.131519 0.175085 0.135127 0.17776 0.133581 0.183793 0.132355 0.183793 0.132355 0.184378 0.131519 0.190703 0.129144 0.192299 0.128821 0.190703 0.129144 0.196716 0.126467 0.183793 0.132355 0.190703 0.129144 0.192299 0.128821 0.192299 0.128821 0.196716 0.126467 0.200498 0.124545 0.203479 0.12651 0.200498 0.124545 0.2022359 0.123592 0.192299 0.128821 0.200498 0.124545 0.203479 0.12651 0.211129 0.121407 0.2022359 0.123592 0.207229 0.120582 0.203479 0.12651 0.2022359 0.123592 0.211129 0.121407 0.211129 0.121407 0.207229 0.120582 0.211758 0.1174499 0.218104 0.115537 0.211758 0.1174499 0.2158139 0.114251 0.211129 0.121407 0.211758 0.1174499 0.218104 0.115537 0.224272 0.108981 0.2158139 0.114251 0.222889 0.107473 0.218104 0.115537 0.2158139 0.114251 0.224272 0.108981 0.229512 0.1018339 0.222889 0.107473 0.228664 0.10021 0.224272 0.108981 0.222889 0.107473 0.229512 0.1018339 0.233718 0.09419697 0.228664 0.10021 0.233066 0.09268999 0.229512 0.1018339 0.228664 0.10021 0.233718 0.09419697 0.236799 0.086178 0.233066 0.09268999 0.236147 0.08503395 0.233718 0.09419697 0.233066 0.09268999 0.236799 0.086178 0.238682 0.07788795 0.236147 0.08503395 0.237984 0.07722198 0.236799 0.086178 0.236147 0.08503395 0.238682 0.07788795 0.238682 0.07788795 0.237984 0.07722198 0.238584 0.06944096 0.238682 0.07788795 0.238584 0.06944096 0.239318 0.06944096 0.238039 0.06200796 0.239318 0.06944096 0.238584 0.06944096 0.237367 0.05992382 0.238039 0.06200796 0.238584 0.06944096 0.24037 0.07542997 0.239318 0.06944096 0.24063 0.06944096 0.238682 0.06097698 0.24063 0.06944096 0.239318 0.06944096 0.240154 0.08147096 0.24037 0.07542997 0.24063 0.06944096 0.238682 0.06097698 0.24037 0.063452 0.24063 0.06944096 0.241203 0.06944096 0.24063 0.06944096 0.24037 0.063452 0.240154 0.08147096 0.24063 0.06944096 0.241203 0.06944096 0.24037 0.07542997 0.238682 0.07788795 0.239318 0.06944096 0.238039 0.06200796 0.238682 0.06097698 0.239318 0.06944096 0.239589 0.08137696 0.236799 0.086178 0.238682 0.07788795 0.24037 0.07542997 0.239589 0.08137696 0.238682 0.07788795 0.236492 0.09296798 0.233718 0.09419697 0.236799 0.086178 0.238294 0.08723896 0.236492 0.09296798 0.236799 0.086178 0.239589 0.08137696 0.238294 0.08723896 0.236799 0.086178 0.234198 0.09851998 0.229512 0.1018339 0.233718 0.09419697 0.236492 0.09296798 0.234198 0.09851998 0.233718 0.09419697 0.231429 0.103851 0.224272 0.108981 0.229512 0.1018339 0.234198 0.09851998 0.231429 0.103851 0.229512 0.1018339 0.224552 0.113687 0.218104 0.115537 0.224272 0.108981 0.228205 0.10892 0.224552 0.113687 0.224272 0.108981 0.231429 0.103851 0.228205 0.10892 0.224272 0.108981 0.220498 0.118117 0.211129 0.121407 0.218104 0.115537 0.224552 0.113687 0.220498 0.118117 0.218104 0.115537 0.211306 0.125838 0.203479 0.12651 0.211129 0.121407 0.216072 0.122177 0.211306 0.125838 0.211129 0.121407 0.220498 0.118117 0.216072 0.122177 0.211129 0.121407 0.206236 0.12907 0.195296 0.130773 0.203479 0.12651 0.192299 0.128821 0.203479 0.12651 0.195296 0.130773 0.211306 0.125838 0.206236 0.12907 0.203479 0.12651 0.2009 0.131848 0.1867229 0.134139 0.195296 0.130773 0.183793 0.132355 0.195296 0.130773 0.1867229 0.134139 0.206236 0.12907 0.2009 0.131848 0.195296 0.130773 0.183793 0.132355 0.192299 0.128821 0.195296 0.130773 0.189602 0.13596 0.177907 0.136564 0.1867229 0.134139 0.175085 0.135127 0.1867229 0.134139 0.177907 0.136564 0.195341 0.134151 0.189602 0.13596 0.1867229 0.134139 0.2009 0.131848 0.195341 0.134151 0.1867229 0.134139 0.175085 0.135127 0.183793 0.132355 0.1867229 0.134139 0.183728 0.137261 0.1689929 0.138021 0.177907 0.136564 0.1663089 0.137111 0.177907 0.136564 0.1689929 0.138021 0.189602 0.13596 0.183728 0.137261 0.177907 0.136564 0.1663089 0.137111 0.175085 0.135127 0.177907 0.136564 0.171764 0.138307 0.160129 0.138501 0.1689929 0.138021 0.157588 0.1382949 0.1689929 0.138021 0.160129 0.138501 0.177767 0.138045 0.171764 0.138307 0.1689929 0.138021 0.183728 0.137261 0.177767 0.138045 0.1689929 0.138021 0.157588 0.1382949 0.1663089 0.137111 0.1689929 0.138021 0.1657609 0.138045 0.160129 0.138501 0.171764 0.138307 0.157917 0.138537 0.157588 0.1382949 0.160129 0.138501 0.1657609 0.138045 0.157917 0.138537 0.160129 0.138501 0.171639 0.138878 0.171764 0.138307 0.177767 0.138045 0.171639 0.138878 0.1657609 0.138045 0.171764 0.138307 0.1836979 0.137847 0.177767 0.138045 0.183728 0.137261 0.1836979 0.137847 0.171639 0.138878 0.177767 0.138045 0.1836979 0.137847 0.183728 0.137261 0.189602 0.13596 0.195416 0.134732 0.189602 0.13596 0.195341 0.134151 0.195416 0.134732 0.1836979 0.137847 0.189602 0.13596 0.195416 0.134732 0.195341 0.134151 0.2009 0.131848 0.206436 0.129615 0.2009 0.131848 0.206236 0.12907 0.206436 0.129615 0.195416 0.134732 0.2009 0.131848 0.211567 0.126354 0.206236 0.12907 0.211306 0.125838 0.211567 0.126354 0.206436 0.129615 0.206236 0.12907 0.2164109 0.12264 0.211306 0.125838 0.216072 0.122177 0.2164109 0.12264 0.211567 0.126354 0.211306 0.125838 0.220896 0.118528 0.216072 0.122177 0.220498 0.118117 0.220896 0.118528 0.2164109 0.12264 0.216072 0.122177 0.220896 0.118528 0.220498 0.118117 0.224552 0.113687 0.2250159 0.114023 0.224552 0.113687 0.228205 0.10892 0.2250159 0.114023 0.220896 0.118528 0.224552 0.113687 0.231928 0.104134 0.228205 0.10892 0.231429 0.103851 0.231928 0.104134 0.2250159 0.114023 0.228205 0.10892 0.231928 0.104134 0.231429 0.103851 0.234198 0.09851998 0.23703 0.093167 0.234198 0.09851998 0.236492 0.09296798 0.23703 0.093167 0.231928 0.104134 0.234198 0.09851998 0.23703 0.093167 0.236492 0.09296798 0.238294 0.08723896 0.23703 0.093167 0.238294 0.08723896 0.239589 0.08137696 0.240154 0.08147096 0.239589 0.08137696 0.24037 0.07542997 0.240154 0.08147096 0.23703 0.093167 0.239589 0.08137696 0.157917 0.138537 0.149043 0.138678 0.157588 0.1382949 0.15062 0.1382099 0.149043 0.138678 0.157917 0.138537 0.15062 0.1382099 0.1448619 0.138742 0.149043 0.138678 0.15062 0.1382099 0.157917 0.138537 0.1657609 0.138045 0.15062 0.1382099 0.1370519 0.138414 0.1448619 0.138742 0.238682 0.06097698 0.239589 0.05750387 0.24037 0.063452 0.241203 0.06944096 0.24037 0.063452 0.239589 0.05750387 0.2368 0.05263996 0.238294 0.05164295 0.239589 0.05750387 0.240146 0.05736196 0.239589 0.05750387 0.238294 0.05164295 0.238682 0.06097698 0.2368 0.05263996 0.239589 0.05750387 0.240146 0.05736196 0.241203 0.06944096 0.239589 0.05750387 0.23372 0.04455399 0.236492 0.04591399 0.238294 0.05164295 0.240146 0.05736196 0.238294 0.05164295 0.236492 0.04591399 0.2368 0.05263996 0.23372 0.04455399 0.238294 0.05164295 0.23372 0.04455399 0.234198 0.04036086 0.236492 0.04591399 0.2370139 0.04567188 0.236492 0.04591399 0.234198 0.04036086 0.2370139 0.04567188 0.240146 0.05736196 0.236492 0.04591399 0.229515 0.03683882 0.231429 0.03503096 0.234198 0.04036086 0.2370139 0.04567188 0.234198 0.04036086 0.231429 0.03503096 0.23372 0.04455399 0.229515 0.03683882 0.234198 0.04036086 0.224277 0.02960985 0.228205 0.029962 0.231429 0.03503096 0.231908 0.03471696 0.231429 0.03503096 0.228205 0.029962 0.229515 0.03683882 0.224277 0.02960985 0.231429 0.03503096 0.231908 0.03471696 0.2370139 0.04567188 0.231429 0.03503096 0.218112 0.02297896 0.224552 0.025195 0.228205 0.029962 0.231908 0.03471696 0.228205 0.029962 0.224552 0.025195 0.224277 0.02960985 0.218112 0.02297896 0.228205 0.029962 0.218112 0.02297896 0.220498 0.02076482 0.224552 0.025195 0.224985 0.02481997 0.224552 0.025195 0.220498 0.02076482 0.224985 0.02481997 0.231908 0.03471696 0.224552 0.025195 0.211141 0.017048 0.216072 0.01670396 0.220498 0.02076482 0.216449 0.01627296 0.220498 0.02076482 0.216072 0.01670396 0.218112 0.02297896 0.211141 0.017048 0.220498 0.02076482 0.216449 0.01627296 0.224985 0.02481997 0.220498 0.02076482 0.2034969 0.01190698 0.211306 0.01304394 0.216072 0.01670396 0.216449 0.01627296 0.216072 0.01670396 0.211306 0.01304394 0.211141 0.017048 0.2034969 0.01190698 0.216072 0.01670396 0.2034969 0.01190698 0.206236 0.009811997 0.211306 0.01304394 0.206551 0.009332954 0.211306 0.01304394 0.206236 0.009811997 0.206551 0.009332954 0.216449 0.01627296 0.211306 0.01304394 0.1953189 0.007638931 0.2009 0.00703299 0.206236 0.009811997 0.206551 0.009332954 0.206236 0.009811997 0.2009 0.00703299 0.2034969 0.01190698 0.1953189 0.007638931 0.206236 0.009811997 0.186754 0.004307985 0.195341 0.004729986 0.2009 0.00703299 0.1955839 0.004209995 0.2009 0.00703299 0.195341 0.004729986 0.1953189 0.007638931 0.186754 0.004307985 0.2009 0.00703299 0.1955839 0.004209995 0.206551 0.009332954 0.2009 0.00703299 0.177946 0.001966953 0.189602 0.002921998 0.195341 0.004729986 0.1955839 0.004209995 0.195341 0.004729986 0.189602 0.002921998 0.186754 0.004307985 0.177946 0.001966953 0.195341 0.004729986 0.177946 0.001966953 0.183728 0.001619935 0.189602 0.002921998 0.183872 0.001063883 0.189602 0.002921998 0.183728 0.001619935 0.183872 0.001063883 0.1955839 0.004209995 0.189602 0.002921998 0.169041 6.52e-4 0.177767 8.37e-4 0.183728 0.001619935 0.183872 0.001063883 0.183728 0.001619935 0.177767 8.37e-4 0.177946 0.001966953 0.169041 6.52e-4 0.183728 0.001619935 0.160176 3.81e-4 0.171764 5.75e-4 0.177767 8.37e-4 0.183872 0.001063883 0.177767 8.37e-4 0.171764 5.75e-4 0.169041 6.52e-4 0.160176 3.81e-4 0.177767 8.37e-4 0.15013 7.17e-4 0.171764 5.75e-4 0.160176 3.81e-4 0.171764 2e-6 0.183872 0.001063883 0.171764 5.75e-4 0.1657249 8.4e-4 0.171764 2e-6 0.171764 5.75e-4 0.15013 7.17e-4 0.1657249 8.4e-4 0.171764 5.75e-4 0.1579059 3.44e-4 0.160176 3.81e-4 0.169041 6.52e-4 0.15013 7.17e-4 0.160176 3.81e-4 0.1579059 3.44e-4 0.166357 0.001238942 0.169041 6.52e-4 0.177946 0.001966953 0.149143 2.05e-4 0.1579059 3.44e-4 0.169041 6.52e-4 0.157667 2.8e-4 0.149143 2.05e-4 0.169041 6.52e-4 0.166357 0.001238942 0.157667 2.8e-4 0.169041 6.52e-4 0.175104 0.003074944 0.177946 0.001966953 0.186754 0.004307985 0.175104 0.003074944 0.166357 0.001238942 0.177946 0.001966953 0.183784 0.005762994 0.186754 0.004307985 0.1953189 0.007638931 0.183784 0.005762994 0.175104 0.003074944 0.186754 0.004307985 0.192265 0.009267985 0.1953189 0.007638931 0.2034969 0.01190698 0.192265 0.009267985 0.183784 0.005762994 0.1953189 0.007638931 0.20041 0.01354295 0.2034969 0.01190698 0.211141 0.017048 0.20041 0.01354295 0.192265 0.009267985 0.2034969 0.01190698 0.205696 0.01663899 0.211141 0.017048 0.218112 0.02297896 0.205696 0.01663899 0.20041 0.01354295 0.211141 0.017048 0.214779 0.02321696 0.218112 0.02297896 0.224277 0.02960985 0.210449 0.01985597 0.205696 0.01663899 0.218112 0.02297896 0.214779 0.02321696 0.210449 0.01985597 0.218112 0.02297896 0.222182 0.030227 0.224277 0.02960985 0.229515 0.03683882 0.222182 0.030227 0.214779 0.02321696 0.224277 0.02960985 0.228491 0.03814399 0.229515 0.03683882 0.23372 0.04455399 0.228491 0.03814399 0.222182 0.030227 0.229515 0.03683882 0.23319 0.04628795 0.23372 0.04455399 0.2368 0.05263996 0.23319 0.04628795 0.228491 0.03814399 0.23372 0.04455399 0.2363 0.05426883 0.2368 0.05263996 0.238682 0.06097698 0.2363 0.05426883 0.23319 0.04628795 0.2368 0.05263996 0.238039 0.06200796 0.2363 0.05426883 0.238682 0.06097698 0.136524 5.14e-4 0.1579059 3.44e-4 0.149143 2.05e-4 0.15013 7.17e-4 0.1579059 3.44e-4 0.136524 5.14e-4 0.144857 1.39e-4 0.149143 2.05e-4 0.157667 2.8e-4 0.136524 5.14e-4 0.149143 2.05e-4 0.144857 1.39e-4 0.154397 4.07e-4 0.157667 2.8e-4 0.166357 0.001238942 0.138659 4.6e-5 0.144857 1.39e-4 0.157667 2.8e-4 0.146638 0 0.138659 4.6e-5 0.157667 2.8e-4 0.154397 4.07e-4 0.146638 0 0.157667 2.8e-4 0.161866 0.001230955 0.166357 0.001238942 0.175104 0.003074944 0.161866 0.001230955 0.154397 4.07e-4 0.166357 0.001238942 0.1758649 0.003995895 0.175104 0.003074944 0.183784 0.005762994 0.168994 0.002430975 0.161866 0.001230955 0.175104 0.003074944 0.1758649 0.003995895 0.168994 0.002430975 0.175104 0.003074944 0.182451 0.005904972 0.183784 0.005762994 0.192265 0.009267985 0.182451 0.005904972 0.1758649 0.003995895 0.183784 0.005762994 0.19477 0.01070886 0.192265 0.009267985 0.20041 0.01354295 0.18874 0.008139967 0.182451 0.005904972 0.192265 0.009267985 0.19477 0.01070886 0.18874 0.008139967 0.192265 0.009267985 0.200633 0.01409184 0.20041 0.01354295 0.205696 0.01663899 0.191035 0.009468972 0.19477 0.01070886 0.20041 0.01354295 0.200633 0.01409184 0.191035 0.009468972 0.20041 0.01354295 0.209578 0.01969099 0.205696 0.01663899 0.210449 0.01985597 0.209578 0.01969099 0.200633 0.01409184 0.205696 0.01663899 0.209578 0.01969099 0.210449 0.01985597 0.214779 0.02321696 0.217663 0.02623695 0.214779 0.02321696 0.222182 0.030227 0.217663 0.02623695 0.209578 0.01969099 0.214779 0.02321696 0.2246789 0.03365695 0.222182 0.030227 0.228491 0.03814399 0.2246789 0.03365695 0.217663 0.02623695 0.222182 0.030227 0.230427 0.04183799 0.228491 0.03814399 0.23319 0.04628795 0.230427 0.04183799 0.2246789 0.03365695 0.228491 0.03814399 0.23471 0.05065596 0.23319 0.04628795 0.2363 0.05426883 0.23471 0.05065596 0.230427 0.04183799 0.23319 0.04628795 0.237367 0.05992382 0.2363 0.05426883 0.238039 0.06200796 0.237367 0.05992382 0.23471 0.05065596 0.2363 0.05426883 0.129814 2.64e-4 0.144857 1.39e-4 0.138659 4.6e-5 0.129814 2.64e-4 0.136524 5.14e-4 0.144857 1.39e-4 0.139481 2.61e-4 0.138659 4.6e-5 0.146638 0 0.138616 4.5e-5 0.129814 2.64e-4 0.138659 4.6e-5 0.139481 2.61e-4 0.138616 4.5e-5 0.138659 4.6e-5 0.149782 3.99e-4 0.146638 0 0.154397 4.07e-4 0.149782 3.99e-4 0.139481 2.61e-4 0.146638 0 0.160209 0.001334965 0.154397 4.07e-4 0.161866 0.001230955 0.160209 0.001334965 0.149782 3.99e-4 0.154397 4.07e-4 0.160209 0.001334965 0.161866 0.001230955 0.168994 0.002430975 0.170652 0.003123939 0.168994 0.002430975 0.1758649 0.003995895 0.170652 0.003123939 0.160209 0.001334965 0.168994 0.002430975 0.180981 0.005820989 0.1758649 0.003995895 0.182451 0.005904972 0.180981 0.005820989 0.170652 0.003123939 0.1758649 0.003995895 0.180981 0.005820989 0.182451 0.005904972 0.18874 0.008139967 0.191035 0.009468972 0.18874 0.008139967 0.19477 0.01070886 0.191035 0.009468972 0.180981 0.005820989 0.18874 0.008139967 0.237049 0.06944096 0.241203 0.06944096 0.240146 0.05736196 0.236051 0.08082097 0.240154 0.08147096 0.241203 0.06944096 0.236796 0.07517296 0.236051 0.08082097 0.241203 0.06944096 0.237049 0.06944096 0.236796 0.07517296 0.241203 0.06944096 0.233123 0.04712986 0.240146 0.05736196 0.2370139 0.04567188 0.236062 0.05812788 0.237049 0.06944096 0.240146 0.05736196 0.233123 0.04712986 0.236062 0.05812788 0.240146 0.05736196 0.2283239 0.03681695 0.2370139 0.04567188 0.231908 0.03471696 0.2283239 0.03681695 0.233123 0.04712986 0.2370139 0.04567188 0.221826 0.02752184 0.231908 0.03471696 0.224985 0.02481997 0.221826 0.02752184 0.2283239 0.03681695 0.231908 0.03471696 0.217956 0.02329099 0.224985 0.02481997 0.216449 0.01627296 0.217956 0.02329099 0.221826 0.02752184 0.224985 0.02481997 0.209187 0.015935 0.216449 0.01627296 0.206551 0.009332954 0.213741 0.019427 0.217956 0.02329099 0.216449 0.01627296 0.209187 0.015935 0.213741 0.019427 0.216449 0.01627296 0.194005 0.008056998 0.206551 0.009332954 0.1955839 0.004209995 0.204364 0.012869 0.209187 0.015935 0.206551 0.009332954 0.194005 0.008056998 0.204364 0.012869 0.206551 0.009332954 0.171657 0.004156947 0.1955839 0.004209995 0.183872 0.001063883 0.18299 0.005127966 0.194005 0.008056998 0.1955839 0.004209995 0.171657 0.004156947 0.18299 0.005127966 0.1955839 0.004209995 0.159657 0.001063883 0.183872 0.001063883 0.171764 2e-6 0.159657 0.001063883 0.147944 0.004209995 0.183872 0.001063883 0.171657 0.004156947 0.183872 0.001063883 0.147944 0.004209995 0.1657249 8.4e-4 0.159657 0.001063883 0.171764 2e-6 0.159601 0.137807 0.1597999 0.137261 0.1657609 0.138045 0.15062 0.1382099 0.1657609 0.138045 0.1597999 0.137261 0.171639 0.138878 0.159601 0.137807 0.1657609 0.138045 0.159601 0.137807 0.153926 0.13596 0.1597999 0.137261 0.14326 0.137242 0.1597999 0.137261 0.153926 0.13596 0.14326 0.137242 0.15062 0.1382099 0.1597999 0.137261 0.14794 0.13467 0.148187 0.134151 0.153926 0.13596 0.135911 0.135633 0.153926 0.13596 0.148187 0.134151 0.159601 0.137807 0.14794 0.13467 0.153926 0.13596 0.135911 0.135633 0.14326 0.137242 0.153926 0.13596 0.14794 0.13467 0.142628 0.131848 0.148187 0.134151 0.128653 0.133394 0.148187 0.134151 0.142628 0.131848 0.128653 0.133394 0.135911 0.135633 0.148187 0.134151 0.136999 0.129562 0.137293 0.12907 0.142628 0.131848 0.1215659 0.130541 0.142628 0.131848 0.137293 0.12907 0.14794 0.13467 0.136999 0.129562 0.142628 0.131848 0.1215659 0.130541 0.128653 0.133394 0.142628 0.131848 0.136999 0.129562 0.1322219 0.125838 0.137293 0.12907 0.114733 0.127099 0.137293 0.12907 0.1322219 0.125838 0.114733 0.127099 0.1215659 0.130541 0.137293 0.12907 0.127099 0.122625 0.127456 0.122178 0.1322219 0.125838 0.108235 0.123097 0.1322219 0.125838 0.127456 0.122178 0.136999 0.129562 0.127099 0.122625 0.1322219 0.125838 0.108235 0.123097 0.114733 0.127099 0.1322219 0.125838 0.118542 0.11406 0.12303 0.118117 0.127456 0.122178 0.108235 0.123097 0.127456 0.122178 0.12303 0.118117 0.127099 0.122625 0.118542 0.11406 0.127456 0.122178 0.118542 0.11406 0.1189759 0.113687 0.12303 0.118117 0.102154 0.118574 0.12303 0.118117 0.1189759 0.113687 0.102154 0.118574 0.108235 0.123097 0.12303 0.118117 0.111647 0.104215 0.115323 0.10892 0.1189759 0.113687 0.09656697 0.11357 0.1189759 0.113687 0.115323 0.10892 0.118542 0.11406 0.111647 0.104215 0.1189759 0.113687 0.09656697 0.11357 0.102154 0.118574 0.1189759 0.113687 0.111647 0.104215 0.1121 0.103851 0.115323 0.10892 0.09154695 0.108133 0.115323 0.10892 0.1121 0.103851 0.09154695 0.108133 0.09656697 0.11357 0.115323 0.10892 0.106534 0.09326398 0.1093299 0.09851998 0.1121 0.103851 0.08716398 0.102313 0.1121 0.103851 0.1093299 0.09851998 0.111647 0.104215 0.106534 0.09326398 0.1121 0.103851 0.08716398 0.102313 0.09154695 0.108133 0.1121 0.103851 0.106534 0.09326398 0.107036 0.09296798 0.1093299 0.09851998 0.08347696 0.096165 0.1093299 0.09851998 0.107036 0.09296798 0.08347696 0.096165 0.08716398 0.102313 0.1093299 0.09851998 0.103386 0.08154296 0.105234 0.08723896 0.107036 0.09296798 0.08054399 0.08974397 0.107036 0.09296798 0.105234 0.08723896 0.106534 0.09326398 0.103386 0.08154296 0.107036 0.09296798 0.08054399 0.08974397 0.08347696 0.096165 0.107036 0.09296798 0.103386 0.08154296 0.1039389 0.08137696 0.105234 0.08723896 0.07840895 0.08310997 0.105234 0.08723896 0.1039389 0.08137696 0.07840895 0.08310997 0.08054399 0.08974397 0.105234 0.08723896 0.102594 0.07553696 0.103159 0.07542997 0.1039389 0.08137696 0.07710999 0.07632195 0.1039389 0.08137696 0.103159 0.07542997 0.103386 0.08154296 0.102594 0.07553696 0.1039389 0.08137696 0.07710999 0.07632195 0.07840895 0.08310997 0.1039389 0.08137696 0.102325 0.06944096 0.102898 0.06944096 0.103159 0.07542997 0.07710999 0.07632195 0.103159 0.07542997 0.102898 0.06944096 0.102594 0.07553696 0.102325 0.06944096 0.103159 0.07542997 0.103382 0.05736196 0.102898 0.06944096 0.102325 0.06944096 0.1031579 0.06345599 0.102898 0.06944096 0.103382 0.05736196 0.07667195 0.06944096 0.102898 0.06944096 0.1031579 0.06345599 0.07710999 0.07632195 0.102898 0.06944096 0.07667195 0.06944096 0.106479 0.06944096 0.102325 0.06944096 0.102594 0.07553696 0.107478 0.05805999 0.103382 0.05736196 0.102325 0.06944096 0.106732 0.063708 0.102325 0.06944096 0.106479 0.06944096 0.106732 0.063708 0.107478 0.05805999 0.102325 0.06944096 0.107466 0.08075398 0.102594 0.07553696 0.103386 0.08154296 0.107466 0.08075398 0.106479 0.06944096 0.102594 0.07553696 0.110405 0.09175097 0.103386 0.08154296 0.106534 0.09326398 0.110405 0.09175097 0.107466 0.08075398 0.103386 0.08154296 0.115205 0.102065 0.106534 0.09326398 0.111647 0.104215 0.115205 0.102065 0.110405 0.09175097 0.106534 0.09326398 0.121702 0.111359 0.111647 0.104215 0.118542 0.11406 0.121702 0.111359 0.115205 0.102065 0.111647 0.104215 0.125572 0.11559 0.118542 0.11406 0.127099 0.122625 0.125572 0.11559 0.121702 0.111359 0.118542 0.11406 0.134341 0.122947 0.127099 0.122625 0.136999 0.129562 0.129787 0.119454 0.125572 0.11559 0.127099 0.122625 0.134341 0.122947 0.129787 0.119454 0.127099 0.122625 0.149523 0.130824 0.136999 0.129562 0.14794 0.13467 0.139165 0.126013 0.134341 0.122947 0.136999 0.129562 0.149523 0.130824 0.139165 0.126013 0.136999 0.129562 0.171871 0.134724 0.14794 0.13467 0.159601 0.137807 0.160538 0.133753 0.149523 0.130824 0.14794 0.13467 0.171871 0.134724 0.160538 0.133753 0.14794 0.13467 0.1836979 0.137847 0.159601 0.137807 0.171639 0.138878 0.195416 0.134732 0.159601 0.137807 0.1836979 0.137847 0.171871 0.134724 0.159601 0.137807 0.195416 0.134732 0.183185 0.133719 0.195416 0.134732 0.206436 0.129615 0.183185 0.133719 0.171871 0.134724 0.195416 0.134732 0.194148 0.130773 0.206436 0.129615 0.211567 0.126354 0.194148 0.130773 0.183185 0.133719 0.206436 0.129615 0.204435 0.125972 0.211567 0.126354 0.2164109 0.12264 0.204435 0.125972 0.194148 0.130773 0.211567 0.126354 0.213746 0.119451 0.2164109 0.12264 0.220896 0.118528 0.213746 0.119451 0.204435 0.125972 0.2164109 0.12264 0.213746 0.119451 0.220896 0.118528 0.2250159 0.114023 0.221789 0.111403 0.2250159 0.114023 0.231928 0.104134 0.221789 0.111403 0.213746 0.119451 0.2250159 0.114023 0.228277 0.102147 0.231928 0.104134 0.23703 0.093167 0.228277 0.102147 0.221789 0.111403 0.231928 0.104134 0.233089 0.09184497 0.23703 0.093167 0.240154 0.08147096 0.233089 0.09184497 0.228277 0.102147 0.23703 0.093167 0.236051 0.08082097 0.233089 0.09184497 0.240154 0.08147096 0.110439 0.047037 0.106514 0.04567188 0.103382 0.05736196 0.105231 0.05165499 0.103382 0.05736196 0.106514 0.04567188 0.107478 0.05805999 0.110439 0.047037 0.103382 0.05736196 0.103937 0.05751287 0.1031579 0.06345599 0.103382 0.05736196 0.105231 0.05165499 0.103937 0.05751287 0.103382 0.05736196 0.115252 0.03673487 0.11162 0.03471696 0.106514 0.04567188 0.10932 0.04038184 0.106514 0.04567188 0.11162 0.03471696 0.110439 0.047037 0.115252 0.03673487 0.106514 0.04567188 0.10703 0.04593098 0.105231 0.05165499 0.106514 0.04567188 0.10932 0.04038184 0.10703 0.04593098 0.106514 0.04567188 0.121739 0.02747792 0.118543 0.02481997 0.11162 0.03471696 0.115305 0.02998799 0.11162 0.03471696 0.118543 0.02481997 0.115252 0.03673487 0.121739 0.02747792 0.11162 0.03471696 0.1120859 0.03505384 0.10932 0.04038184 0.11162 0.03471696 0.115305 0.02998799 0.1120859 0.03505384 0.11162 0.03471696 0.129782 0.01943099 0.12708 0.01627296 0.118543 0.02481997 0.123002 0.02079182 0.118543 0.02481997 0.12708 0.01627296 0.121739 0.02747792 0.129782 0.01943099 0.118543 0.02481997 0.118953 0.025222 0.115305 0.02998799 0.118543 0.02481997 0.123002 0.02079182 0.118953 0.025222 0.118543 0.02481997 0.139093 0.01290982 0.136977 0.009332954 0.12708 0.01627296 0.13218 0.01307284 0.12708 0.01627296 0.136977 0.009332954 0.129782 0.01943099 0.139093 0.01290982 0.12708 0.01627296 0.127422 0.01673299 0.123002 0.02079182 0.12708 0.01627296 0.13218 0.01307284 0.127422 0.01673299 0.12708 0.01627296 0.160343 0.005162954 0.147944 0.004209995 0.136977 0.009332954 0.142566 0.007061958 0.136977 0.009332954 0.147944 0.004209995 0.14938 0.008108973 0.160343 0.005162954 0.136977 0.009332954 0.139093 0.01290982 0.14938 0.008108973 0.136977 0.009332954 0.1372399 0.009841978 0.13218 0.01307284 0.136977 0.009332954 0.142566 0.007061958 0.1372399 0.009841978 0.136977 0.009332954 0.153858 0.002939999 0.147944 0.004209995 0.159657 0.001063883 0.160343 0.005162954 0.171657 0.004156947 0.147944 0.004209995 0.148119 0.00475496 0.142566 0.007061958 0.147944 0.004209995 0.153858 0.002939999 0.148119 0.00475496 0.147944 0.004209995 0.15974 0.001630902 0.153858 0.002939999 0.159657 0.001063883 0.1657249 8.4e-4 0.15974 0.001630902 0.159657 0.001063883 0.109213 0.06944096 0.106479 0.06944096 0.107466 0.08075398 0.110158 0.05860096 0.106732 0.063708 0.106479 0.06944096 0.110158 0.05860096 0.106479 0.06944096 0.109213 0.06944096 0.110169 0.08034497 0.107466 0.08075398 0.110405 0.09175097 0.109455 0.074934 0.109213 0.06944096 0.107466 0.08075398 0.110169 0.08034497 0.109455 0.074934 0.107466 0.08075398 0.113007 0.09090799 0.110405 0.09175097 0.115205 0.102065 0.113007 0.09090799 0.110169 0.08034497 0.110405 0.09175097 0.117619 0.1007789 0.115205 0.102065 0.121702 0.111359 0.117619 0.1007789 0.113007 0.09090799 0.115205 0.102065 0.123836 0.109648 0.121702 0.111359 0.125572 0.11559 0.123836 0.109648 0.117619 0.1007789 0.121702 0.111359 0.131543 0.117358 0.125572 0.11559 0.129787 0.119454 0.131543 0.117358 0.123836 0.109648 0.125572 0.11559 0.131543 0.117358 0.129787 0.119454 0.134341 0.122947 0.1404629 0.123606 0.134341 0.122947 0.139165 0.126013 0.1404629 0.123606 0.131543 0.117358 0.134341 0.122947 0.1503199 0.128205 0.139165 0.126013 0.149523 0.130824 0.1503199 0.128205 0.1404629 0.123606 0.139165 0.126013 0.160822 0.1310279 0.149523 0.130824 0.160538 0.133753 0.160822 0.1310279 0.1503199 0.128205 0.149523 0.130824 0.171662 0.131991 0.160538 0.133753 0.171871 0.134724 0.171662 0.131991 0.160822 0.1310279 0.160538 0.133753 0.182519 0.131061 0.171871 0.134724 0.183185 0.133719 0.182519 0.131061 0.171662 0.131991 0.171871 0.134724 0.193072 0.128255 0.183185 0.133719 0.194148 0.130773 0.193072 0.128255 0.182519 0.131061 0.183185 0.133719 0.202996 0.123645 0.194148 0.130773 0.204435 0.125972 0.202996 0.123645 0.193072 0.128255 0.194148 0.130773 0.207617 0.120707 0.204435 0.125972 0.213746 0.119451 0.207617 0.120707 0.202996 0.123645 0.204435 0.125972 0.21602 0.11366 0.213746 0.119451 0.221789 0.111403 0.2119809 0.117362 0.207617 0.120707 0.213746 0.119451 0.21602 0.11366 0.2119809 0.117362 0.213746 0.119451 0.2197279 0.109606 0.221789 0.111403 0.228277 0.102147 0.2197279 0.109606 0.21602 0.11366 0.221789 0.111403 0.2259539 0.100701 0.228277 0.102147 0.233089 0.09184497 0.2259539 0.100701 0.2197279 0.109606 0.228277 0.102147 0.230554 0.09081798 0.233089 0.09184497 0.236051 0.08082097 0.230554 0.09081798 0.2259539 0.100701 0.233089 0.09184497 0.23337 0.08028095 0.236051 0.08082097 0.236796 0.07517296 0.23337 0.08028095 0.230554 0.09081798 0.236051 0.08082097 0.23337 0.08028095 0.236796 0.07517296 0.237049 0.06944096 0.234316 0.06944096 0.237049 0.06944096 0.236062 0.05812788 0.234316 0.06944096 0.23337 0.08028095 0.237049 0.06944096 0.233359 0.05853599 0.236062 0.05812788 0.233123 0.04712986 0.234073 0.06394797 0.234316 0.06944096 0.236062 0.05812788 0.233359 0.05853599 0.234073 0.06394797 0.236062 0.05812788 0.230521 0.04797399 0.233123 0.04712986 0.2283239 0.03681695 0.230521 0.04797399 0.233359 0.05853599 0.233123 0.04712986 0.2259089 0.03810298 0.2283239 0.03681695 0.221826 0.02752184 0.2259089 0.03810298 0.230521 0.04797399 0.2283239 0.03681695 0.219693 0.02923399 0.221826 0.02752184 0.217956 0.02329099 0.219693 0.02923399 0.2259089 0.03810298 0.221826 0.02752184 0.211986 0.02152395 0.217956 0.02329099 0.213741 0.019427 0.211986 0.02152395 0.219693 0.02923399 0.217956 0.02329099 0.211986 0.02152395 0.213741 0.019427 0.209187 0.015935 0.203065 0.01527583 0.209187 0.015935 0.204364 0.012869 0.203065 0.01527583 0.211986 0.02152395 0.209187 0.015935 0.193208 0.01067584 0.204364 0.012869 0.194005 0.008056998 0.193208 0.01067584 0.203065 0.01527583 0.204364 0.012869 0.1827059 0.007853984 0.194005 0.008056998 0.18299 0.005127966 0.1827059 0.007853984 0.193208 0.01067584 0.194005 0.008056998 0.1718659 0.006889939 0.18299 0.005127966 0.171657 0.004156947 0.1718659 0.006889939 0.1827059 0.007853984 0.18299 0.005127966 0.161009 0.007820963 0.171657 0.004156947 0.160343 0.005162954 0.161009 0.007820963 0.1718659 0.006889939 0.171657 0.004156947 0.150457 0.01062697 0.160343 0.005162954 0.14938 0.008108973 0.150457 0.01062697 0.161009 0.007820963 0.160343 0.005162954 0.140532 0.01523697 0.14938 0.008108973 0.139093 0.01290982 0.140532 0.01523697 0.150457 0.01062697 0.14938 0.008108973 0.135911 0.01817399 0.139093 0.01290982 0.129782 0.01943099 0.135911 0.01817399 0.140532 0.01523697 0.139093 0.01290982 0.1275089 0.025222 0.129782 0.01943099 0.121739 0.02747792 0.131547 0.02151983 0.135911 0.01817399 0.129782 0.01943099 0.1275089 0.025222 0.131547 0.02151983 0.129782 0.01943099 0.123801 0.02927595 0.121739 0.02747792 0.115252 0.03673487 0.123801 0.02927595 0.1275089 0.025222 0.121739 0.02747792 0.117574 0.03818082 0.115252 0.03673487 0.110439 0.047037 0.117574 0.03818082 0.123801 0.02927595 0.115252 0.03673487 0.112975 0.04806298 0.110439 0.047037 0.107478 0.05805999 0.112975 0.04806298 0.117574 0.03818082 0.110439 0.047037 0.110158 0.05860096 0.107478 0.05805999 0.106732 0.063708 0.110158 0.05860096 0.112975 0.04806298 0.107478 0.05805999 0.07716995 0.06210297 0.1031579 0.06345599 0.103937 0.05751287 0.07716995 0.06210297 0.07667195 0.06944096 0.1031579 0.06345599 0.078646 0.05487698 0.103937 0.05751287 0.105231 0.05165499 0.078646 0.05487698 0.07716995 0.06210297 0.103937 0.05751287 0.08106797 0.04783385 0.105231 0.05165499 0.10703 0.04593098 0.08106797 0.04783385 0.078646 0.05487698 0.105231 0.05165499 0.08438897 0.04104799 0.10703 0.04593098 0.10932 0.04038184 0.08438897 0.04104799 0.08106797 0.04783385 0.10703 0.04593098 0.08438897 0.04104799 0.10932 0.04038184 0.1120859 0.03505384 0.08854997 0.03458899 0.1120859 0.03505384 0.115305 0.02998799 0.08854997 0.03458899 0.08438897 0.04104799 0.1120859 0.03505384 0.09348195 0.02852499 0.115305 0.02998799 0.118953 0.025222 0.09348195 0.02852499 0.08854997 0.03458899 0.115305 0.02998799 0.09910798 0.02291995 0.118953 0.025222 0.123002 0.02079182 0.09910798 0.02291995 0.09348195 0.02852499 0.118953 0.025222 0.105341 0.01783299 0.123002 0.02079182 0.127422 0.01673299 0.105341 0.01783299 0.09910798 0.02291995 0.123002 0.02079182 0.112089 0.01331883 0.127422 0.01673299 0.13218 0.01307284 0.112089 0.01331883 0.105341 0.01783299 0.127422 0.01673299 0.112089 0.01331883 0.13218 0.01307284 0.1372399 0.009841978 0.119256 0.009423971 0.1372399 0.009841978 0.142566 0.007061958 0.119256 0.009423971 0.112089 0.01331883 0.1372399 0.009841978 0.126743 0.006188988 0.142566 0.007061958 0.148119 0.00475496 0.126743 0.006188988 0.119256 0.009423971 0.142566 0.007061958 0.13445 0.003645956 0.148119 0.00475496 0.153858 0.002939999 0.13445 0.003645956 0.126743 0.006188988 0.148119 0.00475496 0.142278 0.001816928 0.153858 0.002939999 0.15974 0.001630902 0.142278 0.001816928 0.13445 0.003645956 0.153858 0.002939999 0.15013 7.17e-4 0.15974 0.001630902 0.1657249 8.4e-4 0.15013 7.17e-4 0.142278 0.001816928 0.15974 0.001630902 0.120423 9.59e-4 0.127994 0.001606941 0.136524 5.14e-4 0.15013 7.17e-4 0.136524 5.14e-4 0.127994 0.001606941 0.129814 2.64e-4 0.120423 9.59e-4 0.136524 5.14e-4 0.110829 0.002091944 0.119365 0.003425896 0.127994 0.001606941 0.142278 0.001816928 0.127994 0.001606941 0.119365 0.003425896 0.120423 9.59e-4 0.110829 0.002091944 0.127994 0.001606941 0.15013 7.17e-4 0.127994 0.001606941 0.142278 0.001816928 0.101689 0.004138946 0.11075 0.005957961 0.119365 0.003425896 0.13445 0.003645956 0.119365 0.003425896 0.11075 0.005957961 0.110829 0.002091944 0.101689 0.004138946 0.119365 0.003425896 0.142278 0.001816928 0.119365 0.003425896 0.13445 0.003645956 0.09251898 0.006852984 0.102271 0.009182989 0.11075 0.005957961 0.126743 0.006188988 0.11075 0.005957961 0.102271 0.009182989 0.101689 0.004138946 0.09251898 0.006852984 0.11075 0.005957961 0.13445 0.003645956 0.11075 0.005957961 0.126743 0.006188988 0.083449 0.01021099 0.09405499 0.013071 0.102271 0.009182989 0.119256 0.009423971 0.102271 0.009182989 0.09405499 0.013071 0.09251898 0.006852984 0.083449 0.01021099 0.102271 0.009182989 0.126743 0.006188988 0.102271 0.009182989 0.119256 0.009423971 0.07462 0.01418197 0.086232 0.01758295 0.09405499 0.013071 0.112089 0.01331883 0.09405499 0.013071 0.086232 0.01758295 0.083449 0.01021099 0.07462 0.01418197 0.09405499 0.013071 0.119256 0.009423971 0.09405499 0.013071 0.112089 0.01331883 0.06617796 0.018727 0.07893198 0.02267295 0.086232 0.01758295 0.105341 0.01783299 0.086232 0.01758295 0.07893198 0.02267295 0.07462 0.01418197 0.06617796 0.018727 0.086232 0.01758295 0.112089 0.01331883 0.086232 0.01758295 0.105341 0.01783299 0.05827283 0.02380084 0.07228296 0.02828782 0.07893198 0.02267295 0.09910798 0.02291995 0.07893198 0.02267295 0.07228296 0.02828782 0.06617796 0.018727 0.05827283 0.02380084 0.07893198 0.02267295 0.105341 0.01783299 0.07893198 0.02267295 0.09910798 0.02291995 0.05104982 0.02935296 0.06640499 0.03436696 0.07228296 0.02828782 0.09348195 0.02852499 0.07228296 0.02828782 0.06640499 0.03436696 0.05827283 0.02380084 0.05104982 0.02935296 0.07228296 0.02828782 0.09910798 0.02291995 0.07228296 0.02828782 0.09348195 0.02852499 0.04464983 0.03532797 0.06141096 0.04084897 0.06640499 0.03436696 0.08854997 0.03458899 0.06640499 0.03436696 0.06141096 0.04084897 0.05104982 0.02935296 0.04464983 0.03532797 0.06640499 0.03436696 0.09348195 0.02852499 0.06640499 0.03436696 0.08854997 0.03458899 0.03919982 0.04166787 0.05740195 0.04766595 0.06141096 0.04084897 0.08438897 0.04104799 0.06141096 0.04084897 0.05740195 0.04766595 0.04464983 0.03532797 0.03919982 0.04166787 0.06141096 0.04084897 0.08854997 0.03458899 0.06141096 0.04084897 0.08438897 0.04104799 0.03481882 0.04831099 0.05446285 0.05475085 0.05740195 0.04766595 0.08106797 0.04783385 0.05740195 0.04766595 0.05446285 0.05475085 0.03919982 0.04166787 0.03481882 0.04831099 0.05740195 0.04766595 0.08438897 0.04104799 0.05740195 0.04766595 0.08106797 0.04783385 0.03160399 0.05519586 0.05266499 0.06203198 0.05446285 0.05475085 0.078646 0.05487698 0.05446285 0.05475085 0.05266499 0.06203198 0.03481882 0.04831099 0.03160399 0.05519586 0.05446285 0.05475085 0.08106797 0.04783385 0.05446285 0.05475085 0.078646 0.05487698 0.02897083 0.06944096 0.05205684 0.06944096 0.05266499 0.06203198 0.07716995 0.06210297 0.05266499 0.06203198 0.05205684 0.06944096 0.02963685 0.06225997 0.02897083 0.06944096 0.05266499 0.06203198 0.03160399 0.05519586 0.02963685 0.06225997 0.05266499 0.06203198 0.078646 0.05487698 0.05266499 0.06203198 0.07716995 0.06210297 0.02963685 0.07662498 0.05205684 0.06944096 0.02897083 0.06944096 0.07716995 0.06210297 0.05205684 0.06944096 0.07667195 0.06944096 0.05259186 0.07638996 0.07667195 0.06944096 0.05205684 0.06944096 0.05259186 0.07638996 0.05205684 0.06944096 0.02963685 0.07662498 0.00733298 0.06944096 0.02897083 0.06944096 0.02963685 0.06225997 0.007994949 0.07612097 0.02897083 0.06944096 0.00733298 0.06944096 0.007994949 0.07612097 0.02963685 0.07662498 0.02897083 0.06944096 0.009955942 0.0561589 0.02963685 0.06225997 0.03160399 0.05519586 0.007995963 0.062756 0.00733298 0.06944096 0.02963685 0.06225997 0.009955942 0.0561589 0.007995963 0.062756 0.02963685 0.06225997 0.01316899 0.04969882 0.03160399 0.05519586 0.03481882 0.04831099 0.01316899 0.04969882 0.009955942 0.0561589 0.03160399 0.05519586 0.01755595 0.043428 0.03481882 0.04831099 0.03919982 0.04166787 0.01755595 0.043428 0.01316899 0.04969882 0.03481882 0.04831099 0.02302289 0.03739899 0.03919982 0.04166787 0.04464983 0.03532797 0.02302289 0.03739899 0.01755595 0.043428 0.03919982 0.04166787 0.02945798 0.031663 0.04464983 0.03532797 0.05104982 0.02935296 0.02945798 0.031663 0.02302289 0.03739899 0.04464983 0.03532797 0.03673595 0.02626997 0.05104982 0.02935296 0.05827283 0.02380084 0.03673595 0.02626997 0.02945798 0.031663 0.05104982 0.02935296 0.04471898 0.02126795 0.05827283 0.02380084 0.06617796 0.018727 0.04471898 0.02126795 0.03673595 0.02626997 0.05827283 0.02380084 0.05326396 0.01670295 0.06617796 0.018727 0.07462 0.01418197 0.05326396 0.01670295 0.04471898 0.02126795 0.06617796 0.018727 0.06225585 0.01261287 0.07462 0.01418197 0.083449 0.01021099 0.06225585 0.01261287 0.05326396 0.01670295 0.07462 0.01418197 0.07775598 0.00851798 0.083449 0.01021099 0.09251898 0.006852984 0.06595498 0.01157999 0.06225585 0.01261287 0.083449 0.01021099 0.07775598 0.00851798 0.06595498 0.01157999 0.083449 0.01021099 0.08906698 0.005938947 0.09251898 0.006852984 0.101689 0.004138946 0.08906698 0.005938947 0.07775598 0.00851798 0.09251898 0.006852984 0.110464 0.002141952 0.101689 0.004138946 0.110829 0.002091944 0.09999597 0.003805935 0.08906698 0.005938947 0.101689 0.004138946 0.110464 0.002141952 0.09999597 0.003805935 0.101689 0.004138946 0.109787 0.002284944 0.110829 0.002091944 0.120423 9.59e-4 0.109787 0.002284944 0.110464 0.002141952 0.110829 0.002091944 0.124378 7.2e-4 0.120423 9.59e-4 0.129814 2.64e-4 0.124378 7.2e-4 0.109787 0.002284944 0.120423 9.59e-4 0.138616 4.5e-5 0.1386449 4.4e-5 0.129814 2.64e-4 0.124378 7.2e-4 0.129814 2.64e-4 0.1386449 4.4e-5 0.139393 2.17e-4 0.1386449 4.4e-5 0.138616 4.5e-5 0.124378 7.2e-4 0.1386449 4.4e-5 0.139393 2.17e-4 0.139481 2.61e-4 0.139393 2.17e-4 0.138616 4.5e-5 0.07710999 0.07632195 0.07667195 0.06944096 0.05259186 0.07638996 0.001935899 0.05776399 0.007995963 0.062756 0.009955942 0.0561589 0.001935899 0.05776399 0.001185894 0.06392896 0.007995963 0.062756 0.003337979 0.05125397 0.009955942 0.0561589 0.01316899 0.04969882 0.003337979 0.05125397 0.001935899 0.05776399 0.009955942 0.0561589 0.004315972 0.04790484 0.01316899 0.04969882 0.01755595 0.043428 0.004315972 0.04790484 0.003337979 0.05125397 0.01316899 0.04969882 0.006857991 0.04115986 0.01755595 0.043428 0.02302289 0.03739899 0.005488932 0.04453599 0.004315972 0.04790484 0.01755595 0.043428 0.006857991 0.04115986 0.005488932 0.04453599 0.01755595 0.043428 0.01009386 0.03472495 0.02302289 0.03739899 0.02945798 0.031663 0.00841397 0.03785985 0.006857991 0.04115986 0.02302289 0.03739899 0.01009386 0.03472495 0.00841397 0.03785985 0.02302289 0.03739899 0.06810897 0.01085084 0.06595498 0.01157999 0.07775598 0.00851798 0.08169698 0.0075019 0.07775598 0.00851798 0.08906698 0.005938947 0.08169698 0.0075019 0.06810897 0.01085084 0.07775598 0.00851798 0.095573 0.004607975 0.08906698 0.005938947 0.09999597 0.003805935 0.095573 0.004607975 0.08169698 0.0075019 0.08906698 0.005938947 0.109787 0.002284944 0.09999597 0.003805935 0.110464 0.002141952 0.109787 0.002284944 0.095573 0.004607975 0.09999597 0.003805935 6.89e-4 0.06169492 0.001185894 0.06392896 0.001935899 0.05776399 0.001884937 0.05438894 0.001935899 0.05776399 0.003337979 0.05125397 6.89e-4 0.06169492 0.001935899 0.05776399 0.001884937 0.05438894 0.001884937 0.05438894 0.003337979 0.05125397 0.004315972 0.04790484 0.003672957 0.04777598 0.004315972 0.04790484 0.005488932 0.04453599 0.001884937 0.05438894 0.004315972 0.04790484 0.003672957 0.04777598 0.005862951 0.04193097 0.005488932 0.04453599 0.006857991 0.04115986 0.003672957 0.04777598 0.005488932 0.04453599 0.005862951 0.04193097 0.005862951 0.04193097 0.006857991 0.04115986 0.00841397 0.03785985 0.008298993 0.03681695 0.00841397 0.03785985 0.01009386 0.03472495 0.005862951 0.04193097 0.00841397 0.03785985 0.008298993 0.03681695 0.125229 0.00116986 0.139393 2.17e-4 0.139481 2.61e-4 0.125229 0.00116986 0.124378 7.2e-4 0.139393 2.17e-4 0.150517 0.001223981 0.139481 2.61e-4 0.149782 3.99e-4 0.150517 0.001223981 0.139571 3.12e-4 0.139481 2.61e-4 0.125229 0.00116986 0.139481 2.61e-4 0.139571 3.12e-4 0.160787 0.002183914 0.149782 3.99e-4 0.160209 0.001334965 0.160787 0.002183914 0.150517 0.001223981 0.149782 3.99e-4 0.1710799 0.003984928 0.160209 0.001334965 0.170652 0.003123939 0.1710799 0.003984928 0.160787 0.002183914 0.160209 0.001334965 0.181262 0.006681919 0.170652 0.003123939 0.180981 0.005820989 0.181262 0.006681919 0.1710799 0.003984928 0.170652 0.003123939 0.191172 0.01031899 0.180981 0.005820989 0.191035 0.009468972 0.191172 0.01031899 0.181262 0.006681919 0.180981 0.005820989 0.200628 0.01491987 0.191035 0.009468972 0.200633 0.01409184 0.200628 0.01491987 0.191172 0.01031899 0.191035 0.009468972 0.209432 0.02048099 0.200633 0.01409184 0.209578 0.01969099 0.209432 0.02048099 0.200628 0.01491987 0.200633 0.01409184 0.2173759 0.02696895 0.209578 0.01969099 0.217663 0.02623695 0.2173759 0.02696895 0.209432 0.02048099 0.209578 0.01969099 0.224258 0.03430485 0.217663 0.02623695 0.2246789 0.03365695 0.224258 0.03430485 0.2173759 0.02696895 0.217663 0.02623695 0.229883 0.04237186 0.2246789 0.03365695 0.230427 0.04183799 0.229883 0.04237186 0.224258 0.03430485 0.2246789 0.03365695 0.234063 0.05104082 0.230427 0.04183799 0.23471 0.05065596 0.234063 0.05104082 0.229883 0.04237186 0.230427 0.04183799 0.23665 0.06012797 0.23471 0.05065596 0.237367 0.05992382 0.23665 0.06012797 0.234063 0.05104082 0.23471 0.05065596 0.150517 0.001223981 0.140105 7.37e-4 0.139571 3.12e-4 0.125229 0.00116986 0.139571 3.12e-4 0.140105 7.37e-4 0.150517 0.001223981 0.1403779 0.001046836 0.140105 7.37e-4 0.126017 0.002000987 0.140105 7.37e-4 0.1403779 0.001046836 0.126017 0.002000987 0.125229 0.00116986 0.140105 7.37e-4 0.151086 0.002484977 0.1403779 0.001046836 0.150517 0.001223981 0.151086 0.002484977 0.140434 0.001120865 0.1403779 0.001046836 0.126017 0.002000987 0.1403779 0.001046836 0.140434 0.001120865 0.161194 0.003411889 0.150517 0.001223981 0.160787 0.002183914 0.161194 0.003411889 0.151086 0.002484977 0.150517 0.001223981 0.171331 0.005176961 0.160787 0.002183914 0.1710799 0.003984928 0.171331 0.005176961 0.161194 0.003411889 0.160787 0.002183914 0.18136 0.007837951 0.1710799 0.003984928 0.181262 0.006681919 0.18136 0.007837951 0.171331 0.005176961 0.1710799 0.003984928 0.191117 0.01143586 0.181262 0.006681919 0.191172 0.01031899 0.191117 0.01143586 0.18136 0.007837951 0.181262 0.006681919 0.200416 0.01599097 0.191172 0.01031899 0.200628 0.01491987 0.200416 0.01599097 0.191117 0.01143586 0.191172 0.01031899 0.209059 0.02149397 0.200628 0.01491987 0.209432 0.02048099 0.209059 0.02149397 0.200416 0.01599097 0.200628 0.01491987 0.216838 0.02790397 0.209432 0.02048099 0.2173759 0.02696895 0.216838 0.02790397 0.209059 0.02149397 0.209432 0.02048099 0.223554 0.03513383 0.2173759 0.02696895 0.224258 0.03430485 0.223554 0.03513383 0.216838 0.02790397 0.2173759 0.02696895 0.229023 0.04305785 0.224258 0.03430485 0.229883 0.04237186 0.229023 0.04305785 0.223554 0.03513383 0.224258 0.03430485 0.233069 0.05153685 0.229883 0.04237186 0.234063 0.05104082 0.233069 0.05153685 0.229023 0.04305785 0.229883 0.04237186 0.235562 0.06039083 0.234063 0.05104082 0.23665 0.06012797 0.235562 0.06039083 0.233069 0.05153685 0.234063 0.05104082 0.151086 0.002484977 0.140738 0.001580834 0.140434 0.001120865 0.126017 0.002000987 0.140434 0.001120865 0.140738 0.001580834 0.151086 0.002484977 0.141116 0.002341926 0.140738 0.001580834 0.126689 0.003155887 0.140738 0.001580834 0.141116 0.002341926 0.126689 0.003155887 0.126017 0.002000987 0.140738 0.001580834 0.148869 0.003978967 0.141116 0.002341926 0.151086 0.002484977 0.148869 0.003978967 0.141142 0.002403974 0.141116 0.002341926 0.126689 0.003155887 0.141116 0.002341926 0.141142 0.002403974 0.155193 0.004293978 0.151086 0.002484977 0.161194 0.003411889 0.155193 0.004293978 0.148869 0.003978967 0.151086 0.002484977 0.162787 0.005098998 0.161194 0.003411889 0.171331 0.005176961 0.156198 0.004370987 0.155193 0.004293978 0.161194 0.003411889 0.162787 0.005098998 0.156198 0.004370987 0.161194 0.003411889 0.176363 0.007796943 0.171331 0.005176961 0.18136 0.007837951 0.169382 0.006199896 0.162787 0.005098998 0.171331 0.005176961 0.176363 0.007796943 0.169382 0.006199896 0.171331 0.005176961 0.1832489 0.009850978 0.18136 0.007837951 0.191117 0.01143586 0.1832489 0.009850978 0.176363 0.007796943 0.18136 0.007837951 0.193284 0.01380884 0.191117 0.01143586 0.200416 0.01599097 0.1890709 0.01199597 0.1832489 0.009850978 0.191117 0.01143586 0.193284 0.01380884 0.1890709 0.01199597 0.191117 0.01143586 0.200855 0.01771485 0.200416 0.01599097 0.209059 0.02149397 0.194736 0.01449483 0.193284 0.01380884 0.200416 0.01599097 0.200855 0.01771485 0.194736 0.01449483 0.200416 0.01599097 0.211199 0.02473396 0.209059 0.02149397 0.216838 0.02790397 0.206657 0.02137196 0.200855 0.01771485 0.209059 0.02149397 0.211199 0.02473396 0.206657 0.02137196 0.209059 0.02149397 0.222099 0.035438 0.216838 0.02790397 0.223554 0.03513383 0.215439 0.02837491 0.211199 0.02473396 0.216838 0.02790397 0.222099 0.035438 0.215439 0.02837491 0.216838 0.02790397 0.227266 0.04275482 0.223554 0.03513383 0.229023 0.04305785 0.227266 0.04275482 0.222099 0.035438 0.223554 0.03513383 0.22965 0.04711997 0.229023 0.04305785 0.233069 0.05153685 0.22965 0.04711997 0.227266 0.04275482 0.229023 0.04305785 0.233077 0.05598396 0.233069 0.05153685 0.235562 0.06039083 0.231612 0.05161082 0.22965 0.04711997 0.233069 0.05153685 0.233077 0.05598396 0.231612 0.05161082 0.233069 0.05153685 0.234133 0.06041985 0.233077 0.05598396 0.235562 0.06039083 0.234775 0.06492197 0.234133 0.06041985 0.235562 0.06039083 0.148869 0.003978967 0.141256 0.002695918 0.141142 0.002403974 0.126689 0.003155887 0.141142 0.002403974 0.141256 0.002695918 0.148869 0.003978967 0.1416299 0.004008889 0.141256 0.002695918 0.132623 0.004210889 0.141256 0.002695918 0.1416299 0.004008889 0.132623 0.004210889 0.126689 0.003155887 0.141256 0.002695918 0.1231819 0.004909992 0.1416299 0.004008889 0.148869 0.003978967 0.132623 0.004210889 0.1416299 0.004008889 0.1231819 0.004909992 0.12021 0.005222976 0.148869 0.003978967 0.155193 0.004293978 0.1231819 0.004909992 0.148869 0.003978967 0.12021 0.005222976 0.162787 0.005098998 0.155193 0.004293978 0.156198 0.004370987 0.169382 0.006199896 0.155193 0.004293978 0.162787 0.005098998 0.176363 0.007796943 0.155193 0.004293978 0.169382 0.006199896 0.15631 0.009680986 0.155193 0.004293978 0.176363 0.007796943 0.149378 0.00900197 0.12021 0.005222976 0.155193 0.004293978 0.154955 0.009442985 0.155193 0.004293978 0.15631 0.009680986 0.154955 0.009442985 0.149378 0.00900197 0.155193 0.004293978 0.15631 0.009680986 0.176363 0.007796943 0.1832489 0.009850978 0.169648 0.01203584 0.1832489 0.009850978 0.1890709 0.01199597 0.169648 0.01203584 0.15631 0.009680986 0.1832489 0.009850978 0.169648 0.01203584 0.1890709 0.01199597 0.193284 0.01380884 0.193947 0.01737797 0.193284 0.01380884 0.194736 0.01449483 0.192856 0.01695895 0.193284 0.01380884 0.193947 0.01737797 0.184521 0.014678 0.169648 0.01203584 0.193284 0.01380884 0.192856 0.01695895 0.184521 0.014678 0.193284 0.01380884 0.193947 0.01737797 0.194736 0.01449483 0.200855 0.01771485 0.201135 0.02089095 0.200855 0.01771485 0.206657 0.02137196 0.201135 0.02089095 0.193947 0.01737797 0.200855 0.01771485 0.201135 0.02089095 0.206657 0.02137196 0.211199 0.02473396 0.208926 0.02640396 0.211199 0.02473396 0.215439 0.02837491 0.208926 0.02640396 0.201135 0.02089095 0.211199 0.02473396 0.2157379 0.03321588 0.215439 0.02837491 0.222099 0.035438 0.2157379 0.03321588 0.208926 0.02640396 0.215439 0.02837491 0.221381 0.04118084 0.222099 0.035438 0.227266 0.04275482 0.221381 0.04118084 0.2157379 0.03321588 0.222099 0.035438 0.221381 0.04118084 0.227266 0.04275482 0.22965 0.04711997 0.225634 0.05012583 0.22965 0.04711997 0.231612 0.05161082 0.225634 0.05012583 0.221381 0.04118084 0.22965 0.04711997 0.225634 0.05012583 0.231612 0.05161082 0.233077 0.05598396 0.228248 0.05966883 0.233077 0.05598396 0.234133 0.06041985 0.228248 0.05966883 0.225634 0.05012583 0.233077 0.05598396 0.228248 0.05966883 0.234133 0.06041985 0.234775 0.06492197 0.069283 0.01104086 0.06810897 0.01085084 0.08169698 0.0075019 0.08281195 0.007750988 0.08169698 0.0075019 0.095573 0.004607975 0.08281195 0.007750988 0.069283 0.01104086 0.08169698 0.0075019 0.096619 0.004920959 0.095573 0.004607975 0.109787 0.002284944 0.096619 0.004920959 0.08281195 0.007750988 0.095573 0.004607975 0.110747 0.002664983 0.109787 0.002284944 0.124378 7.2e-4 0.110747 0.002664983 0.096619 0.004920959 0.109787 0.002284944 0.125229 0.00116986 0.110747 0.002664983 0.124378 7.2e-4 0.070463 0.01182097 0.069283 0.01104086 0.08281195 0.007750988 0.08391398 0.008540987 0.08281195 0.007750988 0.096619 0.004920959 0.08391398 0.008540987 0.070463 0.01182097 0.08281195 0.007750988 0.09763395 0.005721986 0.096619 0.004920959 0.110747 0.002664983 0.09763395 0.005721986 0.08391398 0.008540987 0.096619 0.004920959 0.111659 0.003480911 0.110747 0.002664983 0.125229 0.00116986 0.111659 0.003480911 0.09763395 0.005721986 0.110747 0.002664983 0.126017 0.002000987 0.111659 0.003480911 0.125229 0.00116986 0.07152897 0.01310884 0.070463 0.01182097 0.08391398 0.008540987 0.08490198 0.00979495 0.08391398 0.008540987 0.09763395 0.005721986 0.08490198 0.00979495 0.07152897 0.01310884 0.08391398 0.008540987 0.09853398 0.006943941 0.09763395 0.005721986 0.111659 0.003480911 0.09853398 0.006943941 0.08490198 0.00979495 0.09763395 0.005721986 0.112456 0.004669964 0.111659 0.003480911 0.126017 0.002000987 0.112456 0.004669964 0.09853398 0.006943941 0.111659 0.003480911 0.126689 0.003155887 0.112456 0.004669964 0.126017 0.002000987 0.08182495 0.01231884 0.07152897 0.01310884 0.08490198 0.00979495 0.08182495 0.01231884 0.070719 0.01522582 0.07152897 0.01310884 0.08737099 0.01099383 0.08490198 0.00979495 0.09853398 0.006943941 0.08737099 0.01099383 0.08182495 0.01231884 0.08490198 0.00979495 0.103049 0.007763922 0.09853398 0.006943941 0.112456 0.004669964 0.09258699 0.009830951 0.08737099 0.01099383 0.09853398 0.006943941 0.103049 0.007763922 0.09258699 0.009830951 0.09853398 0.006943941 0.113287 0.006108999 0.112456 0.004669964 0.126689 0.003155887 0.113287 0.006108999 0.103049 0.007763922 0.112456 0.004669964 0.12021 0.005222976 0.113287 0.006108999 0.126689 0.003155887 0.1231819 0.004909992 0.12021 0.005222976 0.126689 0.003155887 0.132623 0.004210889 0.1231819 0.004909992 0.126689 0.003155887 0.08996796 0.024782 0.070719 0.01522582 0.08182495 0.01231884 0.08996796 0.024782 0.08182495 0.01231884 0.08737099 0.01099383 0.122503 0.01635396 0.08737099 0.01099383 0.09258699 0.009830951 0.08996796 0.024782 0.08737099 0.01099383 0.122503 0.01635396 0.122503 0.01635396 0.09258699 0.009830951 0.103049 0.007763922 0.122503 0.01635396 0.103049 0.007763922 0.113287 0.006108999 0.122503 0.01635396 0.113287 0.006108999 0.12021 0.005222976 0.1339499 0.01455599 0.122503 0.01635396 0.12021 0.005222976 0.138723 0.01152098 0.1339499 0.01455599 0.12021 0.005222976 0.143847 0.009695947 0.138723 0.01152098 0.12021 0.005222976 0.149378 0.00900197 0.143847 0.009695947 0.12021 0.005222976 0.195917 0.01903897 0.193947 0.01737797 0.201135 0.02089095 0.191529 0.01702797 0.192856 0.01695895 0.193947 0.01737797 0.191529 0.01702797 0.193947 0.01737797 0.195917 0.01903897 0.200112 0.02148896 0.201135 0.02089095 0.208926 0.02640396 0.195917 0.01903897 0.201135 0.02089095 0.200112 0.02148896 0.207791 0.02763897 0.208926 0.02640396 0.2157379 0.03321588 0.200112 0.02148896 0.208926 0.02640396 0.207791 0.02763897 0.214277 0.03524684 0.2157379 0.03321588 0.221381 0.04118084 0.207791 0.02763897 0.2157379 0.03321588 0.214277 0.03524684 0.2193869 0.04410582 0.221381 0.04118084 0.225634 0.05012583 0.214277 0.03524684 0.221381 0.04118084 0.2193869 0.04410582 0.222898 0.05386698 0.225634 0.05012583 0.228248 0.05966883 0.2193869 0.04410582 0.225634 0.05012583 0.222898 0.05386698 0.224686 0.06418597 0.228248 0.05966883 0.2291229 0.06944096 0.222898 0.05386698 0.228248 0.05966883 0.224686 0.06418597 0.224686 0.07470095 0.2291229 0.06944096 0.228283 0.07901799 0.224686 0.06418597 0.2291229 0.06944096 0.224686 0.07470095 0.222891 0.08504098 0.228283 0.07901799 0.225744 0.088458 0.224686 0.07470095 0.228283 0.07901799 0.222891 0.08504098 0.2193599 0.09483295 0.225744 0.088458 0.221567 0.097382 0.222891 0.08504098 0.225744 0.088458 0.2193599 0.09483295 0.214224 0.103709 0.221567 0.097382 0.21596 0.105401 0.2193599 0.09483295 0.221567 0.097382 0.214224 0.103709 0.207723 0.111308 0.21596 0.105401 0.209133 0.112302 0.214224 0.103709 0.21596 0.105401 0.207723 0.111308 0.2000499 0.117433 0.209133 0.112302 0.2013069 0.11789 0.207723 0.111308 0.209133 0.112302 0.2000499 0.117433 0.2000499 0.117433 0.2013069 0.11789 0.193944 0.121505 0.191493 0.121868 0.193944 0.121505 0.1929489 0.121888 0.2000499 0.117433 0.193944 0.121505 0.191493 0.121868 0.152739 0.009168982 0.15631 0.009680986 0.169648 0.01203584 0.152739 0.009168982 0.154955 0.009442985 0.15631 0.009680986 0.152739 0.009168982 0.169648 0.01203584 0.184521 0.014678 0.182384 0.01441782 0.184521 0.014678 0.192856 0.01695895 0.182384 0.01441782 0.152739 0.009168982 0.184521 0.014678 0.182384 0.01441782 0.192856 0.01695895 0.191529 0.01702797 0.126655 0.02352398 0.124414 0.02765583 0.122503 0.01635396 0.08996796 0.024782 0.122503 0.01635396 0.124414 0.02765583 0.129952 0.01854795 0.126655 0.02352398 0.122503 0.01635396 0.1339499 0.01455599 0.129952 0.01854795 0.122503 0.01635396 0.100099 0.052953 0.124414 0.02765583 0.126655 0.02352398 0.09189897 0.038809 0.08996796 0.024782 0.124414 0.02765583 0.118334 0.03834986 0.09189897 0.038809 0.124414 0.02765583 0.100099 0.052953 0.118334 0.03834986 0.124414 0.02765583 0.121172 0.02304196 0.126655 0.02352398 0.129952 0.01854795 0.121172 0.02304196 0.100099 0.052953 0.126655 0.02352398 0.126107 0.01738697 0.129952 0.01854795 0.1339499 0.01455599 0.126107 0.01738697 0.121172 0.02304196 0.129952 0.01854795 0.132001 0.01300096 0.1339499 0.01455599 0.138723 0.01152098 0.132001 0.01300096 0.126107 0.01738697 0.1339499 0.01455599 0.1386 0.01008397 0.138723 0.01152098 0.143847 0.009695947 0.1386 0.01008397 0.132001 0.01300096 0.138723 0.01152098 0.145617 0.008779942 0.143847 0.009695947 0.149378 0.00900197 0.145617 0.008779942 0.1386 0.01008397 0.143847 0.009695947 0.145617 0.008779942 0.149378 0.00900197 0.154955 0.009442985 0.152739 0.009168982 0.145617 0.008779942 0.154955 0.009442985 0.06822896 0.02796697 0.08996796 0.024782 0.09189897 0.038809 0.06822896 0.02796697 0.06214886 0.02351099 0.08996796 0.024782 0.118334 0.03834986 0.093203 0.05300897 0.09189897 0.038809 0.09142696 0.05068999 0.09189897 0.038809 0.093203 0.05300897 0.07427197 0.03295296 0.06822896 0.02796697 0.09189897 0.038809 0.08019399 0.03842484 0.07427197 0.03295296 0.09189897 0.038809 0.08591598 0.04433 0.08019399 0.03842484 0.09189897 0.038809 0.09142696 0.05068999 0.08591598 0.04433 0.09189897 0.038809 0.109218 0.05322498 0.09467899 0.05527883 0.093203 0.05300897 0.08997195 0.05676597 0.093203 0.05300897 0.09467899 0.05527883 0.118334 0.03834986 0.109218 0.05322498 0.093203 0.05300897 0.089531 0.05250597 0.09142696 0.05068999 0.093203 0.05300897 0.08783799 0.05425685 0.089531 0.05250597 0.093203 0.05300897 0.08997195 0.05676597 0.08783799 0.05425685 0.093203 0.05300897 0.106734 0.0582 0.09597796 0.057684 0.09467899 0.05527883 0.09183299 0.05955797 0.09467899 0.05527883 0.09597796 0.057684 0.109218 0.05322498 0.106734 0.0582 0.09467899 0.05527883 0.08997195 0.05676597 0.09467899 0.05527883 0.09183299 0.05955797 0.106734 0.0582 0.09703797 0.06011188 0.09597796 0.057684 0.09183299 0.05955797 0.09597796 0.057684 0.09703797 0.06011188 0.105225 0.06369298 0.09783101 0.06250995 0.09703797 0.06011188 0.09331095 0.06263697 0.09703797 0.06011188 0.09783101 0.06250995 0.106734 0.0582 0.105225 0.06369298 0.09703797 0.06011188 0.09183299 0.05955797 0.09703797 0.06011188 0.09331095 0.06263697 0.105225 0.06369298 0.09838098 0.064875 0.09783101 0.06250995 0.09331095 0.06263697 0.09783101 0.06250995 0.09838098 0.064875 0.1047199 0.06944096 0.0988 0.06944096 0.09838098 0.064875 0.09427601 0.06596499 0.09838098 0.064875 0.0988 0.06944096 0.105225 0.06369298 0.1047199 0.06944096 0.09838098 0.064875 0.09331095 0.06263697 0.09838098 0.064875 0.09427601 0.06596499 0.105225 0.07518798 0.09839397 0.07393598 0.0988 0.06944096 0.09461396 0.06944096 0.0988 0.06944096 0.09839397 0.07393598 0.1047199 0.06944096 0.105225 0.07518798 0.0988 0.06944096 0.09427601 0.06596499 0.0988 0.06944096 0.09461396 0.06944096 0.105225 0.07518798 0.09785497 0.076285 0.09839397 0.07393598 0.09427601 0.07291698 0.09839397 0.07393598 0.09785497 0.076285 0.09461396 0.06944096 0.09839397 0.07393598 0.09427601 0.07291698 0.106734 0.08068096 0.09707099 0.07868099 0.09785497 0.076285 0.09331095 0.07624298 0.09785497 0.076285 0.09707099 0.07868099 0.105225 0.07518798 0.106734 0.08068096 0.09785497 0.076285 0.09427601 0.07291698 0.09785497 0.076285 0.09331095 0.07624298 0.106734 0.08068096 0.096017 0.08111798 0.09707099 0.07868099 0.09331095 0.07624298 0.09707099 0.07868099 0.096017 0.08111798 0.109218 0.085657 0.09471595 0.083543 0.096017 0.08111798 0.09183299 0.07932299 0.096017 0.08111798 0.09471595 0.083543 0.106734 0.08068096 0.109218 0.085657 0.096017 0.08111798 0.09331095 0.07624298 0.096017 0.08111798 0.09183299 0.07932299 0.109218 0.085657 0.09320795 0.085864 0.09471595 0.083543 0.08997297 0.082116 0.09471595 0.083543 0.09320795 0.085864 0.09183299 0.07932299 0.09471595 0.083543 0.08997297 0.082116 0.118334 0.100532 0.09189897 0.1000699 0.09320795 0.085864 0.09142696 0.08819198 0.09320795 0.085864 0.09189897 0.1000699 0.109218 0.085657 0.118334 0.100532 0.09320795 0.085864 0.08997297 0.082116 0.09320795 0.085864 0.09142696 0.08819198 0.124414 0.111226 0.08996897 0.114099 0.09189897 0.1000699 0.080177 0.1004739 0.09189897 0.1000699 0.08996897 0.114099 0.118334 0.100532 0.124414 0.111226 0.09189897 0.1000699 0.08590495 0.09456199 0.09142696 0.08819198 0.09189897 0.1000699 0.080177 0.1004739 0.08590495 0.09456199 0.09189897 0.1000699 0.124414 0.111226 0.122503 0.122529 0.08996897 0.114099 0.07424998 0.105948 0.080177 0.1004739 0.08996897 0.114099 0.06820696 0.110932 0.07424998 0.105948 0.08996897 0.114099 0.06213498 0.115381 0.06820696 0.110932 0.08996897 0.114099 0.126655 0.115357 0.122503 0.122529 0.124414 0.111226 0.138669 0.1273339 0.143715 0.129154 0.122503 0.122529 0.133971 0.124342 0.138669 0.1273339 0.122503 0.122529 0.129995 0.120387 0.133971 0.124342 0.122503 0.122529 0.126655 0.115357 0.129995 0.120387 0.122503 0.122529 0.121172 0.11584 0.124414 0.111226 0.118334 0.100532 0.121172 0.11584 0.126655 0.115357 0.124414 0.111226 0.121172 0.11584 0.118334 0.100532 0.109218 0.085657 0.100099 0.08592897 0.109218 0.085657 0.106734 0.08068096 0.121172 0.11584 0.109218 0.085657 0.100099 0.08592897 0.09558796 0.07530695 0.106734 0.08068096 0.105225 0.07518798 0.09730899 0.08089399 0.106734 0.08068096 0.09558796 0.07530695 0.100099 0.08592897 0.106734 0.08068096 0.09730899 0.08089399 0.09558796 0.07530695 0.105225 0.07518798 0.1047199 0.06944096 0.095007 0.06944096 0.1047199 0.06944096 0.105225 0.06369298 0.09558796 0.07530695 0.1047199 0.06944096 0.095007 0.06944096 0.09558796 0.06357496 0.105225 0.06369298 0.106734 0.0582 0.095007 0.06944096 0.105225 0.06369298 0.09558796 0.06357496 0.09730899 0.05798786 0.106734 0.0582 0.109218 0.05322498 0.09558796 0.06357496 0.106734 0.0582 0.09730899 0.05798786 0.100099 0.052953 0.109218 0.05322498 0.118334 0.03834986 0.09730899 0.05798786 0.109218 0.05322498 0.100099 0.052953 0.06644499 0.03052097 0.06214886 0.02351099 0.06822896 0.02796697 0.06644499 0.03052097 0.05826985 0.02496784 0.06214886 0.02351099 0.06644499 0.03052097 0.06822896 0.02796697 0.07427197 0.03295296 0.07448196 0.03703898 0.07427197 0.03295296 0.08019399 0.03842484 0.07448196 0.03703898 0.06644499 0.03052097 0.07427197 0.03295296 0.08221095 0.04439896 0.08019399 0.03842484 0.08591598 0.04433 0.08221095 0.04439896 0.07448196 0.03703898 0.08019399 0.03842484 0.08221095 0.04439896 0.08591598 0.04433 0.09142696 0.05068999 0.089531 0.05250597 0.08221095 0.04439896 0.09142696 0.05068999 0.089531 0.08637595 0.09142696 0.08819198 0.08590495 0.09456199 0.08997297 0.082116 0.09142696 0.08819198 0.089531 0.08637595 0.08221697 0.09447598 0.08590495 0.09456199 0.080177 0.1004739 0.089531 0.08637595 0.08590495 0.09456199 0.08221697 0.09447598 0.07448697 0.101839 0.080177 0.1004739 0.07424998 0.105948 0.08221697 0.09447598 0.080177 0.1004739 0.07448697 0.101839 0.07448697 0.101839 0.07424998 0.105948 0.06820696 0.110932 0.06644898 0.108358 0.06820696 0.110932 0.06213498 0.115381 0.07448697 0.101839 0.06820696 0.110932 0.06644898 0.108358 0.06644898 0.108358 0.06213498 0.115381 0.05827283 0.113912 0.182384 0.124464 0.15631 0.1292 0.154955 0.1294389 0.182384 0.124464 0.169648 0.126846 0.15631 0.1292 0.152739 0.129712 0.154955 0.1294389 0.1492339 0.129877 0.182384 0.124464 0.154955 0.1294389 0.152739 0.129712 0.145617 0.130102 0.1492339 0.129877 0.143715 0.129154 0.152739 0.129712 0.1492339 0.129877 0.145617 0.130102 0.1386 0.128798 0.143715 0.129154 0.138669 0.1273339 0.145617 0.130102 0.143715 0.129154 0.1386 0.128798 0.132001 0.125881 0.138669 0.1273339 0.133971 0.124342 0.1386 0.128798 0.138669 0.1273339 0.132001 0.125881 0.126107 0.121494 0.133971 0.124342 0.129995 0.120387 0.132001 0.125881 0.133971 0.124342 0.126107 0.121494 0.126107 0.121494 0.129995 0.120387 0.126655 0.115357 0.126107 0.121494 0.126655 0.115357 0.121172 0.11584 0.191493 0.121868 0.1929489 0.121888 0.184521 0.124204 0.182384 0.124464 0.184521 0.124204 0.169648 0.126846 0.191493 0.121868 0.184521 0.124204 0.182384 0.124464 0.05826985 0.02496784 0.05016487 0.02045691 0.05294096 0.02005195 0.04956996 0.01894485 0.05294096 0.02005195 0.05016487 0.02045691 0.04956996 0.01894485 0.052293 0.01842099 0.05294096 0.02005195 0.05222886 0.02504396 0.05016487 0.02045691 0.05826985 0.02496784 0.05222886 0.02504396 0.047634 0.02076786 0.05016487 0.02045691 0.04697483 0.01941084 0.05016487 0.02045691 0.047634 0.02076786 0.04697483 0.01941084 0.04956996 0.01894485 0.05016487 0.02045691 0.06135696 0.03039795 0.05826985 0.02496784 0.06644499 0.03052097 0.06135696 0.03039795 0.05222886 0.02504396 0.05826985 0.02496784 0.07053399 0.03717595 0.06644499 0.03052097 0.07448196 0.03703898 0.07053399 0.03717595 0.06135696 0.03039795 0.06644499 0.03052097 0.07942199 0.04517698 0.07448196 0.03703898 0.08221095 0.04439896 0.07942199 0.04517698 0.07053399 0.03717595 0.07448196 0.03703898 0.07942199 0.04517698 0.08221095 0.04439896 0.089531 0.05250597 0.08783799 0.05425685 0.07942199 0.04517698 0.089531 0.05250597 0.05222886 0.02504396 0.04537683 0.02101182 0.047634 0.02076786 0.04451197 0.019822 0.047634 0.02076786 0.04537683 0.02101182 0.04451197 0.019822 0.04697483 0.01941084 0.047634 0.02076786 0.05222886 0.02504396 0.04343295 0.02119797 0.04537683 0.02101182 0.04451197 0.019822 0.04537683 0.02101182 0.04343295 0.02119797 0.04355895 0.02406698 0.04343295 0.02119797 0.05222886 0.02504396 0.04355895 0.02406698 0.04150682 0.02135795 0.04343295 0.02119797 0.04219299 0.02018398 0.04343295 0.02119797 0.04150682 0.02135795 0.04219299 0.02018398 0.04451197 0.019822 0.04343295 0.02119797 0.05176997 0.02768695 0.05222886 0.02504396 0.06135696 0.03039795 0.05176997 0.02768695 0.04355895 0.02406698 0.05222886 0.02504396 0.06050586 0.03275996 0.06135696 0.03039795 0.07053399 0.03717595 0.06050586 0.03275996 0.05176997 0.02768695 0.06135696 0.03039795 0.069404 0.03927987 0.07053399 0.03717595 0.07942199 0.04517698 0.069404 0.03927987 0.06050586 0.03275996 0.07053399 0.03717595 0.07808995 0.04704385 0.07942199 0.04517698 0.08783799 0.05425685 0.07808995 0.04704385 0.069404 0.03927987 0.07942199 0.04517698 0.08636701 0.05592083 0.07808995 0.04704385 0.08783799 0.05425685 0.08997195 0.05676597 0.08636701 0.05592083 0.08783799 0.05425685 0.04355895 0.02406698 0.03989487 0.021483 0.04150682 0.02135795 0.04002285 0.02050387 0.04150682 0.02135795 0.03989487 0.021483 0.04002285 0.02050387 0.04219299 0.02018398 0.04150682 0.02135795 0.04355895 0.02406698 0.03845387 0.02158099 0.03989487 0.021483 0.03801697 0.02078884 0.03989487 0.021483 0.03845387 0.02158099 0.03801697 0.02078884 0.04002285 0.02050387 0.03989487 0.021483 0.04355895 0.02406698 0.03718996 0.02166295 0.03845387 0.02158099 0.03801697 0.02078884 0.03845387 0.02158099 0.03718996 0.02166295 0.04355895 0.02406698 0.03605985 0.02173388 0.03718996 0.02166295 0.03617286 0.02104598 0.03718996 0.02166295 0.03605985 0.02173388 0.03617286 0.02104598 0.03801697 0.02078884 0.03718996 0.02166295 0.04048997 0.024872 0.03605985 0.02173388 0.04355895 0.02406698 0.03675484 0.02364099 0.03501296 0.02180296 0.03605985 0.02173388 0.03451287 0.021281 0.03605985 0.02173388 0.03501296 0.02180296 0.03712898 0.023754 0.03675484 0.02364099 0.03605985 0.02173388 0.04048997 0.024872 0.03712898 0.023754 0.03605985 0.02173388 0.03451287 0.021281 0.03617286 0.02104598 0.03605985 0.02173388 0.04417598 0.02628988 0.04355895 0.02406698 0.05176997 0.02768695 0.04295682 0.02579897 0.04048997 0.024872 0.04355895 0.02406698 0.04417598 0.02628988 0.04295682 0.02579897 0.04355895 0.02406698 0.05235987 0.03017383 0.05176997 0.02768695 0.06050586 0.03275996 0.04812896 0.02803695 0.04417598 0.02628988 0.05176997 0.02768695 0.05016899 0.02903199 0.04812896 0.02803695 0.05176997 0.02768695 0.05235987 0.03017383 0.05016899 0.02903199 0.05176997 0.02768695 0.06072998 0.03525698 0.06050586 0.03275996 0.069404 0.03927987 0.05889987 0.03404599 0.05235987 0.03017383 0.06050586 0.03275996 0.06072998 0.03525698 0.05889987 0.03404599 0.06050586 0.03275996 0.06882399 0.04133486 0.069404 0.03927987 0.07808995 0.04704385 0.068421 0.041004 0.06072998 0.03525698 0.069404 0.03927987 0.06882399 0.04133486 0.068421 0.041004 0.069404 0.03927987 0.077026 0.04873496 0.07808995 0.04704385 0.08636701 0.05592083 0.077026 0.04873496 0.06882399 0.04133486 0.07808995 0.04704385 0.078956 0.05068182 0.077026 0.04873496 0.08636701 0.05592083 0.08514297 0.05746996 0.078956 0.05068182 0.08636701 0.05592083 0.08997195 0.05676597 0.08514297 0.05746996 0.08636701 0.05592083 0.03412598 0.02290683 0.03406786 0.02186799 0.03501296 0.02180296 0.03451287 0.021281 0.03501296 0.02180296 0.03406786 0.02186799 0.03675484 0.02364099 0.03412598 0.02290683 0.03501296 0.02180296 0.03412598 0.02290683 0.03327 0.02192896 0.03406786 0.02186799 0.03306198 0.021501 0.03406786 0.02186799 0.03327 0.02192896 0.03306198 0.021501 0.03451287 0.021281 0.03406786 0.02186799 0.03412598 0.02290683 0.03260195 0.02199 0.03327 0.02192896 0.03186899 0.02171397 0.03327 0.02192896 0.03260195 0.02199 0.03186899 0.02171397 0.03306198 0.021501 0.03327 0.02192896 0.03133183 0.02225196 0.03165197 0.02211385 0.03260195 0.02199 0.03103798 0.02192384 0.03260195 0.02199 0.03165197 0.02211385 0.03412598 0.02290683 0.03133183 0.02225196 0.03260195 0.02199 0.03103798 0.02192384 0.03186899 0.02171397 0.03260195 0.02199 0.03103798 0.02192384 0.03165197 0.02211385 0.03133183 0.02225196 0.03724282 0.024818 0.03133183 0.02225196 0.03412598 0.02290683 0.03080385 0.02213698 0.03103798 0.02192384 0.03133183 0.02225196 0.03724282 0.024818 0.03138095 0.02227687 0.03133183 0.02225196 0.03724282 0.024818 0.03412598 0.02290683 0.03675484 0.02364099 0.04254084 0.02724796 0.03675484 0.02364099 0.03712898 0.023754 0.03724282 0.024818 0.03675484 0.02364099 0.04254084 0.02724796 0.04254084 0.02724796 0.03712898 0.023754 0.04048997 0.024872 0.04254084 0.02724796 0.04048997 0.024872 0.04295682 0.02579897 0.04871785 0.03077799 0.04295682 0.02579897 0.04417598 0.02628988 0.04254084 0.02724796 0.04295682 0.02579897 0.04871785 0.03077799 0.04871785 0.03077799 0.04417598 0.02628988 0.04812896 0.02803695 0.04871785 0.03077799 0.04812896 0.02803695 0.05016899 0.02903199 0.05601096 0.035703 0.05016899 0.02903199 0.05235987 0.03017383 0.04871785 0.03077799 0.05016899 0.02903199 0.05601096 0.035703 0.05601096 0.035703 0.05235987 0.03017383 0.05889987 0.03404599 0.06443196 0.04263287 0.05889987 0.03404599 0.06072998 0.03525698 0.05601096 0.035703 0.05889987 0.03404599 0.06443196 0.04263287 0.06443196 0.04263287 0.06072998 0.03525698 0.068421 0.041004 0.07343196 0.05180597 0.068421 0.041004 0.06882399 0.04133486 0.06443196 0.04263287 0.068421 0.041004 0.07343196 0.05180597 0.07343196 0.05180597 0.06882399 0.04133486 0.077026 0.04873496 0.07343196 0.05180597 0.077026 0.04873496 0.078956 0.05068182 0.07936596 0.05821084 0.078956 0.05068182 0.08514297 0.05746996 0.07936596 0.05821084 0.07343196 0.05180597 0.078956 0.05068182 0.08243596 0.06361895 0.07936596 0.05821084 0.08514297 0.05746996 0.08663898 0.05902493 0.08514297 0.05746996 0.08997195 0.05676597 0.08243596 0.06361895 0.08514297 0.05746996 0.08663898 0.05902493 0.05111998 0.01722186 0.052293 0.01842099 0.04956996 0.01894485 0.04838395 0.01787286 0.04956996 0.01894485 0.04697483 0.01941084 0.04838395 0.01787286 0.05111998 0.01722186 0.04956996 0.01894485 0.04578685 0.018462 0.04697483 0.01941084 0.04451197 0.019822 0.04578685 0.018462 0.04838395 0.01787286 0.04697483 0.01941084 0.04333299 0.01899397 0.04451197 0.019822 0.04219299 0.02018398 0.04333299 0.01899397 0.04578685 0.018462 0.04451197 0.019822 0.04103487 0.01947093 0.04219299 0.02018398 0.04002285 0.02050387 0.04103487 0.01947093 0.04333299 0.01899397 0.04219299 0.02018398 0.03889799 0.01990085 0.04002285 0.02050387 0.03801697 0.02078884 0.03889799 0.01990085 0.04103487 0.01947093 0.04002285 0.02050387 0.03693687 0.02028685 0.03801697 0.02078884 0.03617286 0.02104598 0.03693687 0.02028685 0.03889799 0.01990085 0.03801697 0.02078884 0.03514999 0.020639 0.03617286 0.02104598 0.03451287 0.021281 0.03514999 0.020639 0.03693687 0.02028685 0.03617286 0.02104598 0.03355985 0.02096194 0.03451287 0.021281 0.03306198 0.021501 0.03355985 0.02096194 0.03514999 0.020639 0.03451287 0.021281 0.03219085 0.02126199 0.03306198 0.021501 0.03186899 0.02171397 0.03219085 0.02126199 0.03355985 0.02096194 0.03306198 0.021501 0.03109395 0.02154499 0.03186899 0.02171397 0.03103798 0.02192384 0.03109395 0.02154499 0.03219085 0.02126199 0.03186899 0.02171397 0.03037399 0.02181386 0.03103798 0.02192384 0.03080385 0.02213698 0.03037399 0.02181386 0.03109395 0.02154499 0.03103798 0.02192384 0.03037399 0.02181386 0.03080385 0.02213698 0.03026497 0.02207297 0.02970182 0.02178198 0.03037399 0.02181386 0.03026497 0.02207297 0.02970182 0.02178198 0.03026497 0.02207297 0.02999287 0.02205985 0.04983294 0.01655 0.05111998 0.01722186 0.04838395 0.01787286 0.04708784 0.01729798 0.04838395 0.01787286 0.04578685 0.018462 0.04708784 0.01729798 0.04983294 0.01655 0.04838395 0.01787286 0.04449594 0.01797497 0.04578685 0.018462 0.04333299 0.01899397 0.04449594 0.01797497 0.04708784 0.01729798 0.04578685 0.018462 0.04206287 0.01858592 0.04333299 0.01899397 0.04103487 0.01947093 0.04206287 0.01858592 0.04449594 0.01797497 0.04333299 0.01899397 0.03979897 0.01913398 0.04103487 0.01947093 0.03889799 0.01990085 0.03979897 0.01913398 0.04206287 0.01858592 0.04103487 0.01947093 0.03770697 0.01962697 0.03889799 0.01990085 0.03693687 0.02028685 0.03770697 0.01962697 0.03979897 0.01913398 0.03889799 0.01990085 0.03580296 0.020069 0.03693687 0.02028685 0.03514999 0.020639 0.03580296 0.020069 0.03770697 0.01962697 0.03693687 0.02028685 0.03408586 0.02047085 0.03514999 0.020639 0.03355985 0.02096194 0.03408586 0.02047085 0.03580296 0.020069 0.03514999 0.020639 0.03257596 0.02083599 0.03355985 0.02096194 0.03219085 0.02126199 0.03257596 0.02083599 0.03408586 0.02047085 0.03355985 0.02096194 0.03129982 0.02117395 0.03219085 0.02126199 0.03109395 0.02154499 0.03129982 0.02117395 0.03257596 0.02083599 0.03219085 0.02126199 0.03030699 0.02148687 0.03109395 0.02154499 0.03037399 0.02181386 0.03030699 0.02148687 0.03129982 0.02117395 0.03109395 0.02154499 0.02970182 0.02178198 0.03030699 0.02148687 0.03037399 0.02181386 0.02972197 0.02205985 0.02970182 0.02178198 0.02999287 0.02205985 0.04856598 0.01647984 0.04983294 0.01655 0.04708784 0.01729798 0.04580599 0.01727795 0.04708784 0.01729798 0.04449594 0.01797497 0.04580599 0.01727795 0.04856598 0.01647984 0.04708784 0.01729798 0.04321485 0.01799297 0.04449594 0.01797497 0.04206287 0.01858592 0.04321485 0.01799297 0.04580599 0.01727795 0.04449594 0.01797497 0.04079896 0.01862984 0.04206287 0.01858592 0.03979897 0.01913398 0.04079896 0.01862984 0.04321485 0.01799297 0.04206287 0.01858592 0.03856682 0.01919597 0.03979897 0.01913398 0.03770697 0.01962697 0.03856682 0.01919597 0.04079896 0.01862984 0.03979897 0.01913398 0.03652 0.01969999 0.03770697 0.01962697 0.03580296 0.020069 0.03652 0.01969999 0.03856682 0.01919597 0.03770697 0.01962697 0.03467297 0.02014595 0.03580296 0.020069 0.03408586 0.02047085 0.03467297 0.02014595 0.03652 0.01969999 0.03580296 0.020069 0.03302484 0.02054697 0.03408586 0.02047085 0.03257596 0.02083599 0.03302484 0.02054697 0.03467297 0.02014595 0.03408586 0.02047085 0.031596 0.02090787 0.03257596 0.02083599 0.03129982 0.02117395 0.031596 0.02090787 0.03302484 0.02054697 0.03257596 0.02083599 0.03041183 0.02123785 0.03129982 0.02117395 0.03030699 0.02148687 0.03041183 0.02123785 0.031596 0.02090787 0.03129982 0.02117395 0.02952086 0.02154296 0.03030699 0.02148687 0.02970182 0.02178198 0.02952086 0.02154296 0.03041183 0.02123785 0.03030699 0.02148687 0.02903199 0.02182799 0.02970182 0.02178198 0.02972197 0.02205985 0.02903199 0.02182799 0.02952086 0.02154296 0.02970182 0.02178198 0.02903199 0.02182799 0.02972197 0.02205985 0.02917885 0.022098 0.07588195 0.05866897 0.06851798 0.05294299 0.07343196 0.05180597 0.06443196 0.04263287 0.07343196 0.05180597 0.06851798 0.05294299 0.07936596 0.05821084 0.07588195 0.05866897 0.07343196 0.05180597 0.06806099 0.06008487 0.06424099 0.05405396 0.06851798 0.05294299 0.06093084 0.044227 0.06851798 0.05294299 0.06424099 0.05405396 0.07200396 0.05928587 0.06806099 0.06008487 0.06851798 0.05294299 0.07588195 0.05866897 0.07200396 0.05928587 0.06851798 0.05294299 0.06093084 0.044227 0.06443196 0.04263287 0.06851798 0.05294299 0.06491196 0.06092596 0.060669 0.05513983 0.06424099 0.05405396 0.05797499 0.04578596 0.06424099 0.05405396 0.060669 0.05513983 0.06806099 0.06008487 0.06491196 0.06092596 0.06424099 0.05405396 0.05797499 0.04578596 0.06093084 0.044227 0.06424099 0.05405396 0.06057095 0.06262499 0.05786883 0.05620098 0.060669 0.05513983 0.05562198 0.04731082 0.060669 0.05513983 0.05786883 0.05620098 0.06246685 0.06177687 0.06057095 0.06262499 0.060669 0.05513983 0.06491196 0.06092596 0.06246685 0.06177687 0.060669 0.05513983 0.05562198 0.04731082 0.05797499 0.04578596 0.060669 0.05513983 0.05803287 0.06434196 0.05590498 0.05723887 0.05786883 0.05620098 0.05393087 0.04880297 0.05786883 0.05620098 0.05590498 0.05723887 0.06057095 0.06262499 0.05803287 0.06434196 0.05786883 0.05620098 0.05393087 0.04880297 0.05562198 0.04731082 0.05786883 0.05620098 0.05495584 0.05864 0.05485385 0.05827397 0.05590498 0.05723887 0.05295795 0.05026286 0.05590498 0.05723887 0.05485385 0.05827397 0.05508697 0.05911797 0.05495584 0.05864 0.05590498 0.05723887 0.05651098 0.06550598 0.05508697 0.05911797 0.05590498 0.05723887 0.05803287 0.06434196 0.05651098 0.06550598 0.05590498 0.05723887 0.05295795 0.05026286 0.05393087 0.04880297 0.05590498 0.05723887 0.0551669 0.05945897 0.05485385 0.05827397 0.05495584 0.05864 0.05328083 0.05319899 0.05295795 0.05026286 0.05485385 0.05827397 0.0551669 0.05945897 0.05328083 0.05319899 0.05485385 0.05827397 0.0551669 0.05945897 0.05495584 0.05864 0.05508697 0.05911797 0.05646497 0.06571698 0.05508697 0.05911797 0.05651098 0.06550598 0.0551669 0.05945897 0.05508697 0.05911797 0.05646497 0.06571698 0.05675399 0.06744599 0.05651098 0.06550598 0.05803287 0.06434196 0.05646497 0.06571698 0.05651098 0.06550598 0.05675399 0.06744599 0.05868196 0.066733 0.05803287 0.06434196 0.06057095 0.06262499 0.05868196 0.066733 0.05675399 0.06744599 0.05803287 0.06434196 0.06158185 0.065889 0.06057095 0.06262499 0.06246685 0.06177687 0.06158185 0.065889 0.05868196 0.066733 0.06057095 0.06262499 0.06544798 0.065171 0.06246685 0.06177687 0.06491196 0.06092596 0.06544798 0.065171 0.06158185 0.065889 0.06246685 0.06177687 0.06544798 0.065171 0.06491196 0.06092596 0.06806099 0.06008487 0.07024496 0.064561 0.06806099 0.06008487 0.07200396 0.05928587 0.07024496 0.064561 0.06544798 0.065171 0.06806099 0.06008487 0.07592695 0.06405097 0.07200396 0.05928587 0.07588195 0.05866897 0.07592695 0.06405097 0.07024496 0.064561 0.07200396 0.05928587 0.07592695 0.06405097 0.07588195 0.05866897 0.07936596 0.05821084 0.08243596 0.06361895 0.07592695 0.06405097 0.07936596 0.05821084 0.05601096 0.035703 0.06443196 0.04263287 0.06093084 0.044227 0.05380195 0.03748399 0.06093084 0.044227 0.05797499 0.04578596 0.05380195 0.03748399 0.05601096 0.035703 0.06093084 0.044227 0.05204898 0.03922498 0.05797499 0.04578596 0.05562198 0.04731082 0.05204898 0.03922498 0.05380195 0.03748399 0.05797499 0.04578596 0.05080085 0.04092997 0.05562198 0.04731082 0.05393087 0.04880297 0.05080085 0.04092997 0.05204898 0.03922498 0.05562198 0.04731082 0.05010885 0.04259783 0.05393087 0.04880297 0.05295795 0.05026286 0.05010885 0.04259783 0.05080085 0.04092997 0.05393087 0.04880297 0.05328083 0.05319899 0.05276799 0.05169987 0.05295795 0.05026286 0.05001884 0.04422998 0.05295795 0.05026286 0.05276799 0.05169987 0.05001884 0.04422998 0.05010885 0.04259783 0.05295795 0.05026286 0.05349683 0.05359697 0.05276799 0.05169987 0.05328083 0.05319899 0.05134499 0.04779595 0.05001884 0.04422998 0.05276799 0.05169987 0.05349683 0.05359697 0.05134499 0.04779595 0.05276799 0.05169987 0.05349683 0.05359697 0.05328083 0.05319899 0.0551669 0.05945897 0.04871785 0.03077799 0.05601096 0.035703 0.05380195 0.03748399 0.04761683 0.03249299 0.05380195 0.03748399 0.05204898 0.03922498 0.04761683 0.03249299 0.04871785 0.03077799 0.05380195 0.03748399 0.046884 0.03417098 0.05204898 0.03922498 0.05080085 0.04092997 0.046884 0.03417098 0.04761683 0.03249299 0.05204898 0.03922498 0.04655796 0.03581297 0.05080085 0.04092997 0.05010885 0.04259783 0.04655796 0.03581297 0.046884 0.03417098 0.05080085 0.04092997 0.04667782 0.03741997 0.05010885 0.04259783 0.05001884 0.04422998 0.04667782 0.03741997 0.04655796 0.03581297 0.05010885 0.04259783 0.05134499 0.04779595 0.050601 0.04586786 0.05001884 0.04422998 0.04728299 0.038993 0.05001884 0.04422998 0.050601 0.04586786 0.04728299 0.038993 0.04667782 0.03741997 0.05001884 0.04422998 0.05166995 0.04823297 0.050601 0.04586786 0.05134499 0.04779595 0.05020797 0.04487395 0.04728299 0.038993 0.050601 0.04586786 0.05166995 0.04823297 0.05020797 0.04487395 0.050601 0.04586786 0.05166995 0.04823297 0.05134499 0.04779595 0.05349683 0.05359697 0.04254084 0.02724796 0.04871785 0.03077799 0.04761683 0.03249299 0.042364 0.02866798 0.04761683 0.03249299 0.046884 0.03417098 0.042364 0.02866798 0.04254084 0.02724796 0.04761683 0.03249299 0.04244399 0.03005695 0.046884 0.03417098 0.04655796 0.03581297 0.04244399 0.03005695 0.042364 0.02866798 0.046884 0.03417098 0.04280591 0.03141695 0.04655796 0.03581297 0.04667782 0.03741997 0.04280591 0.03141695 0.04244399 0.03005695 0.04655796 0.03581297 0.04347383 0.03274697 0.04667782 0.03741997 0.04728299 0.038993 0.04347383 0.03274697 0.04280591 0.03141695 0.04667782 0.03741997 0.04940187 0.04288583 0.04843795 0.04059284 0.04728299 0.038993 0.04447382 0.034051 0.04728299 0.038993 0.04843795 0.04059284 0.05020797 0.04487395 0.04940187 0.04288583 0.04728299 0.038993 0.04447382 0.034051 0.04347383 0.03274697 0.04728299 0.038993 0.04979497 0.043338 0.04843795 0.04059284 0.04940187 0.04288583 0.04587388 0.03537297 0.04447382 0.034051 0.04843795 0.04059284 0.04745882 0.03836095 0.04587388 0.03537297 0.04843795 0.04059284 0.04979497 0.043338 0.04745882 0.03836095 0.04843795 0.04059284 0.05166995 0.04823297 0.04940187 0.04288583 0.05020797 0.04487395 0.04979497 0.043338 0.04940187 0.04288583 0.05166995 0.04823297 0.03724282 0.024818 0.04254084 0.02724796 0.042364 0.02866798 0.03790485 0.02596497 0.042364 0.02866798 0.04244399 0.03005695 0.03790485 0.02596497 0.03724282 0.024818 0.042364 0.02866798 0.03876495 0.027085 0.04244399 0.03005695 0.04280591 0.03141695 0.03876495 0.027085 0.03790485 0.02596497 0.04244399 0.03005695 0.03983891 0.02817696 0.04280591 0.03141695 0.04347383 0.03274697 0.03983891 0.02817696 0.03876495 0.027085 0.04280591 0.03141695 0.04114699 0.02924299 0.04347383 0.03274697 0.04447382 0.034051 0.04114699 0.02924299 0.03983891 0.02817696 0.04347383 0.03274697 0.042732 0.03030186 0.04447382 0.034051 0.04587388 0.03537297 0.042732 0.03030186 0.04114699 0.02924299 0.04447382 0.034051 0.04669195 0.036484 0.04587388 0.03537297 0.04745882 0.03836095 0.04407882 0.03235596 0.042732 0.03030186 0.04587388 0.03537297 0.046148 0.034886 0.04407882 0.03235596 0.04587388 0.03537297 0.04617697 0.03498399 0.046148 0.034886 0.04587388 0.03537297 0.04669195 0.036484 0.04617697 0.03498399 0.04587388 0.03537297 0.04786199 0.03883183 0.04669195 0.036484 0.04745882 0.03836095 0.04786199 0.03883183 0.04745882 0.03836095 0.04979497 0.043338 0.04385387 0.03094995 0.042732 0.03030186 0.04407882 0.03235596 0.046148 0.034886 0.04385387 0.03094995 0.04407882 0.03235596 0.04613697 0.03484886 0.04385387 0.03094995 0.046148 0.034886 0.04574698 0.03220999 0.04429584 0.02967482 0.04385387 0.03094995 0.04613697 0.03484886 0.04574698 0.03220999 0.04385387 0.03094995 0.04693496 0.035613 0.046148 0.034886 0.04617697 0.03498399 0.04693496 0.035613 0.04613697 0.03484886 0.046148 0.034886 0.04786199 0.03883183 0.04617697 0.03498399 0.04669195 0.036484 0.04693496 0.035613 0.04617697 0.03498399 0.04786199 0.03883183 0.04582285 0.02977287 0.04429584 0.02967482 0.04574698 0.03220999 0.04693496 0.035613 0.04574698 0.03220999 0.04613697 0.03484886 0.04674082 0.03058797 0.04582285 0.02977287 0.04574698 0.03220999 0.04670995 0.03287386 0.04674082 0.03058797 0.04574698 0.03220999 0.04693496 0.035613 0.04670995 0.03287386 0.04574698 0.03220999 0.04674082 0.03058797 0.04733383 0.02870082 0.04582285 0.02977287 0.04783797 0.03100287 0.04733383 0.02870082 0.04674082 0.03058797 0.04783797 0.03100287 0.04845899 0.029127 0.04733383 0.02870082 0.04783797 0.03100287 0.04674082 0.03058797 0.04670995 0.03287386 0.04706895 0.03304886 0.04783797 0.03100287 0.04670995 0.03287386 0.04786884 0.03606283 0.04706895 0.03304886 0.04670995 0.03287386 0.04786884 0.03606283 0.04670995 0.03287386 0.04693496 0.035613 0.04984086 0.02909886 0.04963582 0.02770799 0.04845899 0.029127 0.04984086 0.02909886 0.05132198 0.02771699 0.04963582 0.02770799 0.04905086 0.03103399 0.04845899 0.029127 0.04783797 0.03100287 0.04905086 0.03103399 0.04984086 0.02909886 0.04845899 0.029127 0.04706895 0.03304886 0.04783797 0.03332787 0.04783797 0.03100287 0.04905086 0.03103399 0.04783797 0.03100287 0.04783797 0.03332787 0.04786884 0.03606283 0.04783797 0.03332787 0.04706895 0.03304886 0.04865199 0.03349983 0.04905086 0.03103399 0.04783797 0.03332787 0.04893589 0.03631585 0.04865199 0.03349983 0.04783797 0.03332787 0.04893589 0.03631585 0.04783797 0.03332787 0.04786884 0.03606283 0.05379384 0.02725595 0.05329185 0.026802 0.05132198 0.02771699 0.05517786 0.02681297 0.056728 0.02650797 0.05329185 0.026802 0.05379384 0.02725595 0.05517786 0.02681297 0.05329185 0.026802 0.05261182 0.02782785 0.05132198 0.02771699 0.04984086 0.02909886 0.05261182 0.02782785 0.05379384 0.02725595 0.05132198 0.02771699 0.05096298 0.02929699 0.04984086 0.02909886 0.04905086 0.03103399 0.05096298 0.02929699 0.05261182 0.02782785 0.04984086 0.02909886 0.04865199 0.03349983 0.04907184 0.03354597 0.04905086 0.03103399 0.05023497 0.03121984 0.04905086 0.03103399 0.04907184 0.03354597 0.05023497 0.03121984 0.05096298 0.02929699 0.04905086 0.03103399 0.05008482 0.03636085 0.04907184 0.03354597 0.04865199 0.03349983 0.05033987 0.03351998 0.05023497 0.03121984 0.04907184 0.03354597 0.05124396 0.03615397 0.05033987 0.03351998 0.04907184 0.03354597 0.05124396 0.03615397 0.04907184 0.03354597 0.05126297 0.03619498 0.05008482 0.03636085 0.05126297 0.03619498 0.04907184 0.03354597 0.05008482 0.03636085 0.04865199 0.03349983 0.04893589 0.03631585 0.06066387 0.026317 0.058025 0.02631998 0.05844783 0.02633899 0.07580399 0.02596497 0.05844783 0.02633899 0.056728 0.02650797 0.07613295 0.02600383 0.06066387 0.026317 0.05844783 0.02633899 0.07613295 0.02600383 0.05844783 0.02633899 0.07580399 0.02596497 0.07580399 0.02596497 0.056728 0.02650797 0.05517786 0.02681297 0.07580399 0.02596497 0.05517786 0.02681297 0.05379384 0.02725595 0.07504999 0.02688598 0.05379384 0.02725595 0.05261182 0.02782785 0.07580399 0.02596497 0.05379384 0.02725595 0.07504999 0.02688598 0.07504999 0.02688598 0.05261182 0.02782785 0.05096298 0.02929699 0.07431197 0.02931797 0.05096298 0.02929699 0.05023497 0.03121984 0.07504999 0.02688598 0.05096298 0.02929699 0.07431197 0.02931797 0.07431197 0.02931797 0.05023497 0.03121984 0.05033987 0.03351998 0.07431197 0.02931797 0.05033987 0.03351998 0.07362198 0.03322899 0.05124396 0.03615397 0.07362198 0.03322899 0.05033987 0.03351998 0.0385499 0.02709299 0.06295597 0.02648997 0.06356 0.02653586 0.0385499 0.02709299 0.03834682 0.02698493 0.06295597 0.02648997 0.07613295 0.02600383 0.06356 0.02653586 0.06066387 0.026317 0.077196 0.02783685 0.0385499 0.02709299 0.06356 0.02653586 0.07646 0.02626097 0.077196 0.02783685 0.06356 0.02653586 0.07613295 0.02600383 0.07646 0.02626097 0.06356 0.02653586 0.03731983 0.027278 0.03834682 0.02698493 0.0385499 0.02709299 0.03976684 0.02864187 0.03731983 0.027278 0.0385499 0.02709299 0.077196 0.02783685 0.03976684 0.02864187 0.0385499 0.02709299 0.03628695 0.02993798 0.034298 0.02943295 0.03448587 0.02917695 0.03628695 0.02993798 0.03542697 0.03084695 0.034298 0.02943295 0.03628695 0.02993798 0.03448587 0.02917695 0.035133 0.02848196 0.03733599 0.02924096 0.035133 0.02848196 0.03562682 0.02808499 0.03733599 0.02924096 0.03628695 0.02993798 0.035133 0.02848196 0.03733599 0.02924096 0.03562682 0.02808499 0.03615885 0.02774995 0.03851598 0.02879399 0.03615885 0.02774995 0.03702396 0.02736896 0.03851598 0.02879399 0.03733599 0.02924096 0.03615885 0.02774995 0.03851598 0.02879399 0.03702396 0.02736896 0.03731983 0.027278 0.03976684 0.02864187 0.03851598 0.02879399 0.03731983 0.027278 0.03628695 0.1089439 0.03542697 0.108035 0.03604996 0.10545 0.03693199 0.106301 0.03604996 0.10545 0.03625386 0.101817 0.03693199 0.106301 0.03628695 0.1089439 0.03604996 0.10545 0.03715497 0.102594 0.03625386 0.101817 0.03615885 0.09727197 0.03715497 0.102594 0.03693199 0.106301 0.03625386 0.101817 0.03707391 0.09795296 0.03615885 0.09727197 0.03588998 0.09195196 0.03707391 0.09795296 0.03715497 0.102594 0.03615885 0.09727197 0.03681486 0.09251695 0.03588998 0.09195196 0.03556984 0.08600097 0.03681486 0.09251695 0.03707391 0.09795296 0.03588998 0.09195196 0.03650099 0.08642596 0.03556984 0.08600097 0.03529298 0.07957696 0.03650099 0.08642596 0.03681486 0.09251695 0.03556984 0.08600097 0.036228 0.07984197 0.03529298 0.07957696 0.03513383 0.07285398 0.036228 0.07984197 0.03650099 0.08642596 0.03529298 0.07957696 0.036071 0.07294499 0.03513383 0.07285398 0.03513383 0.06602698 0.036071 0.07294499 0.036228 0.07984197 0.03513383 0.07285398 0.036071 0.06593596 0.03513383 0.06602698 0.03529298 0.05930387 0.036071 0.06593596 0.036071 0.07294499 0.03513383 0.06602698 0.036228 0.05903887 0.03529298 0.05930387 0.03556895 0.05287986 0.036228 0.05903887 0.036071 0.06593596 0.03529298 0.05930387 0.03650099 0.05245482 0.03556895 0.05287986 0.03588998 0.04692995 0.03650099 0.05245482 0.036228 0.05903887 0.03556895 0.05287986 0.036816 0.04636496 0.03588998 0.04692995 0.03615999 0.04161083 0.036816 0.04636496 0.03650099 0.05245482 0.03588998 0.04692995 0.03707498 0.04092997 0.03615999 0.04161083 0.03625386 0.03706485 0.03707498 0.04092997 0.036816 0.04636496 0.03615999 0.04161083 0.03715497 0.03628885 0.03625386 0.03706485 0.03604882 0.03343182 0.03715497 0.03628885 0.03707498 0.04092997 0.03625386 0.03706485 0.03693199 0.03258097 0.03604882 0.03343182 0.03542697 0.03084695 0.03693199 0.03258097 0.03715497 0.03628885 0.03604882 0.03343182 0.03628695 0.02993798 0.03693199 0.03258097 0.03542697 0.03084695 0.03733599 0.109641 0.03628695 0.1089439 0.03693199 0.106301 0.03801 0.106945 0.03693199 0.106301 0.03715497 0.102594 0.03801 0.106945 0.03733599 0.109641 0.03693199 0.106301 0.03826493 0.103168 0.03715497 0.102594 0.03707391 0.09795296 0.03826493 0.103168 0.03801 0.106945 0.03715497 0.102594 0.03821682 0.09844499 0.03707391 0.09795296 0.03681486 0.09251695 0.03821682 0.09844499 0.03826493 0.103168 0.03707391 0.09795296 0.03798896 0.09291398 0.03681486 0.09251695 0.03650099 0.08642596 0.03798896 0.09291398 0.03821682 0.09844499 0.03681486 0.09251695 0.03770196 0.086717 0.03650099 0.08642596 0.036228 0.07984197 0.03770196 0.086717 0.03798896 0.09291398 0.03650099 0.08642596 0.03744786 0.08002001 0.036228 0.07984197 0.036071 0.07294499 0.03744786 0.08002001 0.03770196 0.086717 0.036228 0.07984197 0.037301 0.07300496 0.036071 0.07294499 0.036071 0.06593596 0.037301 0.07300496 0.03744786 0.08002001 0.036071 0.07294499 0.037301 0.065876 0.036071 0.06593596 0.036228 0.05903887 0.037301 0.065876 0.037301 0.07300496 0.036071 0.06593596 0.03744786 0.05886083 0.036228 0.05903887 0.03650099 0.05245482 0.03744786 0.05886083 0.037301 0.065876 0.036228 0.05903887 0.03770196 0.052163 0.03650099 0.05245482 0.036816 0.04636496 0.03770196 0.052163 0.03744786 0.05886083 0.03650099 0.05245482 0.03798997 0.04596787 0.036816 0.04636496 0.03707498 0.04092997 0.03798997 0.04596787 0.03770196 0.052163 0.036816 0.04636496 0.03821682 0.04043895 0.03707498 0.04092997 0.03715497 0.03628885 0.03821682 0.04043895 0.03798997 0.04596787 0.03707498 0.04092997 0.03826493 0.03571397 0.03715497 0.03628885 0.03693199 0.03258097 0.03826493 0.03571397 0.03821682 0.04043895 0.03715497 0.03628885 0.03800886 0.031937 0.03693199 0.03258097 0.03628695 0.02993798 0.03800886 0.031937 0.03826493 0.03571397 0.03693199 0.03258097 0.03733599 0.02924096 0.03800886 0.031937 0.03628695 0.02993798 0.03851598 0.110088 0.03733599 0.109641 0.03801 0.106945 0.03921997 0.107345 0.03801 0.106945 0.03826493 0.103168 0.03921997 0.107345 0.03851598 0.110088 0.03801 0.106945 0.039514 0.103507 0.03826493 0.103168 0.03821682 0.09844499 0.039514 0.103507 0.03921997 0.107345 0.03826493 0.103168 0.03950995 0.09871399 0.03821682 0.09844499 0.03798896 0.09291398 0.03950995 0.09871399 0.039514 0.103507 0.03821682 0.09844499 0.03932684 0.093113 0.03798896 0.09291398 0.03770196 0.086717 0.03932684 0.093113 0.03950995 0.09871399 0.03798896 0.09291398 0.03907787 0.08685195 0.03770196 0.086717 0.03744786 0.08002001 0.03907787 0.08685195 0.03932684 0.093113 0.03770196 0.086717 0.038854 0.08009696 0.03744786 0.08002001 0.037301 0.07300496 0.038854 0.08009696 0.03907787 0.08685195 0.03744786 0.08002001 0.03872299 0.07302898 0.037301 0.07300496 0.037301 0.065876 0.03872299 0.07302898 0.038854 0.08009696 0.037301 0.07300496 0.03872299 0.06585198 0.037301 0.065876 0.03744786 0.05886083 0.03872299 0.06585198 0.03872299 0.07302898 0.037301 0.065876 0.038854 0.05878382 0.03744786 0.05886083 0.03770196 0.052163 0.038854 0.05878382 0.03872299 0.06585198 0.03744786 0.05886083 0.03907787 0.05202895 0.03770196 0.052163 0.03798997 0.04596787 0.03907787 0.05202895 0.038854 0.05878382 0.03770196 0.052163 0.03932684 0.04576885 0.03798997 0.04596787 0.03821682 0.04043895 0.03932684 0.04576885 0.03907787 0.05202895 0.03798997 0.04596787 0.03951096 0.040169 0.03821682 0.04043895 0.03826493 0.03571397 0.03951096 0.040169 0.03932684 0.04576885 0.03821682 0.04043895 0.039514 0.03537487 0.03826493 0.03571397 0.03800886 0.031937 0.039514 0.03537487 0.03951096 0.040169 0.03826493 0.03571397 0.03921896 0.03153687 0.03800886 0.031937 0.03733599 0.02924096 0.03921896 0.03153687 0.039514 0.03537487 0.03800886 0.031937 0.03851598 0.02879399 0.03921896 0.03153687 0.03733599 0.02924096 0.03977096 0.110232 0.03851598 0.110088 0.03921997 0.107345 0.04051697 0.107314 0.03921997 0.107345 0.039514 0.103507 0.04051697 0.107314 0.03977096 0.110232 0.03921997 0.107345 0.04084295 0.103132 0.039514 0.103507 0.03950995 0.09871399 0.04084295 0.103132 0.04051697 0.107314 0.039514 0.103507 0.04085499 0.09784299 0.03950995 0.09871399 0.03932684 0.093113 0.04085499 0.09784299 0.04084295 0.103132 0.03950995 0.09871399 0.04068398 0.091596 0.03932684 0.093113 0.03907787 0.08685195 0.04077982 0.094819 0.04085499 0.09784299 0.03932684 0.093113 0.04068398 0.091596 0.04077982 0.094819 0.03932684 0.093113 0.04045796 0.08466196 0.03907787 0.08685195 0.038854 0.08009696 0.04056799 0.08820199 0.04068398 0.091596 0.03907787 0.08685195 0.04045796 0.08466196 0.04056799 0.08820199 0.03907787 0.08685195 0.04027485 0.07725095 0.038854 0.08009696 0.03872299 0.07302898 0.04035395 0.08100301 0.04045796 0.08466196 0.038854 0.08009696 0.04027485 0.07725095 0.04035395 0.08100301 0.038854 0.08009696 0.040205 0.069588 0.03872299 0.07302898 0.03872299 0.06585198 0.04022186 0.07343596 0.04027485 0.07725095 0.03872299 0.07302898 0.040205 0.069588 0.04022186 0.07343596 0.03872299 0.07302898 0.04021996 0.06573498 0.03872299 0.06585198 0.038854 0.05878382 0.04021996 0.06573498 0.040205 0.069588 0.03872299 0.06585198 0.04034799 0.05813497 0.038854 0.05878382 0.03907787 0.05202895 0.04027098 0.06190699 0.04021996 0.06573498 0.038854 0.05878382 0.04034799 0.05813497 0.04027098 0.06190699 0.038854 0.05878382 0.04056096 0.05087482 0.03907787 0.05202895 0.03932684 0.04576885 0.04045099 0.05444782 0.04034799 0.05813497 0.03907787 0.05202895 0.04056096 0.05087482 0.04045099 0.05444782 0.03907787 0.05202895 0.04077684 0.04418796 0.03932684 0.04576885 0.03951096 0.040169 0.04067885 0.04744595 0.04056096 0.05087482 0.03932684 0.04576885 0.04077684 0.04418796 0.04067885 0.04744595 0.03932684 0.04576885 0.04087698 0.03832083 0.03951096 0.040169 0.039514 0.03537487 0.04085499 0.04112899 0.04077684 0.04418796 0.03951096 0.040169 0.04087698 0.03832083 0.04085499 0.04112899 0.03951096 0.040169 0.04051697 0.03156799 0.039514 0.03537487 0.03921896 0.03153687 0.04084396 0.03578299 0.04087698 0.03832083 0.039514 0.03537487 0.04051697 0.03156799 0.04084396 0.03578299 0.039514 0.03537487 0.03976684 0.02864187 0.03921896 0.03153687 0.03851598 0.02879399 0.03976684 0.02864187 0.04051697 0.03156799 0.03921896 0.03153687 0.07719296 0.111056 0.03977096 0.110232 0.04051697 0.107314 0.07719296 0.111056 0.07646 0.11262 0.03977096 0.110232 0.07788896 0.108097 0.04051697 0.107314 0.04084295 0.103132 0.07788896 0.108097 0.07719296 0.111056 0.04051697 0.107314 0.07851999 0.103852 0.04084295 0.103132 0.04085499 0.09784299 0.07851999 0.103852 0.07788896 0.108097 0.04084295 0.103132 0.07906496 0.09849798 0.04085499 0.09784299 0.04077982 0.094819 0.07906496 0.09849798 0.07851999 0.103852 0.04085499 0.09784299 0.07950896 0.09218698 0.04077982 0.094819 0.04068398 0.091596 0.07950896 0.09218698 0.07906496 0.09849798 0.04077982 0.094819 0.07969099 0.08870297 0.04068398 0.091596 0.04056799 0.08820199 0.07969099 0.08870297 0.07950896 0.09218698 0.04068398 0.091596 0.07984095 0.08507895 0.04056799 0.08820199 0.04045796 0.08466196 0.07984095 0.08507895 0.07969099 0.08870297 0.04056799 0.08820199 0.07995998 0.08132195 0.04045796 0.08466196 0.04035395 0.08100301 0.07995998 0.08132195 0.07984095 0.08507895 0.04045796 0.08466196 0.08004498 0.07748597 0.04035395 0.08100301 0.04027485 0.07725095 0.08004498 0.07748597 0.07995998 0.08132195 0.04035395 0.08100301 0.08009696 0.07358598 0.04027485 0.07725095 0.04022186 0.07343596 0.08009696 0.07358598 0.08004498 0.07748597 0.04027485 0.07725095 0.08011597 0.069669 0.04022186 0.07343596 0.040205 0.069588 0.08011597 0.069669 0.08009696 0.07358598 0.04022186 0.07343596 0.08010095 0.06574696 0.040205 0.069588 0.04021996 0.06573498 0.08010095 0.06574696 0.08011597 0.069669 0.040205 0.069588 0.08005297 0.06183499 0.04021996 0.06573498 0.04027098 0.06190699 0.08005297 0.06183499 0.08010095 0.06574696 0.04021996 0.06573498 0.07997095 0.05797696 0.04027098 0.06190699 0.04034799 0.05813497 0.07997095 0.05797696 0.08005297 0.06183499 0.04027098 0.06190699 0.07985496 0.05419099 0.04034799 0.05813497 0.04045099 0.05444782 0.07985496 0.05419099 0.07997095 0.05797696 0.04034799 0.05813497 0.07970798 0.05053097 0.04045099 0.05444782 0.04056096 0.05087482 0.07970798 0.05053097 0.07985496 0.05419099 0.04045099 0.05444782 0.07952696 0.04700398 0.04056096 0.05087482 0.04067885 0.04744595 0.07952696 0.04700398 0.07970798 0.05053097 0.04056096 0.05087482 0.079319 0.04368984 0.04067885 0.04744595 0.04077684 0.04418796 0.079319 0.04368984 0.07952696 0.04700398 0.04067885 0.04744595 0.07908296 0.04059797 0.04077684 0.04418796 0.04085499 0.04112899 0.07908296 0.04059797 0.079319 0.04368984 0.04077684 0.04418796 0.07908296 0.04059797 0.04085499 0.04112899 0.04087698 0.03832083 0.07853496 0.03515297 0.04087698 0.03832083 0.04084396 0.03578299 0.07853496 0.03515297 0.07908296 0.04059797 0.04087698 0.03832083 0.07789796 0.03083688 0.04084396 0.03578299 0.04051697 0.03156799 0.07789796 0.03083688 0.07853496 0.03515297 0.04084396 0.03578299 0.077196 0.02783685 0.04051697 0.03156799 0.03976684 0.02864187 0.077196 0.02783685 0.07789796 0.03083688 0.04051697 0.03156799 0.07687699 0.108488 0.07646 0.11262 0.07719296 0.111056 0.076137 0.109565 0.07613295 0.112878 0.07646 0.11262 0.07687699 0.108488 0.076137 0.109565 0.07646 0.11262 0.077578 0.1059589 0.07719296 0.111056 0.07788896 0.108097 0.077578 0.1059589 0.07687699 0.108488 0.07719296 0.111056 0.078215 0.102097 0.07788896 0.108097 0.07851999 0.103852 0.078215 0.102097 0.077578 0.1059589 0.07788896 0.108097 0.07876795 0.09705799 0.07851999 0.103852 0.07906496 0.09849798 0.07876795 0.09705799 0.078215 0.102097 0.07851999 0.103852 0.07921499 0.09107297 0.07906496 0.09849798 0.07950896 0.09218698 0.07921499 0.09107297 0.07876795 0.09705799 0.07906496 0.09849798 0.07954698 0.084315 0.07950896 0.09218698 0.07969099 0.08870297 0.07954698 0.084315 0.07921499 0.09107297 0.07950896 0.09218698 0.07975095 0.07700997 0.07969099 0.08870297 0.07984095 0.08507895 0.07975095 0.07700997 0.07954698 0.084315 0.07969099 0.08870297 0.07985496 0.05419099 0.07984095 0.08507895 0.07995998 0.08132195 0.07981997 0.06944096 0.07984095 0.08507895 0.07985496 0.05419099 0.07980197 0.07325595 0.07984095 0.08507895 0.07981997 0.06944096 0.07980197 0.07325595 0.07975095 0.07700997 0.07984095 0.08507895 0.07997095 0.05797696 0.07995998 0.08132195 0.08004498 0.07748597 0.07985496 0.05419099 0.07995998 0.08132195 0.07997095 0.05797696 0.08005297 0.06183499 0.08004498 0.07748597 0.08009696 0.07358598 0.07997095 0.05797696 0.08004498 0.07748597 0.08005297 0.06183499 0.08010095 0.06574696 0.08009696 0.07358598 0.08011597 0.069669 0.08005297 0.06183499 0.08009696 0.07358598 0.08010095 0.06574696 0.07981997 0.06944096 0.07985496 0.05419099 0.07970798 0.05053097 0.07954895 0.05462884 0.07970798 0.05053097 0.07952696 0.04700398 0.07975196 0.06191384 0.07981997 0.06944096 0.07970798 0.05053097 0.07954895 0.05462884 0.07975196 0.06191384 0.07970798 0.05053097 0.07954895 0.05462884 0.07952696 0.04700398 0.079319 0.04368984 0.07921898 0.04786795 0.079319 0.04368984 0.07908296 0.04059797 0.07921898 0.04786795 0.07954895 0.05462884 0.079319 0.04368984 0.07877099 0.04185998 0.07908296 0.04059797 0.07853496 0.03515297 0.07877099 0.04185998 0.07921898 0.04786795 0.07908296 0.04059797 0.07821595 0.03679198 0.07853496 0.03515297 0.07789796 0.03083688 0.07821595 0.03679198 0.07877099 0.04185998 0.07853496 0.03515297 0.07757496 0.03290885 0.07789796 0.03083688 0.077196 0.02783685 0.07757496 0.03290885 0.07821595 0.03679198 0.07789796 0.03083688 0.07687097 0.03037798 0.077196 0.02783685 0.07646 0.02626097 0.07687097 0.03037798 0.07757496 0.03290885 0.077196 0.02783685 0.07687097 0.03037798 0.07646 0.02626097 0.07613295 0.02600383 0.07538497 0.109113 0.07580399 0.112916 0.07613295 0.112878 0.05844783 0.112543 0.07613295 0.112878 0.07580399 0.112916 0.076137 0.109565 0.07538497 0.109113 0.07613295 0.112878 0.06104195 0.112551 0.07613295 0.112878 0.05844783 0.112543 0.07538497 0.109113 0.075046 0.111987 0.07580399 0.112916 0.05844783 0.112543 0.07580399 0.112916 0.075046 0.111987 0.074647 0.107104 0.074301 0.109518 0.075046 0.111987 0.052688 0.111099 0.075046 0.111987 0.074301 0.109518 0.07538497 0.109113 0.074647 0.107104 0.075046 0.111987 0.05676686 0.112379 0.05844783 0.112543 0.075046 0.111987 0.05524283 0.112085 0.05676686 0.112379 0.075046 0.111987 0.05387085 0.111656 0.05524283 0.112085 0.075046 0.111987 0.052688 0.111099 0.05387085 0.111656 0.075046 0.111987 0.07395595 0.1035709 0.07360595 0.105535 0.074301 0.109518 0.05024296 0.107718 0.074301 0.109518 0.07360595 0.105535 0.074647 0.107104 0.07395595 0.1035709 0.074301 0.109518 0.05100786 0.109647 0.052688 0.111099 0.074301 0.109518 0.05024296 0.107718 0.05100786 0.109647 0.074301 0.109518 0.07334196 0.09862595 0.07299095 0.100172 0.07360595 0.105535 0.05124199 0.102734 0.07360595 0.105535 0.07299095 0.100172 0.07395595 0.1035709 0.07334196 0.09862595 0.07360595 0.105535 0.05033987 0.105361 0.05024296 0.107718 0.07360595 0.105535 0.05124199 0.102734 0.05033987 0.105361 0.07360595 0.105535 0.07283598 0.09249699 0.072721 0.09702301 0.07299095 0.100172 0.05294895 0.099357 0.07299095 0.100172 0.072721 0.09702301 0.07334196 0.09862595 0.07283598 0.09249699 0.07299095 0.100172 0.05126386 0.102686 0.05124199 0.102734 0.07299095 0.100172 0.05294895 0.099357 0.05126386 0.102686 0.07299095 0.100172 0.072456 0.085388 0.07248097 0.09358596 0.072721 0.09702301 0.05513387 0.09507495 0.072721 0.09702301 0.07248097 0.09358596 0.07283598 0.09249699 0.072456 0.085388 0.072721 0.09702301 0.05513387 0.09507495 0.05294895 0.099357 0.072721 0.09702301 0.072456 0.085388 0.072272 0.08987295 0.07248097 0.09358596 0.05609995 0.09304195 0.07248097 0.09358596 0.072272 0.08987295 0.05609995 0.09304195 0.05513387 0.09507495 0.07248097 0.09358596 0.07213997 0.06944096 0.07209795 0.08597296 0.072272 0.08987295 0.05892282 0.08650696 0.072272 0.08987295 0.07209795 0.08597296 0.07221996 0.077582 0.07213997 0.06944096 0.072272 0.08987295 0.072456 0.085388 0.07221996 0.077582 0.072272 0.08987295 0.05731195 0.09037399 0.05609995 0.09304195 0.072272 0.08987295 0.05892282 0.08650696 0.05731195 0.09037399 0.072272 0.08987295 0.07197499 0.05652898 0.07196199 0.08190095 0.07209795 0.08597296 0.05939882 0.08528 0.07209795 0.08597296 0.07196199 0.08190095 0.072115 0.05249196 0.07197499 0.05652898 0.07209795 0.08597296 0.07213997 0.06944096 0.072115 0.05249196 0.07209795 0.08597296 0.05939882 0.08528 0.05892282 0.08650696 0.07209795 0.08597296 0.07187497 0.06068098 0.07186597 0.07772296 0.07196199 0.08190095 0.06121587 0.079966 0.07196199 0.08190095 0.07186597 0.07772296 0.07197499 0.05652898 0.07187497 0.06068098 0.07196199 0.08190095 0.06121587 0.079966 0.05939882 0.08528 0.07196199 0.08190095 0.07181298 0.06492197 0.07180798 0.07346695 0.07186597 0.07772296 0.06276297 0.07356196 0.07186597 0.07772296 0.07180798 0.07346695 0.07187497 0.06068098 0.07181298 0.06492197 0.07186597 0.07772296 0.06130594 0.079665 0.06121587 0.079966 0.07186597 0.07772296 0.06276297 0.07356196 0.06130594 0.079665 0.07186597 0.07772296 0.07181298 0.06492197 0.07178997 0.06919199 0.07180798 0.07346695 0.06312298 0.06944 0.07180798 0.07346695 0.07178997 0.06919199 0.06312298 0.06944 0.06276297 0.07356196 0.07180798 0.07346695 0.06276297 0.06531995 0.07178997 0.06919199 0.07181298 0.06492197 0.06276297 0.06531995 0.06312298 0.06944 0.07178997 0.06919199 0.06276297 0.06531995 0.07181298 0.06492197 0.07187497 0.06068098 0.06130594 0.05921489 0.07187497 0.06068098 0.07197499 0.05652898 0.06130594 0.05921489 0.06276297 0.06531995 0.07187497 0.06068098 0.05939882 0.05360198 0.07197499 0.05652898 0.072115 0.05249196 0.06121999 0.05892795 0.06130594 0.05921489 0.07197499 0.05652898 0.05939882 0.05360198 0.06121999 0.05892795 0.07197499 0.05652898 0.07222098 0.06125396 0.07229 0.04863482 0.072115 0.05249196 0.05892884 0.05238986 0.072115 0.05249196 0.07229 0.04863482 0.07216095 0.06531 0.07222098 0.06125396 0.072115 0.05249196 0.07213997 0.06944096 0.07216095 0.06531 0.072115 0.05249196 0.05892884 0.05238986 0.05939882 0.05360198 0.072115 0.05249196 0.07245898 0.05342698 0.07250195 0.04497283 0.07229 0.04863482 0.05731195 0.048509 0.07229 0.04863482 0.07250195 0.04497283 0.07222098 0.06125396 0.07245898 0.05342698 0.07229 0.04863482 0.05731195 0.048509 0.05892884 0.05238986 0.07229 0.04863482 0.07283997 0.04632395 0.07301098 0.03849285 0.07250195 0.04497283 0.05513495 0.04380697 0.07250195 0.04497283 0.07301098 0.03849285 0.07245898 0.05342698 0.07283997 0.04632395 0.07250195 0.04497283 0.05610483 0.04584985 0.05731195 0.048509 0.07250195 0.04497283 0.05513495 0.04380697 0.05610483 0.04584985 0.07250195 0.04497283 0.07334595 0.04021996 0.07362198 0.03322899 0.07301098 0.03849285 0.05126297 0.03619498 0.07301098 0.03849285 0.07362198 0.03322899 0.07283997 0.04632395 0.07334595 0.04021996 0.07301098 0.03849285 0.05294895 0.03952383 0.05513495 0.04380697 0.07301098 0.03849285 0.05126297 0.03619498 0.05294895 0.03952383 0.07301098 0.03849285 0.07395696 0.03530395 0.07431197 0.02931797 0.07362198 0.03322899 0.07334595 0.04021996 0.07395696 0.03530395 0.07362198 0.03322899 0.05124396 0.03615397 0.05126297 0.03619498 0.07362198 0.03322899 0.07464396 0.03178983 0.07504999 0.02688598 0.07431197 0.02931797 0.07395696 0.03530395 0.07464396 0.03178983 0.07431197 0.02931797 0.075378 0.02977883 0.07580399 0.02596497 0.07504999 0.02688598 0.07464396 0.03178983 0.075378 0.02977883 0.07504999 0.02688598 0.07612997 0.02931398 0.07613295 0.02600383 0.07580399 0.02596497 0.075378 0.02977883 0.07612997 0.02931398 0.07580399 0.02596497 0.07612997 0.02931398 0.07687097 0.03037798 0.07613295 0.02600383 0.05339694 0.06944096 0.07981997 0.06944096 0.07975196 0.06191384 0.05330985 0.07694697 0.07980197 0.07325595 0.07981997 0.06944096 0.05330985 0.07694697 0.07981997 0.06944096 0.05339694 0.06944096 0.05330896 0.06189286 0.07975196 0.06191384 0.07954895 0.05462884 0.05337482 0.06563699 0.05339694 0.06944096 0.07975196 0.06191384 0.05330896 0.06189286 0.05337482 0.06563699 0.07975196 0.06191384 0.053047 0.05460786 0.07954895 0.05462884 0.07921898 0.04786795 0.053047 0.05460786 0.05330896 0.06189286 0.07954895 0.05462884 0.05262196 0.04786998 0.07921898 0.04786795 0.07877099 0.04185998 0.05262196 0.04786998 0.053047 0.05460786 0.07921898 0.04786795 0.05204784 0.04190182 0.07877099 0.04185998 0.07821595 0.03679198 0.05204784 0.04190182 0.05262196 0.04786998 0.07877099 0.04185998 0.05133998 0.036879 0.07821595 0.03679198 0.07757496 0.03290885 0.05133998 0.036879 0.05204784 0.04190182 0.07821595 0.03679198 0.04962384 0.03050899 0.07757496 0.03290885 0.07687097 0.03037798 0.05052191 0.03302896 0.05133998 0.036879 0.07757496 0.03290885 0.04962384 0.03050899 0.05052191 0.03302896 0.07757496 0.03290885 0.048675 0.02943783 0.07687097 0.03037798 0.07612997 0.02931398 0.048675 0.02943783 0.04962384 0.03050899 0.07687097 0.03037798 0.04771 0.02989 0.07612997 0.02931398 0.075378 0.02977883 0.04771 0.02989 0.048675 0.02943783 0.07612997 0.02931398 0.04676598 0.03189498 0.075378 0.02977883 0.07464396 0.03178983 0.04676598 0.03189498 0.04771 0.02989 0.075378 0.02977883 0.04676598 0.03189498 0.07464396 0.03178983 0.07395696 0.03530395 0.04587996 0.03541797 0.07395696 0.03530395 0.07334595 0.04021996 0.04587996 0.03541797 0.04676598 0.03189498 0.07395696 0.03530395 0.04509294 0.04034882 0.07334595 0.04021996 0.07283997 0.04632395 0.04509294 0.04034882 0.04587996 0.03541797 0.07334595 0.04021996 0.04444396 0.04645884 0.07283997 0.04632395 0.07245898 0.05342698 0.04444396 0.04645884 0.04509294 0.04034882 0.07283997 0.04632395 0.04395699 0.05354487 0.07245898 0.05342698 0.07222098 0.06125396 0.04395699 0.05354487 0.04444396 0.04645884 0.07245898 0.05342698 0.04365485 0.06132584 0.07222098 0.06125396 0.07216095 0.06531 0.04365485 0.06132584 0.04395699 0.05354487 0.07222098 0.06125396 0.04365485 0.06132584 0.07216095 0.06531 0.07213997 0.06944096 0.04355299 0.06944096 0.07213997 0.06944096 0.07221996 0.077582 0.04355299 0.06944096 0.04365485 0.06132584 0.07213997 0.06944096 0.04365599 0.07760095 0.07221996 0.077582 0.072456 0.085388 0.04357898 0.07355797 0.04355299 0.06944096 0.07221996 0.077582 0.04365599 0.07760095 0.04357898 0.07355797 0.07221996 0.077582 0.04395997 0.08540195 0.072456 0.085388 0.07283598 0.09249699 0.04395997 0.08540195 0.04365599 0.07760095 0.072456 0.085388 0.04444897 0.09248298 0.07283598 0.09249699 0.07334196 0.09862595 0.04444897 0.09248298 0.04395997 0.08540195 0.07283598 0.09249699 0.04509699 0.09856897 0.07334196 0.09862595 0.07395595 0.1035709 0.04509699 0.09856897 0.04444897 0.09248298 0.07334196 0.09862595 0.04588097 0.10347 0.07395595 0.1035709 0.074647 0.107104 0.04588097 0.10347 0.04509699 0.09856897 0.07395595 0.1035709 0.04770195 0.108981 0.074647 0.107104 0.07538497 0.109113 0.04676085 0.106975 0.04588097 0.10347 0.074647 0.107104 0.04770195 0.108981 0.04676085 0.106975 0.074647 0.107104 0.048666 0.109447 0.07538497 0.109113 0.076137 0.109565 0.048666 0.109447 0.04770195 0.108981 0.07538497 0.109113 0.04961585 0.108388 0.076137 0.109565 0.07687699 0.108488 0.04961585 0.108388 0.048666 0.109447 0.076137 0.109565 0.05051785 0.105867 0.07687699 0.108488 0.077578 0.1059589 0.05051785 0.105867 0.04961585 0.108388 0.07687699 0.108488 0.05051785 0.105867 0.077578 0.1059589 0.078215 0.102097 0.05134087 0.101996 0.078215 0.102097 0.07876795 0.09705799 0.05134087 0.101996 0.05051785 0.105867 0.078215 0.102097 0.05205297 0.09694296 0.07876795 0.09705799 0.07921499 0.09107297 0.05205297 0.09694296 0.05134087 0.101996 0.07876795 0.09705799 0.05262684 0.09095299 0.07921499 0.09107297 0.07954698 0.084315 0.05262684 0.09095299 0.05205297 0.09694296 0.07921499 0.09107297 0.05304998 0.08421099 0.07954698 0.084315 0.07975095 0.07700997 0.05304998 0.08421099 0.05262684 0.09095299 0.07954698 0.084315 0.05330985 0.07694697 0.07975095 0.07700997 0.07980197 0.07325595 0.05330985 0.07694697 0.05304998 0.08421099 0.07975095 0.07700997 0.05802798 0.112562 0.05844783 0.112543 0.05676686 0.112379 0.05559796 0.112593 0.05676686 0.112379 0.05524283 0.112085 0.05329185 0.11208 0.05524283 0.112085 0.05387085 0.111656 0.05329185 0.11208 0.05559796 0.112593 0.05524283 0.112085 0.05329185 0.11208 0.05387085 0.111656 0.052688 0.111099 0.05132287 0.111165 0.052688 0.111099 0.05100786 0.109647 0.05132287 0.111165 0.05329185 0.11208 0.052688 0.111099 0.049842 0.109783 0.05100786 0.109647 0.05024296 0.107718 0.049842 0.109783 0.05132287 0.111165 0.05100786 0.109647 0.04905086 0.107848 0.05024296 0.107718 0.05033987 0.105361 0.04905086 0.107848 0.049842 0.109783 0.05024296 0.107718 0.05008482 0.10252 0.05033987 0.105361 0.05124199 0.102734 0.04907184 0.1053349 0.04905086 0.107848 0.05033987 0.105361 0.05008482 0.10252 0.04907184 0.1053349 0.05033987 0.105361 0.05008482 0.10252 0.05124199 0.102734 0.05126386 0.102686 0.052109 0.09915 0.05126386 0.102686 0.05294895 0.099357 0.05008482 0.10252 0.05126386 0.102686 0.052109 0.09915 0.05405586 0.09484797 0.05294895 0.099357 0.05513387 0.09507495 0.05405586 0.09484797 0.052109 0.09915 0.05294895 0.099357 0.05612397 0.09013897 0.05513387 0.09507495 0.05609995 0.09304195 0.05612397 0.09013897 0.05405586 0.09484797 0.05513387 0.09507495 0.05612397 0.09013897 0.05609995 0.09304195 0.05731195 0.09037399 0.05811887 0.08497697 0.05731195 0.09037399 0.05892282 0.08650696 0.05811887 0.08497697 0.05612397 0.09013897 0.05731195 0.09037399 0.05811887 0.08497697 0.05892282 0.08650696 0.05939882 0.08528 0.05991286 0.07934695 0.05939882 0.08528 0.06121587 0.079966 0.05991286 0.07934695 0.05811887 0.08497697 0.05939882 0.08528 0.05991286 0.07934695 0.06121587 0.079966 0.06130594 0.079665 0.06102395 0.07330197 0.06130594 0.079665 0.06276297 0.07356196 0.05991286 0.07934695 0.06130594 0.079665 0.06102395 0.07330197 0.06132495 0.06944 0.06276297 0.07356196 0.06312298 0.06944 0.06132495 0.06944 0.06102395 0.07330197 0.06276297 0.07356196 0.06102395 0.06558001 0.06312298 0.06944 0.06276297 0.06531995 0.06102395 0.06558001 0.06132495 0.06944 0.06312298 0.06944 0.05991286 0.05953484 0.06276297 0.06531995 0.06130594 0.05921489 0.05991286 0.05953484 0.06102395 0.06558001 0.06276297 0.06531995 0.05811887 0.05390387 0.06130594 0.05921489 0.06121999 0.05892795 0.05811887 0.05390387 0.05991286 0.05953484 0.06130594 0.05921489 0.05811887 0.05390387 0.06121999 0.05892795 0.05939882 0.05360198 0.05612283 0.04874289 0.05939882 0.05360198 0.05892884 0.05238986 0.05612283 0.04874289 0.05811887 0.05390387 0.05939882 0.05360198 0.05612283 0.04874289 0.05892884 0.05238986 0.05731195 0.048509 0.05405586 0.044034 0.05731195 0.048509 0.05610483 0.04584985 0.05405586 0.044034 0.05612283 0.04874289 0.05731195 0.048509 0.05405586 0.044034 0.05610483 0.04584985 0.05513495 0.04380697 0.05210983 0.03973084 0.05513495 0.04380697 0.05294895 0.03952383 0.05210983 0.03973084 0.05405586 0.044034 0.05513495 0.04380697 0.05008482 0.03636085 0.05294895 0.03952383 0.05126297 0.03619498 0.05008482 0.03636085 0.05210983 0.03973084 0.05294895 0.03952383 0.05511796 0.11257 0.05559796 0.112593 0.05329185 0.11208 0.05121886 0.112194 0.05329185 0.11208 0.05132287 0.111165 0.05287683 0.112397 0.05511796 0.11257 0.05329185 0.11208 0.05121886 0.112194 0.05287683 0.112397 0.05329185 0.11208 0.04963499 0.111173 0.05132287 0.111165 0.049842 0.109783 0.04963499 0.111173 0.05121886 0.112194 0.05132287 0.111165 0.04845899 0.109754 0.049842 0.109783 0.04905086 0.107848 0.04845899 0.109754 0.04963499 0.111173 0.049842 0.109783 0.04783797 0.107879 0.04905086 0.107848 0.04907184 0.1053349 0.04783797 0.107879 0.04845899 0.109754 0.04905086 0.107848 0.04865092 0.105381 0.04783797 0.107879 0.04907184 0.1053349 0.04893589 0.102565 0.04865092 0.105381 0.04907184 0.1053349 0.05008482 0.10252 0.04893589 0.102565 0.04907184 0.1053349 0.05463784 0.112746 0.05511796 0.11257 0.05287683 0.112397 0.05201596 0.112731 0.05287683 0.112397 0.05121886 0.112194 0.05201596 0.112731 0.05463784 0.112746 0.05287683 0.112397 0.05087399 0.112142 0.05121886 0.112194 0.04963499 0.111173 0.05201596 0.112731 0.05121886 0.112194 0.05087399 0.112142 0.04844594 0.111645 0.04963499 0.111173 0.04845899 0.109754 0.04914093 0.111816 0.05087399 0.112142 0.04963499 0.111173 0.04844594 0.111645 0.04914093 0.111816 0.04963499 0.111173 0.04734885 0.110209 0.04845899 0.109754 0.04783797 0.107879 0.04734885 0.110209 0.04844594 0.111645 0.04845899 0.109754 0.04865092 0.105381 0.04783797 0.105554 0.04783797 0.107879 0.046745 0.1083109 0.04783797 0.107879 0.04783797 0.105554 0.046745 0.1083109 0.04734885 0.110209 0.04783797 0.107879 0.04893589 0.102565 0.04783797 0.105554 0.04865092 0.105381 0.04706895 0.105832 0.046745 0.1083109 0.04783797 0.105554 0.04786884 0.102818 0.04706895 0.105832 0.04783797 0.105554 0.04893589 0.102565 0.04786884 0.102818 0.04783797 0.105554 0.049537 0.112655 0.05087399 0.112142 0.04914093 0.111816 0.049537 0.112655 0.05201596 0.112731 0.05087399 0.112142 0.049537 0.112655 0.04914093 0.111816 0.04844594 0.111645 0.04649198 0.111063 0.04844594 0.111645 0.04734885 0.110209 0.047279 0.112527 0.04844594 0.111645 0.04649198 0.111063 0.047279 0.112527 0.049537 0.112655 0.04844594 0.111645 0.04582399 0.109112 0.04734885 0.110209 0.046745 0.1083109 0.04582399 0.109112 0.04649198 0.111063 0.04734885 0.110209 0.04706895 0.105832 0.04670995 0.106007 0.046745 0.1083109 0.04582399 0.109112 0.046745 0.1083109 0.04670995 0.106007 0.04693496 0.103268 0.04670995 0.106007 0.04706895 0.105832 0.04574799 0.106671 0.04582399 0.109112 0.04670995 0.106007 0.046139 0.104028 0.04574799 0.106671 0.04670995 0.106007 0.046148 0.103996 0.046139 0.104028 0.04670995 0.106007 0.04617583 0.1039 0.046148 0.103996 0.04670995 0.106007 0.04693496 0.103268 0.04617583 0.1039 0.04670995 0.106007 0.04786884 0.102818 0.04693496 0.103268 0.04706895 0.105832 0.04452782 0.1113409 0.04649198 0.111063 0.04582399 0.109112 0.04537087 0.112363 0.047279 0.112527 0.04649198 0.111063 0.04159283 0.112743 0.04537087 0.112363 0.04649198 0.111063 0.04159283 0.112743 0.04649198 0.111063 0.04452782 0.1113409 0.04429394 0.109209 0.04582399 0.109112 0.04574799 0.106671 0.04452782 0.1113409 0.04582399 0.109112 0.04276198 0.111574 0.04429394 0.109209 0.04276198 0.111574 0.04582399 0.109112 0.04384785 0.107941 0.04574799 0.106671 0.046139 0.104028 0.04429394 0.109209 0.04574799 0.106671 0.04384785 0.107941 0.054223 0.112833 0.05463784 0.112746 0.05201596 0.112731 0.05141484 0.11292 0.05201596 0.112731 0.049537 0.112655 0.05141484 0.11292 0.054223 0.112833 0.05201596 0.112731 0.048702 0.112993 0.049537 0.112655 0.047279 0.112527 0.048702 0.112993 0.05141484 0.11292 0.049537 0.112655 0.04616385 0.1130599 0.047279 0.112527 0.04537087 0.112363 0.04616385 0.1130599 0.048702 0.112993 0.047279 0.112527 0.04616385 0.1130599 0.04537087 0.112363 0.04393386 0.113137 0.04159283 0.112743 0.04393386 0.113137 0.04537087 0.112363 0.04159283 0.112743 0.040151 0.113421 0.04393386 0.113137 0.04159283 0.112743 0.04452782 0.1113409 0.04276198 0.111574 0.03994786 0.1129299 0.04159283 0.112743 0.04276198 0.111574 0.03994786 0.1129299 0.04276198 0.111574 0.04120987 0.111787 0.04429394 0.109209 0.04120987 0.111787 0.04276198 0.111574 0.03840595 0.113586 0.040151 0.113421 0.04159283 0.112743 0.03840595 0.113586 0.04159283 0.112743 0.03994786 0.1129299 0.03888487 0.113146 0.04120987 0.111787 0.04021787 0.111993 0.04272699 0.108587 0.04021787 0.111993 0.04120987 0.111787 0.03643 0.114044 0.03888487 0.113146 0.04021787 0.111993 0.03891187 0.112553 0.03643 0.114044 0.04021787 0.111993 0.04114699 0.109639 0.03891187 0.112553 0.04021787 0.111993 0.04272699 0.108587 0.04114699 0.109639 0.04021787 0.111993 0.03888487 0.113146 0.03994786 0.1129299 0.04120987 0.111787 0.04384785 0.107941 0.04272699 0.108587 0.04120987 0.111787 0.04429394 0.109209 0.04384785 0.107941 0.04120987 0.111787 0.03725087 0.113807 0.03840595 0.113586 0.03994786 0.1129299 0.03888487 0.113146 0.03725087 0.113807 0.03994786 0.1129299 0.03531485 0.114535 0.03725087 0.113807 0.03888487 0.113146 0.03411698 0.114766 0.03725087 0.113807 0.03531485 0.114535 0.03531485 0.114535 0.03888487 0.113146 0.03643 0.114044 0.03356099 0.115424 0.03600084 0.114122 0.03443884 0.115022 0.03876584 0.111796 0.03443884 0.115022 0.03600084 0.114122 0.03790599 0.112915 0.03291589 0.115844 0.03443884 0.115022 0.03876584 0.111796 0.03790599 0.112915 0.03443884 0.115022 0.03356099 0.115424 0.03741395 0.113319 0.03600084 0.114122 0.03983998 0.110704 0.03600084 0.114122 0.03741395 0.113319 0.03983998 0.110704 0.03876584 0.111796 0.03600084 0.114122 0.03356099 0.115424 0.03643 0.114044 0.03741395 0.113319 0.03753983 0.11325 0.03741395 0.113319 0.03643 0.114044 0.03983998 0.110704 0.03741395 0.113319 0.03753983 0.11325 0.0326249 0.11567 0.03531485 0.114535 0.03643 0.114044 0.03356099 0.115424 0.0326249 0.11567 0.03643 0.114044 0.03891187 0.112553 0.03753983 0.11325 0.03643 0.114044 0.03165996 0.115751 0.03411698 0.114766 0.03531485 0.114535 0.0326249 0.11567 0.03165996 0.115751 0.03531485 0.114535 0.04114699 0.109639 0.03753983 0.11325 0.03891187 0.112553 0.04114699 0.109639 0.03983998 0.110704 0.03753983 0.11325 0.03790599 0.112915 0.03724396 0.114062 0.03291589 0.115844 0.04253995 0.111628 0.03674799 0.115243 0.03724396 0.114062 0.04295682 0.113082 0.03750598 0.115011 0.03674799 0.115243 0.04253995 0.111628 0.04295682 0.113082 0.03674799 0.115243 0.042364 0.110209 0.03724396 0.114062 0.03790599 0.112915 0.042364 0.110209 0.04253995 0.111628 0.03724396 0.114062 0.042445 0.108821 0.03790599 0.112915 0.03876584 0.111796 0.042445 0.108821 0.042364 0.110209 0.03790599 0.112915 0.04280698 0.107462 0.03876584 0.111796 0.03983998 0.110704 0.04280698 0.107462 0.042445 0.108821 0.03876584 0.111796 0.04347497 0.106133 0.03983998 0.110704 0.04114699 0.109639 0.04347497 0.106133 0.04280698 0.107462 0.03983998 0.110704 0.04447484 0.10483 0.04114699 0.109639 0.04272699 0.108587 0.04447484 0.10483 0.04347497 0.106133 0.04114699 0.109639 0.04407882 0.106527 0.04447484 0.10483 0.04272699 0.108587 0.04384785 0.107941 0.04407882 0.106527 0.04272699 0.108587 0.04871195 0.108095 0.04295682 0.113082 0.04253995 0.111628 0.05028986 0.109785 0.04488682 0.112295 0.04295682 0.113082 0.04355299 0.114816 0.04295682 0.113082 0.04488682 0.112295 0.04871195 0.108095 0.05028986 0.109785 0.04295682 0.113082 0.04761296 0.1063809 0.04253995 0.111628 0.042364 0.110209 0.04761296 0.1063809 0.04871195 0.108095 0.04253995 0.111628 0.04688197 0.104705 0.042364 0.110209 0.042445 0.108821 0.04688197 0.104705 0.04761296 0.1063809 0.042364 0.110209 0.04655796 0.103064 0.042445 0.108821 0.04280698 0.107462 0.04655796 0.103064 0.04688197 0.104705 0.042445 0.108821 0.04667896 0.101459 0.04280698 0.107462 0.04347497 0.106133 0.04667896 0.101459 0.04655796 0.103064 0.04280698 0.107462 0.04728299 0.09988796 0.04347497 0.106133 0.04447484 0.10483 0.04728299 0.09988796 0.04667896 0.101459 0.04347497 0.106133 0.04407882 0.106527 0.04587799 0.103501 0.04447484 0.10483 0.04843795 0.09828895 0.04447484 0.10483 0.04587799 0.103501 0.04843795 0.09828895 0.04728299 0.09988796 0.04447484 0.10483 0.04617583 0.1039 0.04587799 0.103501 0.04407882 0.106527 0.04745882 0.100521 0.04843795 0.09828895 0.04587799 0.103501 0.04617583 0.1039 0.04745882 0.100521 0.04587799 0.103501 0.04617583 0.1039 0.04407882 0.106527 0.046148 0.103996 0.04384785 0.107941 0.046148 0.103996 0.04407882 0.106527 0.04355299 0.114816 0.04488682 0.112295 0.05028986 0.109785 0.05600982 0.103178 0.05028986 0.109785 0.04871195 0.108095 0.05878984 0.104909 0.05348485 0.108092 0.05028986 0.109785 0.05176997 0.111195 0.05028986 0.109785 0.05348485 0.108092 0.05600982 0.103178 0.05878984 0.104909 0.05028986 0.109785 0.05176997 0.111195 0.04355299 0.114816 0.05028986 0.109785 0.053801 0.101398 0.04871195 0.108095 0.04761296 0.1063809 0.053801 0.101398 0.05600982 0.103178 0.04871195 0.108095 0.05204784 0.09965598 0.04761296 0.1063809 0.04688197 0.104705 0.05204784 0.09965598 0.053801 0.101398 0.04761296 0.1063809 0.05080085 0.09795099 0.04688197 0.104705 0.04655796 0.103064 0.05080085 0.09795099 0.05204784 0.09965598 0.04688197 0.104705 0.05010885 0.09628397 0.04655796 0.103064 0.04667896 0.101459 0.05010885 0.09628397 0.05080085 0.09795099 0.04655796 0.103064 0.05001884 0.09465098 0.04667896 0.101459 0.04728299 0.09988796 0.05001884 0.09465098 0.05010885 0.09628397 0.04667896 0.101459 0.05020886 0.094006 0.04728299 0.09988796 0.04843795 0.09828895 0.050601 0.093014 0.05001884 0.09465098 0.04728299 0.09988796 0.05020886 0.094006 0.050601 0.093014 0.04728299 0.09988796 0.04786282 0.100049 0.04843795 0.09828895 0.04745882 0.100521 0.04940187 0.095995 0.05020886 0.094006 0.04843795 0.09828895 0.04786282 0.100049 0.04940187 0.095995 0.04843795 0.09828895 0.04693496 0.103268 0.04786282 0.100049 0.04745882 0.100521 0.04693496 0.103268 0.04745882 0.100521 0.04617583 0.1039 0.05176997 0.111195 0.05348485 0.108092 0.05878984 0.104909 0.06442797 0.09624695 0.05878984 0.104909 0.05600982 0.103178 0.068448 0.09785395 0.06155097 0.103062 0.05878984 0.104909 0.06050688 0.106121 0.05878984 0.104909 0.06155097 0.103062 0.06442797 0.09624695 0.068448 0.09785395 0.05878984 0.104909 0.06050688 0.106121 0.05176997 0.111195 0.05878984 0.104909 0.060929 0.09465301 0.05600982 0.103178 0.053801 0.101398 0.060929 0.09465301 0.06442797 0.09624695 0.05600982 0.103178 0.05797284 0.09309399 0.053801 0.101398 0.05204784 0.09965598 0.05797284 0.09309399 0.060929 0.09465301 0.053801 0.101398 0.05562084 0.09156996 0.05204784 0.09965598 0.05080085 0.09795099 0.05562084 0.09156996 0.05797284 0.09309399 0.05204784 0.09965598 0.05392998 0.09007799 0.05080085 0.09795099 0.05010885 0.09628397 0.05392998 0.09007799 0.05562084 0.09156996 0.05080085 0.09795099 0.05295795 0.08861798 0.05010885 0.09628397 0.05001884 0.09465098 0.05295795 0.08861798 0.05392998 0.09007799 0.05010885 0.09628397 0.05276799 0.08718198 0.05001884 0.09465098 0.050601 0.093014 0.05276799 0.08718198 0.05295795 0.08861798 0.05001884 0.09465098 0.04979497 0.09554398 0.050601 0.093014 0.05020886 0.094006 0.051346 0.09108495 0.05276799 0.08718198 0.050601 0.093014 0.04979497 0.09554398 0.051346 0.09108495 0.050601 0.093014 0.04979497 0.09554398 0.05020886 0.094006 0.04940187 0.095995 0.04979497 0.09554398 0.04940187 0.095995 0.04786282 0.100049 0.06050688 0.106121 0.06155097 0.103062 0.068448 0.09785395 0.07343399 0.087076 0.068448 0.09785395 0.06442797 0.09624695 0.07894998 0.08821099 0.06952697 0.096964 0.068448 0.09785395 0.06940698 0.09959995 0.068448 0.09785395 0.06952697 0.096964 0.07343399 0.087076 0.07894998 0.08821099 0.068448 0.09785395 0.06940698 0.09959995 0.06050688 0.106121 0.068448 0.09785395 0.06851899 0.08593899 0.06442797 0.09624695 0.060929 0.09465301 0.06851899 0.08593899 0.07343399 0.087076 0.06442797 0.09624695 0.064242 0.08482795 0.060929 0.09465301 0.05797284 0.09309399 0.064242 0.08482795 0.06851899 0.08593899 0.060929 0.09465301 0.06066983 0.08374196 0.05797284 0.09309399 0.05562084 0.09156996 0.06066983 0.08374196 0.064242 0.08482795 0.05797284 0.09309399 0.05786883 0.082681 0.05562084 0.09156996 0.05392998 0.09007799 0.05786883 0.082681 0.06066983 0.08374196 0.05562084 0.09156996 0.05590498 0.08164298 0.05392998 0.09007799 0.05295795 0.08861798 0.05590498 0.08164298 0.05786883 0.082681 0.05392998 0.09007799 0.05485385 0.08060801 0.05295795 0.08861798 0.05276799 0.08718198 0.05485385 0.08060801 0.05590498 0.08164298 0.05295795 0.08861798 0.05167084 0.09064799 0.05276799 0.08718198 0.051346 0.09108495 0.05328083 0.08568298 0.05485385 0.08060801 0.05276799 0.08718198 0.05167084 0.09064799 0.05328083 0.08568298 0.05276799 0.08718198 0.05167084 0.09064799 0.051346 0.09108495 0.04979497 0.09554398 0.07894998 0.08821099 0.07744598 0.08973097 0.06952697 0.096964 0.078094 0.09183198 0.06952697 0.096964 0.07744598 0.08973097 0.078094 0.09183198 0.06940698 0.09959995 0.06952697 0.096964 0.078094 0.09183198 0.07744598 0.08973097 0.07894998 0.08821099 0.07936996 0.08067095 0.07894998 0.08821099 0.07343399 0.087076 0.07936996 0.08067095 0.08514297 0.08141195 0.07894998 0.08821099 0.078094 0.09183198 0.07894998 0.08821099 0.08514297 0.08141195 0.07589697 0.08021396 0.07343399 0.087076 0.06851899 0.08593899 0.07589697 0.08021396 0.07936996 0.08067095 0.07343399 0.087076 0.07203596 0.079602 0.06851899 0.08593899 0.064242 0.08482795 0.07203596 0.079602 0.07589697 0.08021396 0.06851899 0.08593899 0.06492596 0.07795995 0.064242 0.08482795 0.06066983 0.08374196 0.068084 0.07880198 0.07203596 0.079602 0.064242 0.08482795 0.06492596 0.07795995 0.068084 0.07880198 0.064242 0.08482795 0.06247484 0.07710796 0.06066983 0.08374196 0.05786883 0.082681 0.06247484 0.07710796 0.06492596 0.07795995 0.06066983 0.08374196 0.05803483 0.07454097 0.05786883 0.082681 0.05590498 0.08164298 0.06057596 0.07625895 0.06247484 0.07710796 0.05786883 0.082681 0.05803483 0.07454097 0.06057596 0.07625895 0.05786883 0.082681 0.05495584 0.08024197 0.05590498 0.08164298 0.05485385 0.08060801 0.05651098 0.07337498 0.05803483 0.07454097 0.05590498 0.08164298 0.05508798 0.07976299 0.05651098 0.07337498 0.05590498 0.08164298 0.05495584 0.08024197 0.05508798 0.07976299 0.05590498 0.08164298 0.05349683 0.085285 0.05485385 0.08060801 0.05328083 0.08568298 0.05349683 0.085285 0.05495584 0.08024197 0.05485385 0.08060801 0.05349683 0.085285 0.05328083 0.08568298 0.05167084 0.09064799 0.08243197 0.07525098 0.08514297 0.08141195 0.07936996 0.08067095 0.08636701 0.08296 0.078094 0.09183198 0.08514297 0.08141195 0.08686995 0.07958495 0.08636701 0.08296 0.08514297 0.08141195 0.08686995 0.07958495 0.08514297 0.08141195 0.08948296 0.07578295 0.08243197 0.07525098 0.08948296 0.07578295 0.08514297 0.08141195 0.08243197 0.07525098 0.07936996 0.08067095 0.07589697 0.08021396 0.07592499 0.07481998 0.07589697 0.08021396 0.07203596 0.079602 0.08243197 0.07525098 0.07589697 0.08021396 0.07592499 0.07481998 0.070243 0.07431095 0.07203596 0.079602 0.068084 0.07880198 0.07592499 0.07481998 0.07203596 0.079602 0.070243 0.07431095 0.070243 0.07431095 0.068084 0.07880198 0.06492596 0.07795995 0.06544798 0.07370197 0.06492596 0.07795995 0.06247484 0.07710796 0.070243 0.07431095 0.06492596 0.07795995 0.06544798 0.07370197 0.06158185 0.07298499 0.06247484 0.07710796 0.06057596 0.07625895 0.06544798 0.07370197 0.06247484 0.07710796 0.06158185 0.07298499 0.05868285 0.07214295 0.06057596 0.07625895 0.05803483 0.07454097 0.06158185 0.07298499 0.06057596 0.07625895 0.05868285 0.07214295 0.05675482 0.07143199 0.05803483 0.07454097 0.05651098 0.07337498 0.05868285 0.07214295 0.05803483 0.07454097 0.05675482 0.07143199 0.0551669 0.07942301 0.05651098 0.07337498 0.05508798 0.07976299 0.05646497 0.07316499 0.05675482 0.07143199 0.05651098 0.07337498 0.0551669 0.07942301 0.05646497 0.07316499 0.05651098 0.07337498 0.05349683 0.085285 0.05508798 0.07976299 0.05495584 0.08024197 0.0551669 0.07942301 0.05508798 0.07976299 0.05349683 0.085285 0.05231183 0.113795 0.05176997 0.111195 0.06050688 0.106121 0.06142199 0.108441 0.06050688 0.106121 0.06940698 0.09959995 0.06142199 0.108441 0.05231183 0.113795 0.06050688 0.106121 0.07057899 0.101668 0.06940698 0.09959995 0.078094 0.09183198 0.07057899 0.101668 0.06142199 0.108441 0.06940698 0.09959995 0.07944697 0.09367996 0.078094 0.09183198 0.08636701 0.08296 0.07944697 0.09367996 0.07057899 0.101668 0.078094 0.09183198 0.08783799 0.084625 0.07944697 0.09367996 0.08636701 0.08296 0.08686995 0.07958495 0.08783799 0.084625 0.08636701 0.08296 0.05827283 0.113912 0.05231183 0.113795 0.06142199 0.108441 0.06644898 0.108358 0.06142199 0.108441 0.07057899 0.101668 0.06644898 0.108358 0.05827283 0.113912 0.06142199 0.108441 0.07448697 0.101839 0.07057899 0.101668 0.07944697 0.09367996 0.07448697 0.101839 0.06644898 0.108358 0.07057899 0.101668 0.08221697 0.09447598 0.07944697 0.09367996 0.08783799 0.084625 0.08221697 0.09447598 0.07448697 0.101839 0.07944697 0.09367996 0.089531 0.08637595 0.08221697 0.09447598 0.08783799 0.084625 0.08997297 0.082116 0.089531 0.08637595 0.08783799 0.084625 0.08686995 0.07958495 0.08997297 0.082116 0.08783799 0.084625 0.08821898 0.077874 0.09183299 0.07932299 0.08997297 0.082116 0.08686995 0.07958495 0.08821898 0.077874 0.08997297 0.082116 0.089908 0.07491195 0.09331095 0.07624298 0.09183299 0.07932299 0.08948296 0.07578295 0.089908 0.07491195 0.09183299 0.07932299 0.08918398 0.07634097 0.08948296 0.07578295 0.09183299 0.07932299 0.08821898 0.077874 0.08918398 0.07634097 0.09183299 0.07932299 0.09082496 0.07203596 0.09427601 0.07291698 0.09331095 0.07624298 0.089908 0.07491195 0.09082496 0.07203596 0.09331095 0.07624298 0.09106695 0.07035696 0.09461396 0.06944096 0.09427601 0.07291698 0.09082496 0.07203596 0.09106695 0.07035696 0.09427601 0.07291698 0.091075 0.06870698 0.09427601 0.06596499 0.09461396 0.06944096 0.09109896 0.06943398 0.091075 0.06870698 0.09461396 0.06944096 0.09106695 0.07035696 0.09109896 0.06943398 0.09461396 0.06944096 0.09053599 0.06568098 0.09331095 0.06263697 0.09427601 0.06596499 0.091075 0.06870698 0.09053599 0.06568098 0.09427601 0.06596499 0.088786 0.06187099 0.09183299 0.05955797 0.09331095 0.06263697 0.08947598 0.063075 0.088786 0.06187099 0.09331095 0.06263697 0.08951699 0.06315398 0.08947598 0.063075 0.09331095 0.06263697 0.09053599 0.06568098 0.08951699 0.06315398 0.09331095 0.06263697 0.08785396 0.0605039 0.08997195 0.05676597 0.09183299 0.05955797 0.088786 0.06187099 0.08785396 0.0605039 0.09183299 0.05955797 0.08785396 0.0605039 0.08663898 0.05902493 0.08997195 0.05676597 0.08243596 0.06361895 0.08663898 0.05902493 0.08785396 0.0605039 0.08243596 0.06361895 0.08785396 0.0605039 0.088786 0.06187099 0.08243596 0.06361895 0.088786 0.06187099 0.08947598 0.063075 0.08382195 0.06943595 0.08947598 0.063075 0.08951699 0.06315398 0.08382195 0.06943595 0.08243596 0.06361895 0.08947598 0.063075 0.08382195 0.06943595 0.08951699 0.06315398 0.09053599 0.06568098 0.09109896 0.06943398 0.09053599 0.06568098 0.091075 0.06870698 0.08382195 0.06943595 0.09053599 0.06568098 0.09109896 0.06943398 0.09082496 0.07203596 0.09109896 0.06943398 0.09106695 0.07035696 0.089908 0.07491195 0.09109896 0.06943398 0.09082496 0.07203596 0.08948296 0.07578295 0.09109896 0.06943398 0.089908 0.07491195 0.08382195 0.06943595 0.09109896 0.06943398 0.08948296 0.07578295 0.08821898 0.077874 0.08948296 0.07578295 0.08918398 0.07634097 0.08686995 0.07958495 0.08948296 0.07578295 0.08821898 0.077874 0.08243197 0.07525098 0.08382195 0.06943595 0.08948296 0.07578295 0.05683785 0.06944 0.05675399 0.06744599 0.05868196 0.066733 0.05646497 0.06571698 0.05675399 0.06744599 0.05683785 0.06944 0.05890583 0.06944 0.05868196 0.066733 0.06158185 0.065889 0.05890583 0.06944 0.05683785 0.06944 0.05868196 0.066733 0.06198787 0.06943899 0.06158185 0.065889 0.06544798 0.065171 0.06198787 0.06943899 0.05890583 0.06944 0.06158185 0.065889 0.06606698 0.06943798 0.06544798 0.065171 0.07024496 0.064561 0.06606698 0.06943798 0.06198787 0.06943899 0.06544798 0.065171 0.07110297 0.06943696 0.07024496 0.064561 0.07592695 0.06405097 0.07110297 0.06943696 0.06606698 0.06943798 0.07024496 0.064561 0.07704198 0.06943696 0.07592695 0.06405097 0.08243596 0.06361895 0.07704198 0.06943696 0.07110297 0.06943696 0.07592695 0.06405097 0.08382195 0.06943595 0.07704198 0.06943696 0.08243596 0.06361895 0.05868285 0.07214295 0.05683785 0.06944 0.05890583 0.06944 0.05868285 0.07214295 0.05675482 0.07143199 0.05683785 0.06944 0.05646497 0.07316499 0.05683785 0.06944 0.05675482 0.07143199 0.05674499 0.06944 0.05683785 0.06944 0.05646497 0.07316499 0.05646497 0.06571698 0.05683785 0.06944 0.05674499 0.06944 0.06158185 0.07298499 0.05890583 0.06944 0.06198787 0.06943899 0.06158185 0.07298499 0.05868285 0.07214295 0.05890583 0.06944 0.06544798 0.07370197 0.06198787 0.06943899 0.06606698 0.06943798 0.06544798 0.07370197 0.06158185 0.07298499 0.06198787 0.06943899 0.070243 0.07431095 0.06606698 0.06943798 0.07110297 0.06943696 0.070243 0.07431095 0.06544798 0.07370197 0.06606698 0.06943798 0.07592499 0.07481998 0.07110297 0.06943696 0.07704198 0.06943696 0.07592499 0.07481998 0.070243 0.07431095 0.07110297 0.06943696 0.08243197 0.07525098 0.07704198 0.06943696 0.08382195 0.06943595 0.08243197 0.07525098 0.07592499 0.07481998 0.07704198 0.06943696 0.06132495 0.06944 0.05936795 0.07311695 0.06102395 0.07330197 0.05857098 0.07911396 0.06102395 0.07330197 0.05936795 0.07311695 0.05991286 0.07934695 0.06102395 0.07330197 0.05857098 0.07911396 0.058218 0.06944 0.05796498 0.07302695 0.05936795 0.07311695 0.05735486 0.07900196 0.05936795 0.07311695 0.05796498 0.07302695 0.05963397 0.06944 0.058218 0.06944 0.05936795 0.07311695 0.06132495 0.06944 0.05963397 0.06944 0.05936795 0.07311695 0.05857098 0.07911396 0.05936795 0.07311695 0.05735486 0.07900196 0.05722182 0.06944 0.05696398 0.073044 0.05796498 0.07302695 0.05634182 0.07901799 0.05796498 0.07302695 0.05696398 0.073044 0.058218 0.06944 0.05722182 0.06944 0.05796498 0.07302695 0.05735486 0.07900196 0.05796498 0.07302695 0.05634182 0.07901799 0.05674499 0.06944 0.05646497 0.07316499 0.05696398 0.073044 0.05559682 0.07916098 0.05696398 0.073044 0.05646497 0.07316499 0.05722182 0.06944 0.05674499 0.06944 0.05696398 0.073044 0.05634182 0.07901799 0.05696398 0.073044 0.05559682 0.07916098 0.05559682 0.07916098 0.05646497 0.07316499 0.0551669 0.07942301 0.05696398 0.06583797 0.05674499 0.06944 0.05722182 0.06944 0.05696398 0.06583797 0.05646497 0.06571698 0.05674499 0.06944 0.05796498 0.06585395 0.05722182 0.06944 0.058218 0.06944 0.05796498 0.06585395 0.05696398 0.06583797 0.05722182 0.06944 0.05796498 0.06585395 0.058218 0.06944 0.05963397 0.06944 0.05936795 0.06576496 0.05963397 0.06944 0.06132495 0.06944 0.05936795 0.06576496 0.05796498 0.06585395 0.05963397 0.06944 0.06102395 0.06558001 0.05936795 0.06576496 0.06132495 0.06944 0.05559682 0.05972099 0.05646497 0.06571698 0.05696398 0.06583797 0.05559682 0.05972099 0.0551669 0.05945897 0.05646497 0.06571698 0.05634182 0.05986398 0.05696398 0.06583797 0.05796498 0.06585395 0.05634182 0.05986398 0.05559682 0.05972099 0.05696398 0.06583797 0.05735486 0.05987983 0.05796498 0.06585395 0.05936795 0.06576496 0.05735486 0.05987983 0.05634182 0.05986398 0.05796498 0.06585395 0.05857098 0.05976796 0.05936795 0.06576496 0.06102395 0.06558001 0.05857098 0.05976796 0.05735486 0.05987983 0.05936795 0.06576496 0.05991286 0.05953484 0.05857098 0.05976796 0.06102395 0.06558001 0.05405586 0.09484797 0.05127286 0.09904396 0.052109 0.09915 0.05008482 0.10252 0.052109 0.09915 0.05127286 0.09904396 0.05302399 0.094702 0.05046099 0.09904199 0.05127286 0.09904396 0.05008482 0.10252 0.05127286 0.09904396 0.05046099 0.09904199 0.05405586 0.09484797 0.05302399 0.094702 0.05127286 0.09904396 0.052046 0.09470099 0.04969495 0.099146 0.05046099 0.09904199 0.04893589 0.102565 0.05046099 0.09904199 0.04969495 0.099146 0.05302399 0.094702 0.052046 0.09470099 0.05046099 0.09904199 0.05008482 0.10252 0.05046099 0.09904199 0.04893589 0.102565 0.05115985 0.09484601 0.04899483 0.099352 0.04969495 0.099146 0.04786884 0.102818 0.04969495 0.099146 0.04899483 0.099352 0.052046 0.09470099 0.05115985 0.09484601 0.04969495 0.099146 0.04893589 0.102565 0.04969495 0.099146 0.04786884 0.102818 0.050399 0.09512996 0.04837799 0.09965598 0.04899483 0.099352 0.04786884 0.102818 0.04899483 0.099352 0.04837799 0.09965598 0.05115985 0.09484601 0.050399 0.09512996 0.04899483 0.099352 0.04979497 0.09554398 0.04786282 0.100049 0.04837799 0.09965598 0.04693496 0.103268 0.04837799 0.09965598 0.04786282 0.100049 0.050399 0.09512996 0.04979497 0.09554398 0.04837799 0.09965598 0.04786884 0.102818 0.04837799 0.09965598 0.04693496 0.103268 0.05167084 0.09064799 0.04979497 0.09554398 0.050399 0.09512996 0.05224496 0.09025996 0.050399 0.09512996 0.05115985 0.09484601 0.05224496 0.09025996 0.05167084 0.09064799 0.050399 0.09512996 0.05301582 0.09000796 0.05115985 0.09484601 0.052046 0.09470099 0.05301582 0.09000796 0.05224496 0.09025996 0.05115985 0.09484601 0.05394887 0.08990198 0.052046 0.09470099 0.05302399 0.094702 0.05394887 0.08990198 0.05301582 0.09000796 0.052046 0.09470099 0.05500096 0.08994597 0.05302399 0.094702 0.05405586 0.09484797 0.05500096 0.08994597 0.05394887 0.08990198 0.05302399 0.094702 0.05612397 0.09013897 0.05500096 0.08994597 0.05405586 0.09484797 0.05349683 0.085285 0.05167084 0.09064799 0.05224496 0.09025996 0.05401295 0.08494096 0.05224496 0.09025996 0.05301582 0.09000796 0.05401295 0.08494096 0.05349683 0.085285 0.05224496 0.09025996 0.05478096 0.08473199 0.05301582 0.09000796 0.05394887 0.08990198 0.05478096 0.08473199 0.05401295 0.08494096 0.05301582 0.09000796 0.05575788 0.08466696 0.05394887 0.08990198 0.05500096 0.08994597 0.05575788 0.08466696 0.05478096 0.08473199 0.05394887 0.08990198 0.05689096 0.08474999 0.05500096 0.08994597 0.05612397 0.09013897 0.05689096 0.08474999 0.05575788 0.08466696 0.05500096 0.08994597 0.05811887 0.08497697 0.05689096 0.08474999 0.05612397 0.09013897 0.0551669 0.07942301 0.05349683 0.085285 0.05401295 0.08494096 0.05559682 0.07916098 0.05401295 0.08494096 0.05478096 0.08473199 0.05559682 0.07916098 0.0551669 0.07942301 0.05401295 0.08494096 0.05634182 0.07901799 0.05478096 0.08473199 0.05575788 0.08466696 0.05634182 0.07901799 0.05559682 0.07916098 0.05478096 0.08473199 0.05735486 0.07900196 0.05575788 0.08466696 0.05689096 0.08474999 0.05735486 0.07900196 0.05634182 0.07901799 0.05575788 0.08466696 0.05857098 0.07911396 0.05689096 0.08474999 0.05811887 0.08497697 0.05857098 0.07911396 0.05735486 0.07900196 0.05689096 0.08474999 0.05991286 0.07934695 0.05857098 0.07911396 0.05811887 0.08497697 0.04384785 0.107941 0.046139 0.104028 0.046148 0.103996 0.05349683 0.05359697 0.0551669 0.05945897 0.05559682 0.05972099 0.05401295 0.05393987 0.05559682 0.05972099 0.05634182 0.05986398 0.05401295 0.05393987 0.05349683 0.05359697 0.05559682 0.05972099 0.05478096 0.05414897 0.05634182 0.05986398 0.05735486 0.05987983 0.05478096 0.05414897 0.05401295 0.05393987 0.05634182 0.05986398 0.05575788 0.054214 0.05735486 0.05987983 0.05857098 0.05976796 0.05575788 0.054214 0.05478096 0.05414897 0.05735486 0.05987983 0.05689096 0.05413097 0.05857098 0.05976796 0.05991286 0.05953484 0.05689096 0.05413097 0.05575788 0.054214 0.05857098 0.05976796 0.05811887 0.05390387 0.05689096 0.05413097 0.05991286 0.05953484 0.05166995 0.04823297 0.05349683 0.05359697 0.05401295 0.05393987 0.05224382 0.04862087 0.05401295 0.05393987 0.05478096 0.05414897 0.05224382 0.04862087 0.05166995 0.04823297 0.05401295 0.05393987 0.05301499 0.04887282 0.05478096 0.05414897 0.05575788 0.054214 0.05301499 0.04887282 0.05224382 0.04862087 0.05478096 0.05414897 0.05394798 0.04897898 0.05575788 0.054214 0.05689096 0.05413097 0.05394798 0.04897898 0.05301499 0.04887282 0.05575788 0.054214 0.05499982 0.04893487 0.05689096 0.05413097 0.05811887 0.05390387 0.05499982 0.04893487 0.05394798 0.04897898 0.05689096 0.05413097 0.05612283 0.04874289 0.05499982 0.04893487 0.05811887 0.05390387 0.04979497 0.043338 0.05166995 0.04823297 0.05224382 0.04862087 0.050399 0.043751 0.05224382 0.04862087 0.05301499 0.04887282 0.050399 0.043751 0.04979497 0.043338 0.05224382 0.04862087 0.05115985 0.04403597 0.05301499 0.04887282 0.05394798 0.04897898 0.05115985 0.04403597 0.050399 0.043751 0.05301499 0.04887282 0.052046 0.04417985 0.05394798 0.04897898 0.05499982 0.04893487 0.052046 0.04417985 0.05115985 0.04403597 0.05394798 0.04897898 0.05302399 0.04417896 0.05499982 0.04893487 0.05612283 0.04874289 0.05302399 0.04417896 0.052046 0.04417985 0.05499982 0.04893487 0.05405586 0.044034 0.05302399 0.04417896 0.05612283 0.04874289 0.04837799 0.03922498 0.04979497 0.043338 0.050399 0.043751 0.04837799 0.03922498 0.04786199 0.03883183 0.04979497 0.043338 0.04899483 0.03952884 0.050399 0.043751 0.05115985 0.04403597 0.04899483 0.03952884 0.04837799 0.03922498 0.050399 0.043751 0.04969495 0.03973484 0.05115985 0.04403597 0.052046 0.04417985 0.04969495 0.03973484 0.04899483 0.03952884 0.05115985 0.04403597 0.05046182 0.03983891 0.052046 0.04417985 0.05302399 0.04417896 0.05046182 0.03983891 0.04969495 0.03973484 0.052046 0.04417985 0.051274 0.039837 0.05302399 0.04417896 0.05405586 0.044034 0.051274 0.039837 0.05046182 0.03983891 0.05302399 0.04417896 0.05210983 0.03973084 0.051274 0.039837 0.05405586 0.044034 0.04693496 0.035613 0.04786199 0.03883183 0.04837799 0.03922498 0.04693496 0.035613 0.04837799 0.03922498 0.04899483 0.03952884 0.04786884 0.03606283 0.04899483 0.03952884 0.04969495 0.03973484 0.04786884 0.03606283 0.04693496 0.035613 0.04899483 0.03952884 0.04893589 0.03631585 0.04969495 0.03973484 0.05046182 0.03983891 0.04893589 0.03631585 0.04786884 0.03606283 0.04969495 0.03973484 0.04893589 0.03631585 0.05046182 0.03983891 0.051274 0.039837 0.05008482 0.03636085 0.051274 0.039837 0.05210983 0.03973084 0.05008482 0.03636085 0.04893589 0.03631585 0.051274 0.039837 0.05330985 0.07694697 0.05339694 0.06944096 0.05337482 0.06563699 0.05330985 0.07694697 0.05337482 0.06563699 0.05330896 0.06189286 0.05304998 0.08421099 0.05330896 0.06189286 0.053047 0.05460786 0.05330985 0.07694697 0.05330896 0.06189286 0.05304998 0.08421099 0.05262684 0.09095299 0.053047 0.05460786 0.05262196 0.04786998 0.05304998 0.08421099 0.053047 0.05460786 0.05262684 0.09095299 0.05205297 0.09694296 0.05262196 0.04786998 0.05204784 0.04190182 0.05262684 0.09095299 0.05262196 0.04786998 0.05205297 0.09694296 0.05134087 0.101996 0.05204784 0.04190182 0.05133998 0.036879 0.05205297 0.09694296 0.05204784 0.04190182 0.05134087 0.101996 0.05134087 0.101996 0.05133998 0.036879 0.05052191 0.03302896 0.05051785 0.105867 0.05052191 0.03302896 0.04962384 0.03050899 0.05134087 0.101996 0.05052191 0.03302896 0.05051785 0.105867 0.04961585 0.108388 0.04962384 0.03050899 0.048675 0.02943783 0.05051785 0.105867 0.04962384 0.03050899 0.04961585 0.108388 0.048666 0.109447 0.048675 0.02943783 0.04771 0.02989 0.04961585 0.108388 0.048675 0.02943783 0.048666 0.109447 0.04770195 0.108981 0.04771 0.02989 0.04676598 0.03189498 0.048666 0.109447 0.04771 0.02989 0.04770195 0.108981 0.04676085 0.106975 0.04676598 0.03189498 0.04587996 0.03541797 0.04770195 0.108981 0.04676598 0.03189498 0.04676085 0.106975 0.04509699 0.09856897 0.04587996 0.03541797 0.04509294 0.04034882 0.04588097 0.10347 0.04587996 0.03541797 0.04509699 0.09856897 0.04676085 0.106975 0.04587996 0.03541797 0.04588097 0.10347 0.04444897 0.09248298 0.04509294 0.04034882 0.04444396 0.04645884 0.04509699 0.09856897 0.04509294 0.04034882 0.04444897 0.09248298 0.04395997 0.08540195 0.04444396 0.04645884 0.04395699 0.05354487 0.04444897 0.09248298 0.04444396 0.04645884 0.04395997 0.08540195 0.04365599 0.07760095 0.04395699 0.05354487 0.04365485 0.06132584 0.04395997 0.08540195 0.04395699 0.05354487 0.04365599 0.07760095 0.04357898 0.07355797 0.04365485 0.06132584 0.04355299 0.06944096 0.04365599 0.07760095 0.04365485 0.06132584 0.04357898 0.07355797 0.100099 0.08592897 0.100099 0.052953 0.121172 0.02304196 0.09730899 0.08089399 0.09730899 0.05798786 0.100099 0.052953 0.100099 0.08592897 0.09730899 0.08089399 0.100099 0.052953 0.121172 0.11584 0.121172 0.02304196 0.126107 0.01738697 0.121172 0.11584 0.100099 0.08592897 0.121172 0.02304196 0.132001 0.125881 0.126107 0.01738697 0.132001 0.01300096 0.126107 0.121494 0.121172 0.11584 0.126107 0.01738697 0.132001 0.125881 0.126107 0.121494 0.126107 0.01738697 0.1386 0.128798 0.132001 0.01300096 0.1386 0.01008397 0.1386 0.128798 0.132001 0.125881 0.132001 0.01300096 0.145617 0.130102 0.1386 0.01008397 0.145617 0.008779942 0.145617 0.130102 0.1386 0.128798 0.1386 0.01008397 0.145617 0.130102 0.145617 0.008779942 0.152739 0.009168982 0.152739 0.129712 0.145617 0.130102 0.152739 0.009168982 0.182384 0.01441782 0.152739 0.129712 0.152739 0.009168982 0.09558796 0.07530695 0.09558796 0.06357496 0.09730899 0.05798786 0.09730899 0.08089399 0.09558796 0.07530695 0.09730899 0.05798786 0.09558796 0.07530695 0.095007 0.06944096 0.09558796 0.06357496 0.182384 0.01441782 0.182384 0.124464 0.152739 0.129712 0.191529 0.01702797 0.191493 0.121868 0.182384 0.124464 0.182384 0.01441782 0.191529 0.01702797 0.182384 0.124464 0.195917 0.01903897 0.2000499 0.117433 0.191493 0.121868 0.191529 0.01702797 0.195917 0.01903897 0.191493 0.121868 0.200112 0.02148896 0.207723 0.111308 0.2000499 0.117433 0.195917 0.01903897 0.200112 0.02148896 0.2000499 0.117433 0.207791 0.02763897 0.214224 0.103709 0.207723 0.111308 0.200112 0.02148896 0.207791 0.02763897 0.207723 0.111308 0.214277 0.03524684 0.2193599 0.09483295 0.214224 0.103709 0.207791 0.02763897 0.214277 0.03524684 0.214224 0.103709 0.2193869 0.04410582 0.222891 0.08504098 0.2193599 0.09483295 0.214277 0.03524684 0.2193869 0.04410582 0.2193599 0.09483295 0.222898 0.05386698 0.224686 0.07470095 0.222891 0.08504098 0.2193869 0.04410582 0.222898 0.05386698 0.222891 0.08504098 0.222898 0.05386698 0.224686 0.06418597 0.224686 0.07470095 0.112896 0.133623 0.09255999 0.132042 0.101733 0.134754 0.120984 0.135851 0.112896 0.133623 0.101733 0.134754 0.104899 0.130779 0.083485 0.128686 0.09255999 0.132042 0.112896 0.133623 0.104899 0.130779 0.09255999 0.132042 0.09709697 0.127344 0.074651 0.124715 0.083485 0.128686 0.104899 0.130779 0.09709697 0.127344 0.083485 0.128686 0.08959698 0.123346 0.06620496 0.1201699 0.074651 0.124715 0.05321484 0.122155 0.074651 0.124715 0.06620496 0.1201699 0.09709697 0.127344 0.08959698 0.123346 0.074651 0.124715 0.08250796 0.118822 0.05829495 0.115095 0.06620496 0.1201699 0.04467797 0.11759 0.06620496 0.1201699 0.05829495 0.115095 0.08959698 0.123346 0.08250796 0.118822 0.06620496 0.1201699 0.04467797 0.11759 0.05321484 0.122155 0.06620496 0.1201699 0.075935 0.113813 0.05106699 0.109542 0.05829495 0.115095 0.03670299 0.112589 0.05829495 0.115095 0.05106699 0.109542 0.08250796 0.118822 0.075935 0.113813 0.05829495 0.115095 0.03670299 0.112589 0.04467797 0.11759 0.05829495 0.115095 0.06998199 0.1083649 0.04466187 0.103566 0.05106699 0.109542 0.02943295 0.1071979 0.05106699 0.109542 0.04466187 0.103566 0.075935 0.113813 0.06998199 0.1083649 0.05106699 0.109542 0.02943295 0.1071979 0.03670299 0.112589 0.05106699 0.109542 0.064745 0.102529 0.03920799 0.09722399 0.04466187 0.103566 0.02300482 0.101464 0.04466187 0.103566 0.03920799 0.09722399 0.06998199 0.1083649 0.064745 0.102529 0.04466187 0.103566 0.02300482 0.101464 0.02943295 0.1071979 0.04466187 0.103566 0.06031286 0.09635698 0.03482395 0.09057897 0.03920799 0.09722399 0.01754283 0.095438 0.03920799 0.09722399 0.03482395 0.09057897 0.064745 0.102529 0.06031286 0.09635698 0.03920799 0.09722399 0.01754283 0.095438 0.02300482 0.101464 0.03920799 0.09722399 0.05676686 0.08990496 0.03160583 0.08369195 0.03482395 0.09057897 0.01316183 0.08917099 0.03482395 0.09057897 0.03160583 0.08369195 0.06031286 0.09635698 0.05676686 0.08990496 0.03482395 0.09057897 0.01316183 0.08917099 0.01754283 0.095438 0.03482395 0.09057897 0.05417382 0.08322995 0.02963685 0.07662498 0.03160583 0.08369195 0.009952962 0.08271497 0.03160583 0.08369195 0.02963685 0.07662498 0.05676686 0.08990496 0.05417382 0.08322995 0.03160583 0.08369195 0.009952962 0.08271497 0.01316183 0.08917099 0.03160583 0.08369195 0.05417382 0.08322995 0.05259186 0.07638996 0.02963685 0.07662498 0.007994949 0.07612097 0.009952962 0.08271497 0.02963685 0.07662498 0.07710999 0.07632195 0.05259186 0.07638996 0.05417382 0.08322995 0.07840895 0.08310997 0.05417382 0.08322995 0.05676686 0.08990496 0.07710999 0.07632195 0.05417382 0.08322995 0.07840895 0.08310997 0.08054399 0.08974397 0.05676686 0.08990496 0.06031286 0.09635698 0.07840895 0.08310997 0.05676686 0.08990496 0.08054399 0.08974397 0.08347696 0.096165 0.06031286 0.09635698 0.064745 0.102529 0.08054399 0.08974397 0.06031286 0.09635698 0.08347696 0.096165 0.08716398 0.102313 0.064745 0.102529 0.06998199 0.1083649 0.08347696 0.096165 0.064745 0.102529 0.08716398 0.102313 0.09154695 0.108133 0.06998199 0.1083649 0.075935 0.113813 0.08716398 0.102313 0.06998199 0.1083649 0.09154695 0.108133 0.09656697 0.11357 0.075935 0.113813 0.08250796 0.118822 0.09154695 0.108133 0.075935 0.113813 0.09656697 0.11357 0.102154 0.118574 0.08250796 0.118822 0.08959698 0.123346 0.09656697 0.11357 0.08250796 0.118822 0.102154 0.118574 0.108235 0.123097 0.08959698 0.123346 0.09709697 0.127344 0.102154 0.118574 0.08959698 0.123346 0.108235 0.123097 0.114733 0.127099 0.09709697 0.127344 0.104899 0.130779 0.108235 0.123097 0.09709697 0.127344 0.114733 0.127099 0.1215659 0.130541 0.104899 0.130779 0.112896 0.133623 0.114733 0.127099 0.104899 0.130779 0.1215659 0.130541 0.128653 0.133394 0.112896 0.133623 0.120984 0.135851 0.1215659 0.130541 0.112896 0.133623 0.128653 0.133394 0.135911 0.135633 0.120984 0.135851 0.129067 0.1374509 0.128653 0.133394 0.120984 0.135851 0.135911 0.135633 0.14326 0.137242 0.129067 0.1374509 0.1370519 0.138414 0.135911 0.135633 0.129067 0.1374509 0.14326 0.137242 0.14326 0.137242 0.1370519 0.138414 0.15062 0.1382099 0.01087695 0.03235197 0.01019597 0.03325897 0.007694959 0.03767496 0.01325899 0.02906197 0.01019597 0.03325897 0.01087695 0.03235197 0.01325899 0.02906197 0.01243084 0.030101 0.01019597 0.03325897 0.008298993 0.03681695 0.007694959 0.03767496 0.005343973 0.04270899 0.008298993 0.03681695 0.01087695 0.03235197 0.007694959 0.03767496 0.005862951 0.04193097 0.005343973 0.04270899 0.003242969 0.04843199 0.005862951 0.04193097 0.008298993 0.03681695 0.005343973 0.04270899 0.003672957 0.04777598 0.003242969 0.04843199 0.001536965 0.05487185 0.003672957 0.04777598 0.005862951 0.04193097 0.003242969 0.04843199 0.001884937 0.05438894 0.001536965 0.05487185 4.02e-4 0.06195282 0.001884937 0.05438894 0.003672957 0.04777598 0.001536965 0.05487185 6.89e-4 0.06169492 0.001884937 0.05438894 4.02e-4 0.06195282 0.01960796 0.02508985 0.01820397 0.02633798 0.01651698 0.02667587 0.01771098 0.02546799 0.01651698 0.02667587 0.01457285 0.02790898 0.01771098 0.02546799 0.01960796 0.02508985 0.01651698 0.02667587 0.01557284 0.02677083 0.01457285 0.02790898 0.01243084 0.030101 0.01557284 0.02677083 0.01771098 0.02546799 0.01457285 0.02790898 0.01325899 0.02906197 0.01557284 0.02677083 0.01243084 0.030101 0.234316 0.06944096 0.109213 0.06944096 0.109455 0.074934 0.234073 0.06394797 0.109213 0.06944096 0.234316 0.06944096 0.110158 0.05860096 0.109213 0.06944096 0.234073 0.06394797 0.23337 0.08028095 0.109455 0.074934 0.110169 0.08034497 0.234316 0.06944096 0.109455 0.074934 0.23337 0.08028095 0.230554 0.09081798 0.110169 0.08034497 0.113007 0.09090799 0.23337 0.08028095 0.110169 0.08034497 0.230554 0.09081798 0.2259539 0.100701 0.113007 0.09090799 0.117619 0.1007789 0.230554 0.09081798 0.113007 0.09090799 0.2259539 0.100701 0.2197279 0.109606 0.117619 0.1007789 0.123836 0.109648 0.2259539 0.100701 0.117619 0.1007789 0.2197279 0.109606 0.21602 0.11366 0.123836 0.109648 0.131543 0.117358 0.2197279 0.109606 0.123836 0.109648 0.21602 0.11366 0.2119809 0.117362 0.131543 0.117358 0.1404629 0.123606 0.21602 0.11366 0.131543 0.117358 0.2119809 0.117362 0.202996 0.123645 0.1404629 0.123606 0.1503199 0.128205 0.207617 0.120707 0.1404629 0.123606 0.202996 0.123645 0.2119809 0.117362 0.1404629 0.123606 0.207617 0.120707 0.193072 0.128255 0.1503199 0.128205 0.160822 0.1310279 0.202996 0.123645 0.1503199 0.128205 0.193072 0.128255 0.182519 0.131061 0.160822 0.1310279 0.171662 0.131991 0.193072 0.128255 0.160822 0.1310279 0.182519 0.131061 0.110158 0.05860096 0.234073 0.06394797 0.233359 0.05853599 0.112975 0.04806298 0.233359 0.05853599 0.230521 0.04797399 0.110158 0.05860096 0.233359 0.05853599 0.112975 0.04806298 0.117574 0.03818082 0.230521 0.04797399 0.2259089 0.03810298 0.112975 0.04806298 0.230521 0.04797399 0.117574 0.03818082 0.123801 0.02927595 0.2259089 0.03810298 0.219693 0.02923399 0.117574 0.03818082 0.2259089 0.03810298 0.123801 0.02927595 0.1275089 0.025222 0.219693 0.02923399 0.211986 0.02152395 0.123801 0.02927595 0.219693 0.02923399 0.1275089 0.025222 0.131547 0.02151983 0.211986 0.02152395 0.203065 0.01527583 0.1275089 0.025222 0.211986 0.02152395 0.131547 0.02151983 0.140532 0.01523697 0.203065 0.01527583 0.193208 0.01067584 0.135911 0.01817399 0.203065 0.01527583 0.140532 0.01523697 0.131547 0.02151983 0.203065 0.01527583 0.135911 0.01817399 0.150457 0.01062697 0.193208 0.01067584 0.1827059 0.007853984 0.140532 0.01523697 0.193208 0.01067584 0.150457 0.01062697 0.161009 0.007820963 0.1827059 0.007853984 0.1718659 0.006889939 0.150457 0.01062697 0.1827059 0.007853984 0.161009 0.007820963 0.02431398 0.080388 0.02431398 0.05849283 0.02708399 0.041619 0.02380895 0.07630795 0.02380895 0.06257295 0.02431398 0.05849283 0.02431398 0.080388 0.02380895 0.07630795 0.02431398 0.05849283 0.02708399 0.09726297 0.02708399 0.041619 0.02787399 0.037705 0.02708399 0.09726297 0.02431398 0.080388 0.02708399 0.041619 0.02787399 0.101176 0.02787399 0.037705 0.02881598 0.03461796 0.02787399 0.101176 0.02708399 0.09726297 0.02787399 0.037705 0.02881598 0.104264 0.02881598 0.03461796 0.02986997 0.03246986 0.02881598 0.104264 0.02787399 0.101176 0.02881598 0.03461796 0.02986997 0.106412 0.02986997 0.03246986 0.03099083 0.03133487 0.02986997 0.106412 0.02881598 0.104264 0.02986997 0.03246986 0.03099083 0.107547 0.03099083 0.03133487 0.03213596 0.03124094 0.03099083 0.107547 0.02986997 0.106412 0.03099083 0.03133487 0.03213596 0.10764 0.03099083 0.107547 0.03213596 0.03124094 0.03534787 0.03244096 0.03213596 0.10764 0.03213596 0.03124094 0.02354699 0.07178097 0.02354699 0.067101 0.02380895 0.06257295 0.02380895 0.07630795 0.02354699 0.07178097 0.02380895 0.06257295 0.03534787 0.03244096 0.03534787 0.10644 0.03213596 0.10764 0.03693085 0.03379899 0.036924 0.105093 0.03534787 0.10644 0.03534787 0.03244096 0.03693085 0.03379899 0.03534787 0.10644 0.03693085 0.03379899 0.03840196 0.102314 0.036924 0.105093 0.038414 0.03659784 0.03972095 0.09825199 0.03840196 0.102314 0.03693085 0.03379899 0.038414 0.03659784 0.03840196 0.102314 0.03973299 0.04067498 0.04083585 0.09307998 0.03972095 0.09825199 0.038414 0.03659784 0.03973299 0.04067498 0.03972095 0.09825199 0.04084396 0.04584795 0.04171186 0.08697497 0.04083585 0.09307998 0.03973299 0.04067498 0.04084396 0.04584795 0.04083585 0.09307998 0.04231095 0.05866396 0.04231184 0.08021199 0.04171186 0.08697497 0.04171484 0.05193096 0.04231095 0.05866396 0.04171186 0.08697497 0.04084396 0.04584795 0.04171484 0.05193096 0.04171186 0.08697497 0.04261487 0.06579297 0.04261487 0.073062 0.04231184 0.08021199 0.04231095 0.05866396 0.04261487 0.06579297 0.04231184 0.08021199 0.228379 0.09271395 0.22584 0.09732198 0.225933 0.09715098 0.2258239 0.09735 0.225933 0.09715098 0.22584 0.09732198 0.226243 0.09651398 0.225933 0.09715098 0.225948 0.09706795 0.2258239 0.09735 0.225948 0.09706795 0.225933 0.09715098 0.226624 0.09579396 0.225933 0.09715098 0.226243 0.09651398 0.2271029 0.09486895 0.225933 0.09715098 0.226624 0.09579396 0.227697 0.09369099 0.225933 0.09715098 0.2271029 0.09486895 0.228227 0.09265297 0.225933 0.09715098 0.227697 0.09369099 0.228227 0.09265297 0.228379 0.09271395 0.225933 0.09715098 0.228379 0.09271395 0.225731 0.09748399 0.22584 0.09732198 0.2258239 0.09735 0.22584 0.09732198 0.225731 0.09748399 0.228379 0.09271395 0.225948 0.09706795 0.225731 0.09748399 0.2258239 0.09735 0.225731 0.09748399 0.225948 0.09706795 0.225709 0.09752196 0.225731 0.09748399 0.225702 0.09753799 0.2258239 0.09735 0.225702 0.09753799 0.225731 0.09748399 0.2258239 0.09735 0.225731 0.09748399 0.225709 0.09752196 0.228379 0.09271395 0.226243 0.09651398 0.225948 0.09706795 0.228379 0.09271395 0.226624 0.09579396 0.226243 0.09651398 0.228379 0.09271395 0.2271029 0.09486895 0.226624 0.09579396 0.228217 0.09262299 0.227697 0.09369099 0.2271029 0.09486895 0.228379 0.09271395 0.228217 0.09262299 0.2271029 0.09486895 0.228227 0.09265297 0.227697 0.09369099 0.228217 0.09262299 0.230357 0.08782398 0.228217 0.09262299 0.228379 0.09271395 0.2284229 0.09219199 0.228217 0.09262299 0.230357 0.08782398 0.228227 0.09265297 0.228217 0.09262299 0.2284229 0.09219199 0.228227 0.09265297 0.230357 0.08782398 0.228379 0.09271395 0.03625899 0.02369898 0.02054995 0.03229397 0.028503 0.01845395 0.02401095 0.01833397 0.028503 0.01845395 0.02054995 0.03229397 0.02960985 0.01642799 0.03625899 0.02369898 0.028503 0.01845395 0.02590584 0.01408886 0.02960985 0.01642799 0.028503 0.01845395 0.02590584 0.01408886 0.028503 0.01845395 0.02401095 0.01833397 0.03769385 0.03813886 0.01323199 0.04411482 0.02054995 0.03229397 0.01154887 0.03460294 0.02054995 0.03229397 0.01323199 0.04411482 0.03625899 0.02369898 0.03769385 0.03813886 0.02054995 0.03229397 0.02174896 0.02156597 0.02401095 0.01833397 0.02054995 0.03229397 0.019499 0.02477997 0.02174896 0.02156597 0.02054995 0.03229397 0.01845997 0.02473396 0.019499 0.02477997 0.02054995 0.03229397 0.01154887 0.03460294 0.01845997 0.02473396 0.02054995 0.03229397 0.03841286 0.05271798 0.01079487 0.048985 0.01323199 0.04411482 0.004917979 0.044061 0.01323199 0.04411482 0.01079487 0.048985 0.03769385 0.03813886 0.03841286 0.05271798 0.01323199 0.04411482 0.004917979 0.044061 0.01154887 0.03460294 0.01323199 0.04411482 0.03841286 0.05271798 0.009306967 0.05439299 0.01079487 0.048985 0.001809895 0.04997897 0.01079487 0.048985 0.009306967 0.05439299 0.001809895 0.04997897 0.004917979 0.044061 0.01079487 0.048985 0.03841286 0.067344 0.008809983 0.06002998 0.009306967 0.05439299 2.04e-4 0.05659782 0.009306967 0.05439299 0.008809983 0.06002998 0.03841286 0.05271798 0.03841286 0.067344 0.009306967 0.05439299 0.001809895 0.04997897 0.009306967 0.05439299 2.04e-4 0.05659782 0.03841286 0.067344 0.009306967 0.06566798 0.008809983 0.06002998 2.04e-4 0.06346195 0.008809983 0.06002998 0.009306967 0.06566798 0 0.06002998 0.008809983 0.06002998 2.04e-4 0.06346195 2.04e-4 0.05659782 0.008809983 0.06002998 0 0.06002998 0.03841286 0.067344 0.01079487 0.07107597 0.009306967 0.06566798 0.001809895 0.07008099 0.009306967 0.06566798 0.01079487 0.07107597 2.04e-4 0.06346195 0.009306967 0.06566798 0.001809895 0.07008099 0.03769385 0.081923 0.01323199 0.07594597 0.01079487 0.07107597 0.001809895 0.07008099 0.01079487 0.07107597 0.01323199 0.07594597 0.03841286 0.067344 0.03769385 0.081923 0.01079487 0.07107597 0.03769385 0.081923 0.01878386 0.08484095 0.01323199 0.07594597 0.004917979 0.07599997 0.01323199 0.07594597 0.01878386 0.08484095 0.001809895 0.07008099 0.01323199 0.07594597 0.004917979 0.07599997 0.03625899 0.096363 0.02472382 0.09488397 0.01878386 0.08484095 0.01155185 0.08546096 0.01878386 0.08484095 0.02472382 0.09488397 0.03769385 0.081923 0.03625899 0.096363 0.01878386 0.08484095 0.004917979 0.07599997 0.01878386 0.08484095 0.01155185 0.08546096 0.03625899 0.096363 0.02777397 0.100288 0.02472382 0.09488397 0.019499 0.095281 0.02472382 0.09488397 0.02777397 0.100288 0.019499 0.095281 0.01155185 0.08546096 0.02472382 0.09488397 0.03403699 0.110661 0.03069984 0.105654 0.02777397 0.100288 0.02401 0.101726 0.02777397 0.100288 0.03069984 0.105654 0.03625899 0.096363 0.03403699 0.110661 0.02777397 0.100288 0.02175796 0.098508 0.019499 0.095281 0.02777397 0.100288 0.02401 0.101726 0.02175796 0.098508 0.02777397 0.100288 0.02590584 0.105971 0.03069984 0.105654 0.03403699 0.110661 0.02297782 0.101785 0.03069984 0.105654 0.02590584 0.105971 0.02401 0.101726 0.03069984 0.105654 0.02297782 0.101785 0.06579399 0.104374 0.03403699 0.110661 0.03625899 0.096363 0.06330299 0.118712 0.03471595 0.111454 0.03403699 0.110661 0.03073799 0.111557 0.03403699 0.110661 0.03471595 0.111454 0.06579399 0.104374 0.06330299 0.118712 0.03403699 0.110661 0.02819395 0.108912 0.03403699 0.110661 0.03073799 0.111557 0.02590584 0.105971 0.03403699 0.110661 0.02819395 0.108912 0.06757897 0.08974897 0.03625899 0.096363 0.03769385 0.081923 0.06757897 0.08974897 0.06579399 0.104374 0.03625899 0.096363 0.06865197 0.07493698 0.03769385 0.081923 0.03841286 0.067344 0.06865197 0.07493698 0.06757897 0.08974897 0.03769385 0.081923 0.06900995 0.06002998 0.03841286 0.067344 0.03841286 0.05271798 0.06900995 0.06002998 0.06865197 0.07493698 0.03841286 0.067344 0.06865197 0.04512399 0.03841286 0.05271798 0.03769385 0.03813886 0.06865197 0.04512399 0.06900995 0.06002998 0.03841286 0.05271798 0.06757897 0.03031086 0.03769385 0.03813886 0.03625899 0.02369898 0.06757897 0.03031086 0.06865197 0.04512399 0.03769385 0.03813886 0.03069984 0.01440685 0.03403896 0.009397983 0.03625899 0.02369898 0.06579399 0.01568686 0.03625899 0.02369898 0.03403896 0.009397983 0.02960985 0.01642799 0.03069984 0.01440685 0.03625899 0.02369898 0.06579399 0.01568686 0.06757897 0.03031086 0.03625899 0.02369898 0.02819395 0.01114886 0.03403896 0.009397983 0.03069984 0.01440685 0.03472495 0.008595943 0.06579399 0.01568686 0.03403896 0.009397983 0.03073799 0.00850296 0.03472495 0.008595943 0.03403896 0.009397983 0.03073799 0.00850296 0.03403896 0.009397983 0.02819395 0.01114886 0.02590584 0.01408886 0.03069984 0.01440685 0.02960985 0.01642799 0.02819395 0.01114886 0.03069984 0.01440685 0.02590584 0.01408886 0.06330299 0.118712 0.03710198 0.1138229 0.03471595 0.111454 0.03352296 0.113892 0.03471595 0.111454 0.03710198 0.1138229 0.03073799 0.111557 0.03471595 0.111454 0.03352296 0.113892 0.06330299 0.118712 0.03973895 0.115841 0.03710198 0.1138229 0.03651696 0.115889 0.03710198 0.1138229 0.03973895 0.115841 0.03352296 0.113892 0.03710198 0.1138229 0.03651696 0.115889 0.06330299 0.118712 0.04557496 0.118694 0.03973895 0.115841 0.04298496 0.118768 0.03973895 0.115841 0.04557496 0.118694 0.03651696 0.115889 0.03973895 0.115841 0.04298496 0.118768 0.058631 0.119536 0.05197685 0.119924 0.04557496 0.118694 0.049878 0.12006 0.04557496 0.118694 0.05197685 0.119924 0.06330299 0.118712 0.058631 0.119536 0.04557496 0.118694 0.04298496 0.118768 0.04557496 0.118694 0.049878 0.12006 0.049878 0.12006 0.05197685 0.119924 0.058631 0.119536 0.05688196 0.119681 0.058631 0.119536 0.06330299 0.118712 0.049878 0.12006 0.058631 0.119536 0.05688196 0.119681 0.07335597 0.116934 0.06330299 0.118712 0.06579399 0.104374 0.07155597 0.1170819 0.06330299 0.118712 0.07335597 0.116934 0.05688196 0.119681 0.06330299 0.118712 0.07155597 0.1170819 0.09814399 0.09747195 0.06579399 0.104374 0.06757897 0.08974897 0.09545201 0.112389 0.08819198 0.114294 0.06579399 0.104374 0.07335597 0.116934 0.06579399 0.104374 0.08819198 0.114294 0.09607297 0.112168 0.09545201 0.112389 0.06579399 0.104374 0.09814399 0.09747195 0.09607297 0.112168 0.06579399 0.104374 0.099536 0.08258795 0.06757897 0.08974897 0.06865197 0.07493698 0.099536 0.08258795 0.09814399 0.09747195 0.06757897 0.08974897 0.100233 0.06756496 0.06865197 0.07493698 0.06900995 0.06002998 0.100233 0.06756496 0.099536 0.08258795 0.06865197 0.07493698 0.100233 0.05249583 0.06900995 0.06002998 0.06865197 0.04512399 0.100233 0.05249583 0.100233 0.06756496 0.06900995 0.06002998 0.099536 0.03747296 0.06865197 0.04512399 0.06757897 0.03031086 0.099536 0.03747296 0.100233 0.05249583 0.06865197 0.04512399 0.09814399 0.02258795 0.06757897 0.03031086 0.06579399 0.01568686 0.09814399 0.02258795 0.099536 0.03747296 0.06757897 0.03031086 0.03973084 0.004223883 0.06330299 0.001347959 0.06579399 0.01568686 0.09607297 0.007891952 0.06579399 0.01568686 0.06330299 0.001347959 0.03710496 0.006234884 0.03973084 0.004223883 0.06579399 0.01568686 0.03472495 0.008595943 0.03710496 0.006234884 0.06579399 0.01568686 0.09607297 0.007891952 0.09814399 0.02258795 0.06579399 0.01568686 0.04553896 0.001378953 0.058631 5.24e-4 0.06330299 0.001347959 0.07155597 0.002977967 0.06330299 0.001347959 0.058631 5.24e-4 0.03973084 0.004223883 0.04553896 0.001378953 0.06330299 0.001347959 0.09545099 0.007671952 0.09607297 0.007891952 0.06330299 0.001347959 0.07335597 0.003126919 0.09545099 0.007671952 0.06330299 0.001347959 0.07155597 0.002977967 0.07335597 0.003126919 0.06330299 0.001347959 0.04553896 0.001378953 0.05192995 1.39e-4 0.058631 5.24e-4 0.05688196 3.8e-4 0.058631 5.24e-4 0.05192995 1.39e-4 0.07155597 0.002977967 0.058631 5.24e-4 0.05688196 3.8e-4 0.049878 0 0.05192995 1.39e-4 0.04553896 0.001378953 0.05688196 3.8e-4 0.05192995 1.39e-4 0.049878 0 0.04298496 0.00129199 0.04553896 0.001378953 0.03973084 0.004223883 0.049878 0 0.04553896 0.001378953 0.04298496 0.00129199 0.03651696 0.004171967 0.03973084 0.004223883 0.03710496 0.006234884 0.04298496 0.00129199 0.03973084 0.004223883 0.03651696 0.004171967 0.03352296 0.006167948 0.03710496 0.006234884 0.03472495 0.008595943 0.03651696 0.004171967 0.03710496 0.006234884 0.03352296 0.006167948 0.03352296 0.006167948 0.03472495 0.008595943 0.03073799 0.00850296 0.08650499 0.114426 0.08819198 0.114294 0.09545201 0.112389 0.07155597 0.1170819 0.07335597 0.116934 0.08819198 0.114294 0.07155597 0.1170819 0.08819198 0.114294 0.08650499 0.114426 0.09373199 0.112521 0.09545201 0.112389 0.09607297 0.112168 0.08650499 0.114426 0.09545201 0.112389 0.09373199 0.112521 0.1026239 0.109264 0.09607297 0.112168 0.09814399 0.09747195 0.101593 0.109372 0.09607297 0.112168 0.1026239 0.109264 0.101593 0.109372 0.09373199 0.112521 0.09607297 0.112168 0.123644 0.089742 0.09814399 0.09747195 0.099536 0.08258795 0.109521 0.104918 0.1026239 0.109264 0.09814399 0.09747195 0.113526 0.101658 0.109521 0.104918 0.09814399 0.09747195 0.117242 0.09802097 0.113526 0.101658 0.09814399 0.09747195 0.123644 0.089742 0.117242 0.09802097 0.09814399 0.09747195 0.128418 0.08042097 0.099536 0.08258795 0.100233 0.06756496 0.128418 0.08042097 0.123644 0.089742 0.099536 0.08258795 0.132355 0.06002998 0.100233 0.06756496 0.100233 0.05249583 0.1313689 0.07034999 0.128418 0.08042097 0.100233 0.06756496 0.132355 0.06002998 0.1313689 0.07034999 0.100233 0.06756496 0.1313689 0.04970699 0.100233 0.05249583 0.099536 0.03747296 0.1313689 0.04970699 0.132355 0.06002998 0.100233 0.05249583 0.123642 0.03031384 0.099536 0.03747296 0.09814399 0.02258795 0.128416 0.039635 0.1313689 0.04970699 0.099536 0.03747296 0.123642 0.03031384 0.128416 0.039635 0.099536 0.03747296 0.11724 0.02203691 0.09814399 0.02258795 0.09607297 0.007891952 0.11724 0.02203691 0.123642 0.03031384 0.09814399 0.02258795 0.09373199 0.007539987 0.09607297 0.007891952 0.09545099 0.007671952 0.109521 0.01514196 0.11724 0.02203691 0.09607297 0.007891952 0.102622 0.01079595 0.109521 0.01514196 0.09607297 0.007891952 0.101593 0.01068782 0.102622 0.01079595 0.09607297 0.007891952 0.09373199 0.007539987 0.100643 0.01061987 0.09607297 0.007891952 0.101593 0.01068782 0.09607297 0.007891952 0.100643 0.01061987 0.07335597 0.003126919 0.08819097 0.005765974 0.09545099 0.007671952 0.09373199 0.007539987 0.09545099 0.007671952 0.08819097 0.005765974 0.08650499 0.005634963 0.08819097 0.005765974 0.07335597 0.003126919 0.09373199 0.007539987 0.08819097 0.005765974 0.08650499 0.005634963 0.08650499 0.005634963 0.07335597 0.003126919 0.07155597 0.002977967 0.105243 0.10717 0.1026239 0.109264 0.109521 0.104918 0.105243 0.10717 0.101593 0.109372 0.1026239 0.109264 0.107286 0.105086 0.109521 0.104918 0.113526 0.101658 0.108876 0.104974 0.109521 0.104918 0.107286 0.105086 0.108219 0.10503 0.109521 0.104918 0.108876 0.104974 0.105243 0.10717 0.109521 0.104918 0.108219 0.10503 0.114473 0.09828197 0.113526 0.101658 0.117242 0.09802097 0.107286 0.105086 0.113526 0.101658 0.114473 0.09828197 0.120406 0.09003698 0.117242 0.09802097 0.123644 0.089742 0.114473 0.09828197 0.117242 0.09802097 0.120406 0.09003698 0.122815 0.08547198 0.123644 0.089742 0.128418 0.08042097 0.120406 0.09003698 0.123644 0.089742 0.122815 0.08547198 0.127528 0.07056397 0.128418 0.08042097 0.1313689 0.07034999 0.124823 0.08065497 0.128418 0.08042097 0.127528 0.07056397 0.122815 0.08547198 0.128418 0.08042097 0.124823 0.08065497 0.128216 0.065333 0.1313689 0.07034999 0.132355 0.06002998 0.127528 0.07056397 0.1313689 0.07034999 0.128216 0.065333 0.128219 0.05475884 0.132355 0.06002998 0.1313689 0.04970699 0.1284469 0.06004887 0.132355 0.06002998 0.128219 0.05475884 0.128216 0.065333 0.132355 0.06002998 0.1284469 0.06004887 0.127529 0.04950284 0.1313689 0.04970699 0.128416 0.039635 0.128219 0.05475884 0.1313689 0.04970699 0.127529 0.04950284 0.124807 0.03935986 0.128416 0.039635 0.123642 0.03031384 0.126388 0.044357 0.128416 0.039635 0.124807 0.03935986 0.127529 0.04950284 0.128416 0.039635 0.126388 0.044357 0.120404 0.03002095 0.123642 0.03031384 0.11724 0.02203691 0.124807 0.03935986 0.123642 0.03031384 0.120404 0.03002095 0.114485 0.02179199 0.11724 0.02203691 0.109521 0.01514196 0.120404 0.03002095 0.11724 0.02203691 0.114485 0.02179199 0.108875 0.01508796 0.109521 0.01514196 0.102622 0.01079595 0.108875 0.01508796 0.114485 0.02179199 0.109521 0.01514196 0.108219 0.01502984 0.108875 0.01508796 0.102622 0.01079595 0.106863 0.01399987 0.108219 0.01502984 0.102622 0.01079595 0.104364 0.01232296 0.106863 0.01399987 0.102622 0.01079595 0.101593 0.01068782 0.104364 0.01232296 0.102622 0.01079595 0.02297782 0.01827496 0.02590584 0.01408886 0.02401095 0.01833397 0.02174896 0.02156597 0.02297782 0.01827496 0.02401095 0.01833397 0.02590584 0.105971 0.02590584 0.01408886 0.02297782 0.01827496 0.02590584 0.105971 0.02819395 0.108912 0.02590584 0.01408886 0.02819395 0.01114886 0.02590584 0.01408886 0.02819395 0.108912 0.019499 0.02477997 0.02297782 0.01827496 0.02174896 0.02156597 0.01845997 0.02473396 0.02297782 0.01827496 0.019499 0.02477997 0.02297782 0.101785 0.02297782 0.01827496 0.01845997 0.02473396 0.02297782 0.101785 0.02590584 0.105971 0.02297782 0.01827496 0.01845997 0.09532696 0.01845997 0.02473396 0.01154887 0.03460294 0.01845997 0.09532696 0.02297782 0.101785 0.01845997 0.02473396 0.01155185 0.08546096 0.01154887 0.03460294 0.004917979 0.044061 0.01155185 0.08546096 0.01845997 0.09532696 0.01154887 0.03460294 0.004917979 0.07599997 0.01155185 0.08546096 0.004917979 0.044061 0.001809895 0.04997897 0.004917979 0.07599997 0.004917979 0.044061 0.10403 0.107412 0.10403 0.01264894 0.100643 0.01061987 0.104364 0.01232296 0.100643 0.01061987 0.10403 0.01264894 0.100643 0.109441 0.10403 0.107412 0.100643 0.01061987 0.09373199 0.007539987 0.100643 0.109441 0.100643 0.01061987 0.101593 0.01068782 0.100643 0.01061987 0.104364 0.01232296 0.107286 0.105086 0.107286 0.01497387 0.10403 0.01264894 0.106863 0.01399987 0.10403 0.01264894 0.107286 0.01497387 0.10403 0.107412 0.107286 0.105086 0.10403 0.01264894 0.104364 0.01232296 0.10403 0.01264894 0.106863 0.01399987 0.114473 0.09828197 0.114485 0.02179199 0.107286 0.01497387 0.108219 0.01502984 0.107286 0.01497387 0.114485 0.02179199 0.107286 0.105086 0.114473 0.09828197 0.107286 0.01497387 0.106863 0.01399987 0.107286 0.01497387 0.108219 0.01502984 0.120406 0.09003698 0.120404 0.03002095 0.114485 0.02179199 0.114473 0.09828197 0.120406 0.09003698 0.114485 0.02179199 0.108219 0.01502984 0.114485 0.02179199 0.108875 0.01508796 0.122815 0.08547198 0.124807 0.03935986 0.120404 0.03002095 0.120406 0.09003698 0.122815 0.08547198 0.120404 0.03002095 0.124823 0.08065497 0.126388 0.044357 0.124807 0.03935986 0.122815 0.08547198 0.124823 0.08065497 0.124807 0.03935986 0.127528 0.07056397 0.127529 0.04950284 0.126388 0.044357 0.124823 0.08065497 0.127528 0.07056397 0.126388 0.044357 0.128216 0.065333 0.128219 0.05475884 0.127529 0.04950284 0.127528 0.07056397 0.128216 0.065333 0.127529 0.04950284 0.128216 0.065333 0.1284469 0.06004887 0.128219 0.05475884 0.105243 0.10717 0.107286 0.105086 0.10403 0.107412 0.108219 0.10503 0.108876 0.104974 0.107286 0.105086 0.105243 0.10717 0.108219 0.10503 0.107286 0.105086 0.105243 0.10717 0.10403 0.107412 0.100643 0.109441 0.09373199 0.007539987 0.09373199 0.112521 0.100643 0.109441 0.101593 0.109372 0.100643 0.109441 0.09373199 0.112521 0.105243 0.10717 0.100643 0.109441 0.101593 0.109372 0.08650499 0.005634963 0.08650499 0.114426 0.09373199 0.112521 0.09373199 0.007539987 0.08650499 0.005634963 0.09373199 0.112521 0.07155597 0.002977967 0.07155597 0.1170819 0.08650499 0.114426 0.08650499 0.005634963 0.07155597 0.002977967 0.08650499 0.114426 0.05688196 3.8e-4 0.05688196 0.119681 0.07155597 0.1170819 0.07155597 0.002977967 0.05688196 3.8e-4 0.07155597 0.1170819 0.049878 0 0.049878 0.12006 0.05688196 0.119681 0.05688196 3.8e-4 0.049878 0 0.05688196 0.119681 0.04298496 0.00129199 0.04298496 0.118768 0.049878 0.12006 0.049878 0 0.04298496 0.00129199 0.049878 0.12006 0.03651696 0.004171967 0.03651696 0.115889 0.04298496 0.118768 0.04298496 0.00129199 0.03651696 0.004171967 0.04298496 0.118768 0.03352296 0.006167948 0.03352296 0.113892 0.03651696 0.115889 0.03651696 0.004171967 0.03352296 0.006167948 0.03651696 0.115889 0.03073799 0.00850296 0.03073799 0.111557 0.03352296 0.113892 0.03352296 0.006167948 0.03073799 0.00850296 0.03352296 0.113892 0.02819395 0.01114886 0.02819395 0.108912 0.03073799 0.111557 0.03073799 0.00850296 0.02819395 0.01114886 0.03073799 0.111557 0.02401 0.101726 0.02297782 0.101785 0.01845997 0.09532696 0.019499 0.095281 0.01845997 0.09532696 0.01155185 0.08546096 0.02175796 0.098508 0.01845997 0.09532696 0.019499 0.095281 0.02401 0.101726 0.01845997 0.09532696 0.02175796 0.098508 0.001809895 0.04997897 0.001809895 0.07008099 0.004917979 0.07599997 2.04e-4 0.05659782 2.04e-4 0.06346195 0.001809895 0.07008099 0.001809895 0.04997897 2.04e-4 0.05659782 0.001809895 0.07008099 2.04e-4 0.05659782 0 0.06002998 2.04e-4 0.06346195 0.01736187 0.07500696 0.009876966 0.07033598 0.007442951 0.06569999 0.01171886 0.06567996 0.007442951 0.06569999 0.009876966 0.07033598 0.01426297 0.064619 0.01736187 0.07500696 0.007442951 0.06569999 0.004074931 0.05714684 0.01426297 0.064619 0.007442951 0.06569999 0.01163697 0.06518501 0.004074931 0.05714684 0.007442951 0.06569999 0.01167798 0.06543296 0.01163697 0.06518501 0.007442951 0.06569999 0.01171886 0.06567996 0.01167798 0.06543296 0.007442951 0.06569999 0.01736187 0.07500696 0.01222884 0.07350897 0.009876966 0.07033598 0.01581192 0.07328897 0.009876966 0.07033598 0.01222884 0.07350897 0.01411098 0.06785398 0.01171886 0.06567996 0.009876966 0.07033598 0.01464498 0.07004797 0.01411098 0.06785398 0.009876966 0.07033598 0.01581192 0.07328897 0.01464498 0.07004797 0.009876966 0.07033598 0.01736187 0.07500696 0.01434898 0.07526397 0.01222884 0.07350897 0.01646596 0.07441598 0.01222884 0.07350897 0.01434898 0.07526397 0.01646596 0.07441598 0.01581192 0.07328897 0.01222884 0.07350897 0.01736187 0.07500696 0.015989 0.07550299 0.01434898 0.07526397 0.01786983 0.07553499 0.01434898 0.07526397 0.015989 0.07550299 0.01716095 0.075181 0.01646596 0.07441598 0.01434898 0.07526397 0.01786983 0.07553499 0.01716095 0.075181 0.01434898 0.07526397 0.01858484 0.075477 0.015989 0.07550299 0.01736187 0.07500696 0.01858484 0.075477 0.01786983 0.07553499 0.015989 0.07550299 0.01764595 0.07490497 0.01736187 0.07500696 0.01426297 0.064619 0.01858484 0.075477 0.01736187 0.07500696 0.01764595 0.07490497 0.004074931 0.05714684 0.01218187 0.05397886 0.01426297 0.064619 0.02180182 0.06143587 0.01426297 0.064619 0.01218187 0.05397886 0.02049398 0.073237 0.01928496 0.07431197 0.01426297 0.064619 0.01764595 0.07490497 0.01426297 0.064619 0.01928496 0.07431197 0.02093786 0.07229 0.02049398 0.073237 0.01426297 0.064619 0.02128183 0.07107597 0.02093786 0.07229 0.01426297 0.064619 0.02169698 0.06791597 0.02128183 0.07107597 0.01426297 0.064619 0.02182096 0.06382399 0.02169698 0.06791597 0.01426297 0.064619 0.02180182 0.06143587 0.02182096 0.06382399 0.01426297 0.064619 7.79e-4 0.04598885 0.01113796 0.04318785 0.01218187 0.05397886 0.0215469 0.05218982 0.01218187 0.05397886 0.01113796 0.04318785 0.001342952 0.04841798 7.79e-4 0.04598885 0.01218187 0.05397886 0.004074931 0.05714684 0.001342952 0.04841798 0.01218187 0.05397886 0.02174592 0.05882591 0.02180182 0.06143587 0.01218187 0.05397886 0.02165091 0.05556082 0.02174592 0.05882591 0.01218187 0.05397886 0.0215469 0.05218982 0.02165091 0.05556082 0.01218187 0.05397886 3.53e-4 0.03217583 0.01113796 0.03234696 0.01113796 0.04318785 0.02129983 0.03776592 0.01113796 0.04318785 0.01113796 0.03234696 8.9e-5 0.03493696 3.53e-4 0.03217583 0.01113796 0.04318785 0 0.03776997 8.9e-5 0.03493696 0.01113796 0.04318785 9e-5 0.04060184 0 0.03776997 0.01113796 0.04318785 3.54e-4 0.04336297 9e-5 0.04060184 0.01113796 0.04318785 7.79e-4 0.04598885 3.54e-4 0.04336297 0.01113796 0.04318785 0.02136898 0.04510897 0.0215469 0.05218982 0.01113796 0.04318785 0.02129983 0.03776592 0.02136898 0.04510897 0.01113796 0.04318785 0.001342952 0.027116 0.01218187 0.02155596 0.01113796 0.03234696 0.02136898 0.03042 0.01113796 0.03234696 0.01218187 0.02155596 7.79e-4 0.02954697 0.001342952 0.027116 0.01113796 0.03234696 3.53e-4 0.03217583 7.79e-4 0.02954697 0.01113796 0.03234696 0.02136898 0.03042 0.02129983 0.03776592 0.01113796 0.03234696 0.004075944 0.01838696 0.01426297 0.01091599 0.01218187 0.02155596 0.02165091 0.01996392 0.01218187 0.02155596 0.01426297 0.01091599 0.001342952 0.027116 0.004075944 0.01838696 0.01218187 0.02155596 0.02154797 0.02333599 0.02136898 0.03042 0.01218187 0.02155596 0.02165091 0.01996392 0.02154797 0.02333599 0.01218187 0.02155596 0.01434797 2.71e-4 0.01736187 5.28e-4 0.01426297 0.01091599 0.02182096 0.011702 0.01426297 0.01091599 0.01736187 5.28e-4 0.01222687 0.002026975 0.01434797 2.71e-4 0.01426297 0.01091599 0.009874999 0.005200982 0.01222687 0.002026975 0.01426297 0.01091599 0.007442951 0.009832978 0.009874999 0.005200982 0.01426297 0.01091599 0.004075944 0.01838696 0.007442951 0.009832978 0.01426297 0.01091599 0.02174699 0.016698 0.02165091 0.01996392 0.01426297 0.01091599 0.02180182 0.01408886 0.02174699 0.016698 0.01426297 0.01091599 0.02182096 0.011702 0.02180182 0.01408886 0.01426297 0.01091599 0.01434797 2.71e-4 0.015989 3.2e-5 0.01736187 5.28e-4 0.02180695 0.001248896 0.01736187 5.28e-4 0.015989 3.2e-5 0.02169698 0.007612943 0.02182096 0.011702 0.01736187 5.28e-4 0.021281 0.00445497 0.02169698 0.007612943 0.01736187 5.28e-4 0.02093696 0.003242969 0.021281 0.00445497 0.01736187 5.28e-4 0.02049297 0.002295911 0.02093696 0.003242969 0.01736187 5.28e-4 0.02049297 0.002295911 0.01736187 5.28e-4 0.01764595 6.3e-4 0.01764595 6.3e-4 0.01928496 0.001222968 0.02049297 0.002295911 0.02180695 0.001248896 0.01764595 6.3e-4 0.01736187 5.28e-4 0.01858484 5.7e-5 0.015989 3.2e-5 0.01434797 2.71e-4 0.02180695 0.001248896 0.015989 3.2e-5 0.01858484 5.7e-5 0.01715987 3.54e-4 0.01434797 2.71e-4 0.01222687 0.002026975 0.01786983 0 0.01434797 2.71e-4 0.01715987 3.54e-4 0.01858484 5.7e-5 0.01434797 2.71e-4 0.01786983 0 0.01581096 0.002246916 0.01222687 0.002026975 0.009874999 0.005200982 0.01646482 0.001119971 0.01222687 0.002026975 0.01581096 0.002246916 0.01715987 3.54e-4 0.01222687 0.002026975 0.01646482 0.001119971 0.01464498 0.005486965 0.009874999 0.005200982 0.007442951 0.009832978 0.01581096 0.002246916 0.009874999 0.005200982 0.01464498 0.005486965 0.01171886 0.009852945 0.007442951 0.009832978 0.004075944 0.01838696 0.01464498 0.005486965 0.007442951 0.009832978 0.01411098 0.007680952 0.01171886 0.009852945 0.01411098 0.007680952 0.007442951 0.009832978 0.01225286 0.01866495 0.004075944 0.01838696 0.001342952 0.027116 0.01361083 0.01035785 0.004075944 0.01838696 0.01225286 0.01866495 0.01163697 0.010351 0.004075944 0.01838696 0.01361083 0.01035785 0.01167798 0.01010197 0.004075944 0.01838696 0.01163697 0.010351 0.01171886 0.009852945 0.004075944 0.01838696 0.01167798 0.01010197 0.01052397 0.02959299 0.001342952 0.027116 7.79e-4 0.02954697 0.01085597 0.02719396 0.001342952 0.027116 0.01052397 0.02959299 0.01225286 0.01866495 0.001342952 0.027116 0.01085597 0.02719396 0.01028198 0.03219985 7.79e-4 0.02954697 3.53e-4 0.03217583 0.01052397 0.02959299 7.79e-4 0.02954697 0.01028198 0.03219985 0.01013284 0.03494799 3.53e-4 0.03217583 8.9e-5 0.03493696 0.01028198 0.03219985 3.53e-4 0.03217583 0.01013284 0.03494799 0.01008296 0.03776699 8.9e-5 0.03493696 0 0.03776997 0.01013284 0.03494799 8.9e-5 0.03493696 0.01008296 0.03776699 0.01008296 0.03776699 0 0.03776997 9e-5 0.04060184 0.01013284 0.04058682 9e-5 0.04060184 3.54e-4 0.04336297 0.01008296 0.03776699 9e-5 0.04060184 0.01013284 0.04058682 0.01028198 0.04333496 3.54e-4 0.04336297 7.79e-4 0.04598885 0.01013284 0.04058682 3.54e-4 0.04336297 0.01028198 0.04333496 0.01052397 0.04594182 7.79e-4 0.04598885 0.001342952 0.04841798 0.01028198 0.04333496 7.79e-4 0.04598885 0.01052397 0.04594182 0.01085597 0.04834085 0.001342952 0.04841798 0.004074931 0.05714684 0.01052397 0.04594182 0.001342952 0.04841798 0.01085597 0.04834085 0.01225286 0.05686998 0.004074931 0.05714684 0.01163697 0.06518501 0.01225286 0.05686998 0.01085597 0.04834085 0.004074931 0.05714684 0.02180695 0.07428598 0.01928496 0.07431197 0.02049398 0.073237 0.01858484 0.075477 0.01764595 0.07490497 0.01928496 0.07431197 0.02180695 0.07428598 0.01858484 0.075477 0.01928496 0.07431197 0.02318698 0.07318896 0.02049398 0.073237 0.02093786 0.07229 0.02250397 0.07387995 0.02049398 0.073237 0.02318698 0.07318896 0.02180695 0.07428598 0.02049398 0.073237 0.02250397 0.07387995 0.023853 0.072218 0.02093786 0.07229 0.02128183 0.07107597 0.02318698 0.07318896 0.02093786 0.07229 0.023853 0.072218 0.02449697 0.07097697 0.02128183 0.07107597 0.02169698 0.06791597 0.023853 0.072218 0.02128183 0.07107597 0.02449697 0.07097697 0.02569586 0.06773597 0.02169698 0.06791597 0.02182096 0.06382399 0.02511286 0.06947797 0.02169698 0.06791597 0.02569586 0.06773597 0.02449697 0.07097697 0.02169698 0.06791597 0.02511286 0.06947797 0.02489387 0.06359601 0.02182096 0.06382399 0.02180182 0.06143587 0.02569586 0.06773597 0.02182096 0.06382399 0.02624297 0.06576496 0.02489387 0.06359601 0.02624297 0.06576496 0.02182096 0.06382399 0.02528399 0.06164383 0.02180182 0.06143587 0.02174592 0.05882591 0.02528399 0.06164383 0.02489387 0.06359601 0.02180182 0.06143587 0.02576082 0.05880099 0.02174592 0.05882591 0.02165091 0.05556082 0.02528399 0.06164383 0.02174592 0.05882591 0.02576082 0.05880099 0.02767992 0.05829596 0.02165091 0.05556082 0.0215469 0.05218982 0.02583485 0.05830097 0.02165091 0.05556082 0.02767992 0.05829596 0.02579796 0.05855184 0.02576082 0.05880099 0.02165091 0.05556082 0.02583485 0.05830097 0.02579796 0.05855184 0.02165091 0.05556082 0.02841699 0.05192583 0.0215469 0.05218982 0.02136898 0.04510897 0.02767992 0.05829596 0.0215469 0.05218982 0.02841699 0.05192583 0.02887094 0.04499 0.02136898 0.04510897 0.02129983 0.03776592 0.02841699 0.05192583 0.02136898 0.04510897 0.02887094 0.04499 0.02887094 0.03054195 0.02129983 0.03776592 0.02136898 0.03042 0.02902483 0.03776592 0.02129983 0.03776592 0.02887094 0.03054195 0.02887094 0.04499 0.02129983 0.03776592 0.02902483 0.03776592 0.02841585 0.02360785 0.02136898 0.03042 0.02154797 0.02333599 0.02887094 0.03054195 0.02136898 0.03042 0.02841585 0.02360785 0.02841585 0.02360785 0.02154797 0.02333599 0.02165091 0.01996392 0.02583485 0.01723384 0.02165091 0.01996392 0.02174699 0.016698 0.02583485 0.01723384 0.02841585 0.02360785 0.02165091 0.01996392 0.025451 0.01499086 0.02174699 0.016698 0.02180182 0.01408886 0.025451 0.01499086 0.02575898 0.01672285 0.02174699 0.016698 0.02579897 0.01698696 0.02174699 0.016698 0.02575898 0.01672285 0.02579897 0.01698696 0.02583485 0.01723384 0.02174699 0.016698 0.02523899 0.01347297 0.02180182 0.01408886 0.02182096 0.011702 0.02523899 0.01347297 0.025451 0.01499086 0.02180182 0.01408886 0.02624297 0.009769976 0.02182096 0.011702 0.02169698 0.007612943 0.02624297 0.009769976 0.02674984 0.01195585 0.02182096 0.011702 0.02489387 0.01193886 0.02182096 0.011702 0.02674984 0.01195585 0.02507787 0.012546 0.02523899 0.01347297 0.02182096 0.011702 0.02489387 0.01193886 0.02507787 0.012546 0.02182096 0.011702 0.02511286 0.006056964 0.02169698 0.007612943 0.021281 0.00445497 0.02569586 0.00779891 0.02169698 0.007612943 0.02511286 0.006056964 0.02624297 0.009769976 0.02169698 0.007612943 0.02569586 0.00779891 0.023853 0.003316998 0.021281 0.00445497 0.02093696 0.003242969 0.02449697 0.004557967 0.021281 0.00445497 0.023853 0.003316998 0.02511286 0.006056964 0.021281 0.00445497 0.02449697 0.004557967 0.02318698 0.002345979 0.02093696 0.003242969 0.02049297 0.002295911 0.023853 0.003316998 0.02093696 0.003242969 0.02318698 0.002345979 0.02250397 0.001654863 0.02049297 0.002295911 0.01928496 0.001222968 0.02318698 0.002345979 0.02049297 0.002295911 0.02250397 0.001654863 0.02180695 0.001248896 0.01928496 0.001222968 0.01764595 6.3e-4 0.02250397 0.001654863 0.01928496 0.001222968 0.02180695 0.001248896 0.01167798 0.06543296 0.01361083 0.06517696 0.01163697 0.06518501 0.01225286 0.05686998 0.01163697 0.06518501 0.01361083 0.06517696 0.01171886 0.06567996 0.01361083 0.06517696 0.01167798 0.06543296 0.01411098 0.06785398 0.01361083 0.06517696 0.01171886 0.06567996 0.01361083 0.01035785 0.01225286 0.05686998 0.01361083 0.06517696 0.01411098 0.007680952 0.01361083 0.06517696 0.01411098 0.06785398 0.01411098 0.007680952 0.01361083 0.01035785 0.01361083 0.06517696 0.01085597 0.02719396 0.01085597 0.04834085 0.01225286 0.05686998 0.01052397 0.02959299 0.01052397 0.04594182 0.01085597 0.04834085 0.01085597 0.02719396 0.01052397 0.02959299 0.01085597 0.04834085 0.01225286 0.01866495 0.01085597 0.02719396 0.01225286 0.05686998 0.01361083 0.01035785 0.01225286 0.01866495 0.01225286 0.05686998 0.01464498 0.005486965 0.01411098 0.06785398 0.01464498 0.07004797 0.01464498 0.005486965 0.01411098 0.007680952 0.01411098 0.06785398 0.01581096 0.002246916 0.01464498 0.07004797 0.01581192 0.07328897 0.01581096 0.002246916 0.01464498 0.005486965 0.01464498 0.07004797 0.01646482 0.001119971 0.01581192 0.07328897 0.01646596 0.07441598 0.01646482 0.001119971 0.01581096 0.002246916 0.01581192 0.07328897 0.01715987 3.54e-4 0.01646596 0.07441598 0.01716095 0.075181 0.01715987 3.54e-4 0.01646482 0.001119971 0.01646596 0.07441598 0.01786983 0 0.01716095 0.075181 0.01786983 0.07553499 0.01786983 0 0.01715987 3.54e-4 0.01716095 0.075181 0.01786983 0 0.01786983 0.07553499 0.01858484 0.075477 0.01858484 5.7e-5 0.01858484 0.075477 0.02180695 0.07428598 0.01858484 5.7e-5 0.01786983 0 0.01858484 0.075477 0.02722597 0.06112384 0.02722787 0.0144189 0.02674984 0.01195585 0.02581495 0.01194983 0.02674984 0.01195585 0.02722787 0.0144189 0.02674984 0.06357896 0.02722597 0.06112384 0.02674984 0.01195585 0.02624297 0.009769976 0.02674984 0.06357896 0.02674984 0.01195585 0.02581495 0.01194983 0.02489387 0.01193886 0.02674984 0.01195585 0.02752298 0.05933797 0.02752399 0.0162 0.02722787 0.0144189 0.025451 0.01499086 0.02722787 0.0144189 0.02752399 0.0162 0.02722597 0.06112384 0.02752298 0.05933797 0.02722787 0.0144189 0.02523899 0.01347297 0.02722787 0.0144189 0.025451 0.01499086 0.02507787 0.012546 0.02722787 0.0144189 0.02523899 0.01347297 0.02581495 0.01194983 0.02722787 0.0144189 0.02507787 0.012546 0.02767992 0.05829596 0.02767992 0.01723897 0.02752399 0.0162 0.02575898 0.01672285 0.02752399 0.0162 0.02767992 0.01723897 0.02752298 0.05933797 0.02767992 0.05829596 0.02752399 0.0162 0.025451 0.01499086 0.02752399 0.0162 0.02575898 0.01672285 0.02841699 0.05192583 0.02841585 0.02360785 0.02767992 0.01723897 0.02583485 0.01723384 0.02767992 0.01723897 0.02841585 0.02360785 0.02767992 0.05829596 0.02841699 0.05192583 0.02767992 0.01723897 0.02579897 0.01698696 0.02575898 0.01672285 0.02767992 0.01723897 0.02583485 0.01723384 0.026748 0.01723295 0.02767992 0.01723897 0.02579897 0.01698696 0.02767992 0.01723897 0.026748 0.01723295 0.02841699 0.05192583 0.02887094 0.03054195 0.02841585 0.02360785 0.02887094 0.04499 0.02902483 0.03776592 0.02887094 0.03054195 0.02841699 0.05192583 0.02887094 0.04499 0.02887094 0.03054195 0.026748 0.05830198 0.02767992 0.05829596 0.02752298 0.05933797 0.026748 0.05830198 0.02583485 0.05830097 0.02767992 0.05829596 0.02576082 0.05880099 0.02752298 0.05933797 0.02722597 0.06112384 0.02579796 0.05855184 0.02752298 0.05933797 0.02576082 0.05880099 0.026748 0.05830198 0.02752298 0.05933797 0.02579796 0.05855184 0.02528399 0.06164383 0.02722597 0.06112384 0.02674984 0.06357896 0.02528399 0.06164383 0.02576082 0.05880099 0.02722597 0.06112384 0.02624297 0.009769976 0.02624297 0.06576496 0.02674984 0.06357896 0.02489387 0.06359601 0.02674984 0.06357896 0.02624297 0.06576496 0.02581596 0.06358498 0.02674984 0.06357896 0.02489387 0.06359601 0.02581596 0.06358498 0.02528399 0.06164383 0.02674984 0.06357896 0.02569586 0.00779891 0.02569586 0.06773597 0.02624297 0.06576496 0.02624297 0.009769976 0.02569586 0.00779891 0.02624297 0.06576496 0.02511286 0.006056964 0.02511286 0.06947797 0.02569586 0.06773597 0.02569586 0.00779891 0.02511286 0.006056964 0.02569586 0.06773597 0.02449697 0.004557967 0.02449697 0.07097697 0.02511286 0.06947797 0.02511286 0.006056964 0.02449697 0.004557967 0.02511286 0.06947797 0.023853 0.003316998 0.023853 0.072218 0.02449697 0.07097697 0.02449697 0.004557967 0.023853 0.003316998 0.02449697 0.07097697 0.02318698 0.002345979 0.02318698 0.07318896 0.023853 0.072218 0.023853 0.003316998 0.02318698 0.002345979 0.023853 0.072218 0.02250397 0.001654863 0.02250397 0.07387995 0.02318698 0.07318896 0.02318698 0.002345979 0.02250397 0.001654863 0.02318698 0.07318896 0.02180695 0.001248896 0.02180695 0.07428598 0.02250397 0.07387995 0.02250397 0.001654863 0.02180695 0.001248896 0.02250397 0.07387995 0.02180695 0.001248896 0.01858484 5.7e-5 0.02180695 0.07428598 0.01028198 0.03219985 0.01028198 0.04333496 0.01052397 0.04594182 0.01052397 0.02959299 0.01028198 0.03219985 0.01052397 0.04594182 0.01013284 0.03494799 0.01013284 0.04058682 0.01028198 0.04333496 0.01028198 0.03219985 0.01013284 0.03494799 0.01028198 0.04333496 0.01013284 0.03494799 0.01008296 0.03776699 0.01013284 0.04058682 0.01167798 0.01010197 0.01361083 0.01035785 0.01411098 0.007680952 0.01167798 0.01010197 0.01163697 0.010351 0.01361083 0.01035785 0.01171886 0.009852945 0.01167798 0.01010197 0.01411098 0.007680952 0.02581495 0.01194983 0.02507787 0.012546 0.02489387 0.01193886 0.026748 0.05830198 0.02579796 0.05855184 0.02583485 0.05830097 0.02579897 0.01698696 0.026748 0.01723295 0.02583485 0.01723384 0.02581596 0.06358498 0.02489387 0.06359601 0.02528399 0.06164383 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 8 7 10 9 7 11 10 8 12 9 9 13 8 10 14 10 8 15 8 10 16 11 11 17 3 3 18 12 12 19 4 4 20 13 13 21 14 14 22 1 1 23 15 15 24 5 5 25 16 16 26 0 0 27 13 13 28 1 1 29 3 3 30 5 5 31 15 15 32 17 17 33 18 18 34 14 14 35 19 19 36 16 16 37 20 20 38 13 13 39 17 17 40 14 14 41 15 15 42 16 16 43 19 19 44 21 21 45 22 22 46 18 18 47 23 23 48 20 20 49 24 24 50 17 17 51 21 21 52 18 18 53 19 19 54 20 20 55 23 23 56 25 25 57 26 26 58 22 22 59 27 27 60 24 24 61 28 28 62 29 29 63 25 25 64 22 22 65 21 21 66 29 29 67 22 22 68 23 23 69 24 24 70 27 27 71 30 30 72 31 31 73 32 32 74 33 33 75 31 31 76 30 30 77 34 34 78 35 35 79 36 36 80 34 34 81 37 37 82 35 35 83 30 30 84 32 32 85 38 38 86 39 39 87 40 40 88 41 41 89 42 42 90 40 40 91 39 39 92 30 30 93 38 38 94 43 43 95 44 44 96 41 41 97 45 45 98 39 39 99 41 41 100 44 44 101 46 46 102 45 45 103 47 47 104 44 44 105 45 45 106 46 46 107 48 48 108 47 47 109 49 49 110 46 46 111 47 47 112 48 48 113 6 6 114 50 50 115 0 0 116 51 51 117 49 49 118 52 52 119 53 53 120 49 49 121 51 51 122 48 48 123 49 49 124 53 53 125 54 54 126 55 55 127 56 56 128 57 57 129 55 55 130 54 54 131 58 58 132 59 59 133 60 60 134 61 61 135 62 62 136 63 63 137 64 64 138 58 58 139 60 60 140 65 65 141 66 66 142 67 67 143 68 68 144 69 69 145 70 70 146 71 71 147 72 72 148 62 62 149 73 73 150 71 71 151 62 62 152 61 61 153 73 73 154 62 62 155 58 58 156 74 74 157 59 59 158 61 61 159 63 63 160 75 75 161 58 58 162 76 76 163 74 74 164 77 77 165 78 78 166 79 79 167 58 58 168 80 80 169 76 76 170 81 81 171 79 79 172 82 82 173 81 81 174 77 77 175 79 79 176 58 58 177 83 83 178 80 80 179 81 81 180 82 82 181 84 84 182 58 58 183 85 85 184 83 83 185 86 86 186 84 84 187 87 87 188 81 81 189 84 84 190 86 86 191 58 58 192 88 88 193 85 85 194 89 89 195 87 87 196 90 90 197 86 86 198 87 87 199 89 89 200 91 91 201 88 88 202 58 58 203 91 91 204 92 92 205 88 88 206 89 89 207 90 90 208 93 93 209 64 64 210 94 94 211 58 58 212 95 95 213 58 58 214 94 94 215 96 96 216 91 91 217 58 58 218 95 95 219 96 96 220 58 58 221 64 64 222 97 97 223 94 94 224 98 98 225 99 99 226 100 100 227 98 98 228 101 101 229 99 99 230 64 64 231 102 102 232 97 97 233 103 103 234 100 100 235 104 104 236 98 98 237 100 100 238 103 103 239 64 64 240 105 105 241 102 102 242 103 103 243 104 104 244 106 106 245 65 65 246 107 107 247 66 66 248 108 108 249 107 107 250 65 65 251 109 109 252 110 110 253 111 111 254 112 112 255 110 110 256 109 109 257 113 113 258 110 110 259 112 112 260 103 103 261 106 106 262 114 114 263 91 91 264 115 115 265 92 92 266 116 116 267 93 93 268 117 117 269 89 89 270 93 93 271 116 116 272 91 91 273 118 118 274 115 115 275 119 119 276 117 117 277 120 120 278 116 116 279 117 117 280 119 119 281 91 91 282 121 121 283 118 118 284 119 119 285 120 120 286 122 122 287 91 91 288 123 123 289 121 121 290 124 124 291 122 122 292 125 125 293 119 119 294 122 122 295 124 124 296 91 91 297 126 126 298 123 123 299 127 127 300 125 125 301 128 128 302 124 124 303 125 125 304 127 127 305 129 129 306 126 126 307 91 91 308 130 130 309 131 131 310 126 126 311 127 127 312 128 128 313 132 132 314 129 129 315 130 130 316 126 126 317 133 133 318 91 91 319 96 96 320 133 133 321 129 129 322 91 91 323 134 134 324 135 135 325 101 101 326 136 136 327 133 133 328 96 96 329 134 134 330 137 137 331 135 135 332 134 134 333 101 101 334 98 98 335 138 138 336 139 139 337 131 131 338 140 140 339 132 132 340 141 141 341 130 130 342 138 138 343 131 131 344 127 127 345 132 132 346 140 140 347 138 138 348 142 142 349 139 139 350 143 143 351 141 141 352 144 144 353 140 140 354 141 141 355 143 143 356 138 138 357 145 145 358 142 142 359 146 146 360 144 144 361 147 147 362 143 143 363 144 144 364 146 146 365 10 8 366 148 148 367 145 145 368 149 149 369 147 147 370 150 150 371 138 138 372 10 8 373 145 145 374 146 146 375 147 147 376 149 149 377 10 8 378 11 11 379 148 148 380 3 3 381 150 150 382 12 12 383 149 149 384 150 150 385 3 3 386 54 54 387 56 56 388 151 151 389 152 152 390 151 151 391 153 153 392 54 54 393 151 151 394 152 152 395 152 152 396 153 153 397 154 154 398 155 155 399 154 154 400 156 156 401 152 152 402 154 154 403 155 155 404 136 136 405 157 157 406 133 133 407 155 155 408 156 156 409 158 158 410 159 159 411 160 160 412 137 137 413 155 155 414 158 158 415 161 161 416 162 162 417 161 161 418 158 158 419 163 163 420 164 164 421 165 165 422 163 163 423 165 165 424 166 166 425 134 134 426 159 159 427 137 137 428 108 108 429 65 65 430 167 167 431 68 68 432 168 168 433 69 69 434 169 169 435 108 108 436 167 167 437 170 170 438 171 171 439 172 172 440 173 173 441 168 168 442 68 68 443 174 174 444 175 175 445 176 176 446 109 109 447 111 111 448 177 177 449 178 178 450 171 171 451 170 170 452 179 179 453 171 171 454 178 178 455 180 180 456 181 181 457 182 182 458 183 183 459 181 181 460 180 180 461 184 184 462 185 185 463 186 186 464 187 187 465 188 188 466 189 189 467 190 190 468 191 191 469 192 192 470 193 193 471 190 190 472 192 192 473 194 194 474 195 195 475 188 188 476 194 194 477 188 188 478 187 187 479 184 184 480 196 196 481 185 185 482 197 197 483 189 189 484 198 198 485 187 187 486 189 189 487 197 197 488 199 199 489 68 68 490 196 196 491 200 200 492 201 201 493 72 72 494 184 184 495 199 199 496 196 196 497 197 197 498 198 198 499 202 202 500 199 199 501 173 173 502 68 68 503 203 203 504 204 204 505 72 72 506 200 200 507 72 72 508 204 204 509 205 205 510 203 203 511 72 72 512 71 71 513 205 205 514 72 72 515 206 206 516 176 176 517 207 207 518 174 174 519 176 176 520 206 206 521 208 208 522 207 207 523 191 191 524 206 206 525 207 207 526 208 208 527 208 208 528 191 191 529 190 190 530 209 209 531 210 210 532 211 211 533 212 212 534 213 213 535 214 214 536 215 215 537 216 216 538 217 217 539 215 215 540 217 217 541 218 218 542 219 219 543 220 220 544 221 221 545 209 209 546 222 222 547 210 210 548 223 223 549 214 214 550 224 224 551 212 212 552 214 214 553 223 223 554 209 209 555 225 225 556 222 222 557 223 223 558 224 224 559 226 226 560 209 209 561 190 190 562 225 225 563 193 193 564 225 225 565 190 190 566 227 227 567 226 226 568 195 195 569 223 223 570 226 226 571 227 227 572 209 209 573 208 208 574 190 190 575 228 228 576 206 206 577 208 208 578 209 209 579 228 228 580 208 208 581 229 229 582 174 174 583 206 206 584 230 230 585 229 229 586 206 206 587 228 228 588 230 230 589 206 206 590 179 179 591 178 178 592 231 231 593 232 232 594 233 233 595 234 234 596 235 235 597 231 231 598 236 236 599 235 235 600 179 179 601 231 231 602 237 237 603 234 234 604 216 216 605 232 232 606 234 234 607 237 237 608 238 238 609 239 238 610 240 238 611 237 237 612 216 216 613 215 215 614 227 227 615 195 195 616 194 194 617 241 239 618 218 218 619 242 240 620 243 241 621 244 242 622 220 220 623 245 243 624 246 244 625 247 245 626 248 246 627 249 247 628 250 248 629 251 249 630 250 248 631 249 247 632 245 243 633 247 245 634 252 250 635 253 251 636 244 242 637 243 241 638 251 249 639 249 247 640 254 252 641 241 239 642 215 215 643 218 218 644 243 241 645 220 220 646 219 219 647 255 253 648 237 237 649 215 215 650 241 239 651 255 253 652 215 215 653 255 253 654 232 232 655 237 237 656 255 253 657 256 254 658 232 232 659 235 235 660 236 236 661 257 255 662 258 256 663 259 257 664 260 258 665 261 259 666 262 260 667 263 261 668 235 235 669 257 255 670 264 262 671 265 263 672 263 261 673 246 244 674 266 264 675 261 259 676 263 261 677 265 263 678 266 264 679 263 261 680 245 243 681 265 263 682 246 244 683 245 243 684 252 250 685 267 265 686 268 266 687 269 267 688 270 268 689 271 269 690 272 270 691 273 271 692 271 269 693 273 271 694 274 272 695 235 235 696 264 262 697 275 273 698 276 274 699 277 275 700 278 276 701 279 277 702 277 275 703 276 274 704 235 235 705 275 273 706 280 278 707 281 279 708 278 276 709 269 267 710 276 274 711 278 276 712 281 279 713 268 266 714 282 280 715 269 267 716 281 279 717 269 267 718 282 280 719 283 281 720 284 282 721 285 283 722 286 284 723 287 285 724 288 286 725 289 287 726 283 281 727 285 283 728 290 288 729 291 289 730 292 290 731 293 291 732 294 292 733 295 293 734 293 291 735 295 293 736 296 294 737 283 281 738 297 295 739 284 282 740 298 296 741 288 286 742 299 297 743 300 298 744 288 286 745 298 296 746 301 299 747 286 284 748 288 286 749 300 298 750 301 299 751 288 286 752 283 281 753 302 300 754 297 295 755 298 296 756 299 297 757 303 301 758 304 302 759 305 303 760 302 300 761 298 296 762 303 301 763 306 304 764 283 281 765 304 302 766 302 300 767 281 279 768 307 305 769 305 303 770 308 306 771 306 304 772 309 307 773 304 302 774 281 279 775 305 303 776 310 308 777 306 304 778 308 306 779 310 308 780 298 296 781 306 304 782 281 279 783 311 309 784 307 305 785 308 306 786 309 307 787 312 310 788 281 279 789 282 280 790 311 309 791 308 306 792 312 310 793 313 311 794 271 269 795 313 311 796 272 270 797 314 312 798 313 311 799 271 269 800 314 312 801 308 306 802 313 311 803 276 274 804 281 279 805 304 302 806 315 313 807 304 302 808 283 281 809 315 313 810 276 274 811 304 302 812 316 314 813 283 281 814 289 287 815 316 314 816 315 313 817 283 281 818 316 314 819 289 287 820 317 315 821 290 288 822 318 316 823 291 289 824 319 317 825 316 314 826 317 315 827 290 288 828 320 318 829 318 316 830 321 319 831 276 274 832 315 313 833 321 319 834 279 277 835 276 274 836 322 320 837 315 313 838 316 314 839 323 321 840 321 319 841 315 313 842 322 320 843 323 321 844 315 313 845 324 322 846 316 314 847 319 317 848 324 322 849 322 320 850 316 314 851 324 322 852 319 317 853 325 323 854 290 288 855 326 324 856 320 318 857 327 325 858 328 326 859 329 327 860 330 328 861 326 324 862 290 288 863 327 325 864 329 327 865 331 329 866 327 325 867 280 278 868 332 330 869 327 325 870 235 235 871 280 278 872 327 325 873 332 330 874 333 331 875 327 325 876 333 331 877 334 332 878 327 325 879 334 332 880 328 326 881 335 333 882 336 334 883 337 335 884 338 336 885 339 336 886 340 336 887 341 337 888 335 333 889 337 335 890 327 325 891 342 338 892 343 339 893 344 340 894 327 325 895 343 339 896 345 341 897 346 342 898 336 334 899 347 343 900 340 343 901 348 343 902 335 333 903 345 341 904 336 334 905 338 344 906 340 344 907 347 344 908 345 341 909 349 345 910 346 342 911 347 346 912 348 346 913 350 346 914 347 347 915 350 348 916 351 349 917 352 350 918 353 351 919 354 352 920 355 353 921 347 353 922 351 353 923 355 354 924 351 354 925 356 354 926 341 337 927 357 355 928 335 333 929 293 291 930 354 352 931 358 356 932 359 357 933 352 350 934 354 352 935 293 291 936 359 357 937 354 352 938 330 328 939 290 288 940 357 355 941 293 291 942 358 356 943 294 292 944 341 337 945 330 328 946 357 355 947 327 325 948 331 329 949 342 338 950 180 180 951 182 182 952 360 358 953 180 180 954 360 358 955 361 359 956 344 340 957 362 340 958 327 325 959 180 180 960 361 359 961 363 360 962 364 361 963 365 362 964 366 363 965 367 364 966 366 363 967 368 365 968 367 364 969 364 361 970 366 363 971 369 366 972 370 367 973 371 368 974 372 369 975 373 370 976 374 371 977 375 372 978 369 366 979 371 368 980 376 373 981 377 373 982 378 373 983 379 374 984 380 375 985 370 367 986 381 376 987 374 371 988 382 377 989 369 366 990 379 374 991 370 367 992 372 369 993 374 371 994 383 378 995 384 379 996 383 378 997 374 371 998 385 380 999 384 379 1000 374 371 1001 381 376 1002 385 380 1003 374 371 1004 386 381 1005 180 180 1006 380 375 1007 387 382 1008 382 377 1009 365 362 1010 388 383 1011 386 381 1012 380 375 1013 379 374 1014 388 383 1015 380 375 1016 389 384 1017 381 376 1018 382 377 1019 387 382 1020 389 384 1021 382 377 1022 386 381 1023 183 183 1024 180 180 1025 364 361 1026 387 382 1027 365 362 1028 113 113 1029 112 112 1030 390 385 1031 113 113 1032 390 385 1033 391 386 1034 392 387 1035 391 386 1036 393 388 1037 113 113 1038 391 386 1039 392 387 1040 394 389 1041 395 390 1042 369 366 1043 392 387 1044 393 388 1045 396 391 1046 397 392 1047 394 389 1048 369 366 1049 375 372 1050 397 392 1051 369 366 1052 398 393 1053 399 394 1054 400 395 1055 401 396 1056 399 394 1057 398 393 1058 392 387 1059 396 391 1060 402 397 1061 403 398 1062 400 395 1063 404 399 1064 405 400 1065 398 393 1066 400 395 1067 406 401 1068 405 400 1069 400 395 1070 407 402 1071 406 401 1072 400 395 1073 408 403 1074 407 402 1075 400 395 1076 409 404 1077 408 403 1078 400 395 1079 410 405 1080 409 404 1081 400 395 1082 403 398 1083 410 405 1084 400 395 1085 411 406 1086 404 399 1087 377 407 1088 412 408 1089 404 399 1090 411 406 1091 412 408 1092 403 398 1093 404 399 1094 413 409 1095 414 410 1096 377 407 1097 411 406 1098 377 407 1099 414 410 1100 376 411 1101 413 411 1102 377 411 1103 415 412 1104 416 413 1105 417 414 1106 418 415 1107 419 416 1108 420 417 1109 421 418 1110 415 412 1111 417 414 1112 422 419 1113 421 418 1114 417 414 1115 423 420 1116 422 419 1117 417 414 1118 424 421 1119 425 422 1120 426 423 1121 424 421 1122 426 423 1123 427 424 1124 428 425 1125 429 426 1126 416 413 1127 430 427 1128 420 417 1129 431 428 1130 415 412 1131 428 425 1132 416 413 1133 430 427 1134 418 415 1135 420 417 1136 428 425 1137 432 429 1138 429 426 1139 433 430 1140 431 428 1141 434 431 1142 433 430 1143 430 427 1144 431 428 1145 428 425 1146 435 432 1147 432 429 1148 433 430 1149 434 431 1150 436 433 1151 437 434 1152 438 435 1153 435 432 1154 439 436 1155 436 433 1156 440 437 1157 428 425 1158 437 434 1159 435 432 1160 439 436 1161 433 430 1162 436 433 1163 437 434 1164 441 438 1165 438 435 1166 439 436 1167 440 437 1168 442 439 1169 437 434 1170 443 440 1171 441 438 1172 444 441 1173 442 439 1174 445 442 1175 444 441 1176 439 436 1177 442 439 1178 437 434 1179 446 443 1180 443 440 1181 447 444 1182 445 442 1183 448 445 1184 447 444 1185 444 441 1186 445 442 1187 449 446 1188 450 447 1189 446 443 1190 447 444 1191 448 445 1192 451 448 1193 437 434 1194 449 446 1195 446 443 1196 449 446 1197 452 449 1198 450 447 1199 453 450 1200 454 451 1201 455 452 1202 456 453 1203 447 444 1204 451 448 1205 449 446 1206 457 454 1207 452 449 1208 458 455 1209 455 452 1210 459 456 1211 458 455 1212 453 450 1213 455 452 1214 449 446 1215 460 457 1216 457 454 1217 461 458 1218 459 456 1219 462 459 1220 461 458 1221 458 455 1222 459 456 1223 449 446 1224 463 460 1225 460 457 1226 461 458 1227 462 459 1228 464 461 1229 449 446 1230 465 462 1231 463 460 1232 466 463 1233 464 461 1234 467 464 1235 466 463 1236 461 458 1237 464 461 1238 465 465 1239 449 465 1240 468 465 1241 466 463 1242 467 464 1243 469 466 1244 468 467 1245 470 467 1246 465 467 1247 471 468 1248 472 469 1249 473 470 1250 474 471 1251 466 463 1252 469 466 1253 471 468 1254 475 472 1255 472 469 1256 449 473 1257 476 473 1258 468 473 1259 471 468 1260 473 470 1261 477 474 1262 478 475 1263 479 476 1264 480 477 1265 478 475 1266 481 478 1267 479 476 1268 482 479 1269 449 446 1270 437 434 1271 483 480 1272 484 481 1273 449 446 1274 478 475 1275 480 477 1276 485 482 1277 486 483 1278 483 480 1279 449 446 1280 487 484 1281 486 483 1282 449 446 1283 482 479 1284 487 484 1285 449 446 1286 488 485 1287 437 434 1288 428 425 1289 489 486 1290 482 479 1291 437 434 1292 490 487 1293 489 486 1294 437 434 1295 491 488 1296 490 487 1297 437 434 1298 492 489 1299 491 488 1300 437 434 1301 488 485 1302 492 489 1303 437 434 1304 493 490 1305 428 425 1306 415 412 1307 494 491 1308 488 485 1309 428 425 1310 495 492 1311 494 491 1312 428 425 1313 493 490 1314 495 492 1315 428 425 1316 496 493 1317 497 494 1318 498 495 1319 499 496 1320 500 497 1321 497 494 1322 499 496 1323 497 494 1324 496 493 1325 501 498 1326 498 495 1327 502 499 1328 496 493 1329 498 495 1330 501 498 1331 423 420 1332 503 500 1333 422 419 1334 501 498 1335 502 499 1336 504 501 1337 505 502 1338 506 503 1339 503 500 1340 507 504 1341 503 500 1342 506 503 1343 508 505 1344 505 502 1345 503 500 1346 423 420 1347 508 505 1348 503 500 1349 501 498 1350 504 501 1351 509 506 1352 510 507 1353 398 393 1354 506 503 1355 511 508 1356 506 503 1357 398 393 1358 512 509 1359 510 507 1360 506 503 1361 513 510 1362 512 509 1363 506 503 1364 514 511 1365 513 510 1366 506 503 1367 505 502 1368 514 511 1369 506 503 1370 515 512 1371 507 504 1372 506 503 1373 511 508 1374 515 512 1375 506 503 1376 516 513 1377 401 396 1378 398 393 1379 517 514 1380 516 513 1381 398 393 1382 518 515 1383 517 514 1384 398 393 1385 519 516 1386 518 515 1387 398 393 1388 520 517 1389 519 516 1390 398 393 1391 521 518 1392 520 517 1393 398 393 1394 522 519 1395 521 518 1396 398 393 1397 523 520 1398 522 519 1399 398 393 1400 510 507 1401 523 520 1402 398 393 1403 524 521 1404 511 508 1405 398 393 1406 405 400 1407 524 521 1408 398 393 1409 392 387 1410 402 397 1411 525 397 1412 526 522 1413 527 523 1414 528 524 1415 529 525 1416 528 524 1417 530 526 1418 529 525 1419 526 522 1420 528 524 1421 529 525 1422 530 526 1423 531 527 1424 532 528 1425 531 527 1426 533 529 1427 532 528 1428 529 525 1429 531 527 1430 534 530 1431 533 529 1432 535 531 1433 534 530 1434 532 528 1435 533 529 1436 534 530 1437 535 531 1438 536 532 1439 537 533 1440 538 534 1441 539 535 1442 534 530 1443 536 532 1444 540 536 1445 541 537 1446 539 535 1447 542 538 1448 541 537 1449 537 533 1450 539 535 1451 543 539 1452 542 538 1453 544 540 1454 543 539 1455 541 537 1456 542 538 1457 543 539 1458 544 540 1459 545 541 1460 546 542 1461 545 541 1462 547 543 1463 546 542 1464 543 539 1465 545 541 1466 546 542 1467 547 543 1468 548 544 1469 549 545 1470 548 544 1471 550 546 1472 549 545 1473 546 542 1474 548 544 1475 424 421 1476 550 546 1477 425 422 1478 424 421 1479 549 545 1480 550 546 1481 478 475 1482 485 482 1483 551 547 1484 552 548 1485 553 548 1486 483 548 1487 554 549 1488 483 549 1489 553 549 1490 486 483 1491 552 550 1492 483 480 1493 554 551 1494 555 551 1495 483 551 1496 478 475 1497 551 547 1498 556 552 1499 557 553 1500 558 553 1501 559 553 1502 560 554 1503 554 554 1504 553 554 1505 561 555 1506 560 556 1507 553 557 1508 562 558 1509 561 558 1510 553 558 1511 557 559 1512 563 559 1513 558 559 1514 557 560 1515 559 560 1516 564 560 1517 565 561 1518 566 562 1519 567 563 1520 557 564 1521 564 564 1522 568 564 1523 569 565 1524 567 563 1525 570 566 1526 565 561 1527 567 563 1528 569 565 1529 571 567 1530 570 566 1531 572 568 1532 569 565 1533 570 566 1534 571 567 1535 573 569 1536 572 568 1537 574 570 1538 571 567 1539 572 568 1540 573 569 1541 573 569 1542 574 570 1543 575 571 1544 576 572 1545 575 571 1546 577 573 1547 573 569 1548 575 571 1549 576 572 1550 576 572 1551 577 573 1552 578 574 1553 579 575 1554 580 575 1555 581 575 1556 576 572 1557 578 574 1558 582 576 1559 579 577 1560 581 577 1561 583 577 1562 584 578 1563 585 579 1564 500 497 1565 579 580 1566 583 580 1567 586 580 1568 584 578 1569 500 497 1570 499 496 1571 587 581 1572 588 582 1573 589 583 1574 587 581 1575 590 584 1576 588 582 1577 587 581 1578 589 583 1579 591 585 1580 592 586 1581 593 587 1582 594 588 1583 595 589 1584 596 590 1585 561 555 1586 597 591 1587 594 588 1588 598 592 1589 562 593 1590 595 593 1591 561 593 1592 597 591 1593 592 586 1594 594 588 1595 599 594 1596 600 595 1597 596 590 1598 601 596 1599 598 592 1600 602 597 1601 603 598 1602 599 594 1603 596 590 1604 595 589 1605 603 598 1606 596 590 1607 601 596 1608 597 591 1609 598 592 1610 604 599 1611 605 600 1612 600 595 1613 606 601 1614 602 597 1615 607 602 1616 608 603 1617 604 599 1618 600 595 1619 599 594 1620 608 603 1621 600 595 1622 609 604 1623 601 596 1624 602 597 1625 606 601 1626 609 604 1627 602 597 1628 610 605 1629 611 606 1630 605 600 1631 606 601 1632 607 602 1633 612 607 1634 604 599 1635 610 605 1636 605 600 1637 613 608 1638 614 609 1639 611 606 1640 615 610 1641 612 607 1642 616 611 1643 610 605 1644 613 608 1645 611 606 1646 615 610 1647 606 601 1648 612 607 1649 617 612 1650 618 613 1651 614 609 1652 615 610 1653 616 611 1654 619 614 1655 613 608 1656 617 612 1657 614 609 1658 617 612 1659 620 615 1660 618 613 1661 621 616 1662 619 614 1663 622 617 1664 621 616 1665 615 610 1666 619 614 1667 623 618 1668 624 619 1669 620 615 1670 621 616 1671 622 617 1672 625 620 1673 617 612 1674 623 618 1675 620 615 1676 623 618 1677 626 621 1678 624 619 1679 627 622 1680 625 620 1681 628 623 1682 627 622 1683 621 616 1684 625 620 1685 629 624 1686 630 625 1687 626 621 1688 627 622 1689 628 623 1690 631 626 1691 623 618 1692 629 624 1693 626 621 1694 629 624 1695 632 627 1696 630 625 1697 633 628 1698 631 626 1699 634 629 1700 633 628 1701 627 622 1702 631 626 1703 635 630 1704 636 631 1705 632 627 1706 637 632 1707 634 629 1708 638 633 1709 629 624 1710 635 630 1711 632 627 1712 637 632 1713 633 628 1714 634 629 1715 635 630 1716 639 634 1717 636 631 1718 637 632 1719 638 633 1720 640 635 1721 641 636 1722 642 637 1723 639 634 1724 643 638 1725 640 635 1726 644 639 1727 635 630 1728 641 636 1729 639 634 1730 643 638 1731 637 632 1732 640 635 1733 645 640 1734 646 641 1735 642 637 1736 643 638 1737 644 639 1738 647 642 1739 641 636 1740 645 640 1741 642 637 1742 648 643 1743 649 644 1744 646 641 1745 650 645 1746 647 642 1747 651 646 1748 645 640 1749 648 643 1750 646 641 1751 650 645 1752 643 638 1753 647 642 1754 652 647 1755 653 648 1756 649 644 1757 650 645 1758 651 646 1759 654 649 1760 648 643 1761 652 647 1762 649 644 1763 655 650 1764 656 651 1765 653 648 1766 657 652 1767 654 649 1768 658 653 1769 652 647 1770 655 650 1771 653 648 1772 657 652 1773 650 645 1774 654 649 1775 659 654 1776 660 655 1777 656 651 1778 657 652 1779 658 653 1780 661 656 1781 655 650 1782 659 654 1783 656 651 1784 662 657 1785 663 658 1786 660 655 1787 664 659 1788 661 656 1789 665 660 1790 666 661 1791 662 657 1792 660 655 1793 659 654 1794 666 661 1795 660 655 1796 664 659 1797 657 652 1798 661 656 1799 667 662 1800 668 663 1801 663 658 1802 664 659 1803 665 660 1804 669 664 1805 662 657 1806 667 662 1807 663 658 1808 667 662 1809 670 665 1810 668 663 1811 671 666 1812 669 664 1813 672 667 1814 671 666 1815 664 659 1816 669 664 1817 673 668 1818 414 410 1819 670 665 1820 674 669 1821 672 667 1822 675 670 1823 676 671 1824 673 668 1825 670 665 1826 667 662 1827 676 671 1828 670 665 1829 674 669 1830 671 666 1831 672 667 1832 677 672 1833 675 670 1834 678 673 1835 673 668 1836 411 406 1837 414 410 1838 677 672 1839 674 669 1840 675 670 1841 677 672 1842 678 673 1843 679 674 1844 680 675 1845 681 675 1846 682 675 1847 680 676 1848 683 676 1849 681 676 1850 684 677 1851 685 678 1852 686 679 1853 687 680 1854 680 680 1855 682 680 1856 688 681 1857 686 679 1858 689 682 1859 684 677 1860 686 679 1861 688 681 1862 690 683 1863 689 682 1864 691 684 1865 688 681 1866 689 682 1867 690 683 1868 692 685 1869 691 684 1870 693 686 1871 690 683 1872 691 684 1873 692 685 1874 692 685 1875 693 686 1876 694 687 1877 695 688 1878 694 687 1879 696 689 1880 692 685 1881 694 687 1882 695 688 1883 695 688 1884 696 689 1885 697 690 1886 698 691 1887 697 690 1888 699 692 1889 695 688 1890 697 690 1891 698 691 1892 700 693 1893 699 692 1894 701 694 1895 698 691 1896 699 692 1897 700 693 1898 700 693 1899 701 694 1900 702 695 1901 703 696 1902 702 695 1903 704 697 1904 700 693 1905 702 695 1906 703 696 1907 705 698 1908 704 697 1909 706 699 1910 703 696 1911 704 697 1912 705 698 1913 705 698 1914 706 699 1915 707 700 1916 708 701 1917 707 700 1918 709 702 1919 705 698 1920 707 700 1921 708 701 1922 710 703 1923 709 702 1924 711 704 1925 708 701 1926 709 702 1927 710 703 1928 712 705 1929 711 704 1930 713 706 1931 710 703 1932 711 704 1933 712 705 1934 712 705 1935 713 706 1936 714 707 1937 715 708 1938 714 707 1939 716 709 1940 712 705 1941 714 707 1942 715 708 1943 717 710 1944 716 709 1945 718 711 1946 715 708 1947 716 709 1948 717 710 1949 717 710 1950 718 711 1951 719 712 1952 720 713 1953 719 712 1954 721 714 1955 717 710 1956 719 712 1957 720 713 1958 720 713 1959 721 714 1960 722 715 1961 720 713 1962 722 715 1963 723 716 1964 724 717 1965 509 506 1966 725 718 1967 501 498 1968 509 506 1969 724 717 1970 726 719 1971 727 719 1972 728 719 1973 724 717 1974 725 718 1975 729 720 1976 726 721 1977 728 721 1978 730 721 1979 731 722 1980 732 723 1981 733 724 1982 734 725 1983 726 725 1984 730 725 1985 735 726 1986 733 724 1987 736 727 1988 735 726 1989 731 722 1990 733 724 1991 735 726 1992 736 727 1993 737 728 1994 738 729 1995 737 728 1996 739 730 1997 738 729 1998 735 726 1999 737 728 2000 740 731 2001 739 730 2002 741 732 2003 740 731 2004 738 729 2005 739 730 2006 742 733 2007 741 732 2008 743 734 2009 742 733 2010 740 731 2011 741 732 2012 742 733 2013 743 734 2014 744 735 2015 680 736 2016 745 736 2017 683 736 2018 746 737 2019 742 733 2020 744 735 2021 747 738 2022 418 415 2023 430 427 2024 748 739 2025 427 424 2026 749 740 2027 748 739 2028 424 421 2029 427 424 2030 750 741 2031 430 427 2032 433 430 2033 750 741 2034 747 738 2035 430 427 2036 751 742 2037 433 430 2038 439 436 2039 751 742 2040 750 741 2041 433 430 2042 752 743 2043 439 436 2044 444 441 2045 752 743 2046 751 742 2047 439 436 2048 753 744 2049 444 441 2050 447 444 2051 753 744 2052 752 743 2053 444 441 2054 754 745 2055 447 444 2056 456 453 2057 754 745 2058 753 744 2059 447 444 2060 754 745 2061 456 453 2062 755 746 2063 756 747 2064 757 748 2065 453 450 2066 756 747 2067 453 450 2068 458 455 2069 758 749 2070 754 745 2071 755 746 2072 758 749 2073 755 746 2074 759 750 2075 760 751 2076 761 752 2077 757 748 2078 760 751 2079 757 748 2080 756 747 2081 762 753 2082 747 738 2083 750 741 2084 763 754 2085 749 740 2086 764 755 2087 748 739 2088 749 740 2089 763 754 2090 765 756 2091 750 741 2092 751 742 2093 766 757 2094 762 753 2095 750 741 2096 765 756 2097 766 757 2098 750 741 2099 767 758 2100 751 742 2101 752 743 2102 768 759 2103 765 756 2104 751 742 2105 767 758 2106 768 759 2107 751 742 2108 769 760 2109 752 743 2110 753 744 2111 769 760 2112 767 758 2113 752 743 2114 770 761 2115 753 744 2116 754 745 2117 771 762 2118 769 760 2119 753 744 2120 770 761 2121 771 762 2122 753 744 2123 758 749 2124 770 761 2125 754 745 2126 772 763 2127 773 764 2128 774 765 2129 775 766 2130 776 767 2131 777 768 2132 778 769 2133 776 767 2134 775 766 2135 772 763 2136 774 765 2137 779 770 2138 780 771 2139 781 772 2140 782 773 2141 783 774 2142 784 775 2143 785 776 2144 786 777 2145 784 775 2146 783 774 2147 787 778 2148 782 773 2149 788 779 2150 787 778 2151 780 771 2152 782 773 2153 789 780 2154 788 779 2155 790 781 2156 787 778 2157 788 779 2158 789 780 2159 789 780 2160 790 781 2161 791 782 2162 792 783 2163 791 782 2164 793 784 2165 789 780 2166 791 782 2167 792 783 2168 794 785 2169 793 784 2170 795 786 2171 792 783 2172 793 784 2173 794 785 2174 794 785 2175 795 786 2176 796 787 2177 797 788 2178 796 787 2179 773 764 2180 794 785 2181 796 787 2182 797 788 2183 797 788 2184 773 764 2185 772 763 2186 756 747 2187 458 455 2188 461 458 2189 798 789 2190 461 458 2191 466 463 2192 798 789 2193 756 747 2194 461 458 2195 799 790 2196 466 463 2197 474 471 2198 799 790 2199 798 789 2200 466 463 2201 799 790 2202 474 471 2203 800 791 2204 801 792 2205 802 793 2206 475 472 2207 803 794 2208 801 792 2209 475 472 2210 471 468 2211 803 794 2212 475 472 2213 804 795 2214 799 790 2215 800 791 2216 804 795 2217 800 791 2218 805 796 2219 806 797 2220 807 798 2221 802 793 2222 808 799 2223 806 797 2224 802 793 2225 801 792 2226 808 799 2227 802 793 2228 809 800 2229 756 747 2230 798 789 2231 809 800 2232 760 751 2233 756 747 2234 810 801 2235 798 789 2236 799 790 2237 811 802 2238 809 800 2239 798 789 2240 810 801 2241 811 802 2242 798 789 2243 812 803 2244 810 801 2245 799 790 2246 813 804 2247 812 803 2248 799 790 2249 804 795 2250 813 804 2251 799 790 2252 814 805 2253 815 806 2254 816 807 2255 806 797 2256 817 808 2257 807 798 2258 818 809 2259 819 810 2260 820 811 2261 821 812 2262 822 813 2263 819 810 2264 818 809 2265 821 812 2266 819 810 2267 775 766 2268 777 768 2269 823 814 2270 824 815 2271 823 814 2272 825 816 2273 826 817 2274 823 814 2275 824 815 2276 775 766 2277 823 814 2278 826 817 2279 824 815 2280 825 816 2281 827 818 2282 824 815 2283 827 818 2284 828 819 2285 814 805 2286 828 819 2287 829 820 2288 830 821 2289 828 819 2290 814 805 2291 831 822 2292 828 819 2293 830 821 2294 831 822 2295 832 823 2296 828 819 2297 824 815 2298 828 819 2299 832 823 2300 814 805 2301 829 820 2302 815 806 2303 806 797 2304 833 824 2305 817 808 2306 818 809 2307 820 811 2308 834 825 2309 835 826 2310 836 827 2311 837 828 2312 838 829 2313 839 830 2314 840 831 2315 818 809 2316 834 825 2317 841 832 2318 842 833 2319 837 828 2320 843 834 2321 842 833 2322 844 835 2323 837 828 2324 845 836 2325 837 828 2326 844 835 2327 846 837 2328 835 826 2329 837 828 2330 845 836 2331 846 837 2332 837 828 2333 842 833 2334 843 834 2335 847 838 2336 848 839 2337 847 838 2338 849 840 2339 848 839 2340 842 833 2341 847 838 2342 478 475 2343 849 840 2344 481 478 2345 478 475 2346 848 839 2347 849 840 2348 850 841 2349 851 842 2350 852 843 2351 853 844 2352 854 845 2353 855 846 2354 856 847 2355 857 848 2356 858 849 2357 856 850 2358 859 850 2359 860 850 2360 860 851 2361 857 851 2362 856 851 2363 861 852 2364 855 846 2365 862 853 2366 863 854 2367 855 846 2368 861 852 2369 864 855 2370 855 846 2371 863 854 2372 865 856 2373 855 846 2374 864 855 2375 866 857 2376 855 846 2377 865 856 2378 867 858 2379 853 844 2380 855 846 2381 868 859 2382 867 858 2383 855 846 2384 866 857 2385 868 859 2386 855 846 2387 869 860 2388 852 843 2389 870 861 2390 871 862 2391 850 841 2392 852 843 2393 872 863 2394 871 862 2395 852 843 2396 869 860 2397 872 863 2398 852 843 2399 873 864 2400 870 861 2401 590 584 2402 874 865 2403 869 860 2404 870 861 2405 875 866 2406 874 865 2407 870 861 2408 873 864 2409 875 866 2410 870 861 2411 876 867 2412 873 864 2413 590 584 2414 587 581 2415 876 867 2416 590 584 2417 877 868 2418 840 831 2419 878 869 2420 879 870 2421 838 829 2422 840 831 2423 880 871 2424 879 870 2425 840 831 2426 877 868 2427 880 871 2428 840 831 2429 881 872 2430 878 869 2431 854 845 2432 881 872 2433 877 868 2434 878 869 2435 258 256 2436 260 258 2437 882 873 2438 883 874 2439 881 872 2440 854 845 2441 884 875 2442 883 874 2443 854 845 2444 885 876 2445 884 875 2446 854 845 2447 886 877 2448 885 876 2449 854 845 2450 853 844 2451 886 877 2452 854 845 2453 887 878 2454 858 878 2455 888 878 2456 889 879 2457 856 847 2458 858 849 2459 890 880 2460 889 880 2461 858 880 2462 891 881 2463 890 881 2464 858 881 2465 887 882 2466 891 882 2467 858 882 2468 892 883 2469 893 884 2470 894 885 2471 895 886 2472 887 886 2473 888 886 2474 896 887 2475 897 888 2476 898 889 2477 899 890 2478 893 884 2479 892 883 2480 900 891 2481 894 885 2482 901 892 2483 892 883 2484 894 885 2485 900 891 2486 900 891 2487 901 892 2488 902 893 2489 903 894 2490 902 893 2491 904 895 2492 900 891 2493 902 893 2494 903 894 2495 903 894 2496 904 895 2497 905 896 2498 597 591 2499 905 896 2500 906 897 2501 903 894 2502 905 896 2503 597 591 2504 597 591 2505 906 897 2506 592 586 2507 907 898 2508 908 899 2509 909 900 2510 861 901 2511 862 901 2512 910 901 2513 907 898 2514 911 902 2515 908 899 2516 907 898 2517 909 900 2518 912 903 2519 907 898 2520 912 903 2521 913 904 2522 907 898 2523 913 904 2524 914 905 2525 915 906 2526 916 907 2527 917 908 2528 915 906 2529 918 909 2530 916 907 2531 915 906 2532 917 908 2533 919 910 2534 920 911 2535 897 888 2536 896 887 2537 921 912 2538 922 913 2539 923 914 2540 924 915 2541 922 913 2542 921 912 2543 925 916 2544 926 917 2545 911 902 2546 907 898 2547 925 916 2548 911 902 2549 927 918 2550 928 919 2551 926 917 2552 925 916 2553 927 918 2554 926 917 2555 929 920 2556 930 921 2557 928 919 2558 931 922 2559 929 920 2560 928 919 2561 932 923 2562 931 922 2563 928 919 2564 933 924 2565 932 923 2566 928 919 2567 927 918 2568 933 924 2569 928 919 2570 934 925 2571 935 926 2572 936 927 2573 934 925 2574 937 928 2575 935 926 2576 938 929 2577 936 927 2578 939 930 2579 934 925 2580 936 927 2581 938 929 2582 938 929 2583 939 930 2584 940 931 2585 941 932 2586 940 931 2587 942 933 2588 943 934 2589 940 931 2590 941 932 2591 938 929 2592 940 931 2593 943 934 2594 944 935 2595 945 936 2596 946 937 2597 947 938 2598 948 939 2599 949 940 2600 950 941 2601 949 940 2602 948 939 2603 951 942 2604 946 937 2605 952 943 2606 944 935 2607 946 937 2608 951 942 2609 915 906 2610 952 943 2611 918 909 2612 915 906 2613 951 942 2614 952 943 2615 953 944 2616 954 945 2617 955 946 2618 956 947 2619 957 948 2620 958 949 2621 959 950 2622 954 945 2623 953 944 2624 960 951 2625 955 946 2626 961 952 2627 953 944 2628 955 946 2629 960 951 2630 960 951 2631 961 952 2632 962 953 2633 963 954 2634 964 955 2635 965 956 2636 966 957 2637 967 958 2638 968 959 2639 963 954 2640 965 956 2641 969 960 2642 970 961 2643 965 956 2644 971 962 2645 969 960 2646 965 956 2647 970 961 2648 972 963 2649 973 964 2650 974 965 2651 975 966 2652 973 964 2653 972 963 2654 972 963 2655 974 965 2656 976 967 2657 977 968 2658 978 969 2659 979 970 2660 980 971 2661 979 970 2662 981 972 2663 980 971 2664 977 968 2665 979 970 2666 982 973 2667 981 972 2668 983 974 2669 980 971 2670 981 972 2671 982 973 2672 984 975 2673 983 974 2674 985 976 2675 982 973 2676 983 974 2677 984 975 2678 984 975 2679 985 976 2680 937 928 2681 984 975 2682 937 928 2683 934 925 2684 956 947 2685 986 977 2686 957 948 2687 987 978 2688 988 979 2689 989 980 2690 956 947 2691 990 981 2692 986 977 2693 987 978 2694 991 982 2695 988 979 2696 992 983 2697 824 815 2698 832 823 2699 993 984 2700 994 985 2701 995 986 2702 996 987 2703 991 982 2704 987 978 2705 993 984 2706 995 986 2707 997 988 2708 998 989 2709 826 817 2710 824 815 2711 999 990 2712 998 989 2713 824 815 2714 1000 991 2715 999 990 2716 824 815 2717 992 983 2718 1000 991 2719 824 815 2720 1001 992 2721 1002 993 2722 1003 994 2723 1004 995 2724 775 766 2725 826 817 2726 1005 996 2727 1006 997 2728 1002 993 2729 1005 996 2730 1002 993 2731 1001 992 2732 1007 998 2733 1003 994 2734 1008 999 2735 1001 992 2736 1003 994 2737 1007 998 2738 1007 998 2739 1008 999 2740 1009 1000 2741 993 984 2742 1009 1000 2743 994 985 2744 1007 998 2745 1009 1000 2746 993 984 2747 1010 1001 2748 1011 1002 2749 775 766 2750 1012 1003 2751 775 766 2752 1011 1002 2753 1013 1004 2754 1010 1001 2755 775 766 2756 1014 1005 2757 1013 1004 2758 775 766 2759 1015 1006 2760 1014 1005 2761 775 766 2762 1004 995 2763 1015 1006 2764 775 766 2765 1012 1003 2766 778 769 2767 775 766 2768 1016 1007 2769 1017 1008 2770 1018 1009 2771 1019 1010 2772 1012 1003 2773 1011 1002 2774 1020 1011 2775 1019 1010 2776 1011 1002 2777 1016 1007 2778 1021 1012 2779 1017 1008 2780 1022 1013 2781 1018 1009 2782 1023 1014 2783 1016 1007 2784 1018 1009 2785 1022 1013 2786 1024 1015 2787 1023 1014 2788 1025 1016 2789 1022 1013 2790 1023 1014 2791 1024 1015 2792 1026 1017 2793 1025 1016 2794 1027 1018 2795 1024 1015 2796 1025 1016 2797 1026 1017 2798 1005 996 2799 1027 1018 2800 1006 997 2801 1026 1017 2802 1027 1018 2803 1005 996 2804 1028 1019 2805 779 770 2806 1029 1020 2807 772 763 2808 779 770 2809 1028 1019 2810 1028 1019 2811 1029 1020 2812 1030 1021 2813 1031 1022 2814 1032 1023 2815 1019 1010 2816 1033 1024 2817 1030 1021 2818 1034 1025 2819 1035 1026 2820 1031 1022 2821 1019 1010 2822 1036 1027 2823 1035 1026 2824 1019 1010 2825 1020 1011 2826 1036 1027 2827 1019 1010 2828 1028 1019 2829 1030 1021 2830 1033 1024 2831 1037 1028 2832 1038 1029 2833 1032 1023 2834 1033 1024 2835 1034 1025 2836 1039 1030 2837 1040 1031 2838 1037 1028 2839 1032 1023 2840 1031 1022 2841 1040 1031 2842 1032 1023 2843 1041 1032 2844 1042 1033 2845 1038 1029 2846 1043 1034 2847 1039 1030 2848 1044 1035 2849 1045 1036 2850 1041 1032 2851 1038 1029 2852 1046 1037 2853 1045 1036 2854 1038 1029 2855 1037 1028 2856 1046 1037 2857 1038 1029 2858 1033 1024 2859 1039 1030 2860 1043 1034 2861 1047 1038 2862 1048 1039 2863 1049 1040 2864 1050 1041 2865 1048 1039 2866 1047 1038 2867 1051 1042 2868 1052 1043 2869 1053 1044 2870 1054 1045 2871 1052 1043 2872 1051 1042 2873 1043 1034 2874 1044 1035 2875 1055 1046 2876 1047 1038 2877 1049 1040 2878 1056 1047 2879 1057 1048 2880 1058 1049 2881 1059 1050 2882 1060 1051 2883 1059 1050 2884 1061 1052 2885 1060 1051 2886 1057 1048 2887 1059 1050 2888 1062 1053 2889 1061 1052 2890 1063 1054 2891 1060 1051 2892 1061 1052 2893 1062 1053 2894 1064 1055 2895 1063 1054 2896 1065 1056 2897 1062 1053 2898 1063 1054 2899 1064 1055 2900 1064 1055 2901 1065 1056 2902 1066 1057 2903 1067 1058 2904 1066 1057 2905 1068 1059 2906 1064 1055 2907 1066 1057 2908 1067 1058 2909 1069 1060 2910 1068 1059 2911 1021 1012 2912 1067 1058 2913 1068 1059 2914 1069 1060 2915 1069 1060 2916 1021 1012 2917 1016 1007 2918 1070 1061 2919 1071 1062 2920 1072 1063 2921 1073 1064 2922 1074 1065 2923 1075 1066 2924 1076 1067 2925 1070 1061 2926 1072 1063 2927 1077 1068 2928 1078 1069 2929 1079 1070 2930 1080 1071 2931 1081 1072 2932 1082 1073 2933 1073 1064 2934 1075 1066 2935 1083 1074 2936 1084 1075 2937 987 978 2938 1070 1061 2939 1085 1076 2940 1086 1077 2941 990 981 2942 1076 1067 2943 1084 1075 2944 1070 1061 2945 1087 1078 2946 1083 1074 2947 1088 1079 2948 1087 1078 2949 1073 1064 2950 1083 1074 2951 1089 1080 2952 996 987 2953 987 978 2954 1090 1081 2955 1089 1080 2956 987 978 2957 1084 1075 2958 1090 1081 2959 987 978 2960 1091 1082 2961 1092 1083 2962 990 981 2963 1085 1076 2964 990 981 2965 1092 1083 2966 1093 1084 2967 990 981 2968 956 947 2969 1091 1082 2970 990 981 2971 1093 1084 2972 1094 1085 2973 997 988 2974 1095 1086 2975 993 984 2976 997 988 2977 1094 1085 2978 1096 1087 2979 1095 1086 2980 1097 1088 2981 1094 1085 2982 1095 1086 2983 1096 1087 2984 1096 1087 2985 1097 1088 2986 1098 1089 2987 1099 1090 2988 1098 1089 2989 1078 1069 2990 1096 1087 2991 1098 1089 2992 1099 1090 2993 1099 1090 2994 1078 1069 2995 1077 1068 2996 1100 1091 2997 1101 1092 2998 1102 1093 2999 1103 1094 3000 1104 1095 3001 1105 1096 3002 1106 1097 3003 1100 1091 3004 1102 1093 3005 1107 1098 3006 1108 1099 3007 1109 1100 3008 1107 1098 3009 1109 1100 3010 1110 1101 3011 1111 1102 3012 1112 1103 3013 1113 1104 3014 1114 1105 3015 1111 1102 3016 1113 1104 3017 1103 1094 3018 1115 1106 3019 1104 1095 3020 1100 1091 3021 1116 1107 3022 1101 1092 3023 1103 1094 3024 1105 1096 3025 1117 1108 3026 1118 1109 3027 1119 1110 3028 1116 1107 3029 1103 1094 3030 1117 1108 3031 1120 1111 3032 1100 1091 3033 1118 1109 3034 1116 1107 3035 1121 1112 3036 1122 1113 3037 1119 1110 3038 1123 1114 3039 1120 1111 3040 1124 1115 3041 1118 1109 3042 1121 1112 3043 1119 1110 3044 1103 1094 3045 1120 1111 3046 1123 1114 3047 1121 1112 3048 1125 1116 3049 1122 1113 3050 1123 1114 3051 1124 1115 3052 1126 1117 3053 1127 1118 3054 1128 1119 3055 1125 1116 3056 1123 1114 3057 1126 1117 3058 1129 1120 3059 1121 1112 3060 1127 1118 3061 1125 1116 3062 1130 1121 3063 1131 1122 3064 1128 1119 3065 1123 1114 3066 1129 1120 3067 1132 1123 3068 1127 1118 3069 1130 1121 3070 1128 1119 3071 1133 1124 3072 1134 1125 3073 1131 1122 3074 1135 1126 3075 1132 1123 3076 1136 1127 3077 1130 1121 3078 1133 1124 3079 1131 1122 3080 1137 1128 3081 1132 1123 3082 1135 1126 3083 1123 1114 3084 1132 1123 3085 1137 1128 3086 1133 1124 3087 1138 1129 3088 1134 1125 3089 1135 1126 3090 1136 1127 3091 1139 1130 3092 1140 1131 3093 1141 1132 3094 1138 1129 3095 1135 1126 3096 1139 1130 3097 1142 1133 3098 1133 1124 3099 1140 1131 3100 1138 1129 3101 1143 1134 3102 1144 1135 3103 1141 1132 3104 1135 1126 3105 1142 1133 3106 1145 1136 3107 1140 1131 3108 1143 1134 3109 1141 1132 3110 1143 1134 3111 1146 1137 3112 1144 1135 3113 1135 1126 3114 1145 1136 3115 1147 1138 3116 1148 1139 3117 1149 1140 3118 1146 1137 3119 1135 1126 3120 1147 1138 3121 1150 1141 3122 1143 1134 3123 1148 1139 3124 1146 1137 3125 1151 1142 3126 1152 1143 3127 1149 1140 3128 1153 1144 3129 1150 1141 3130 1154 1145 3131 1148 1139 3132 1151 1142 3133 1149 1140 3134 1155 1146 3135 1150 1141 3136 1153 1144 3137 1135 1126 3138 1150 1141 3139 1155 1146 3140 1151 1142 3141 1156 1147 3142 1152 1143 3143 1080 1071 3144 1154 1145 3145 1157 1148 3146 1153 1144 3147 1154 1145 3148 1080 1071 3149 1158 1149 3150 1159 1150 3151 1156 1147 3152 1080 1071 3153 1157 1148 3154 1160 1151 3155 1151 1142 3156 1158 1149 3157 1156 1147 3158 1158 1149 3159 1161 1152 3160 1159 1150 3161 1080 1071 3162 1160 1151 3163 1162 1153 3164 1163 1154 3165 1164 1155 3166 1161 1152 3167 1080 1071 3168 1162 1153 3169 1165 1156 3170 1158 1149 3171 1163 1154 3172 1161 1152 3173 1163 1154 3174 1166 1157 3175 1164 1155 3176 1080 1071 3177 1165 1156 3178 1167 1158 3179 1099 1090 3180 1077 1068 3181 1166 1157 3182 1080 1071 3183 1167 1158 3184 1081 1072 3185 1163 1154 3186 1099 1090 3187 1166 1157 3188 1096 1087 3189 1099 1090 3190 1163 1154 3191 1168 1159 3192 1163 1154 3193 1158 1149 3194 1168 1159 3195 1096 1087 3196 1163 1154 3197 1169 1160 3198 1158 1149 3199 1151 1142 3200 1169 1160 3201 1168 1159 3202 1158 1149 3203 1170 1161 3204 1151 1142 3205 1148 1139 3206 1170 1161 3207 1169 1160 3208 1151 1142 3209 1171 1162 3210 1148 1139 3211 1143 1134 3212 1171 1162 3213 1170 1161 3214 1148 1139 3215 1172 1163 3216 1143 1134 3217 1140 1131 3218 1172 1163 3219 1171 1162 3220 1143 1134 3221 1173 1164 3222 1140 1131 3223 1133 1124 3224 1173 1164 3225 1172 1163 3226 1140 1131 3227 1174 1165 3228 1133 1124 3229 1130 1121 3230 1174 1165 3231 1173 1164 3232 1133 1124 3233 1175 1166 3234 1130 1121 3235 1127 1118 3236 1175 1166 3237 1174 1165 3238 1130 1121 3239 1176 1167 3240 1127 1118 3241 1121 1112 3242 1176 1167 3243 1175 1166 3244 1127 1118 3245 1177 1168 3246 1121 1112 3247 1118 1109 3248 1177 1168 3249 1176 1167 3250 1121 1112 3251 1178 1169 3252 1118 1109 3253 1100 1091 3254 1178 1169 3255 1177 1168 3256 1118 1109 3257 1179 1170 3258 1100 1091 3259 1106 1097 3260 1179 1170 3261 1178 1169 3262 1100 1091 3263 1179 1170 3264 1106 1097 3265 1180 1171 3266 1181 1172 3267 1182 1173 3268 1108 1099 3269 1107 1098 3270 1181 1172 3271 1108 1099 3272 1183 1174 3273 1179 1170 3274 1180 1171 3275 1183 1174 3276 1180 1171 3277 1184 1175 3278 1185 1176 3279 1186 1177 3280 1182 1173 3281 1181 1172 3282 1185 1176 3283 1182 1173 3284 1094 1085 3285 1096 1087 3286 1168 1159 3287 1187 1178 3288 1168 1159 3289 1169 1160 3290 1187 1178 3291 1094 1085 3292 1168 1159 3293 1188 1179 3294 1169 1160 3295 1170 1161 3296 1188 1179 3297 1187 1178 3298 1169 1160 3299 1189 1180 3300 1170 1161 3301 1171 1162 3302 1189 1180 3303 1188 1179 3304 1170 1161 3305 1190 1181 3306 1171 1162 3307 1172 1163 3308 1190 1181 3309 1189 1180 3310 1171 1162 3311 1191 1182 3312 1172 1163 3313 1173 1164 3314 1191 1182 3315 1190 1181 3316 1172 1163 3317 1192 1183 3318 1173 1164 3319 1174 1165 3320 1192 1183 3321 1191 1182 3322 1173 1164 3323 1193 1184 3324 1174 1165 3325 1175 1166 3326 1193 1184 3327 1192 1183 3328 1174 1165 3329 1194 1185 3330 1175 1166 3331 1176 1167 3332 1194 1185 3333 1193 1184 3334 1175 1166 3335 1195 1186 3336 1176 1167 3337 1177 1168 3338 1195 1186 3339 1194 1185 3340 1176 1167 3341 1196 1187 3342 1177 1168 3343 1178 1169 3344 1196 1187 3345 1195 1186 3346 1177 1168 3347 1197 1188 3348 1178 1169 3349 1179 1170 3350 1197 1188 3351 1196 1187 3352 1178 1169 3353 1183 1174 3354 1197 1188 3355 1179 1170 3356 1060 1051 3357 1183 1174 3358 1184 1175 3359 1060 1051 3360 1184 1175 3361 1057 1048 3362 1050 1041 3363 1047 1038 3364 1186 1177 3365 1185 1176 3366 1050 1041 3367 1186 1177 3368 993 984 3369 1094 1085 3370 1187 1178 3371 1007 998 3372 1187 1178 3373 1188 1179 3374 1007 998 3375 993 984 3376 1187 1178 3377 1001 992 3378 1188 1179 3379 1189 1180 3380 1001 992 3381 1007 998 3382 1188 1179 3383 1005 996 3384 1189 1180 3385 1190 1181 3386 1005 996 3387 1001 992 3388 1189 1180 3389 1026 1017 3390 1190 1181 3391 1191 1182 3392 1026 1017 3393 1005 996 3394 1190 1181 3395 1024 1015 3396 1191 1182 3397 1192 1183 3398 1024 1015 3399 1026 1017 3400 1191 1182 3401 1022 1013 3402 1192 1183 3403 1193 1184 3404 1022 1013 3405 1024 1015 3406 1192 1183 3407 1016 1007 3408 1193 1184 3409 1194 1185 3410 1016 1007 3411 1022 1013 3412 1193 1184 3413 1069 1060 3414 1194 1185 3415 1195 1186 3416 1069 1060 3417 1016 1007 3418 1194 1185 3419 1067 1058 3420 1195 1186 3421 1196 1187 3422 1067 1058 3423 1069 1060 3424 1195 1186 3425 1064 1055 3426 1196 1187 3427 1197 1188 3428 1064 1055 3429 1067 1058 3430 1196 1187 3431 1062 1053 3432 1197 1188 3433 1183 1174 3434 1062 1053 3435 1064 1055 3436 1197 1188 3437 1060 1051 3438 1062 1053 3439 1183 1174 3440 1107 1098 3441 1110 1101 3442 1198 1189 3443 1111 1102 3444 1199 1190 3445 1112 1103 3446 1200 1191 3447 1201 1192 3448 1202 1193 3449 1203 1194 3450 1199 1190 3451 1111 1102 3452 1204 1195 3453 1053 1044 3454 1205 1196 3455 1051 1042 3456 1053 1044 3457 1204 1195 3458 1206 1197 3459 1205 1196 3460 1207 1198 3461 1204 1195 3462 1205 1196 3463 1206 1197 3464 1208 1199 3465 1207 1198 3466 1201 1192 3467 1206 1197 3468 1207 1198 3469 1208 1199 3470 1208 1199 3471 1201 1192 3472 1200 1191 3473 1209 1200 3474 1210 1201 3475 1211 1202 3476 1212 1203 3477 1213 1204 3478 1214 1205 3479 1215 1206 3480 1210 1201 3481 1209 1200 3482 1216 1207 3483 1212 1203 3484 1214 1205 3485 1217 1208 3486 1218 1209 3487 1219 1210 3488 1212 1203 3489 1220 1211 3490 1213 1204 3491 1221 1212 3492 1222 1213 3493 1220 1211 3494 1215 1206 3495 1209 1200 3496 1223 1214 3497 1212 1203 3498 1221 1212 3499 1220 1211 3500 1224 1215 3501 1223 1214 3502 1225 1216 3503 1221 1212 3504 1226 1217 3505 1222 1213 3506 1227 1218 3507 1223 1214 3508 1224 1215 3509 1111 1102 3510 1223 1214 3511 1227 1218 3512 1228 1219 3513 1223 1214 3514 1111 1102 3515 1215 1206 3516 1223 1214 3517 1229 1220 3518 1228 1219 3519 1229 1220 3520 1223 1214 3521 1221 1212 3522 1230 1221 3523 1226 1217 3524 1231 1222 3525 1232 1223 3526 1230 1221 3527 1221 1212 3528 1231 1222 3529 1230 1221 3530 1233 1224 3531 1234 1225 3532 1232 1223 3533 1231 1222 3534 1233 1224 3535 1232 1223 3536 1203 1194 3537 1111 1102 3538 1235 1226 3539 1233 1224 3540 1236 1227 3541 1234 1225 3542 1228 1219 3543 1111 1102 3544 1237 1228 3545 1114 1105 3546 1237 1228 3547 1111 1102 3548 1208 1199 3549 1200 1191 3550 1236 1227 3551 1233 1224 3552 1208 1199 3553 1236 1227 3554 1206 1197 3555 1208 1199 3556 1233 1224 3557 1238 1229 3558 1233 1224 3559 1231 1222 3560 1238 1229 3561 1206 1197 3562 1233 1224 3563 1239 1230 3564 1231 1222 3565 1221 1212 3566 1239 1230 3567 1238 1229 3568 1231 1222 3569 1240 1231 3570 1221 1212 3571 1212 1203 3572 1240 1231 3573 1239 1230 3574 1221 1212 3575 1241 1232 3576 1212 1203 3577 1216 1207 3578 1241 1232 3579 1240 1231 3580 1212 1203 3581 1241 1232 3582 1216 1207 3583 1242 1233 3584 1217 1208 3585 1243 1234 3586 1218 1209 3587 1244 1235 3588 1241 1232 3589 1242 1233 3590 1245 1236 3591 1246 1237 3592 1243 1234 3593 1217 1208 3594 1245 1236 3595 1243 1234 3596 1204 1195 3597 1206 1197 3598 1238 1229 3599 1247 1238 3600 1238 1229 3601 1239 1230 3602 1247 1238 3603 1204 1195 3604 1238 1229 3605 1248 1239 3606 1239 1230 3607 1240 1231 3608 1248 1239 3609 1247 1238 3610 1239 1230 3611 1249 1240 3612 1240 1231 3613 1241 1232 3614 1249 1240 3615 1248 1239 3616 1240 1231 3617 1250 1241 3618 1241 1232 3619 1244 1235 3620 1250 1241 3621 1249 1240 3622 1241 1232 3623 1250 1241 3624 1244 1235 3625 1251 1242 3626 1245 1236 3627 1252 1243 3628 1246 1237 3629 1253 1244 3630 1250 1241 3631 1251 1242 3632 1254 1245 3633 1255 1246 3634 1252 1243 3635 1254 1245 3636 1252 1243 3637 1245 1236 3638 1051 1042 3639 1204 1195 3640 1247 1238 3641 1256 1247 3642 1247 1238 3643 1248 1239 3644 1256 1247 3645 1051 1042 3646 1247 1238 3647 1257 1248 3648 1248 1239 3649 1249 1240 3650 1257 1248 3651 1256 1247 3652 1248 1239 3653 1258 1249 3654 1249 1240 3655 1250 1241 3656 1258 1249 3657 1257 1248 3658 1249 1240 3659 1259 1250 3660 1250 1241 3661 1253 1244 3662 1259 1250 3663 1258 1249 3664 1250 1241 3665 1259 1250 3666 1253 1244 3667 1260 1251 3668 1254 1245 3669 1261 1252 3670 1255 1246 3671 1262 1253 3672 1259 1250 3673 1260 1251 3674 1263 1254 3675 1264 1255 3676 1261 1252 3677 1263 1254 3678 1261 1252 3679 1254 1245 3680 1265 1256 3681 1051 1042 3682 1256 1247 3683 1266 1257 3684 1054 1045 3685 1051 1042 3686 1265 1256 3687 1266 1257 3688 1051 1042 3689 1267 1258 3690 1256 1247 3691 1257 1248 3692 1267 1258 3693 1265 1256 3694 1256 1247 3695 1268 1259 3696 1257 1248 3697 1258 1249 3698 1269 1260 3699 1267 1258 3700 1257 1248 3701 1268 1259 3702 1269 1260 3703 1257 1248 3704 1270 1261 3705 1258 1249 3706 1259 1250 3707 1271 1262 3708 1268 1259 3709 1258 1249 3710 1270 1261 3711 1271 1262 3712 1258 1249 3713 1272 1263 3714 1259 1250 3715 1262 1253 3716 1273 1264 3717 1270 1261 3718 1259 1250 3719 1274 1265 3720 1273 1264 3721 1259 1250 3722 1272 1263 3723 1274 1265 3724 1259 1250 3725 1272 1263 3726 1262 1253 3727 1275 1266 3728 1263 1254 3729 1276 1267 3730 1264 1255 3731 1277 1268 3732 1278 1269 3733 1279 1270 3734 1280 1271 3735 1276 1267 3736 1263 1254 3737 1281 1272 3738 1282 1272 3739 1283 1273 3740 1277 1268 3741 1279 1270 3742 1284 1274 3743 1285 1275 3744 1055 1046 3745 1286 1276 3746 1043 1034 3747 1055 1046 3748 1285 1275 3749 1287 1277 3750 1286 1276 3751 1288 1278 3752 1285 1275 3753 1286 1276 3754 1287 1277 3755 1287 1277 3756 1288 1278 3757 1289 1279 3758 1290 1280 3759 1289 1279 3760 1291 1281 3761 1287 1277 3762 1289 1279 3763 1290 1280 3764 1290 1280 3765 1291 1281 3766 1292 1282 3767 1293 1283 3768 1292 1282 3769 1294 1284 3770 1290 1280 3771 1292 1282 3772 1293 1283 3773 1293 1283 3774 1294 1284 3775 1295 1285 3776 1296 1286 3777 1295 1285 3778 1297 1287 3779 1296 1286 3780 1293 1283 3781 1295 1285 3782 1298 1288 3783 1297 1287 3784 1299 1289 3785 1298 1288 3786 1296 1286 3787 1297 1287 3788 1277 1268 3789 1299 1289 3790 1278 1269 3791 1277 1268 3792 1298 1288 3793 1299 1289 3794 1300 1290 3795 1301 1291 3796 1245 1236 3797 1254 1245 3798 1245 1236 3799 1301 1291 3800 1302 1292 3801 1300 1290 3802 1245 1236 3803 1303 1293 3804 1302 1292 3805 1245 1236 3806 1217 1208 3807 1303 1293 3808 1245 1236 3809 1304 1294 3810 1305 1295 3811 1301 1291 3812 1306 1296 3813 1301 1291 3814 1305 1295 3815 1300 1290 3816 1304 1294 3817 1301 1291 3818 1306 1296 3819 1254 1245 3820 1301 1291 3821 1307 1297 3822 1308 1298 3823 1305 1295 3824 1309 1299 3825 1305 1295 3826 1308 1298 3827 1310 1300 3828 1307 1297 3829 1305 1295 3830 1304 1294 3831 1310 1300 3832 1305 1295 3833 1309 1299 3834 1306 1296 3835 1305 1295 3836 1311 1301 3837 1312 1302 3838 1308 1298 3839 1313 1303 3840 1308 1298 3841 1312 1302 3842 1314 1304 3843 1311 1301 3844 1308 1298 3845 1307 1297 3846 1314 1304 3847 1308 1298 3848 1313 1303 3849 1309 1299 3850 1308 1298 3851 1315 1305 3852 1316 1306 3853 1312 1302 3854 1317 1307 3855 1312 1302 3856 1316 1306 3857 1318 1308 3858 1315 1305 3859 1312 1302 3860 1311 1301 3861 1318 1308 3862 1312 1302 3863 1317 1307 3864 1313 1303 3865 1312 1302 3866 1319 1309 3867 1320 1310 3868 1316 1306 3869 1321 1311 3870 1316 1306 3871 1320 1310 3872 1322 1312 3873 1319 1309 3874 1316 1306 3875 1315 1305 3876 1322 1312 3877 1316 1306 3878 1321 1311 3879 1317 1307 3880 1316 1306 3881 1323 1313 3882 1324 1314 3883 1320 1310 3884 1325 1315 3885 1320 1310 3886 1324 1314 3887 1319 1309 3888 1323 1313 3889 1320 1310 3890 1325 1315 3891 1321 1311 3892 1320 1310 3893 1326 1316 3894 1327 1317 3895 1324 1314 3896 1328 1318 3897 1324 1314 3898 1327 1317 3899 1329 1319 3900 1326 1316 3901 1324 1314 3902 1323 1313 3903 1329 1319 3904 1324 1314 3905 1328 1318 3906 1325 1315 3907 1324 1314 3908 1330 1320 3909 1331 1321 3910 1327 1317 3911 1332 1322 3912 1327 1317 3913 1331 1321 3914 1333 1323 3915 1330 1320 3916 1327 1317 3917 1326 1316 3918 1333 1323 3919 1327 1317 3920 1332 1322 3921 1328 1318 3922 1327 1317 3923 1334 1324 3924 1335 1325 3925 1331 1321 3926 1336 1326 3927 1331 1321 3928 1335 1325 3929 1330 1320 3930 1334 1324 3931 1331 1321 3932 1336 1326 3933 1332 1322 3934 1331 1321 3935 1337 1327 3936 1338 1328 3937 1335 1325 3938 1339 1329 3939 1335 1325 3940 1338 1328 3941 1340 1330 3942 1337 1327 3943 1335 1325 3944 1334 1324 3945 1340 1330 3946 1335 1325 3947 1339 1329 3948 1336 1326 3949 1335 1325 3950 1341 1331 3951 1342 1332 3952 1338 1328 3953 1343 1333 3954 1338 1328 3955 1342 1332 3956 1337 1327 3957 1341 1331 3958 1338 1328 3959 1343 1333 3960 1339 1329 3961 1338 1328 3962 1344 1334 3963 1345 1335 3964 1342 1332 3965 1346 1336 3966 1342 1332 3967 1345 1335 3968 1347 1337 3969 1344 1334 3970 1342 1332 3971 1341 1331 3972 1347 1337 3973 1342 1332 3974 1346 1336 3975 1343 1333 3976 1342 1332 3977 1348 1338 3978 1349 1339 3979 1350 1340 3980 1351 1341 3981 1346 1336 3982 1345 1335 3983 1352 1342 3984 1353 1343 3985 1349 1339 3986 1348 1338 3987 1352 1342 3988 1349 1339 3989 1354 1344 3990 1355 1345 3991 1356 1346 3992 1357 1347 3993 1358 1348 3994 1355 1345 3995 1354 1344 3996 1357 1347 3997 1355 1345 3998 1359 1349 3999 1356 1346 4000 1360 1350 4001 1359 1349 4002 1354 1344 4003 1356 1346 4004 1359 1349 4005 1360 1350 4006 1361 1351 4007 1362 1352 4008 1361 1351 4009 1363 1353 4010 1362 1352 4011 1359 1349 4012 1361 1351 4013 1362 1352 4014 1363 1353 4015 1364 1354 4016 1365 1355 4017 1364 1354 4018 1366 1356 4019 1365 1355 4020 1362 1352 4021 1364 1354 4022 1365 1355 4023 1366 1356 4024 1367 1357 4025 1368 1358 4026 1367 1357 4027 1369 1359 4028 1368 1358 4029 1365 1355 4030 1367 1357 4031 1368 1358 4032 1369 1359 4033 1370 1360 4034 1371 1361 4035 1370 1360 4036 1372 1362 4037 1371 1361 4038 1368 1358 4039 1370 1360 4040 1373 1363 4041 1372 1362 4042 1374 1364 4043 1373 1363 4044 1371 1361 4045 1372 1362 4046 1375 1365 4047 1374 1364 4048 1376 1366 4049 1375 1365 4050 1373 1363 4051 1374 1364 4052 1375 1365 4053 1376 1366 4054 1377 1367 4055 1378 1368 4056 1377 1367 4057 1379 1369 4058 1380 1370 4059 1375 1365 4060 1377 1367 4061 1378 1368 4062 1380 1370 4063 1377 1367 4064 1378 1368 4065 1379 1369 4066 1381 1371 4067 1382 1372 4068 1381 1371 4069 1383 1373 4070 1382 1372 4071 1378 1368 4072 1381 1371 4073 1384 1374 4074 1383 1373 4075 1385 1375 4076 1382 1372 4077 1383 1373 4078 1384 1374 4079 1384 1374 4080 1385 1375 4081 1386 1376 4082 1384 1374 4083 1386 1376 4084 1387 1377 4085 1384 1374 4086 1387 1377 4087 1388 1378 4088 1384 1374 4089 1388 1378 4090 1389 1379 4091 1228 1219 4092 1389 1379 4093 1229 1220 4094 1390 1380 4095 1389 1379 4096 1228 1219 4097 1391 1381 4098 1384 1381 4099 1389 1381 4100 1392 1382 4101 1391 1383 4102 1389 1379 4103 1390 1380 4104 1392 1382 4105 1389 1379 4106 1263 1254 4107 1254 1245 4108 1306 1296 4109 1393 1384 4110 1306 1296 4111 1309 1299 4112 1393 1384 4113 1263 1254 4114 1306 1296 4115 1394 1385 4116 1309 1299 4117 1313 1303 4118 1394 1385 4119 1393 1384 4120 1309 1299 4121 1395 1386 4122 1313 1303 4123 1317 1307 4124 1395 1386 4125 1394 1385 4126 1313 1303 4127 1396 1387 4128 1317 1307 4129 1321 1311 4130 1396 1387 4131 1395 1386 4132 1317 1307 4133 1397 1388 4134 1321 1311 4135 1325 1315 4136 1397 1388 4137 1396 1387 4138 1321 1311 4139 1398 1389 4140 1325 1315 4141 1328 1318 4142 1398 1389 4143 1397 1388 4144 1325 1315 4145 1399 1390 4146 1328 1318 4147 1332 1322 4148 1399 1390 4149 1398 1389 4150 1328 1318 4151 1400 1391 4152 1332 1322 4153 1336 1326 4154 1400 1391 4155 1399 1390 4156 1332 1322 4157 1401 1392 4158 1336 1326 4159 1339 1329 4160 1401 1392 4161 1400 1391 4162 1336 1326 4163 1402 1393 4164 1339 1329 4165 1343 1333 4166 1402 1393 4167 1401 1392 4168 1339 1329 4169 1403 1394 4170 1343 1333 4171 1346 1336 4172 1403 1394 4173 1402 1393 4174 1343 1333 4175 1404 1395 4176 1346 1336 4177 1351 1341 4178 1404 1395 4179 1403 1394 4180 1346 1336 4181 1405 1396 4182 1404 1395 4183 1351 1341 4184 1406 1397 4185 1407 1398 4186 1353 1343 4187 1352 1342 4188 1406 1397 4189 1353 1343 4190 1408 1399 4191 1263 1254 4192 1393 1384 4193 1408 1399 4194 1280 1271 4195 1263 1254 4196 1409 1400 4197 1393 1384 4198 1394 1385 4199 1409 1400 4200 1408 1399 4201 1393 1384 4202 1410 1401 4203 1394 1385 4204 1395 1386 4205 1410 1401 4206 1409 1400 4207 1394 1385 4208 1411 1402 4209 1395 1386 4210 1396 1387 4211 1411 1402 4212 1410 1401 4213 1395 1386 4214 1412 1403 4215 1396 1387 4216 1397 1388 4217 1413 1404 4218 1411 1402 4219 1396 1387 4220 1412 1403 4221 1413 1404 4222 1396 1387 4223 1414 1405 4224 1397 1388 4225 1398 1389 4226 1414 1405 4227 1412 1403 4228 1397 1388 4229 1415 1406 4230 1398 1389 4231 1399 1390 4232 1416 1407 4233 1414 1405 4234 1398 1389 4235 1417 1408 4236 1416 1407 4237 1398 1389 4238 1415 1406 4239 1417 1408 4240 1398 1389 4241 1418 1409 4242 1399 1390 4243 1400 1391 4244 1419 1410 4245 1415 1406 4246 1399 1390 4247 1418 1409 4248 1419 1410 4249 1399 1390 4250 1420 1411 4251 1400 1391 4252 1401 1392 4253 1420 1411 4254 1418 1409 4255 1400 1391 4256 1421 1412 4257 1401 1392 4258 1402 1393 4259 1421 1412 4260 1420 1411 4261 1401 1392 4262 1422 1413 4263 1402 1393 4264 1403 1394 4265 1422 1413 4266 1421 1412 4267 1402 1393 4268 1423 1414 4269 1403 1394 4270 1404 1395 4271 1423 1414 4272 1422 1413 4273 1403 1394 4274 1424 1415 4275 1404 1395 4276 1405 1396 4277 1424 1415 4278 1423 1414 4279 1404 1395 4280 1425 1416 4281 1424 1415 4282 1405 1396 4283 1426 1417 4284 1427 1418 4285 1407 1398 4286 1406 1397 4287 1426 1417 4288 1407 1398 4289 1428 1419 4290 1283 1273 4291 1429 1420 4292 1430 1421 4293 1283 1273 4294 1428 1419 4295 1281 1272 4296 1283 1273 4297 1430 1421 4298 1431 1422 4299 1429 1420 4300 1432 1423 4301 1428 1419 4302 1429 1420 4303 1431 1422 4304 1431 1422 4305 1432 1423 4306 1433 1424 4307 1434 1425 4308 1433 1424 4309 1435 1426 4310 1431 1422 4311 1433 1424 4312 1434 1425 4313 1436 1427 4314 1435 1426 4315 1437 1428 4316 1434 1425 4317 1435 1426 4318 1436 1427 4319 1436 1427 4320 1437 1428 4321 1438 1429 4322 1439 1430 4323 1438 1429 4324 1440 1431 4325 1436 1427 4326 1438 1429 4327 1439 1430 4328 1439 1430 4329 1440 1431 4330 1441 1432 4331 1442 1433 4332 1441 1432 4333 1443 1434 4334 1439 1430 4335 1441 1432 4336 1442 1433 4337 1444 1435 4338 1443 1434 4339 1445 1436 4340 1442 1433 4341 1443 1434 4342 1444 1435 4343 1444 1435 4344 1445 1436 4345 1446 1437 4346 1447 1438 4347 1446 1437 4348 1448 1439 4349 1444 1435 4350 1446 1437 4351 1447 1438 4352 1449 1440 4353 1448 1439 4354 1450 1441 4355 1447 1438 4356 1448 1439 4357 1449 1440 4358 1451 1442 4359 1450 1441 4360 1452 1443 4361 1449 1440 4362 1450 1441 4363 1451 1442 4364 1453 1444 4365 1452 1443 4366 1454 1445 4367 1451 1442 4368 1452 1443 4369 1453 1444 4370 1455 1446 4371 1454 1445 4372 1456 1447 4373 1453 1444 4374 1454 1445 4375 1455 1446 4376 1457 1448 4377 1456 1447 4378 1458 1449 4379 1455 1446 4380 1456 1447 4381 1457 1448 4382 1457 1448 4383 1458 1449 4384 1459 1450 4385 1457 1448 4386 1459 1450 4387 1460 1451 4388 1461 1452 4389 1462 1453 4390 1463 1454 4391 1426 1417 4392 1464 1455 4393 1427 1418 4394 1465 1456 4395 1460 1451 4396 1466 1457 4397 1467 1458 4398 1468 1459 4399 1462 1453 4400 1469 1460 4401 1470 1461 4402 1471 1462 4403 1467 1458 4404 1472 1463 4405 1468 1459 4406 1473 1464 4407 1471 1462 4408 1474 1465 4409 1469 1460 4410 1471 1462 4411 1473 1464 4412 1465 1456 4413 1457 1448 4414 1460 1451 4415 1461 1452 4416 1467 1458 4417 1462 1453 4418 1475 1466 4419 1455 1446 4420 1457 1448 4421 1465 1456 4422 1475 1466 4423 1457 1448 4424 1476 1467 4425 1453 1444 4426 1455 1446 4427 1477 1468 4428 1476 1467 4429 1455 1446 4430 1475 1466 4431 1477 1468 4432 1455 1446 4433 1478 1469 4434 1451 1442 4435 1453 1444 4436 1476 1467 4437 1478 1469 4438 1453 1444 4439 1479 1470 4440 1449 1440 4441 1451 1442 4442 1478 1469 4443 1479 1470 4444 1451 1442 4445 1480 1471 4446 1447 1438 4447 1449 1440 4448 1481 1472 4449 1480 1471 4450 1449 1440 4451 1479 1470 4452 1481 1472 4453 1449 1440 4454 1482 1473 4455 1444 1435 4456 1447 1438 4457 1480 1471 4458 1482 1473 4459 1447 1438 4460 1483 1474 4461 1442 1433 4462 1444 1435 4463 1484 1475 4464 1483 1474 4465 1444 1435 4466 1482 1473 4467 1484 1475 4468 1444 1435 4469 1485 1476 4470 1486 1477 4471 1442 1433 4472 1439 1430 4473 1442 1433 4474 1486 1477 4475 1483 1474 4476 1485 1476 4477 1442 1433 4478 1487 1478 4479 1488 1479 4480 1486 1477 4481 1436 1427 4482 1486 1477 4483 1488 1479 4484 1485 1476 4485 1487 1478 4486 1486 1477 4487 1436 1427 4488 1439 1430 4489 1486 1477 4490 1489 1480 4491 1490 1481 4492 1488 1479 4493 1434 1425 4494 1488 1479 4495 1490 1481 4496 1491 1482 4497 1489 1480 4498 1488 1479 4499 1487 1478 4500 1491 1482 4501 1488 1479 4502 1434 1425 4503 1436 1427 4504 1488 1479 4505 1492 1483 4506 1493 1484 4507 1490 1481 4508 1431 1422 4509 1490 1481 4510 1493 1484 4511 1489 1480 4512 1492 1483 4513 1490 1481 4514 1431 1422 4515 1434 1425 4516 1490 1481 4517 1494 1485 4518 1495 1486 4519 1493 1484 4520 1428 1419 4521 1493 1484 4522 1495 1486 4523 1496 1487 4524 1494 1485 4525 1493 1484 4526 1492 1483 4527 1496 1487 4528 1493 1484 4529 1428 1419 4530 1431 1422 4531 1493 1484 4532 1497 1488 4533 1498 1489 4534 1499 1489 4535 1500 1490 4536 1428 1419 4537 1495 1486 4538 1497 1488 4539 1501 1491 4540 1498 1489 4541 1502 1492 4542 1503 1493 4543 1504 1494 4544 1502 1492 4545 1505 1495 4546 1503 1493 4547 1506 1496 4548 1504 1494 4549 1507 1497 4550 1506 1496 4551 1502 1492 4552 1504 1494 4553 1506 1496 4554 1507 1497 4555 1508 1498 4556 1509 1499 4557 1508 1498 4558 1510 1500 4559 1509 1499 4560 1506 1496 4561 1508 1498 4562 1509 1499 4563 1510 1500 4564 1511 1501 4565 1512 1502 4566 1511 1501 4567 1513 1503 4568 1512 1502 4569 1509 1499 4570 1511 1501 4571 1514 1504 4572 1513 1503 4573 1515 1505 4574 1514 1504 4575 1512 1502 4576 1513 1503 4577 1516 1506 4578 1515 1505 4579 1517 1507 4580 1516 1506 4581 1514 1504 4582 1515 1505 4583 1518 1508 4584 1517 1507 4585 1519 1509 4586 1518 1508 4587 1516 1506 4588 1517 1507 4589 1518 1508 4590 1519 1509 4591 1520 1510 4592 1521 1511 4593 1520 1510 4594 1522 1512 4595 1521 1511 4596 1518 1508 4597 1520 1510 4598 1523 1513 4599 1522 1512 4600 1524 1514 4601 1523 1513 4602 1521 1511 4603 1522 1512 4604 1523 1513 4605 1524 1514 4606 1525 1515 4607 1526 1516 4608 1525 1515 4609 1527 1517 4610 1526 1516 4611 1523 1513 4612 1525 1515 4613 1526 1516 4614 1527 1517 4615 1528 1518 4616 1526 1516 4617 1528 1518 4618 1529 1519 4619 1469 1460 4620 1529 1519 4621 1470 1461 4622 1469 1460 4623 1526 1516 4624 1529 1519 4625 1500 1490 4626 1430 1421 4627 1428 1419 4628 1530 1520 4629 1531 1521 4630 1501 1491 4631 1530 1520 4632 1284 1274 4633 1531 1521 4634 1530 1520 4635 1501 1491 4636 1497 1488 4637 1530 1520 4638 1277 1268 4639 1284 1274 4640 1467 1458 4641 1532 1522 4642 1472 1463 4643 1473 1464 4644 1474 1465 4645 1533 1523 4646 1534 1524 4647 1535 1525 4648 1532 1522 4649 1536 1526 4650 1533 1523 4651 1537 1527 4652 1467 1458 4653 1534 1524 4654 1532 1522 4655 1536 1526 4656 1473 1464 4657 1533 1523 4658 1538 1528 4659 1539 1529 4660 1535 1525 4661 1536 1526 4662 1537 1527 4663 1540 1530 4664 1534 1524 4665 1538 1528 4666 1535 1525 4667 1538 1528 4668 1541 1531 4669 1539 1529 4670 1542 1532 4671 1540 1530 4672 1543 1533 4673 1542 1532 4674 1536 1526 4675 1540 1530 4676 1544 1534 4677 1545 1535 4678 1541 1531 4679 1542 1532 4680 1543 1533 4681 1546 1536 4682 1538 1528 4683 1544 1534 4684 1541 1531 4685 1547 1537 4686 1548 1538 4687 1545 1535 4688 1549 1539 4689 1546 1536 4690 1550 1540 4691 1544 1534 4692 1547 1537 4693 1545 1535 4694 1549 1539 4695 1542 1532 4696 1546 1536 4697 1551 1541 4698 1552 1542 4699 1548 1538 4700 1549 1539 4701 1550 1540 4702 1553 1543 4703 1547 1537 4704 1551 1541 4705 1548 1538 4706 1551 1541 4707 1554 1544 4708 1552 1542 4709 1555 1545 4710 1553 1543 4711 1556 1546 4712 1555 1545 4713 1549 1539 4714 1553 1543 4715 1557 1547 4716 1558 1548 4717 1554 1544 4718 1559 1549 4719 1556 1546 4720 1560 1550 4721 1551 1541 4722 1557 1547 4723 1554 1544 4724 1559 1549 4725 1555 1545 4726 1556 1546 4727 1561 1551 4728 1562 1552 4729 1558 1548 4730 1559 1549 4731 1560 1550 4732 1563 1553 4733 1557 1547 4734 1561 1551 4735 1558 1548 4736 1561 1551 4737 1564 1554 4738 1562 1552 4739 1565 1555 4740 1563 1553 4741 1566 1556 4742 1565 1555 4743 1559 1549 4744 1563 1553 4745 1567 1557 4746 1568 1558 4747 1564 1554 4748 1565 1555 4749 1566 1556 4750 1569 1559 4751 1561 1551 4752 1567 1557 4753 1564 1554 4754 1570 1560 4755 1571 1561 4756 1568 1558 4757 1572 1562 4758 1569 1559 4759 1573 1563 4760 1567 1557 4761 1570 1560 4762 1568 1558 4763 1572 1562 4764 1565 1555 4765 1569 1559 4766 1574 1564 4767 1575 1565 4768 1571 1561 4769 1572 1562 4770 1573 1563 4771 1576 1566 4772 1570 1560 4773 1574 1564 4774 1571 1561 4775 1574 1564 4776 1577 1567 4777 1575 1565 4778 1578 1568 4779 1576 1566 4780 1579 1569 4781 1578 1568 4782 1572 1562 4783 1576 1566 4784 1580 1570 4785 1581 1571 4786 1577 1567 4787 1578 1568 4788 1579 1569 4789 1582 1572 4790 1574 1564 4791 1580 1570 4792 1577 1567 4793 1583 1573 4794 1584 1574 4795 1581 1571 4796 1578 1568 4797 1582 1572 4798 1585 1575 4799 1580 1570 4800 1583 1573 4801 1581 1571 4802 1586 1576 4803 1587 1577 4804 1588 1578 4805 1589 1579 4806 1578 1568 4807 1585 1575 4808 1590 1580 4809 1591 1581 4810 1592 1582 4811 1586 1576 4812 1593 1583 4813 1587 1577 4814 1594 1584 4815 1583 1573 4816 1580 1570 4817 1586 1576 4818 1588 1578 4819 1595 1585 4820 1596 1586 4821 1580 1570 4822 1574 1564 4823 1597 1587 4824 1594 1584 4825 1580 1570 4826 1598 1588 4827 1597 1587 4828 1580 1570 4829 1596 1586 4830 1598 1588 4831 1580 1570 4832 1599 1589 4833 1574 1564 4834 1570 1560 4835 1599 1589 4836 1596 1586 4837 1574 1564 4838 1600 1590 4839 1570 1560 4840 1567 1557 4841 1600 1590 4842 1599 1589 4843 1570 1560 4844 1601 1591 4845 1567 1557 4846 1561 1551 4847 1601 1591 4848 1600 1590 4849 1567 1557 4850 1602 1592 4851 1561 1551 4852 1557 1547 4853 1602 1592 4854 1601 1591 4855 1561 1551 4856 1603 1593 4857 1557 1547 4858 1551 1541 4859 1603 1593 4860 1602 1592 4861 1557 1547 4862 1604 1594 4863 1551 1541 4864 1547 1537 4865 1605 1595 4866 1603 1593 4867 1551 1541 4868 1604 1594 4869 1605 1595 4870 1551 1541 4871 1606 1596 4872 1547 1537 4873 1544 1534 4874 1606 1596 4875 1604 1594 4876 1547 1537 4877 1607 1597 4878 1544 1534 4879 1538 1528 4880 1607 1597 4881 1606 1596 4882 1544 1534 4883 1608 1598 4884 1538 1528 4885 1534 1524 4886 1608 1598 4887 1607 1597 4888 1538 1528 4889 1609 1599 4890 1534 1524 4891 1467 1458 4892 1609 1599 4893 1608 1598 4894 1534 1524 4895 1461 1452 4896 1609 1599 4897 1467 1458 4898 1610 1600 4899 1595 1585 4900 1611 1601 4901 1586 1576 4902 1595 1585 4903 1610 1600 4904 1612 1602 4905 1597 1587 4906 1598 1588 4907 1610 1600 4908 1611 1601 4909 1613 1603 4910 1614 1604 4911 1598 1588 4912 1596 1586 4913 1615 1605 4914 1612 1602 4915 1598 1588 4916 1616 1606 4917 1615 1605 4918 1598 1588 4919 1614 1604 4920 1616 1606 4921 1598 1588 4922 1617 1607 4923 1596 1586 4924 1599 1589 4925 1617 1607 4926 1614 1604 4927 1596 1586 4928 1618 1608 4929 1599 1589 4930 1600 1590 4931 1619 1609 4932 1617 1607 4933 1599 1589 4934 1618 1608 4935 1619 1609 4936 1599 1589 4937 1620 1610 4938 1600 1590 4939 1601 1591 4940 1620 1610 4941 1618 1608 4942 1600 1590 4943 1621 1611 4944 1601 1591 4945 1602 1592 4946 1622 1612 4947 1620 1610 4948 1601 1591 4949 1621 1611 4950 1622 1612 4951 1601 1591 4952 1623 1613 4953 1624 1614 4954 1625 1615 4955 1626 1616 4956 1627 1617 4957 1624 1614 4958 1623 1613 4959 1626 1616 4960 1624 1614 4961 1628 1618 4962 1625 1615 4963 1629 1619 4964 1628 1618 4965 1623 1613 4966 1625 1615 4967 1628 1618 4968 1629 1619 4969 1630 1620 4970 1631 1621 4971 1630 1620 4972 1632 1622 4973 1631 1621 4974 1628 1618 4975 1630 1620 4976 1633 1623 4977 1632 1622 4978 1634 1624 4979 1633 1623 4980 1631 1621 4981 1632 1622 4982 1635 1625 4983 1634 1624 4984 1636 1626 4985 1635 1625 4986 1633 1623 4987 1634 1624 4988 1637 1627 4989 1636 1626 4990 1638 1628 4991 1637 1627 4992 1635 1625 4993 1636 1626 4994 1426 1417 4995 1638 1628 4996 1464 1455 4997 1426 1417 4998 1637 1627 4999 1638 1628 5000 1639 1629 5001 1613 1603 5002 1640 1630 5003 1639 1629 5004 1610 1600 5005 1613 1603 5006 1641 1631 5007 1642 1632 5008 1643 1633 5009 1644 1634 5010 1639 1629 5011 1640 1630 5012 1641 1631 5013 1645 1635 5014 1642 1632 5015 1646 1636 5016 1643 1633 5017 1647 1637 5018 1646 1636 5019 1641 1631 5020 1643 1633 5021 1648 1638 5022 1647 1637 5023 1649 1639 5024 1648 1638 5025 1646 1636 5026 1647 1637 5027 1648 1638 5028 1649 1639 5029 1650 1640 5030 1651 1641 5031 1650 1640 5032 1652 1642 5033 1651 1641 5034 1648 1638 5035 1650 1640 5036 1653 1643 5037 1652 1642 5038 1654 1644 5039 1653 1643 5040 1651 1641 5041 1652 1642 5042 1653 1643 5043 1654 1644 5044 1655 1645 5045 1626 1616 5046 1655 1645 5047 1627 1617 5048 1626 1616 5049 1653 1643 5050 1655 1645 5051 1656 1646 5052 1657 1646 5053 1658 1646 5054 1659 1647 5055 1660 1647 5056 1657 1647 5057 1661 1648 5058 1659 1648 5059 1657 1648 5060 1656 1648 5061 1661 1648 5062 1657 1648 5063 1662 1649 5064 1658 1649 5065 1663 1649 5066 1664 1650 5067 1656 1650 5068 1658 1650 5069 1662 1648 5070 1664 1648 5071 1658 1648 5072 1665 1648 5073 1663 1648 5074 1666 1648 5075 1665 1651 5076 1662 1651 5077 1663 1651 5078 1667 1652 5079 1666 1652 5080 1668 1652 5081 1667 1653 5082 1665 1653 5083 1666 1653 5084 1669 1648 5085 1668 1648 5086 1670 1648 5087 1669 1648 5088 1667 1648 5089 1668 1648 5090 1671 1648 5091 1670 1648 5092 1672 1648 5093 1673 1648 5094 1669 1648 5095 1670 1648 5096 1671 1648 5097 1673 1648 5098 1670 1648 5099 1674 1648 5100 1672 1648 5101 1675 1648 5102 1676 1648 5103 1671 1648 5104 1672 1648 5105 1674 1654 5106 1676 1654 5107 1672 1654 5108 1677 1648 5109 1675 1648 5110 1678 1648 5111 1679 1655 5112 1674 1655 5113 1675 1655 5114 1677 1648 5115 1679 1648 5116 1675 1648 5117 1680 1648 5118 1678 1648 5119 1681 1648 5120 1680 1648 5121 1682 1648 5122 1678 1648 5123 1677 1648 5124 1678 1648 5125 1682 1648 5126 1590 1580 5127 1683 1656 5128 1591 1581 5129 1684 1657 5130 1685 1658 5131 1505 1495 5132 1530 1520 5133 1497 1488 5134 1686 1659 5135 1502 1492 5136 1684 1657 5137 1505 1495 5138 1684 1657 5139 1687 1660 5140 1685 1658 5141 1688 1661 5142 1686 1659 5143 1689 1662 5144 1688 1661 5145 1530 1520 5146 1686 1659 5147 1690 1663 5148 1691 1664 5149 1687 1660 5150 1692 1665 5151 1689 1662 5152 1693 1666 5153 1684 1657 5154 1690 1663 5155 1687 1660 5156 1692 1665 5157 1688 1661 5158 1689 1662 5159 1690 1663 5160 1694 1667 5161 1691 1664 5162 1695 1668 5163 1693 1666 5164 1696 1669 5165 1695 1668 5166 1692 1665 5167 1693 1666 5168 1697 1670 5169 1698 1671 5170 1694 1667 5171 1699 1672 5172 1696 1669 5173 1700 1673 5174 1690 1663 5175 1697 1670 5176 1694 1667 5177 1699 1672 5178 1695 1668 5179 1696 1669 5180 1697 1670 5181 1701 1674 5182 1698 1671 5183 1702 1675 5184 1700 1673 5185 1703 1676 5186 1702 1675 5187 1699 1672 5188 1700 1673 5189 1704 1677 5190 1705 1678 5191 1701 1674 5192 1706 1679 5193 1703 1676 5194 1707 1680 5195 1697 1670 5196 1704 1677 5197 1701 1674 5198 1706 1679 5199 1702 1675 5200 1703 1676 5201 1708 1681 5202 1709 1682 5203 1705 1678 5204 1706 1679 5205 1707 1680 5206 1710 1683 5207 1704 1677 5208 1708 1681 5209 1705 1678 5210 1708 1681 5211 1711 1684 5212 1709 1682 5213 1712 1685 5214 1710 1683 5215 1713 1686 5216 1712 1685 5217 1706 1679 5218 1710 1683 5219 1714 1687 5220 1715 1688 5221 1711 1684 5222 1716 1689 5223 1713 1686 5224 1717 1690 5225 1708 1681 5226 1714 1687 5227 1711 1684 5228 1716 1689 5229 1712 1685 5230 1713 1686 5231 1714 1687 5232 1718 1691 5233 1715 1688 5234 1719 1692 5235 1717 1690 5236 1720 1693 5237 1719 1692 5238 1716 1689 5239 1717 1690 5240 1721 1694 5241 1722 1695 5242 1718 1691 5243 1723 1696 5244 1720 1693 5245 1724 1697 5246 1714 1687 5247 1721 1694 5248 1718 1691 5249 1723 1696 5250 1719 1692 5251 1720 1693 5252 1721 1694 5253 1725 1698 5254 1722 1695 5255 1726 1699 5256 1724 1697 5257 1727 1700 5258 1726 1699 5259 1723 1696 5260 1724 1697 5261 1728 1701 5262 1729 1702 5263 1725 1698 5264 1730 1703 5265 1727 1700 5266 1731 1704 5267 1721 1694 5268 1728 1701 5269 1725 1698 5270 1730 1703 5271 1726 1699 5272 1727 1700 5273 1728 1701 5274 1732 1705 5275 1729 1702 5276 1733 1706 5277 1731 1704 5278 1734 1707 5279 1733 1706 5280 1730 1703 5281 1731 1704 5282 1735 1708 5283 1736 1709 5284 1732 1705 5285 1737 1710 5286 1734 1707 5287 1738 1711 5288 1728 1701 5289 1735 1708 5290 1732 1705 5291 1737 1710 5292 1733 1706 5293 1734 1707 5294 1739 1712 5295 1740 1713 5296 1736 1709 5297 1737 1710 5298 1738 1711 5299 1741 1714 5300 1735 1708 5301 1739 1712 5302 1736 1709 5303 1742 1715 5304 1743 1716 5305 1744 1717 5306 1745 1718 5307 1743 1716 5308 1742 1715 5309 1746 1719 5310 1747 1720 5311 1748 1721 5312 1737 1710 5313 1741 1714 5314 1749 1722 5315 1750 1723 5316 1751 1723 5317 1752 1723 5318 1753 1724 5319 1754 1724 5320 1751 1724 5321 1755 1648 5322 1751 1648 5323 1750 1648 5324 1755 1648 5325 1753 1648 5326 1751 1648 5327 1756 1725 5328 1752 1725 5329 1757 1725 5330 1756 1648 5331 1750 1648 5332 1752 1648 5333 1758 1648 5334 1757 1648 5335 1759 1648 5336 1758 1648 5337 1756 1648 5338 1757 1648 5339 1760 1726 5340 1759 1726 5341 1761 1726 5342 1760 1727 5343 1758 1727 5344 1759 1727 5345 1762 1648 5346 1761 1648 5347 1763 1648 5348 1762 1728 5349 1760 1728 5350 1761 1728 5351 1764 1648 5352 1763 1648 5353 1765 1648 5354 1764 1648 5355 1762 1648 5356 1763 1648 5357 1766 1648 5358 1765 1648 5359 1767 1648 5360 1768 1729 5361 1764 1729 5362 1765 1729 5363 1766 1648 5364 1768 1648 5365 1765 1648 5366 1769 1730 5367 1767 1730 5368 1770 1730 5369 1771 1731 5370 1766 1731 5371 1767 1731 5372 1769 1732 5373 1771 1732 5374 1767 1732 5375 1772 1733 5376 1770 1733 5377 1773 1733 5378 1774 1734 5379 1769 1734 5380 1770 1734 5381 1772 1735 5382 1774 1735 5383 1770 1735 5384 1775 1736 5385 1773 1736 5386 1776 1736 5387 1777 1737 5388 1773 1737 5389 1775 1737 5390 1772 1648 5391 1773 1648 5392 1777 1648 5393 1778 1648 5394 1777 1648 5395 1779 1648 5396 1778 1648 5397 1772 1648 5398 1777 1648 5399 1780 1738 5400 1779 1738 5401 1781 1738 5402 1780 1648 5403 1778 1648 5404 1779 1648 5405 1782 1739 5406 1781 1739 5407 1783 1739 5408 1782 1648 5409 1780 1648 5410 1781 1648 5411 1784 1648 5412 1783 1648 5413 1785 1648 5414 1784 1740 5415 1782 1740 5416 1783 1740 5417 1784 1741 5418 1785 1741 5419 1786 1741 5420 1787 1742 5421 1786 1742 5422 1788 1742 5423 1787 1648 5424 1784 1648 5425 1786 1648 5426 1789 1743 5427 1788 1743 5428 1790 1743 5429 1789 1648 5430 1787 1648 5431 1788 1648 5432 1791 1744 5433 1790 1744 5434 1660 1744 5435 1791 1648 5436 1789 1648 5437 1790 1648 5438 1659 1745 5439 1791 1745 5440 1660 1745 5441 1792 1648 5442 1793 1648 5443 1754 1648 5444 1794 1746 5445 1742 1715 5446 1795 1747 5447 1753 1748 5448 1792 1748 5449 1754 1748 5450 1796 1749 5451 1745 1718 5452 1742 1715 5453 1794 1746 5454 1796 1749 5455 1742 1715 5456 1797 1648 5457 1798 1648 5458 1793 1648 5459 1799 1750 5460 1795 1747 5461 1800 1751 5462 1792 1648 5463 1797 1648 5464 1793 1648 5465 1801 1752 5466 1794 1746 5467 1795 1747 5468 1799 1750 5469 1801 1752 5470 1795 1747 5471 1802 1648 5472 1803 1648 5473 1798 1648 5474 1804 1753 5475 1800 1751 5476 1805 1754 5477 1797 1648 5478 1802 1648 5479 1798 1648 5480 1806 1755 5481 1799 1750 5482 1800 1751 5483 1804 1753 5484 1806 1755 5485 1800 1751 5486 1807 1756 5487 1808 1756 5488 1803 1756 5489 1809 1757 5490 1805 1754 5491 1810 1758 5492 1802 1648 5493 1807 1648 5494 1803 1648 5495 1811 1759 5496 1804 1753 5497 1805 1754 5498 1809 1757 5499 1811 1759 5500 1805 1754 5501 1812 1648 5502 1813 1648 5503 1808 1648 5504 1814 1760 5505 1810 1758 5506 1815 1761 5507 1807 1648 5508 1812 1648 5509 1808 1648 5510 1816 1762 5511 1809 1757 5512 1810 1758 5513 1814 1760 5514 1816 1762 5515 1810 1758 5516 1817 1763 5517 1682 1763 5518 1813 1763 5519 1818 1764 5520 1815 1761 5521 1819 1765 5522 1820 1648 5523 1817 1648 5524 1813 1648 5525 1812 1766 5526 1820 1766 5527 1813 1766 5528 1821 1767 5529 1814 1760 5530 1815 1761 5531 1818 1764 5532 1821 1767 5533 1815 1761 5534 1822 1768 5535 1819 1765 5536 1683 1656 5537 1817 1648 5538 1677 1648 5539 1682 1648 5540 1823 1769 5541 1818 1764 5542 1819 1765 5543 1822 1768 5544 1823 1769 5545 1819 1765 5546 1824 1770 5547 1822 1768 5548 1683 1656 5549 1590 1580 5550 1824 1770 5551 1683 1656 5552 1825 1771 5553 1826 1772 5554 1827 1773 5555 1828 1774 5556 1829 1775 5557 1830 1776 5558 1828 1774 5559 1830 1776 5560 1831 1777 5561 1832 1778 5562 1827 1773 5563 1833 1779 5564 1834 1780 5565 1825 1771 5566 1827 1773 5567 1832 1778 5568 1834 1780 5569 1827 1773 5570 1835 1781 5571 1833 1779 5572 1836 1782 5573 1835 1781 5574 1832 1778 5575 1833 1779 5576 1837 1783 5577 1836 1782 5578 1838 1784 5579 1837 1783 5580 1835 1781 5581 1836 1782 5582 1839 1785 5583 1838 1784 5584 1840 1786 5585 1839 1785 5586 1837 1783 5587 1838 1784 5588 1841 1787 5589 1840 1786 5590 1842 1788 5591 1841 1787 5592 1839 1785 5593 1840 1786 5594 1841 1787 5595 1842 1788 5596 1843 1789 5597 1844 1790 5598 1843 1789 5599 1845 1791 5600 1844 1790 5601 1841 1787 5602 1843 1789 5603 1846 1792 5604 1845 1791 5605 1847 1793 5606 1846 1792 5607 1844 1790 5608 1845 1791 5609 1848 1794 5610 1847 1793 5611 1849 1795 5612 1848 1794 5613 1846 1792 5614 1847 1793 5615 1850 1796 5616 1849 1795 5617 1851 1797 5618 1850 1796 5619 1848 1794 5620 1849 1795 5621 1852 1798 5622 1851 1797 5623 1853 1799 5624 1852 1798 5625 1850 1796 5626 1851 1797 5627 1854 1800 5628 1853 1799 5629 1855 1801 5630 1854 1800 5631 1852 1798 5632 1853 1799 5633 1856 1802 5634 1855 1801 5635 1857 1803 5636 1856 1802 5637 1854 1800 5638 1855 1801 5639 1858 1804 5640 1857 1803 5641 1859 1805 5642 1858 1804 5643 1856 1802 5644 1857 1803 5645 1860 1806 5646 1859 1805 5647 1861 1807 5648 1862 1808 5649 1858 1804 5650 1859 1805 5651 1860 1806 5652 1862 1808 5653 1859 1805 5654 1863 1809 5655 1861 1807 5656 1864 1810 5657 1863 1809 5658 1860 1806 5659 1861 1807 5660 1865 1811 5661 1864 1810 5662 1866 1812 5663 1865 1811 5664 1863 1809 5665 1864 1810 5666 1867 1813 5667 1866 1812 5668 1868 1814 5669 1867 1813 5670 1865 1811 5671 1866 1812 5672 1869 1815 5673 1868 1814 5674 1870 1816 5675 1869 1815 5676 1867 1813 5677 1868 1814 5678 1869 1815 5679 1870 1816 5680 1871 1817 5681 1872 1818 5682 1873 1819 5683 1874 1820 5684 1875 1821 5685 1869 1815 5686 1871 1817 5687 1876 1822 5688 1874 1820 5689 1877 1823 5690 1878 1824 5691 1872 1818 5692 1874 1820 5693 1876 1822 5694 1878 1824 5695 1874 1820 5696 1879 1825 5697 1877 1823 5698 1880 1826 5699 1879 1825 5700 1876 1822 5701 1877 1823 5702 1881 1827 5703 1880 1826 5704 1882 1828 5705 1881 1827 5706 1879 1825 5707 1880 1826 5708 1883 1829 5709 1882 1828 5710 1884 1830 5711 1883 1829 5712 1881 1827 5713 1882 1828 5714 1885 1831 5715 1884 1830 5716 1886 1832 5717 1885 1831 5718 1883 1829 5719 1884 1830 5720 1885 1831 5721 1886 1832 5722 1887 1833 5723 1888 1834 5724 1887 1833 5725 1889 1835 5726 1888 1834 5727 1885 1831 5728 1887 1833 5729 1890 1836 5730 1889 1835 5731 1891 1837 5732 1890 1836 5733 1888 1834 5734 1889 1835 5735 1892 1838 5736 1891 1837 5737 1893 1839 5738 1892 1838 5739 1890 1836 5740 1891 1837 5741 1894 1840 5742 1893 1839 5743 1895 1841 5744 1894 1840 5745 1892 1838 5746 1893 1839 5747 1896 1842 5748 1895 1841 5749 1897 1843 5750 1896 1842 5751 1894 1840 5752 1895 1841 5753 1898 1844 5754 1897 1843 5755 1899 1845 5756 1898 1844 5757 1896 1842 5758 1897 1843 5759 1900 1846 5760 1899 1845 5761 1901 1847 5762 1900 1846 5763 1898 1844 5764 1899 1845 5765 1902 1848 5766 1901 1847 5767 1903 1849 5768 1902 1848 5769 1900 1846 5770 1901 1847 5771 1904 1850 5772 1903 1849 5773 1905 1851 5774 1906 1852 5775 1902 1848 5776 1903 1849 5777 1904 1850 5778 1906 1852 5779 1903 1849 5780 1907 1853 5781 1905 1851 5782 1908 1854 5783 1907 1853 5784 1904 1850 5785 1905 1851 5786 1909 1855 5787 1908 1854 5788 1910 1856 5789 1909 1855 5790 1907 1853 5791 1908 1854 5792 1911 1857 5793 1910 1856 5794 1912 1858 5795 1911 1857 5796 1909 1855 5797 1910 1856 5798 1828 1774 5799 1912 1858 5800 1829 1775 5801 1828 1774 5802 1911 1857 5803 1912 1858 5804 1913 1859 5805 1748 1721 5806 1914 1860 5807 1913 1859 5808 1746 1719 5809 1748 1721 5810 1915 1861 5811 1914 1860 5812 1916 1862 5813 1915 1861 5814 1913 1859 5815 1914 1860 5816 1917 1863 5817 1916 1862 5818 1918 1864 5819 1917 1863 5820 1915 1861 5821 1916 1862 5822 1919 1865 5823 1918 1864 5824 1920 1866 5825 1919 1865 5826 1917 1863 5827 1918 1864 5828 1919 1865 5829 1920 1866 5830 1921 1867 5831 1922 1868 5832 1921 1867 5833 1923 1869 5834 1922 1868 5835 1919 1865 5836 1921 1867 5837 1924 1870 5838 1923 1869 5839 1925 1871 5840 1924 1870 5841 1922 1868 5842 1923 1869 5843 1926 1872 5844 1925 1871 5845 1927 1873 5846 1926 1872 5847 1924 1870 5848 1925 1871 5849 1928 1874 5850 1927 1873 5851 1929 1875 5852 1928 1874 5853 1926 1872 5854 1927 1873 5855 1930 1876 5856 1929 1875 5857 1931 1877 5858 1930 1876 5859 1928 1874 5860 1929 1875 5861 1930 1876 5862 1931 1877 5863 1932 1878 5864 1933 1879 5865 1932 1878 5866 1934 1880 5867 1933 1879 5868 1930 1876 5869 1932 1878 5870 1935 1881 5871 1934 1880 5872 1936 1882 5873 1935 1881 5874 1933 1879 5875 1934 1880 5876 1937 1883 5877 1936 1882 5878 1938 1884 5879 1937 1883 5880 1935 1881 5881 1936 1882 5882 1939 1885 5883 1938 1884 5884 1940 1886 5885 1939 1885 5886 1937 1883 5887 1938 1884 5888 1586 1576 5889 1940 1886 5890 1593 1583 5891 1586 1576 5892 1939 1885 5893 1940 1886 5894 1941 1887 5895 1942 1888 5896 1610 1600 5897 1586 1576 5898 1610 1600 5899 1942 1888 5900 1639 1629 5901 1941 1887 5902 1610 1600 5903 1943 1889 5904 1944 1890 5905 1942 1888 5906 1939 1885 5907 1942 1888 5908 1944 1890 5909 1941 1887 5910 1943 1889 5911 1942 1888 5912 1586 1576 5913 1942 1888 5914 1939 1885 5915 1945 1891 5916 1946 1892 5917 1944 1890 5918 1937 1883 5919 1944 1890 5920 1946 1892 5921 1943 1889 5922 1945 1891 5923 1944 1890 5924 1939 1885 5925 1944 1890 5926 1937 1883 5927 1947 1893 5928 1948 1894 5929 1946 1892 5930 1935 1881 5931 1946 1892 5932 1948 1894 5933 1945 1891 5934 1947 1893 5935 1946 1892 5936 1937 1883 5937 1946 1892 5938 1935 1881 5939 1949 1895 5940 1950 1896 5941 1948 1894 5942 1933 1879 5943 1948 1894 5944 1950 1896 5945 1947 1893 5946 1949 1895 5947 1948 1894 5948 1935 1881 5949 1948 1894 5950 1933 1879 5951 1951 1897 5952 1952 1898 5953 1950 1896 5954 1930 1876 5955 1950 1896 5956 1952 1898 5957 1949 1895 5958 1951 1897 5959 1950 1896 5960 1933 1879 5961 1950 1896 5962 1930 1876 5963 1953 1899 5964 1954 1900 5965 1952 1898 5966 1928 1874 5967 1952 1898 5968 1954 1900 5969 1951 1897 5970 1953 1899 5971 1952 1898 5972 1930 1876 5973 1952 1898 5974 1928 1874 5975 1955 1901 5976 1956 1902 5977 1954 1900 5978 1926 1872 5979 1954 1900 5980 1956 1902 5981 1953 1899 5982 1955 1901 5983 1954 1900 5984 1928 1874 5985 1954 1900 5986 1926 1872 5987 1957 1903 5988 1958 1904 5989 1956 1902 5990 1924 1870 5991 1956 1902 5992 1958 1904 5993 1955 1901 5994 1957 1903 5995 1956 1902 5996 1926 1872 5997 1956 1902 5998 1924 1870 5999 1959 1905 6000 1960 1906 6001 1958 1904 6002 1922 1868 6003 1958 1904 6004 1960 1906 6005 1957 1903 6006 1959 1905 6007 1958 1904 6008 1924 1870 6009 1958 1904 6010 1922 1868 6011 1961 1907 6012 1962 1908 6013 1960 1906 6014 1919 1865 6015 1960 1906 6016 1962 1908 6017 1959 1905 6018 1961 1907 6019 1960 1906 6020 1922 1868 6021 1960 1906 6022 1919 1865 6023 1963 1909 6024 1964 1910 6025 1962 1908 6026 1917 1863 6027 1962 1908 6028 1964 1910 6029 1961 1907 6030 1963 1909 6031 1962 1908 6032 1919 1865 6033 1962 1908 6034 1917 1863 6035 1965 1911 6036 1966 1912 6037 1964 1910 6038 1915 1861 6039 1964 1910 6040 1966 1912 6041 1963 1909 6042 1965 1911 6043 1964 1910 6044 1917 1863 6045 1964 1910 6046 1915 1861 6047 1967 1913 6048 1968 1914 6049 1966 1912 6050 1913 1859 6051 1966 1912 6052 1968 1914 6053 1969 1915 6054 1967 1913 6055 1966 1912 6056 1965 1911 6057 1969 1915 6058 1966 1912 6059 1915 1861 6060 1966 1912 6061 1913 1859 6062 1970 1916 6063 1971 1917 6064 1972 1918 6065 1913 1859 6066 1968 1914 6067 1746 1719 6068 1973 1919 6069 1749 1722 6070 1971 1917 6071 1973 1919 6072 1971 1917 6073 1970 1916 6074 785 776 6075 1967 1913 6076 1969 1915 6077 787 778 6078 1972 1918 6079 780 771 6080 787 778 6081 1970 1916 6082 1972 1918 6083 1974 1920 6084 1969 1915 6085 1965 1911 6086 783 774 6087 785 776 6088 1969 1915 6089 1974 1920 6090 783 774 6091 1969 1915 6092 1975 1921 6093 1965 1911 6094 1963 1909 6095 1975 1921 6096 1974 1920 6097 1965 1911 6098 1976 1922 6099 1963 1909 6100 1961 1907 6101 1976 1922 6102 1975 1921 6103 1963 1909 6104 1977 1923 6105 1961 1907 6106 1959 1905 6107 1977 1923 6108 1976 1922 6109 1961 1907 6110 161 161 6111 1959 1905 6112 1957 1903 6113 161 161 6114 1977 1923 6115 1959 1905 6116 155 155 6117 1957 1903 6118 1955 1901 6119 155 155 6120 161 161 6121 1957 1903 6122 152 152 6123 1955 1901 6124 1953 1899 6125 152 152 6126 155 155 6127 1955 1901 6128 54 54 6129 1953 1899 6130 1951 1897 6131 54 54 6132 152 152 6133 1953 1899 6134 57 57 6135 1951 1897 6136 1949 1895 6137 57 57 6138 54 54 6139 1951 1897 6140 1978 1924 6141 1949 1895 6142 1947 1893 6143 1979 1925 6144 57 57 6145 1949 1895 6146 1978 1924 6147 1979 1925 6148 1949 1895 6149 1980 1926 6150 1947 1893 6151 1945 1891 6152 1980 1926 6153 1978 1924 6154 1947 1893 6155 1981 1927 6156 1945 1891 6157 1943 1889 6158 1982 1928 6159 1980 1926 6160 1945 1891 6161 1981 1927 6162 1982 1928 6163 1945 1891 6164 1983 1929 6165 1984 1930 6166 1985 1931 6167 1983 1929 6168 1986 1932 6169 1984 1930 6170 1987 1933 6171 1985 1931 6172 1988 1934 6173 1987 1933 6174 1983 1929 6175 1985 1931 6176 1644 1634 6177 1989 1935 6178 1639 1629 6179 1987 1933 6180 1988 1934 6181 1990 1936 6182 1991 1937 6183 1992 1938 6184 1645 1635 6185 1987 1933 6186 1990 1936 6187 1993 1939 6188 1641 1631 6189 1991 1937 6190 1645 1635 6191 1737 1710 6192 1749 1722 6193 1973 1919 6194 1994 1940 6195 783 774 6196 1974 1920 6197 1994 1940 6198 786 777 6199 783 774 6200 1995 1941 6201 1974 1920 6202 1975 1921 6203 1995 1941 6204 1994 1940 6205 1974 1920 6206 1996 1942 6207 1975 1921 6208 1976 1922 6209 1996 1942 6210 1995 1941 6211 1975 1921 6212 1997 1943 6213 1976 1922 6214 1977 1923 6215 1998 1944 6216 1996 1942 6217 1976 1922 6218 1997 1943 6219 1998 1944 6220 1976 1922 6221 162 162 6222 1977 1923 6223 161 161 6224 1999 1945 6225 1997 1943 6226 1977 1923 6227 162 162 6228 1999 1945 6229 1977 1923 6230 48 48 6231 53 53 6232 2000 1946 6233 2001 1947 6234 2000 1946 6235 2002 1948 6236 2001 1947 6237 48 48 6238 2000 1946 6239 2003 1949 6240 2002 1948 6241 2004 1950 6242 2003 1949 6243 2001 1947 6244 2002 1948 6245 1983 1929 6246 2004 1950 6247 1986 1932 6248 1983 1929 6249 2003 1949 6250 2004 1950 6251 748 739 6252 763 754 6253 2005 1951 6254 2006 1952 6255 2005 1951 6256 2007 1953 6257 748 739 6258 2005 1951 6259 2006 1952 6260 2006 1952 6261 2007 1953 6262 2008 1954 6263 2009 1955 6264 2008 1954 6265 2010 1956 6266 2006 1952 6267 2008 1954 6268 2009 1955 6269 2011 1957 6270 2010 1956 6271 2012 1958 6272 2009 1955 6273 2010 1956 6274 2011 1957 6275 2011 1957 6276 2012 1958 6277 2013 1959 6278 163 163 6279 2013 1959 6280 164 164 6281 2011 1957 6282 2013 1959 6283 163 163 6284 2014 1960 6285 1993 1939 6286 2015 1961 6287 2014 1960 6288 1987 1933 6289 1993 1939 6290 2016 1962 6291 1641 1631 6292 1646 1636 6293 2016 1962 6294 2017 1963 6295 1641 1631 6296 2014 1960 6297 2015 1961 6298 2018 1964 6299 2019 1965 6300 1646 1636 6301 1648 1638 6302 2019 1965 6303 2016 1962 6304 1646 1636 6305 2020 1966 6306 1648 1638 6307 1651 1641 6308 2020 1966 6309 2019 1965 6310 1648 1638 6311 2021 1967 6312 1651 1641 6313 1653 1643 6314 2021 1967 6315 2020 1966 6316 1651 1641 6317 2022 1968 6318 1653 1643 6319 1626 1616 6320 2022 1968 6321 2021 1967 6322 1653 1643 6323 2023 1969 6324 1626 1616 6325 1623 1613 6326 2023 1969 6327 2022 1968 6328 1626 1616 6329 2024 1970 6330 1623 1613 6331 1628 1618 6332 2024 1970 6333 2023 1969 6334 1623 1613 6335 2025 1971 6336 1628 1618 6337 1631 1621 6338 2025 1971 6339 2024 1970 6340 1628 1618 6341 2026 1972 6342 1631 1621 6343 1633 1623 6344 2026 1972 6345 2025 1971 6346 1631 1621 6347 2027 1973 6348 1633 1623 6349 1635 1625 6350 2027 1973 6351 2026 1972 6352 1633 1623 6353 2028 1974 6354 1635 1625 6355 1637 1627 6356 2028 1974 6357 2027 1973 6358 1635 1625 6359 1406 1397 6360 1637 1627 6361 1426 1417 6362 1406 1397 6363 2028 1974 6364 1637 1627 6365 2016 1962 6366 2029 1975 6367 2017 1963 6368 2014 1960 6369 2018 1964 6370 2030 1976 6371 2016 1962 6372 2031 1977 6373 2029 1975 6374 2032 1978 6375 2030 1976 6376 2033 1979 6377 2032 1978 6378 2014 1960 6379 2030 1976 6380 2034 1980 6381 2031 1977 6382 2016 1962 6383 2034 1980 6384 2035 1981 6385 2031 1977 6386 2032 1978 6387 2033 1979 6388 2036 1982 6389 2037 1983 6390 2016 1962 6391 2019 1965 6392 2037 1983 6393 2034 1980 6394 2016 1962 6395 2038 1984 6396 2019 1965 6397 2020 1966 6398 2038 1984 6399 2037 1983 6400 2019 1965 6401 2039 1985 6402 2020 1966 6403 2021 1967 6404 2039 1985 6405 2038 1984 6406 2020 1966 6407 2040 1986 6408 2021 1967 6409 2022 1968 6410 2040 1986 6411 2039 1985 6412 2021 1967 6413 2041 1987 6414 2022 1968 6415 2023 1969 6416 2041 1987 6417 2040 1986 6418 2022 1968 6419 2042 1988 6420 2023 1969 6421 2024 1970 6422 2042 1988 6423 2041 1987 6424 2023 1969 6425 2043 1989 6426 2024 1970 6427 2025 1971 6428 2043 1989 6429 2042 1988 6430 2024 1970 6431 2044 1990 6432 2025 1971 6433 2026 1972 6434 2044 1990 6435 2043 1989 6436 2025 1971 6437 2045 1991 6438 2026 1972 6439 2027 1973 6440 2045 1991 6441 2044 1990 6442 2026 1972 6443 2046 1992 6444 2027 1973 6445 2028 1974 6446 2046 1992 6447 2045 1991 6448 2027 1973 6449 1352 1342 6450 2028 1974 6451 1406 1397 6452 1352 1342 6453 2046 1992 6454 2028 1974 6455 2034 1980 6456 2047 1993 6457 2035 1981 6458 2032 1978 6459 2036 1982 6460 2048 1994 6461 2034 1980 6462 2049 1995 6463 2047 1993 6464 2050 1996 6465 2048 1994 6466 2051 1997 6467 2050 1996 6468 2032 1978 6469 2048 1994 6470 2052 1998 6471 2049 1995 6472 2034 1980 6473 2052 1998 6474 2053 1999 6475 2049 1995 6476 2050 1996 6477 2051 1997 6478 2054 2000 6479 2055 2001 6480 2034 1980 6481 2037 1983 6482 2055 2001 6483 2052 1998 6484 2034 1980 6485 2056 2002 6486 2037 1983 6487 2038 1984 6488 2057 2003 6489 2055 2001 6490 2037 1983 6491 2056 2002 6492 2057 2003 6493 2037 1983 6494 2058 2004 6495 2038 1984 6496 2039 1985 6497 2059 2005 6498 2056 2002 6499 2038 1984 6500 2058 2004 6501 2059 2005 6502 2038 1984 6503 2060 2006 6504 2039 1985 6505 2040 1986 6506 2060 2006 6507 2058 2004 6508 2039 1985 6509 2061 2007 6510 2040 1986 6511 2041 1987 6512 2062 2008 6513 2060 2006 6514 2040 1986 6515 2061 2007 6516 2062 2008 6517 2040 1986 6518 2063 2009 6519 2041 1987 6520 2042 1988 6521 2064 2010 6522 2061 2007 6523 2041 1987 6524 2063 2009 6525 2064 2010 6526 2041 1987 6527 2065 2011 6528 2042 1988 6529 2043 1989 6530 2066 2012 6531 2063 2009 6532 2042 1988 6533 2065 2011 6534 2066 2012 6535 2042 1988 6536 2067 2013 6537 2043 1989 6538 2044 1990 6539 2068 2014 6540 2065 2011 6541 2043 1989 6542 2067 2013 6543 2068 2014 6544 2043 1989 6545 2069 2015 6546 2044 1990 6547 2045 1991 6548 2069 2015 6549 2067 2013 6550 2044 1990 6551 2070 2016 6552 2045 1991 6553 2046 1992 6554 2070 2016 6555 2069 2015 6556 2045 1991 6557 2071 2017 6558 2046 1992 6559 1352 1342 6560 2072 2018 6561 2070 2016 6562 2046 1992 6563 2071 2017 6564 2072 2018 6565 2046 1992 6566 2073 2019 6567 2071 2017 6568 1352 1342 6569 1348 1338 6570 2073 2019 6571 1352 1342 6572 2052 1998 6573 2074 2020 6574 2053 1999 6575 2050 1996 6576 2054 2000 6577 2075 2021 6578 2052 1998 6579 2076 2022 6580 2074 2020 6581 2077 2023 6582 2075 2021 6583 2078 2024 6584 2077 2023 6585 2050 1996 6586 2075 2021 6587 2079 2025 6588 2080 2026 6589 2081 2027 6590 2082 2028 6591 2080 2026 6592 2079 2025 6593 2083 2029 6594 2081 2027 6595 2084 2030 6596 2079 2025 6597 2081 2027 6598 2083 2029 6599 2085 2031 6600 2084 2030 6601 2086 2032 6602 2087 2033 6603 2084 2030 6604 2085 2031 6605 2088 2034 6606 2084 2030 6607 2087 2033 6608 2089 2035 6609 2084 2030 6610 2088 2034 6611 2090 2036 6612 2083 2029 6613 2084 2030 6614 2091 2037 6615 2084 2037 6616 2089 2037 6617 2091 2038 6618 2090 2036 6619 2084 2030 6620 2089 2035 6621 2088 2034 6622 2092 2039 6623 2093 2040 6624 2092 2039 6625 2094 2041 6626 2093 2040 6627 2089 2035 6628 2092 2039 6629 2093 2040 6630 2094 2041 6631 2095 2042 6632 2096 2043 6633 2095 2042 6634 2097 2044 6635 2098 2045 6636 2095 2042 6637 2096 2043 6638 2099 2046 6639 2093 2040 6640 2095 2042 6641 2098 2045 6642 2099 2046 6643 2095 2042 6644 2096 2043 6645 2097 2044 6646 2100 2047 6647 2101 2048 6648 2100 2047 6649 2102 2049 6650 2101 2048 6651 2096 2043 6652 2100 2047 6653 2101 2048 6654 2102 2049 6655 2103 2050 6656 2104 2051 6657 2103 2050 6658 2105 2052 6659 2104 2051 6660 2101 2048 6661 2103 2050 6662 2106 2053 6663 2105 2052 6664 2107 2054 6665 2106 2053 6666 2104 2051 6667 2105 2052 6668 2108 2055 6669 2107 2054 6670 2109 2056 6671 2108 2055 6672 2106 2053 6673 2107 2054 6674 2108 2055 6675 2109 2056 6676 2110 2057 6677 2111 2058 6678 2110 2057 6679 2112 2059 6680 2111 2058 6681 2108 2055 6682 2110 2057 6683 2111 2058 6684 2112 2059 6685 2113 2060 6686 1357 1347 6687 2113 2060 6688 2114 2061 6689 1357 1347 6690 2111 2058 6691 2113 2060 6692 1357 1347 6693 2114 2061 6694 1358 1348 6695 46 46 6696 48 48 6697 2001 1947 6698 2115 2062 6699 2001 1947 6700 2003 1949 6701 2115 2062 6702 46 46 6703 2001 1947 6704 2116 2063 6705 2003 1949 6706 1983 1929 6707 2116 2063 6708 2115 2062 6709 2003 1949 6710 2117 2064 6711 1983 1929 6712 1987 1933 6713 2117 2064 6714 2116 2063 6715 1983 1929 6716 2014 1960 6717 2117 2064 6718 1987 1933 6719 44 44 6720 46 46 6721 2115 2062 6722 2118 2065 6723 2115 2062 6724 2116 2063 6725 2118 2065 6726 44 44 6727 2115 2062 6728 2119 2066 6729 2116 2063 6730 2117 2064 6731 2119 2066 6732 2118 2065 6733 2116 2063 6734 2120 2067 6735 2117 2064 6736 2014 1960 6737 2120 2067 6738 2119 2066 6739 2117 2064 6740 2032 1978 6741 2120 2067 6742 2014 1960 6743 39 39 6744 44 44 6745 2118 2065 6746 2121 2068 6747 2118 2065 6748 2119 2066 6749 2121 2068 6750 39 39 6751 2118 2065 6752 2122 2069 6753 2119 2066 6754 2120 2067 6755 2122 2069 6756 2121 2068 6757 2119 2066 6758 2123 2070 6759 2120 2067 6760 2032 1978 6761 2123 2070 6762 2122 2069 6763 2120 2067 6764 2050 1996 6765 2123 2070 6766 2032 1978 6767 2124 2071 6768 39 39 6769 2121 2068 6770 2124 2071 6771 42 42 6772 39 39 6773 2125 2072 6774 2121 2068 6775 2122 2069 6776 2125 2072 6777 2124 2071 6778 2121 2068 6779 2126 2073 6780 2122 2069 6781 2123 2070 6782 2127 2074 6783 2125 2072 6784 2122 2069 6785 2126 2073 6786 2127 2074 6787 2122 2069 6788 2128 2075 6789 2123 2070 6790 2050 1996 6791 2128 2075 6792 2126 2073 6793 2123 2070 6794 2129 2076 6795 2128 2075 6796 2050 1996 6797 2130 2077 6798 2129 2076 6799 2050 1996 6800 2077 2023 6801 2130 2077 6802 2050 1996 6803 30 30 6804 43 43 6805 2131 2078 6806 30 30 6807 2131 2078 6808 2132 2079 6809 2133 2080 6810 2132 2079 6811 2134 2081 6812 30 30 6813 2132 2079 6814 2133 2080 6815 2133 2080 6816 2134 2081 6817 2135 2082 6818 2133 2080 6819 2135 2082 6820 2136 2083 6821 2133 2080 6822 2136 2083 6823 2083 2029 6824 2137 2084 6825 2133 2080 6826 2083 2029 6827 2138 2085 6828 2137 2084 6829 2083 2029 6830 2139 2086 6831 2138 2085 6832 2083 2029 6833 2090 2036 6834 2139 2086 6835 2083 2029 6836 2140 2087 6837 2141 2088 6838 2142 2089 6839 2143 2090 6840 2144 2091 6841 2141 2088 6842 2143 2090 6843 2141 2088 6844 2140 2087 6845 2145 2092 6846 2142 2089 6847 2146 2093 6848 2140 2087 6849 2142 2089 6850 2145 2092 6851 2147 2094 6852 2146 2093 6853 2148 2095 6854 2145 2092 6855 2146 2093 6856 2147 2094 6857 2149 2096 6858 2148 2095 6859 2150 2097 6860 2147 2094 6861 2148 2095 6862 2149 2096 6863 2151 2098 6864 2150 2097 6865 2152 2099 6866 2149 2096 6867 2150 2097 6868 2151 2098 6869 2153 2100 6870 2152 2099 6871 2154 2101 6872 2151 2098 6873 2152 2099 6874 2153 2100 6875 2155 2102 6876 2154 2101 6877 2156 2103 6878 2153 2100 6879 2154 2101 6880 2155 2102 6881 2157 2104 6882 2156 2103 6883 2158 2105 6884 2155 2102 6885 2156 2103 6886 2157 2104 6887 2159 2106 6888 2158 2105 6889 2160 2107 6890 2157 2104 6891 2158 2105 6892 2159 2106 6893 2161 2108 6894 2160 2107 6895 2162 2109 6896 2159 2106 6897 2160 2107 6898 2161 2108 6899 2163 2110 6900 2162 2109 6901 2164 2111 6902 2161 2108 6903 2162 2109 6904 2163 2110 6905 2165 2112 6906 2164 2111 6907 2166 2113 6908 2163 2110 6909 2164 2111 6910 2165 2112 6911 2167 2114 6912 2166 2113 6913 2168 2115 6914 2165 2112 6915 2166 2113 6916 2167 2114 6917 2167 2114 6918 2168 2115 6919 2169 2116 6920 2170 2117 6921 2169 2116 6922 2171 2118 6923 2167 2114 6924 2169 2116 6925 2170 2117 6926 2172 2119 6927 2173 2119 6928 2174 2119 6929 2172 2120 6930 2175 2120 6931 2173 2120 6932 2172 2121 6933 2174 2121 6934 2176 2121 6935 2177 2122 6936 2178 2123 6937 2144 2091 6938 2179 2124 6939 2172 2124 6940 2176 2124 6941 2177 2122 6942 2144 2091 6943 2143 2090 6944 2180 2125 6945 2181 2126 6946 2133 2080 6947 30 30 6948 2133 2080 6949 2181 2126 6950 2182 2127 6951 2180 2125 6952 2133 2080 6953 2137 2084 6954 2182 2127 6955 2133 2080 6956 2183 2128 6957 2184 2128 6958 2185 2128 6959 2186 2129 6960 30 30 6961 2181 2126 6962 2187 2130 6963 2186 2129 6964 2181 2126 6965 2183 2131 6966 2188 2131 6967 2184 2131 6968 2189 2132 6969 2190 2133 6970 2191 2134 6971 2192 2135 6972 2183 2135 6973 2185 2135 6974 2193 2136 6975 2191 2134 6976 2194 2137 6977 2193 2136 6978 2189 2132 6979 2191 2134 6980 2195 2138 6981 2194 2137 6982 2196 2139 6983 2195 2138 6984 2193 2136 6985 2194 2137 6986 2197 2140 6987 2196 2139 6988 2198 2141 6989 2197 2140 6990 2195 2138 6991 2196 2139 6992 2199 2142 6993 2198 2141 6994 2200 2143 6995 2199 2142 6996 2197 2140 6997 2198 2141 6998 2199 2142 6999 2200 2143 7000 2201 2144 7001 2202 2145 7002 2199 2142 7003 2201 2144 7004 2203 2146 7005 30 30 7006 2186 2129 7007 2203 2146 7008 33 33 7009 30 30 7010 2187 2130 7011 2204 2147 7012 2186 2129 7013 2205 2148 7014 2186 2129 7015 2204 2147 7016 2206 2149 7017 2203 2146 7018 2186 2129 7019 2207 2150 7020 2206 2149 7021 2186 2129 7022 2208 2151 7023 2207 2150 7024 2186 2129 7025 2205 2148 7026 2208 2151 7027 2186 2129 7028 2209 2152 7029 2210 2153 7030 2204 2147 7031 2211 2154 7032 2212 2155 7033 2213 2156 7034 2187 2130 7035 2209 2152 7036 2204 2147 7037 2214 2157 7038 2215 2158 7039 2212 2155 7040 2216 2159 7041 2214 2157 7042 2212 2155 7043 2211 2154 7044 2216 2159 7045 2212 2155 7046 2217 2160 7047 2218 2161 7048 2210 2153 7049 2219 2162 7050 2213 2156 7051 2220 2163 7052 2209 2152 7053 2217 2160 7054 2210 2153 7055 2211 2154 7056 2213 2156 7057 2219 2162 7058 2217 2160 7059 2221 2164 7060 2218 2161 7061 2219 2162 7062 2220 2163 7063 2222 2165 7064 2223 2166 7065 2224 2167 7066 2221 2164 7067 2225 2168 7068 2222 2165 7069 2226 2169 7070 2217 2160 7071 2223 2166 7072 2221 2164 7073 2219 2162 7074 2222 2165 7075 2225 2168 7076 2223 2166 7077 2227 2170 7078 2224 2167 7079 2225 2168 7080 2226 2169 7081 2228 2171 7082 2229 2172 7083 2230 2173 7084 2227 2170 7085 2231 2174 7086 2228 2171 7087 2232 2175 7088 2223 2166 7089 2229 2172 7090 2227 2170 7091 2225 2168 7092 2228 2171 7093 2231 2174 7094 2233 2176 7095 2234 2177 7096 2230 2173 7097 2235 2178 7098 2232 2175 7099 2236 2179 7100 2229 2172 7101 2233 2176 7102 2230 2173 7103 2231 2174 7104 2232 2175 7105 2235 2178 7106 2233 2176 7107 2237 2180 7108 2234 2177 7109 2238 2181 7110 2236 2179 7111 2239 2182 7112 2235 2178 7113 2236 2179 7114 2238 2181 7115 2240 2183 7116 2241 2184 7117 2237 2180 7118 2242 2185 7119 2239 2182 7120 2243 2186 7121 2233 2176 7122 2240 2183 7123 2237 2180 7124 2238 2181 7125 2239 2182 7126 2242 2185 7127 2240 2183 7128 2244 2187 7129 2241 2184 7130 2242 2185 7131 2243 2186 7132 2245 2188 7133 2246 2189 7134 2247 2190 7135 2244 2187 7136 2248 2191 7137 2245 2188 7138 2249 2192 7139 2240 2183 7140 2246 2189 7141 2244 2187 7142 2242 2185 7143 2245 2188 7144 2248 2191 7145 2246 2189 7146 2250 2193 7147 2247 2190 7148 2251 2194 7149 2249 2192 7150 2252 2195 7151 2248 2191 7152 2249 2192 7153 2251 2194 7154 2253 2196 7155 2254 2197 7156 2250 2193 7157 2255 2198 7158 2250 2193 7159 2254 2197 7160 2246 2189 7161 2253 2196 7162 2250 2193 7163 2251 2194 7164 2252 2195 7165 2256 2199 7166 2257 2200 7167 1237 1228 7168 2254 2197 7169 2258 2201 7170 2254 2197 7171 1237 1228 7172 2253 2196 7173 2257 2200 7174 2254 2197 7175 2259 2202 7176 2255 2198 7177 2254 2197 7178 2258 2201 7179 2259 2202 7180 2254 2197 7181 2257 2200 7182 1228 1219 7183 1237 1228 7184 2260 2203 7185 2258 2201 7186 1237 1228 7187 2261 2204 7188 2260 2203 7189 1237 1228 7190 1114 1105 7191 2261 2204 7192 1237 1228 7193 2262 2205 7194 1228 1219 7195 2257 2200 7196 2263 2206 7197 1390 1380 7198 1228 1219 7199 2264 2207 7200 2263 2206 7201 1228 1219 7202 2265 2208 7203 2264 2207 7204 1228 1219 7205 2262 2205 7206 2265 2208 7207 1228 1219 7208 2266 2209 7209 2267 2209 7210 2268 2209 7211 2266 2210 7212 2269 2210 7213 2267 2210 7214 2266 2211 7215 2268 2211 7216 2270 2211 7217 2271 2212 7218 2272 2213 7219 2273 2214 7220 2266 2215 7221 2270 2215 7222 2274 2215 7223 2275 2216 7224 2273 2214 7225 2276 2217 7226 2277 2218 7227 2273 2214 7228 2275 2216 7229 2271 2212 7230 2273 2214 7231 2277 2218 7232 2275 2216 7233 2276 2217 7234 2278 2219 7235 2279 2219 7236 2278 2219 7237 2280 2220 7238 2275 2216 7239 2278 2219 7240 2279 2219 7241 2281 2221 7242 2280 2220 7243 2282 2222 7244 2279 2219 7245 2280 2220 7246 2281 2221 7247 2283 2223 7248 2282 2222 7249 2284 2224 7250 2281 2221 7251 2282 2222 7252 2283 2223 7253 2183 2225 7254 2285 2225 7255 2188 2225 7256 2283 2223 7257 2284 2224 7258 2286 2226 7259 2287 2227 7260 36 36 7261 2288 2228 7262 2287 2227 7263 34 34 7264 36 36 7265 2287 2227 7266 2288 2228 7267 2289 2229 7268 2290 2230 7269 2289 2229 7270 2291 2231 7271 2290 2230 7272 2287 2227 7273 2289 2229 7274 2292 2232 7275 2291 2231 7276 2293 2233 7277 2292 2232 7278 2290 2230 7279 2291 2231 7280 2292 2232 7281 2293 2233 7282 2294 2234 7283 2295 2235 7284 2292 2232 7285 2294 2234 7286 2296 2236 7287 2297 2237 7288 2298 2238 7289 2251 2194 7290 2256 2199 7291 2299 2239 7292 2300 2240 7293 2298 2238 7294 2301 2241 7295 2296 2236 7296 2298 2238 7297 2300 2240 7298 2302 2242 7299 2301 2241 7300 2303 2243 7301 2300 2240 7302 2301 2241 7303 2302 2242 7304 2302 2242 7305 2303 2243 7306 2304 2244 7307 2305 2245 7308 2304 2244 7309 1115 1106 7310 2302 2242 7311 2304 2244 7312 2305 2245 7313 2305 2245 7314 1115 1106 7315 1103 1094 7316 2306 2246 7317 2307 2246 7318 2308 2246 7319 2306 2247 7320 2309 2247 7321 2307 2247 7322 2310 2248 7323 2311 2249 7324 2312 2250 7325 2306 2251 7326 2308 2251 7327 2313 2251 7328 2314 2252 7329 2312 2250 7330 2315 2253 7331 2310 2248 7332 2312 2250 7333 2314 2252 7334 2316 2254 7335 2315 2253 7336 2317 2255 7337 2314 2252 7338 2315 2253 7339 2316 2254 7340 2318 2256 7341 2317 2255 7342 2319 2257 7343 2316 2254 7344 2317 2255 7345 2318 2256 7346 2320 2258 7347 2319 2257 7348 2321 2259 7349 2318 2256 7350 2319 2257 7351 2320 2258 7352 2320 2258 7353 2321 2259 7354 2322 2260 7355 2320 2258 7356 2322 2260 7357 2323 2261 7358 2170 2117 7359 2171 2118 7360 2324 2262 7361 2306 2263 7362 2325 2263 7363 2309 2263 7364 2170 2117 7365 2324 2262 7366 2326 2264 7367 34 34 7368 2327 2265 7369 37 37 7370 2328 2266 7371 27 27 7372 2329 2267 7373 2328 2266 7374 23 23 7375 27 27 7376 2330 2268 7377 2327 2265 7378 34 34 7379 2330 2268 7380 2331 2269 7381 2327 2265 7382 2332 2270 7383 2329 2267 7384 2333 2271 7385 2332 2270 7386 2328 2266 7387 2329 2267 7388 2334 2272 7389 34 34 7390 2287 2227 7391 2334 2272 7392 2330 2268 7393 34 34 7394 2335 2273 7395 2287 2227 7396 2290 2230 7397 2335 2273 7398 2334 2272 7399 2287 2227 7400 2336 2274 7401 2290 2230 7402 2292 2232 7403 2336 2274 7404 2335 2273 7405 2290 2230 7406 2336 2274 7407 2292 2232 7408 2295 2235 7409 2337 2275 7410 2336 2274 7411 2295 2235 7412 2330 2268 7413 2338 2276 7414 2331 2269 7415 2339 2277 7416 2333 2271 7417 2340 2278 7418 2339 2277 7419 2332 2270 7420 2333 2271 7421 2330 2268 7422 2341 2279 7423 2338 2276 7424 2339 2277 7425 2340 2278 7426 2342 2280 7427 2343 2281 7428 2341 2279 7429 2330 2268 7430 2343 2281 7431 2344 2282 7432 2341 2279 7433 2345 2283 7434 2342 2280 7435 2346 2284 7436 2345 2283 7437 2339 2277 7438 2342 2280 7439 2347 2285 7440 2330 2268 7441 2334 2272 7442 2347 2285 7443 2343 2281 7444 2330 2268 7445 2348 2286 7446 2334 2272 7447 2335 2273 7448 2348 2286 7449 2347 2285 7450 2334 2272 7451 2349 2287 7452 2335 2273 7453 2336 2274 7454 2349 2287 7455 2348 2286 7456 2335 2273 7457 2350 2288 7458 2336 2274 7459 2337 2275 7460 2350 2288 7461 2349 2287 7462 2336 2274 7463 2351 2289 7464 2350 2288 7465 2337 2275 7466 2211 2154 7467 2352 2290 7468 2216 2159 7469 2343 2281 7470 2353 2291 7471 2344 2282 7472 2354 2292 7473 2346 2284 7474 2355 2293 7475 2354 2292 7476 2345 2283 7477 2346 2284 7478 2343 2281 7479 2356 2294 7480 2353 2291 7481 2357 2295 7482 2355 2293 7483 2358 2296 7484 2357 2295 7485 2354 2292 7486 2355 2293 7487 2343 2281 7488 2359 2297 7489 2356 2294 7490 2357 2295 7491 2358 2296 7492 2360 2298 7493 2343 2281 7494 2361 2299 7495 2359 2297 7496 2362 2300 7497 2360 2298 7498 2363 2301 7499 2362 2300 7500 2357 2295 7501 2360 2298 7502 2364 2302 7503 2361 2299 7504 2343 2281 7505 2365 2303 7506 2366 2304 7507 2361 2299 7508 2367 2305 7509 2363 2301 7510 2368 2306 7511 2369 2307 7512 2365 2303 7513 2361 2299 7514 2364 2302 7515 2369 2307 7516 2361 2299 7517 2367 2305 7518 2362 2300 7519 2363 2301 7520 2370 2308 7521 2343 2281 7522 2347 2285 7523 2371 2309 7524 2364 2302 7525 2343 2281 7526 2370 2308 7527 2371 2309 7528 2343 2281 7529 2372 2310 7530 2347 2285 7531 2348 2286 7532 2373 2311 7533 2370 2308 7534 2347 2285 7535 2374 2312 7536 2373 2311 7537 2347 2285 7538 2372 2310 7539 2374 2312 7540 2347 2285 7541 2375 2313 7542 2348 2286 7543 2349 2287 7544 2376 2314 7545 2372 2310 7546 2348 2286 7547 2375 2313 7548 2376 2314 7549 2348 2286 7550 2377 2315 7551 2349 2287 7552 2350 2288 7553 2378 2316 7554 2375 2313 7555 2349 2287 7556 2377 2315 7557 2378 2316 7558 2349 2287 7559 2379 2317 7560 2350 2288 7561 2351 2289 7562 2379 2317 7563 2377 2315 7564 2350 2288 7565 2380 2318 7566 2379 2317 7567 2351 2289 7568 2381 2319 7569 2380 2318 7570 2351 2289 7571 2211 2154 7572 2382 2320 7573 2352 2290 7574 2383 2321 7575 2384 2322 7576 2366 2304 7577 2367 2305 7578 2368 2306 7579 2385 2323 7580 2365 2303 7581 2383 2321 7582 2366 2304 7583 2383 2321 7584 2386 2324 7585 2384 2322 7586 2387 2325 7587 2385 2323 7588 2388 2326 7589 2387 2325 7590 2367 2305 7591 2385 2323 7592 2383 2321 7593 2389 2327 7594 2386 2324 7595 2390 2328 7596 2388 2326 7597 2391 2329 7598 2390 2328 7599 2387 2325 7600 2388 2326 7601 2392 2330 7602 2393 2331 7603 2389 2327 7604 2394 2332 7605 2391 2329 7606 2395 2333 7607 2383 2321 7608 2392 2330 7609 2389 2327 7610 2394 2332 7611 2390 2328 7612 2391 2329 7613 2394 2332 7614 2395 2333 7615 2396 2334 7616 197 197 7617 2397 2335 7618 2398 2336 7619 2399 2337 7620 2394 2332 7621 2396 2334 7622 197 197 7623 202 202 7624 2397 2335 7625 197 197 7626 2398 2336 7627 2400 2338 7628 2401 2339 7629 2400 2338 7630 2402 2340 7631 197 197 7632 2400 2338 7633 2401 2339 7634 2401 2339 7635 2402 2340 7636 2403 2341 7637 2401 2339 7638 2403 2341 7639 2404 2342 7640 2405 2343 7641 2404 2342 7642 2406 2344 7643 2401 2339 7644 2404 2342 7645 2405 2343 7646 2405 2343 7647 2406 2344 7648 2407 2345 7649 2405 2343 7650 2407 2345 7651 2408 2346 7652 2409 2347 7653 2408 2346 7654 2410 2348 7655 2405 2343 7656 2408 2346 7657 2409 2347 7658 2409 2347 7659 2410 2348 7660 2411 2349 7661 2412 2350 7662 2411 2349 7663 2413 2351 7664 2409 2347 7665 2411 2349 7666 2412 2350 7667 2412 2350 7668 2413 2351 7669 2414 2352 7670 2415 2353 7671 2414 2352 7672 2416 2354 7673 2412 2350 7674 2414 2352 7675 2415 2353 7676 2415 2353 7677 2416 2354 7678 2417 2355 7679 2415 2353 7680 2417 2355 7681 2418 2356 7682 2419 2357 7683 2418 2356 7684 2420 2358 7685 2419 2357 7686 2415 2353 7687 2418 2356 7688 2421 2359 7689 2422 2360 7690 2423 2361 7691 2424 2362 7692 2382 2320 7693 2211 2154 7694 2421 2359 7695 2423 2361 7696 2425 2363 7697 19 19 7698 23 23 7699 2328 2266 7700 2426 2364 7701 2328 2266 7702 2332 2270 7703 2426 2364 7704 19 19 7705 2328 2266 7706 2427 2365 7707 2332 2270 7708 2339 2277 7709 2427 2365 7710 2426 2364 7711 2332 2270 7712 2428 2366 7713 2339 2277 7714 2345 2283 7715 2428 2366 7716 2427 2365 7717 2339 2277 7718 2429 2367 7719 2345 2283 7720 2354 2292 7721 2429 2367 7722 2428 2366 7723 2345 2283 7724 2430 2368 7725 2354 2292 7726 2357 2295 7727 2430 2368 7728 2429 2367 7729 2354 2292 7730 2431 2369 7731 2357 2295 7732 2362 2300 7733 2431 2369 7734 2430 2368 7735 2357 2295 7736 2432 2370 7737 2362 2300 7738 2367 2305 7739 2432 2370 7740 2431 2369 7741 2362 2300 7742 2433 2371 7743 2367 2305 7744 2387 2325 7745 2433 2371 7746 2432 2370 7747 2367 2305 7748 2434 2372 7749 2387 2325 7750 2390 2328 7751 2434 2372 7752 2433 2371 7753 2387 2325 7754 2435 2373 7755 2390 2328 7756 2394 2332 7757 2435 2373 7758 2434 2372 7759 2390 2328 7760 2436 2374 7761 2394 2332 7762 2399 2337 7763 2436 2374 7764 2435 2373 7765 2394 2332 7766 2436 2374 7767 2399 2337 7768 2437 2375 7769 2438 2376 7770 2436 2374 7771 2437 2375 7772 2438 2376 7773 2437 2375 7774 2439 2377 7775 15 15 7776 19 19 7777 2426 2364 7778 2440 2378 7779 2426 2364 7780 2427 2365 7781 2440 2378 7782 15 15 7783 2426 2364 7784 2441 2379 7785 2427 2365 7786 2428 2366 7787 2441 2379 7788 2440 2378 7789 2427 2365 7790 2442 2380 7791 2428 2366 7792 2429 2367 7793 2442 2380 7794 2441 2379 7795 2428 2366 7796 2443 2381 7797 2429 2367 7798 2430 2368 7799 2443 2381 7800 2442 2380 7801 2429 2367 7802 2444 2382 7803 2430 2368 7804 2431 2369 7805 2444 2382 7806 2443 2381 7807 2430 2368 7808 2445 2383 7809 2431 2369 7810 2432 2370 7811 2445 2383 7812 2444 2382 7813 2431 2369 7814 2446 2384 7815 2432 2370 7816 2433 2371 7817 2446 2384 7818 2445 2383 7819 2432 2370 7820 2447 2385 7821 2433 2371 7822 2434 2372 7823 2447 2385 7824 2446 2384 7825 2433 2371 7826 2448 2386 7827 2434 2372 7828 2435 2373 7829 2448 2386 7830 2447 2385 7831 2434 2372 7832 2449 2387 7833 2435 2373 7834 2436 2374 7835 2449 2387 7836 2448 2386 7837 2435 2373 7838 2438 2376 7839 2449 2387 7840 2436 2374 7841 2450 2388 7842 2438 2376 7843 2439 2377 7844 3 3 7845 15 15 7846 2440 2378 7847 149 149 7848 2440 2378 7849 2441 2379 7850 149 149 7851 3 3 7852 2440 2378 7853 146 146 7854 2441 2379 7855 2442 2380 7856 146 146 7857 149 149 7858 2441 2379 7859 143 143 7860 2442 2380 7861 2443 2381 7862 143 143 7863 146 146 7864 2442 2380 7865 140 140 7866 2443 2381 7867 2444 2382 7868 140 140 7869 143 143 7870 2443 2381 7871 127 127 7872 2444 2382 7873 2445 2383 7874 127 127 7875 140 140 7876 2444 2382 7877 124 124 7878 2445 2383 7879 2446 2384 7880 124 124 7881 127 127 7882 2445 2383 7883 119 119 7884 2446 2384 7885 2447 2385 7886 119 119 7887 124 124 7888 2446 2384 7889 116 116 7890 2447 2385 7891 2448 2386 7892 116 116 7893 119 119 7894 2447 2385 7895 89 89 7896 2448 2386 7897 2449 2387 7898 89 89 7899 116 116 7900 2448 2386 7901 86 86 7902 2449 2387 7903 2438 2376 7904 86 86 7905 89 89 7906 2449 2387 7907 81 81 7908 2438 2376 7909 2450 2388 7910 81 81 7911 86 86 7912 2438 2376 7913 81 81 7914 2450 2388 7915 77 77 7916 2451 2389 7917 2452 2390 7918 2415 2353 7919 2412 2350 7920 2415 2353 7921 2452 2390 7922 2419 2357 7923 2451 2389 7924 2415 2353 7925 2453 2391 7926 2454 2392 7927 2452 2390 7928 2455 2393 7929 2452 2390 7930 2454 2392 7931 2456 2394 7932 2453 2391 7933 2452 2390 7934 2451 2389 7935 2456 2394 7936 2452 2390 7937 2455 2393 7938 2412 2350 7939 2452 2390 7940 2457 2395 7941 2458 2396 7942 2454 2392 7943 2459 2397 7944 2454 2392 7945 2458 2396 7946 2453 2391 7947 2457 2395 7948 2454 2392 7949 2459 2397 7950 2455 2393 7951 2454 2392 7952 2460 2398 7953 2461 2399 7954 2458 2396 7955 2462 2400 7956 2458 2396 7957 2461 2399 7958 2463 2401 7959 2460 2398 7960 2458 2396 7961 2457 2395 7962 2463 2401 7963 2458 2396 7964 2462 2400 7965 2459 2397 7966 2458 2396 7967 2464 2402 7968 2465 2403 7969 2461 2399 7970 2466 2404 7971 2461 2399 7972 2465 2403 7973 2460 2398 7974 2464 2402 7975 2461 2399 7976 2466 2404 7977 2462 2400 7978 2461 2399 7979 2467 2405 7980 2468 2406 7981 2465 2403 7982 2469 2407 7983 2465 2403 7984 2468 2406 7985 2470 2408 7986 2467 2405 7987 2465 2403 7988 2471 2409 7989 2470 2408 7990 2465 2403 7991 2464 2402 7992 2471 2409 7993 2465 2403 7994 2469 2407 7995 2466 2404 7996 2465 2403 7997 2472 2410 7998 2473 2411 7999 2474 2412 8000 2475 2413 8001 2469 2407 8002 2468 2406 8003 2472 2410 8004 2476 2414 8005 2473 2411 8006 2472 2410 8007 2474 2412 8008 2477 2415 8009 2478 2416 8010 2477 2415 8011 2479 2417 8012 2472 2410 8013 2477 2415 8014 2478 2416 8015 2480 2418 8016 2481 2419 8017 2482 2420 8018 2483 2421 8019 2484 2422 8020 2485 2423 8021 2486 2424 8022 2482 2420 8023 2487 2425 8024 2486 2424 8025 2480 2418 8026 2482 2420 8027 2488 2426 8028 2487 2425 8029 2489 2427 8030 2488 2426 8031 2486 2424 8032 2487 2425 8033 2490 2428 8034 2489 2427 8035 2491 2429 8036 2490 2428 8037 2488 2426 8038 2489 2427 8039 2490 2428 8040 2491 2429 8041 2492 2430 8042 2493 2431 8043 2492 2430 8044 2494 2432 8045 2493 2431 8046 2490 2428 8047 2492 2430 8048 2495 2433 8049 2494 2432 8050 2496 2434 8051 2495 2433 8052 2493 2431 8053 2494 2432 8054 2495 2433 8055 2496 2434 8056 2422 2360 8057 2421 2359 8058 2495 2433 8059 2422 2360 8060 2409 2347 8061 2412 2350 8062 2455 2393 8063 2497 2435 8064 2455 2393 8065 2459 2397 8066 2497 2435 8067 2409 2347 8068 2455 2393 8069 2498 2436 8070 2459 2397 8071 2462 2400 8072 2498 2436 8073 2497 2435 8074 2459 2397 8075 2499 2437 8076 2462 2400 8077 2466 2404 8078 2499 2437 8079 2498 2436 8080 2462 2400 8081 2500 2438 8082 2466 2404 8083 2469 2407 8084 2500 2438 8085 2499 2437 8086 2466 2404 8087 2475 2413 8088 2501 2439 8089 2469 2407 8090 2502 2440 8091 2469 2407 8092 2501 2439 8093 2502 2440 8094 2500 2438 8095 2469 2407 8096 2503 2441 8097 2504 2442 8098 2476 2414 8099 2505 2443 8100 2502 2440 8101 2501 2439 8102 2503 2441 8103 2506 2444 8104 2504 2442 8105 2503 2441 8106 2476 2414 8107 2472 2410 8108 2405 2343 8109 2409 2347 8110 2497 2435 8111 2507 2445 8112 2497 2435 8113 2498 2436 8114 2507 2445 8115 2405 2343 8116 2497 2435 8117 2508 2446 8118 2498 2436 8119 2499 2437 8120 2508 2446 8121 2507 2445 8122 2498 2436 8123 2509 2447 8124 2499 2437 8125 2500 2438 8126 2509 2447 8127 2508 2446 8128 2499 2437 8129 2510 2448 8130 2500 2438 8131 2502 2440 8132 2510 2448 8133 2509 2447 8134 2500 2438 8135 2505 2443 8136 2511 2449 8137 2502 2440 8138 2512 2450 8139 2502 2440 8140 2511 2449 8141 2512 2450 8142 2510 2448 8143 2502 2440 8144 2513 2451 8145 2514 2452 8146 2506 2444 8147 2515 2453 8148 2512 2450 8149 2511 2449 8150 2513 2451 8151 2516 2454 8152 2514 2452 8153 2513 2451 8154 2506 2444 8155 2503 2441 8156 2401 2339 8157 2405 2343 8158 2507 2445 8159 2517 2455 8160 2507 2445 8161 2508 2446 8162 2517 2455 8163 2401 2339 8164 2507 2445 8165 2518 2456 8166 2508 2446 8167 2509 2447 8168 2518 2456 8169 2517 2455 8170 2508 2446 8171 2519 2457 8172 2509 2447 8173 2510 2448 8174 2519 2457 8175 2518 2456 8176 2509 2447 8177 2520 2458 8178 2510 2448 8179 2512 2450 8180 2520 2458 8181 2519 2457 8182 2510 2448 8183 2521 2459 8184 2522 2460 8185 2512 2450 8186 2523 2461 8187 2512 2450 8188 2522 2460 8189 2515 2453 8190 2521 2459 8191 2512 2450 8192 2523 2461 8193 2520 2458 8194 2512 2450 8195 2524 2462 8196 2525 2463 8197 2526 2464 8198 2527 2465 8199 2523 2461 8200 2522 2460 8201 2528 2466 8202 2527 2465 8203 2522 2460 8204 2524 2462 8205 2529 2467 8206 2525 2463 8207 2513 2451 8208 2526 2464 8209 2516 2454 8210 2524 2462 8211 2526 2464 8212 2513 2451 8213 197 197 8214 2401 2339 8215 2517 2455 8216 187 187 8217 2517 2455 8218 2518 2456 8219 187 187 8220 197 197 8221 2517 2455 8222 194 194 8223 2518 2456 8224 2519 2457 8225 194 194 8226 187 187 8227 2518 2456 8228 227 227 8229 2519 2457 8230 2520 2458 8231 227 227 8232 194 194 8233 2519 2457 8234 223 223 8235 2520 2458 8236 2523 2461 8237 223 223 8238 227 227 8239 2520 2458 8240 212 212 8241 2523 2461 8242 2527 2465 8243 212 212 8244 223 223 8245 2523 2461 8246 2530 2468 8247 2531 2469 8248 2532 2470 8249 2533 2471 8250 212 212 8251 2527 2465 8252 2534 2472 8253 2535 2473 8254 2531 2469 8255 2536 2474 8256 2534 2472 8257 2531 2469 8258 2530 2468 8259 2536 2474 8260 2531 2469 8261 2537 2475 8262 2538 2476 8263 2539 2477 8264 2540 2478 8265 2529 2467 8266 2524 2462 8267 243 241 8268 219 219 8269 2535 2473 8270 2534 2472 8271 243 241 8272 2535 2473 8273 2541 2479 8274 243 241 8275 2534 2472 8276 2542 2480 8277 253 251 8278 243 241 8279 2541 2479 8280 2542 2480 8281 243 241 8282 2543 2481 8283 2544 2482 8284 2545 2483 8285 2543 2481 8286 2546 2484 8287 2544 2482 8288 2537 2475 8289 2545 2483 8290 2538 2476 8291 2543 2481 8292 2545 2483 8293 2537 2475 8294 251 249 8295 254 252 8296 2547 2485 8297 2543 2481 8298 2548 2486 8299 2546 2484 8300 2549 2487 8301 274 272 8302 2550 2488 8303 2551 2489 8304 2549 2487 8305 2550 2488 8306 2543 2481 8307 2552 2490 8308 2548 2486 8309 2549 2487 8310 271 269 8311 274 272 8312 2553 2491 8313 271 269 8314 2549 2487 8315 2553 2491 8316 314 312 8317 271 269 8318 2553 2491 8319 2549 2487 8320 2551 2489 8321 2554 2492 8322 2553 2491 8323 2551 2489 8324 2555 2493 8325 2556 2494 8326 2552 2490 8327 2555 2493 8328 2552 2490 8329 2543 2481 8330 2557 2495 8331 308 306 8332 314 312 8333 2557 2495 8334 310 308 8335 308 306 8336 2558 2496 8337 314 312 8338 2553 2491 8339 2558 2496 8340 2557 2495 8341 314 312 8342 2554 2492 8343 2559 2497 8344 2553 2491 8345 2558 2496 8346 2553 2491 8347 2559 2497 8348 2555 2493 8349 2560 2498 8350 2556 2494 8351 2561 2499 8352 2558 2496 8353 2559 2497 8354 2562 2500 8355 2563 2501 8356 2560 2498 8357 2562 2500 8358 2560 2498 8359 2555 2493 8360 2564 2502 8361 298 296 8362 310 308 8363 2565 2503 8364 300 298 8365 298 296 8366 2564 2502 8367 2565 2503 8368 298 296 8369 2566 2504 8370 310 308 8371 2557 2495 8372 2566 2504 8373 2564 2502 8374 310 308 8375 2567 2505 8376 2557 2495 8377 2558 2496 8378 2567 2505 8379 2566 2504 8380 2557 2495 8381 2561 2499 8382 2568 2506 8383 2558 2496 8384 2569 2507 8385 2558 2496 8386 2568 2506 8387 2569 2507 8388 2567 2505 8389 2558 2496 8390 2570 2508 8391 2571 2509 8392 2563 2501 8393 2572 2510 8394 2569 2507 8395 2568 2506 8396 2573 2511 8397 2574 2512 8398 2571 2509 8399 2573 2511 8400 2571 2509 8401 2575 2513 8402 2570 2508 8403 2575 2513 8404 2571 2509 8405 2570 2508 8406 2563 2501 8407 2562 2500 8408 293 291 8409 296 294 8410 2576 2514 8411 2577 2515 8412 2578 2516 8413 2579 2517 8414 2580 2518 8415 2581 2519 8416 2582 2520 8417 2580 2518 8418 2582 2520 8419 2583 2521 8420 2577 2515 8421 2579 2517 8422 2584 2522 8423 2577 2515 8424 2584 2522 8425 2585 2523 8426 2586 2524 8427 2585 2523 8428 2587 2525 8429 2577 2515 8430 2585 2523 8431 2586 2524 8432 2586 2524 8433 2587 2525 8434 2588 2526 8435 2589 2527 8436 2588 2526 8437 2590 2528 8438 2586 2524 8439 2588 2526 8440 2589 2527 8441 2589 2527 8442 2590 2528 8443 2591 2529 8444 2589 2527 8445 2591 2529 8446 2592 2530 8447 2593 2531 8448 2592 2530 8449 2591 2529 8450 2594 2532 8451 356 2532 8452 2595 2532 8453 2594 2533 8454 355 2533 8455 356 2533 8456 2580 2518 8457 2596 2534 8458 2581 2519 8459 2597 2535 8460 2598 2536 8461 2599 2537 8462 2600 2538 8463 2597 2535 8464 2599 2537 8465 2580 2518 8466 2601 2539 8467 2596 2534 8468 367 364 8469 368 365 8470 2602 2540 8471 2603 2541 8472 2604 2542 8473 2605 2543 8474 2597 2535 8475 2606 2544 8476 2598 2536 8477 2607 2545 8478 679 674 8479 2608 2546 8480 2607 2545 8481 677 672 8482 679 674 8483 2607 2545 8484 2608 2546 8485 2609 2547 8486 2610 2548 8487 2609 2547 8488 2611 2549 8489 2610 2548 8490 2607 2545 8491 2609 2547 8492 2610 2548 8493 2611 2549 8494 2612 2550 8495 2613 2551 8496 2612 2550 8497 2614 2552 8498 2613 2551 8499 2610 2548 8500 2612 2550 8501 2613 2551 8502 2614 2552 8503 2604 2542 8504 2603 2541 8505 2613 2551 8506 2604 2542 8507 903 894 8508 597 591 8509 601 596 8510 2615 2553 8511 601 596 8512 609 604 8513 2615 2553 8514 903 894 8515 601 596 8516 2616 2554 8517 609 604 8518 606 601 8519 2616 2554 8520 2615 2553 8521 609 604 8522 2617 2555 8523 606 601 8524 615 610 8525 2617 2555 8526 2616 2554 8527 606 601 8528 2618 2556 8529 615 610 8530 621 616 8531 2618 2556 8532 2617 2555 8533 615 610 8534 2619 2557 8535 621 616 8536 627 622 8537 2619 2557 8538 2618 2556 8539 621 616 8540 2620 2558 8541 627 622 8542 633 628 8543 2620 2558 8544 2619 2557 8545 627 622 8546 2621 2559 8547 633 628 8548 637 632 8549 2621 2559 8550 2620 2558 8551 633 628 8552 2622 2560 8553 637 632 8554 643 638 8555 2622 2560 8556 2621 2559 8557 637 632 8558 2623 2561 8559 643 638 8560 650 645 8561 2623 2561 8562 2622 2560 8563 643 638 8564 2624 2562 8565 650 645 8566 657 652 8567 2624 2562 8568 2623 2561 8569 650 645 8570 2625 2563 8571 657 652 8572 664 659 8573 2625 2563 8574 2624 2562 8575 657 652 8576 2626 2564 8577 664 659 8578 671 666 8579 2626 2564 8580 2625 2563 8581 664 659 8582 2627 2565 8583 671 666 8584 674 669 8585 2627 2565 8586 2626 2564 8587 671 666 8588 2628 2566 8589 674 669 8590 677 672 8591 2628 2566 8592 2627 2565 8593 674 669 8594 2607 2545 8595 2628 2566 8596 677 672 8597 900 891 8598 903 894 8599 2615 2553 8600 2629 2567 8601 2615 2553 8602 2616 2554 8603 2629 2567 8604 900 891 8605 2615 2553 8606 2630 2568 8607 2616 2554 8608 2617 2555 8609 2630 2568 8610 2629 2567 8611 2616 2554 8612 2631 2569 8613 2617 2555 8614 2618 2556 8615 2631 2569 8616 2630 2568 8617 2617 2555 8618 2632 2570 8619 2618 2556 8620 2619 2557 8621 2632 2570 8622 2631 2569 8623 2618 2556 8624 2633 2571 8625 2619 2557 8626 2620 2558 8627 2633 2571 8628 2632 2570 8629 2619 2557 8630 2634 2572 8631 2620 2558 8632 2621 2559 8633 2634 2572 8634 2633 2571 8635 2620 2558 8636 2635 2573 8637 2621 2559 8638 2622 2560 8639 2635 2573 8640 2634 2572 8641 2621 2559 8642 2636 2574 8643 2622 2560 8644 2623 2561 8645 2636 2574 8646 2635 2573 8647 2622 2560 8648 2637 2575 8649 2623 2561 8650 2624 2562 8651 2637 2575 8652 2636 2574 8653 2623 2561 8654 2638 2576 8655 2624 2562 8656 2625 2563 8657 2638 2576 8658 2637 2575 8659 2624 2562 8660 2639 2577 8661 2625 2563 8662 2626 2564 8663 2639 2577 8664 2638 2576 8665 2625 2563 8666 2640 2578 8667 2626 2564 8668 2627 2565 8669 2640 2578 8670 2639 2577 8671 2626 2564 8672 2641 2579 8673 2627 2565 8674 2628 2566 8675 2641 2579 8676 2640 2578 8677 2627 2565 8678 2642 2580 8679 2628 2566 8680 2607 2545 8681 2642 2580 8682 2641 2579 8683 2628 2566 8684 2610 2548 8685 2642 2580 8686 2607 2545 8687 892 883 8688 900 891 8689 2629 2567 8690 2643 2581 8691 2629 2567 8692 2630 2568 8693 2643 2581 8694 892 883 8695 2629 2567 8696 2644 2582 8697 2630 2568 8698 2631 2569 8699 2644 2582 8700 2643 2581 8701 2630 2568 8702 2645 2583 8703 2631 2569 8704 2632 2570 8705 2645 2583 8706 2644 2582 8707 2631 2569 8708 2646 2584 8709 2632 2570 8710 2633 2571 8711 2646 2584 8712 2645 2583 8713 2632 2570 8714 2647 2585 8715 2633 2571 8716 2634 2572 8717 2647 2585 8718 2646 2584 8719 2633 2571 8720 2648 2586 8721 2634 2572 8722 2635 2573 8723 2648 2586 8724 2647 2585 8725 2634 2572 8726 2649 2587 8727 2635 2573 8728 2636 2574 8729 2649 2587 8730 2648 2586 8731 2635 2573 8732 2650 2588 8733 2636 2574 8734 2637 2575 8735 2650 2588 8736 2649 2587 8737 2636 2574 8738 2651 2589 8739 2637 2575 8740 2638 2576 8741 2651 2589 8742 2650 2588 8743 2637 2575 8744 2652 2590 8745 2638 2576 8746 2639 2577 8747 2652 2590 8748 2651 2589 8749 2638 2576 8750 2653 2591 8751 2639 2577 8752 2640 2578 8753 2653 2591 8754 2652 2590 8755 2639 2577 8756 2654 2592 8757 2640 2578 8758 2641 2579 8759 2654 2592 8760 2653 2591 8761 2640 2578 8762 2655 2593 8763 2641 2579 8764 2642 2580 8765 2655 2593 8766 2654 2592 8767 2641 2579 8768 2656 2594 8769 2642 2580 8770 2610 2548 8771 2656 2594 8772 2655 2593 8773 2642 2580 8774 2613 2551 8775 2656 2594 8776 2610 2548 8777 899 890 8778 892 883 8779 2643 2581 8780 2657 2595 8781 2643 2581 8782 2644 2582 8783 2657 2595 8784 899 890 8785 2643 2581 8786 2658 2596 8787 2644 2582 8788 2645 2583 8789 2658 2596 8790 2657 2595 8791 2644 2582 8792 2659 2597 8793 2645 2583 8794 2646 2584 8795 2659 2597 8796 2658 2596 8797 2645 2583 8798 2660 2598 8799 2646 2584 8800 2647 2585 8801 2661 2599 8802 2659 2597 8803 2646 2584 8804 2660 2598 8805 2661 2599 8806 2646 2584 8807 2662 2600 8808 2647 2585 8809 2648 2586 8810 2663 2601 8811 2660 2598 8812 2647 2585 8813 2662 2600 8814 2663 2601 8815 2647 2585 8816 2664 2602 8817 2648 2586 8818 2649 2587 8819 2665 2603 8820 2662 2600 8821 2648 2586 8822 2664 2602 8823 2665 2603 8824 2648 2586 8825 2666 2604 8826 2649 2587 8827 2650 2588 8828 2667 2605 8829 2664 2602 8830 2649 2587 8831 2666 2604 8832 2667 2605 8833 2649 2587 8834 2668 2606 8835 2650 2588 8836 2651 2589 8837 2668 2606 8838 2666 2604 8839 2650 2588 8840 2669 2607 8841 2651 2589 8842 2652 2590 8843 2670 2608 8844 2668 2606 8845 2651 2589 8846 2669 2607 8847 2670 2608 8848 2651 2589 8849 2671 2609 8850 2652 2590 8851 2653 2591 8852 2672 2610 8853 2669 2607 8854 2652 2590 8855 2671 2609 8856 2672 2610 8857 2652 2590 8858 2673 2611 8859 2653 2591 8860 2654 2592 8861 2674 2612 8862 2671 2609 8863 2653 2591 8864 2673 2611 8865 2674 2612 8866 2653 2591 8867 2675 2613 8868 2654 2592 8869 2655 2593 8870 2676 2614 8871 2673 2611 8872 2654 2592 8873 2675 2613 8874 2676 2614 8875 2654 2592 8876 2677 2615 8877 2655 2593 8878 2656 2594 8879 2678 2616 8880 2675 2613 8881 2655 2593 8882 2677 2615 8883 2678 2616 8884 2655 2593 8885 2603 2541 8886 2656 2594 8887 2613 2551 8888 2603 2541 8889 2677 2615 8890 2656 2594 8891 2679 2617 8892 896 887 8893 2680 2618 8894 2679 2617 8895 920 911 8896 896 887 8897 2681 2619 8898 2680 2618 8899 2682 2620 8900 2681 2619 8901 2679 2617 8902 2680 2618 8903 2683 2621 8904 2682 2620 8905 2684 2622 8906 2683 2621 8907 2681 2619 8908 2682 2620 8909 2685 2623 8910 2684 2622 8911 2686 2624 8912 2685 2623 8913 2683 2621 8914 2684 2622 8915 2687 2625 8916 2686 2624 8917 2688 2626 8918 2687 2625 8919 2685 2623 8920 2686 2624 8921 2689 2627 8922 2688 2626 8923 2690 2628 8924 2689 2627 8925 2687 2625 8926 2688 2626 8927 2691 2629 8928 2690 2628 8929 2692 2630 8930 2691 2629 8931 2689 2627 8932 2690 2628 8933 2693 2631 8934 2692 2630 8935 2694 2632 8936 2693 2631 8937 2691 2629 8938 2692 2630 8939 2695 2633 8940 2694 2632 8941 2696 2634 8942 2695 2633 8943 2693 2631 8944 2694 2632 8945 2697 2635 8946 2696 2634 8947 2698 2636 8948 2697 2635 8949 2695 2633 8950 2696 2634 8951 2699 2637 8952 2698 2636 8953 2700 2638 8954 2699 2637 8955 2697 2635 8956 2698 2636 8957 2701 2639 8958 2700 2638 8959 2702 2640 8960 2701 2639 8961 2699 2637 8962 2700 2638 8963 2703 2641 8964 2702 2640 8965 2704 2642 8966 2703 2641 8967 2701 2639 8968 2702 2640 8969 2705 2643 8970 2704 2642 8971 2706 2644 8972 2705 2643 8973 2703 2641 8974 2704 2642 8975 2707 2645 8976 2706 2644 8977 2708 2646 8978 2707 2645 8979 2705 2643 8980 2706 2644 8981 2709 2647 8982 2708 2646 8983 2710 2648 8984 2709 2647 8985 2707 2645 8986 2708 2646 8987 2711 2649 8988 2710 2648 8989 2712 2650 8990 2711 2649 8991 2709 2647 8992 2710 2648 8993 2713 2651 8994 2712 2650 8995 2714 2652 8996 2713 2651 8997 2711 2649 8998 2712 2650 8999 2715 2653 9000 2714 2652 9001 2716 2654 9002 2715 2653 9003 2713 2651 9004 2714 2652 9005 2715 2653 9006 2716 2654 9007 2717 2655 9008 2718 2656 9009 2717 2655 9010 2719 2657 9011 2718 2656 9012 2715 2653 9013 2717 2655 9014 2720 2658 9015 2719 2657 9016 2721 2659 9017 2720 2658 9018 2718 2656 9019 2719 2657 9020 2597 2535 9021 2721 2659 9022 2606 2544 9023 2597 2535 9024 2720 2658 9025 2721 2659 9026 2722 2660 9027 2723 2660 9028 2724 2660 9029 2725 2660 9030 2726 2660 9031 2723 2660 9032 2722 2660 9033 2725 2660 9034 2723 2660 9035 2727 2660 9036 2724 2660 9037 2728 2660 9038 2727 2660 9039 2722 2660 9040 2724 2660 9041 2729 2660 9042 2728 2660 9043 2730 2660 9044 2729 2660 9045 2727 2660 9046 2728 2660 9047 2731 2661 9048 2730 2661 9049 2732 2661 9050 2731 2662 9051 2729 2662 9052 2730 2662 9053 2733 2663 9054 2732 2663 9055 2734 2663 9056 2733 2664 9057 2731 2664 9058 2732 2664 9059 2735 2660 9060 2734 2660 9061 2736 2660 9062 2735 2665 9063 2733 2665 9064 2734 2665 9065 2737 2660 9066 2736 2660 9067 2738 2660 9068 2737 2660 9069 2735 2660 9070 2736 2660 9071 2739 2666 9072 2738 2666 9073 2740 2666 9074 2741 2660 9075 2738 2660 9076 2739 2660 9077 2742 2667 9078 2738 2667 9079 2741 2667 9080 2742 2668 9081 2737 2668 9082 2738 2668 9083 2743 2669 9084 2740 2669 9085 2744 2669 9086 2739 2670 9087 2740 2670 9088 2743 2670 9089 2745 2671 9090 2744 2671 9091 2746 2671 9092 2743 2672 9093 2744 2672 9094 2745 2672 9095 2747 2660 9096 2746 2660 9097 2748 2660 9098 2745 2660 9099 2746 2660 9100 2747 2660 9101 2741 2673 9102 2739 2673 9103 2749 2673 9104 2750 2674 9105 2749 2674 9106 2751 2674 9107 2752 2675 9108 2741 2675 9109 2749 2675 9110 2750 2676 9111 2752 2676 9112 2749 2676 9113 2750 2660 9114 2751 2660 9115 2753 2660 9116 2754 2677 9117 2753 2677 9118 2755 2677 9119 2754 2660 9120 2750 2660 9121 2753 2660 9122 2756 2678 9123 2755 2678 9124 2757 2678 9125 2756 2660 9126 2754 2660 9127 2755 2660 9128 2758 2679 9129 2757 2679 9130 2759 2679 9131 2758 2660 9132 2756 2660 9133 2757 2660 9134 2760 2660 9135 2759 2660 9136 2761 2660 9137 2760 2660 9138 2758 2660 9139 2759 2660 9140 2762 2660 9141 2761 2660 9142 2763 2660 9143 2762 2660 9144 2760 2660 9145 2761 2660 9146 2762 2660 9147 2763 2660 9148 2764 2660 9149 2765 2660 9150 2766 2660 9151 2726 2660 9152 2767 2680 9153 921 912 9154 2768 2681 9155 2725 2660 9156 2765 2660 9157 2726 2660 9158 924 915 9159 921 912 9160 2767 2680 9161 2765 2660 9162 2769 2660 9163 2766 2660 9164 2770 2682 9165 2771 2683 9166 2772 2684 9167 2773 2660 9168 2774 2660 9169 2769 2660 9170 2775 2685 9171 2772 2684 9172 2776 2686 9173 2765 2660 9174 2773 2660 9175 2769 2660 9176 2777 2687 9177 2770 2682 9178 2772 2684 9179 2778 2688 9180 2777 2687 9181 2772 2684 9182 2779 2689 9183 2778 2688 9184 2772 2684 9185 2775 2685 9186 2779 2689 9187 2772 2684 9188 2780 2660 9189 2781 2660 9190 2774 2660 9191 2782 2690 9192 2776 2686 9193 2783 2691 9194 2773 2692 9195 2780 2692 9196 2774 2692 9197 2784 2693 9198 2775 2685 9199 2776 2686 9200 2782 2690 9201 2784 2693 9202 2776 2686 9203 2785 2660 9204 2786 2660 9205 2781 2660 9206 2787 2694 9207 2783 2691 9208 2788 2695 9209 2780 2660 9210 2785 2660 9211 2781 2660 9212 2789 2696 9213 2782 2690 9214 2783 2691 9215 2787 2694 9216 2789 2696 9217 2783 2691 9218 2790 2697 9219 2791 2697 9220 2786 2697 9221 2792 2698 9222 2788 2695 9223 2793 2699 9224 2785 2660 9225 2790 2660 9226 2786 2660 9227 2794 2700 9228 2787 2694 9229 2788 2695 9230 2792 2698 9231 2794 2700 9232 2788 2695 9233 2795 2660 9234 2796 2660 9235 2791 2660 9236 2797 2701 9237 2793 2699 9238 2798 2702 9239 2790 2660 9240 2795 2660 9241 2791 2660 9242 2797 2701 9243 2792 2698 9244 2793 2699 9245 2795 2703 9246 2799 2703 9247 2796 2703 9248 2800 2704 9249 2798 2702 9250 2801 2705 9251 2800 2704 9252 2797 2701 9253 2798 2702 9254 2802 2706 9255 2803 2706 9256 2799 2706 9257 2804 2707 9258 2801 2705 9259 2805 2708 9260 2806 2709 9261 2802 2709 9262 2799 2709 9263 2795 2710 9264 2806 2710 9265 2799 2710 9266 2807 2711 9267 2800 2704 9268 2801 2705 9269 2804 2707 9270 2807 2711 9271 2801 2705 9272 2808 2712 9273 2809 2712 9274 2803 2712 9275 2810 2713 9276 2805 2708 9277 2811 2714 9278 2812 2660 9279 2808 2660 9280 2803 2660 9281 2802 2660 9282 2812 2660 9283 2803 2660 9284 2810 2713 9285 2804 2707 9286 2805 2708 9287 2813 2715 9288 2814 2715 9289 2809 2715 9290 2815 2716 9291 2811 2714 9292 2816 2717 9293 2808 2718 9294 2813 2718 9295 2809 2718 9296 2815 2716 9297 2810 2713 9298 2811 2714 9299 2817 2719 9300 2818 2719 9301 2814 2719 9302 2819 2720 9303 2816 2717 9304 2820 2721 9305 2813 2722 9306 2817 2722 9307 2814 2722 9308 2821 2723 9309 2815 2716 9310 2816 2717 9311 2819 2720 9312 2821 2723 9313 2816 2717 9314 2817 2660 9315 2822 2660 9316 2818 2660 9317 2823 2724 9318 2820 2721 9319 2824 2725 9320 2823 2724 9321 2819 2720 9322 2820 2721 9323 2825 2726 9324 2824 2725 9325 2826 2727 9326 2825 2726 9327 2823 2724 9328 2824 2725 9329 2825 2726 9330 2826 2727 9331 2827 2728 9332 2828 2729 9333 2827 2728 9334 2829 2730 9335 2828 2729 9336 2825 2726 9337 2827 2728 9338 2830 2731 9339 2829 2730 9340 2831 2732 9341 2832 2733 9342 2828 2729 9343 2829 2730 9344 2830 2731 9345 2832 2733 9346 2829 2730 9347 2833 2660 9348 2834 2660 9349 2812 2660 9350 2835 2734 9351 2831 2732 9352 2836 2735 9353 2837 2736 9354 2833 2736 9355 2812 2736 9356 2802 2737 9357 2837 2737 9358 2812 2737 9359 2835 2734 9360 2830 2731 9361 2831 2732 9362 2838 2660 9363 2839 2660 9364 2834 2660 9365 2840 2738 9366 2836 2735 9367 2841 2739 9368 2833 2740 9369 2838 2740 9370 2834 2740 9371 2840 2738 9372 2835 2734 9373 2836 2735 9374 2842 2660 9375 2843 2660 9376 2839 2660 9377 2844 2741 9378 2841 2739 9379 2845 2742 9380 2838 2743 9381 2842 2743 9382 2839 2743 9383 2846 2744 9384 2840 2738 9385 2841 2739 9386 2844 2741 9387 2846 2744 9388 2841 2739 9389 2847 2745 9390 2848 2745 9391 2843 2745 9392 2849 2746 9393 2845 2742 9394 2592 2530 9395 2842 2747 9396 2847 2747 9397 2843 2747 9398 2850 2748 9399 2844 2741 9400 2845 2742 9401 2849 2746 9402 2850 2748 9403 2845 2742 9404 2851 2660 9405 2852 2660 9406 2848 2660 9407 2847 2749 9408 2851 2749 9409 2848 2749 9410 2593 2531 9411 2849 2746 9412 2592 2530 9413 2853 2660 9414 2854 2660 9415 2852 2660 9416 2851 2660 9417 2853 2660 9418 2852 2660 9419 2855 2660 9420 2856 2660 9421 2854 2660 9422 2853 2660 9423 2855 2660 9424 2854 2660 9425 2857 2660 9426 2764 2660 9427 2856 2660 9428 2855 2660 9429 2857 2660 9430 2856 2660 9431 2857 2660 9432 2762 2660 9433 2764 2660 9434 2858 2750 9435 2859 2751 9436 2860 2752 9437 2861 2753 9438 2862 2754 9439 2863 2755 9440 2861 2753 9441 2863 2755 9442 2864 2756 9443 2865 2757 9444 2860 2752 9445 2866 2758 9446 2867 2759 9447 2858 2750 9448 2860 2752 9449 2865 2757 9450 2867 2759 9451 2860 2752 9452 2868 2760 9453 2866 2758 9454 2869 2761 9455 2868 2760 9456 2865 2757 9457 2866 2758 9458 2870 2762 9459 2869 2761 9460 2871 2763 9461 2870 2762 9462 2868 2760 9463 2869 2761 9464 2872 2764 9465 2871 2763 9466 2873 2765 9467 2872 2764 9468 2870 2762 9469 2871 2763 9470 2874 2766 9471 2873 2765 9472 2875 2767 9473 2874 2766 9474 2872 2764 9475 2873 2765 9476 2876 2768 9477 2875 2767 9478 2877 2769 9479 2878 2770 9480 2874 2766 9481 2875 2767 9482 2876 2768 9483 2878 2770 9484 2875 2767 9485 2879 2771 9486 2877 2769 9487 2880 2772 9488 2879 2771 9489 2876 2768 9490 2877 2769 9491 2881 2773 9492 2880 2772 9493 2882 2774 9494 2881 2773 9495 2879 2771 9496 2880 2772 9497 2883 2775 9498 2882 2774 9499 2884 2776 9500 2883 2775 9501 2881 2773 9502 2882 2774 9503 2883 2775 9504 2884 2776 9505 2885 2777 9506 2886 2778 9507 2885 2777 9508 2887 2779 9509 2886 2778 9510 2883 2775 9511 2885 2777 9512 2888 2780 9513 2887 2779 9514 2889 2781 9515 2888 2780 9516 2886 2778 9517 2887 2779 9518 2890 2782 9519 2889 2781 9520 2891 2783 9521 2890 2782 9522 2888 2780 9523 2889 2781 9524 2892 2784 9525 2891 2783 9526 2893 2785 9527 2892 2784 9528 2890 2782 9529 2891 2783 9530 2894 2786 9531 2893 2785 9532 2895 2787 9533 2894 2786 9534 2892 2784 9535 2893 2785 9536 2894 2786 9537 2895 2787 9538 2896 2788 9539 2897 2789 9540 2898 2790 9541 2899 2791 9542 2900 2792 9543 2894 2786 9544 2896 2788 9545 2901 2793 9546 2899 2791 9547 2902 2794 9548 2903 2795 9549 2897 2789 9550 2899 2791 9551 2901 2793 9552 2903 2795 9553 2899 2791 9554 2904 2796 9555 2902 2794 9556 2905 2797 9557 2904 2796 9558 2901 2793 9559 2902 2794 9560 2906 2798 9561 2905 2797 9562 2907 2799 9563 2906 2798 9564 2904 2796 9565 2905 2797 9566 2908 2800 9567 2907 2799 9568 2909 2801 9569 2908 2800 9570 2906 2798 9571 2907 2799 9572 2910 2802 9573 2909 2801 9574 2911 2803 9575 2910 2802 9576 2908 2800 9577 2909 2801 9578 2912 2804 9579 2911 2803 9580 2913 2805 9581 2914 2806 9582 2910 2802 9583 2911 2803 9584 2912 2804 9585 2914 2806 9586 2911 2803 9587 2915 2807 9588 2913 2805 9589 2916 2808 9590 2915 2807 9591 2912 2804 9592 2913 2805 9593 2917 2809 9594 2916 2808 9595 2918 2810 9596 2917 2809 9597 2915 2807 9598 2916 2808 9599 2919 2811 9600 2918 2810 9601 2920 2812 9602 2919 2811 9603 2917 2809 9604 2918 2810 9605 2919 2811 9606 2920 2812 9607 2921 2813 9608 2922 2814 9609 2921 2813 9610 2923 2815 9611 2922 2814 9612 2919 2811 9613 2921 2813 9614 2924 2816 9615 2923 2815 9616 2925 2817 9617 2924 2816 9618 2922 2814 9619 2923 2815 9620 2926 2818 9621 2925 2817 9622 2927 2819 9623 2926 2818 9624 2924 2816 9625 2925 2817 9626 2928 2820 9627 2927 2819 9628 2929 2821 9629 2928 2820 9630 2926 2818 9631 2927 2819 9632 2861 2753 9633 2929 2821 9634 2862 2754 9635 2861 2753 9636 2928 2820 9637 2929 2821 9638 947 938 9639 2930 2822 9640 948 939 9641 950 941 9642 948 939 9643 2931 2823 9644 2932 2824 9645 2931 2823 9646 2933 2825 9647 2932 2824 9648 950 941 9649 2931 2823 9650 2932 2824 9651 2933 2825 9652 2934 2826 9653 2935 2827 9654 2934 2826 9655 2936 2828 9656 2935 2827 9657 2932 2824 9658 2934 2826 9659 2937 2829 9660 2936 2828 9661 2938 2830 9662 2937 2829 9663 2935 2827 9664 2936 2828 9665 2939 2831 9666 2938 2830 9667 2940 2832 9668 2939 2831 9669 2937 2829 9670 2938 2830 9671 2941 2833 9672 2942 2834 9673 2943 2835 9674 2944 2836 9675 2939 2831 9676 2940 2832 9677 2941 2833 9678 2945 2837 9679 2942 2834 9680 2941 2833 9681 2943 2835 9682 2946 2838 9683 2947 2839 9684 2946 2838 9685 2948 2840 9686 2941 2833 9687 2946 2838 9688 2947 2839 9689 2949 2841 9690 2950 2842 9691 2951 2843 9692 2949 2841 9693 2952 2844 9694 2950 2842 9695 2953 2845 9696 2951 2843 9697 2954 2846 9698 2953 2845 9699 2949 2841 9700 2951 2843 9701 2953 2845 9702 2954 2846 9703 2955 2847 9704 2956 2848 9705 2955 2847 9706 2957 2849 9707 2956 2848 9708 2953 2845 9709 2955 2847 9710 2956 2848 9711 2957 2849 9712 2958 2850 9713 2959 2851 9714 2958 2850 9715 2960 2852 9716 2959 2851 9717 2956 2848 9718 2958 2850 9719 2959 2851 9720 2960 2852 9721 2961 2853 9722 2962 2854 9723 2961 2853 9724 2963 2855 9725 2959 2851 9726 2961 2853 9727 2962 2854 9728 2964 2856 9729 2965 2857 9730 2966 2858 9731 2964 2856 9732 2967 2859 9733 2965 2857 9734 2968 2860 9735 2966 2858 9736 2969 2861 9737 2968 2860 9738 2964 2856 9739 2966 2858 9740 2970 2862 9741 2971 2863 9742 2972 2864 9743 2970 2862 9744 2973 2865 9745 2971 2863 9746 2974 2866 9747 2972 2864 9748 2975 2867 9749 2974 2866 9750 2970 2862 9751 2972 2864 9752 2974 2866 9753 2975 2867 9754 2976 2868 9755 2977 2869 9756 2976 2868 9757 2978 2870 9758 2977 2869 9759 2974 2866 9760 2976 2868 9761 2977 2869 9762 2978 2870 9763 2979 2871 9764 2980 2872 9765 2979 2871 9766 2981 2873 9767 2980 2872 9768 2977 2869 9769 2979 2871 9770 2980 2872 9771 2981 2873 9772 2982 2874 9773 2983 2875 9774 2982 2874 9775 2984 2876 9776 2983 2875 9777 2980 2872 9778 2982 2874 9779 2570 2508 9780 2985 2877 9781 2575 2513 9782 2570 2508 9783 2986 2878 9784 2985 2877 9785 2987 2879 9786 950 941 9787 2932 2824 9788 2988 2880 9789 2932 2824 9790 2935 2827 9791 2989 2881 9792 2987 2879 9793 2932 2824 9794 2988 2880 9795 2989 2881 9796 2932 2824 9797 2990 2882 9798 2935 2827 9799 2937 2829 9800 2990 2882 9801 2988 2880 9802 2935 2827 9803 2991 2883 9804 2937 2829 9805 2939 2831 9806 2991 2883 9807 2990 2882 9808 2937 2829 9809 2992 2884 9810 2939 2831 9811 2944 2836 9812 2992 2884 9813 2991 2883 9814 2939 2831 9815 2993 2885 9816 2992 2884 9817 2944 2836 9818 2994 2886 9819 2995 2887 9820 2945 2837 9821 2941 2833 9822 2994 2886 9823 2945 2837 9824 938 929 9825 943 934 9826 2996 2888 9827 2997 2889 9828 2996 2888 9829 2998 2890 9830 2997 2889 9831 938 929 9832 2996 2888 9833 2999 2891 9834 2988 2880 9835 2990 2882 9836 2997 2889 9837 2998 2890 9838 3000 2892 9839 3001 2893 9840 2990 2882 9841 2991 2883 9842 3002 2894 9843 2999 2891 9844 2990 2882 9845 3001 2893 9846 3002 2894 9847 2990 2882 9848 3003 2895 9849 2991 2883 9850 2992 2884 9851 3003 2895 9852 3001 2893 9853 2991 2883 9854 2993 2885 9855 3004 2896 9856 2992 2884 9857 3005 2897 9858 2992 2884 9859 3004 2896 9860 3005 2897 9861 3003 2895 9862 2992 2884 9863 2994 2886 9864 3006 2898 9865 2995 2887 9866 3007 2899 9867 3005 2897 9868 3004 2896 9869 3008 2900 9870 3009 2901 9871 3006 2898 9872 2994 2886 9873 3008 2900 9874 3006 2898 9875 3010 2902 9876 3000 2892 9877 3011 2903 9878 3010 2902 9879 2997 2889 9880 3000 2892 9881 3010 2902 9882 3011 2903 9883 3012 2904 9884 3013 2905 9885 3001 2893 9886 3003 2895 9887 3014 2906 9888 3012 2904 9889 3015 2907 9890 3014 2906 9891 3010 2902 9892 3012 2904 9893 3016 2908 9894 3003 2895 9895 3005 2897 9896 3016 2908 9897 3013 2905 9898 3003 2895 9899 3007 2899 9900 3017 2909 9901 3005 2897 9902 3016 2908 9903 3005 2897 9904 3017 2909 9905 3018 2910 9906 3019 2911 9907 3009 2901 9908 3020 2912 9909 3016 2908 9910 3017 2909 9911 3021 2913 9912 3022 2914 9913 3019 2911 9914 3023 2915 9915 3021 2913 9916 3019 2911 9917 3024 2916 9918 3023 2915 9919 3019 2911 9920 3018 2910 9921 3024 2916 9922 3019 2911 9923 3008 2900 9924 3018 2910 9925 3009 2901 9926 3025 2917 9927 3026 2918 9928 3027 2919 9929 3028 2920 9930 3014 2906 9931 3015 2907 9932 3029 2921 9933 3030 2922 9934 3031 2923 9935 3029 2921 9936 3031 2923 9937 3032 2924 9938 3033 2925 9939 3027 2919 9940 3034 2926 9941 3025 2917 9942 3027 2919 9943 3035 2927 9944 3033 2925 9945 3035 2927 9946 3027 2919 9947 3036 2928 9948 3037 2929 9949 3038 2930 9950 3039 2931 9951 3037 2929 9952 3036 2928 9953 934 925 9954 938 929 9955 2997 2889 9956 984 975 9957 2997 2889 9958 3010 2902 9959 984 975 9960 934 925 9961 2997 2889 9962 982 973 9963 3010 2902 9964 3014 2906 9965 982 973 9966 984 975 9967 3010 2902 9968 980 971 9969 3014 2906 9970 3028 2920 9971 980 971 9972 982 973 9973 3014 2906 9974 980 971 9975 3028 2920 9976 977 968 9977 3029 2921 9978 972 963 9979 3030 2922 9980 3029 2921 9981 975 966 9982 972 963 9983 3029 2921 9984 3032 2924 9985 3040 2932 9986 3041 2933 9987 3042 2934 9988 3043 2935 9989 3041 2933 9990 3043 2935 9991 3044 2936 9992 3039 2931 9993 3045 2937 9994 3046 2938 9995 969 960 9996 970 961 9997 3042 2934 9998 969 960 9999 3042 2934 10000 3041 2933 10001 3047 2939 10002 3044 2936 10003 3048 2940 10004 3049 2941 10005 3050 2942 10006 3045 2937 10007 3051 2943 10008 3052 2944 10009 3053 2945 10010 3054 2946 10011 3051 2943 10012 3053 2945 10013 3055 2947 10014 3056 2948 10015 3057 2949 10016 3058 2950 10017 3055 2947 10018 3057 2949 10019 3047 2939 10020 3041 2933 10021 3044 2936 10022 3036 2928 10023 3049 2941 10024 3045 2937 10025 3039 2931 10026 3036 2928 10027 3045 2937 10028 963 954 10029 969 960 10030 3041 2933 10031 3047 2939 10032 963 954 10033 3041 2933 10034 3059 2951 10035 960 951 10036 3052 2944 10037 953 944 10038 960 951 10039 3059 2951 10040 3059 2951 10041 3052 2944 10042 3051 2943 10043 3060 2952 10044 3061 2953 10045 3062 2954 10046 3063 2955 10047 3064 2956 10048 3065 2957 10049 3066 2958 10050 1088 1079 10051 3064 2956 10052 3063 2955 10053 3066 2958 10054 3064 2956 10055 3060 2952 10056 3067 2959 10057 3061 2953 10058 3068 2960 10059 3065 2957 10060 3069 2961 10061 3068 2960 10062 3063 2955 10063 3065 2957 10064 3060 2952 10065 3051 2943 10066 3067 2959 10067 3070 2962 10068 3067 2959 10069 3051 2943 10070 3068 2960 10071 3069 2961 10072 3071 2963 10073 3072 2964 10074 3059 2951 10075 3051 2943 10076 3060 2952 10077 3072 2964 10078 3051 2943 10079 3054 2946 10080 3070 2962 10081 3051 2943 10082 959 950 10083 953 944 10084 3059 2951 10085 3072 2964 10086 959 950 10087 3059 2951 10088 3055 2947 10089 3071 2963 10090 3056 2948 10091 3055 2947 10092 3068 2960 10093 3071 2963 10094 3066 2958 10095 1087 1078 10096 1088 1079 10097 3073 2965 10098 1073 1064 10099 1087 1078 10100 3074 2966 10101 3075 2967 10102 1073 1064 10103 3073 2965 10104 3074 2966 10105 1073 1064 10106 3076 2968 10107 1087 1078 10108 3066 2958 10109 3076 2968 10110 3073 2965 10111 1087 1078 10112 3077 2969 10113 3066 2958 10114 3063 2955 10115 3077 2969 10116 3076 2968 10117 3066 2958 10118 3078 2970 10119 3063 2955 10120 3068 2960 10121 3078 2970 10122 3077 2969 10123 3063 2955 10124 3079 2971 10125 3068 2960 10126 3055 2947 10127 3079 2971 10128 3078 2970 10129 3068 2960 10130 3080 2972 10131 3055 2947 10132 3058 2950 10133 3080 2972 10134 3079 2971 10135 3055 2947 10136 3081 2973 10137 3080 2972 10138 3058 2950 10139 3036 2928 10140 3082 2974 10141 3049 2941 10142 3083 2975 10143 3074 2966 10144 3073 2965 10145 3084 2976 10146 3085 2977 10147 3074 2966 10148 1135 1126 10149 1155 1146 10150 3086 2978 10151 3083 2975 10152 3084 2976 10153 3074 2966 10154 3087 2979 10155 3073 2965 10156 3076 2968 10157 3087 2979 10158 3083 2975 10159 3073 2965 10160 3088 2980 10161 3076 2968 10162 3077 2969 10163 3088 2980 10164 3087 2979 10165 3076 2968 10166 3089 2981 10167 3077 2969 10168 3078 2970 10169 3089 2981 10170 3088 2980 10171 3077 2969 10172 3090 2982 10173 3078 2970 10174 3079 2971 10175 3090 2982 10176 3089 2981 10177 3078 2970 10178 3091 2983 10179 3079 2971 10180 3080 2972 10181 3091 2983 10182 3090 2982 10183 3079 2971 10184 3081 2973 10185 3092 2984 10186 3080 2972 10187 3093 2985 10188 3080 2972 10189 3092 2984 10190 3093 2985 10191 3091 2983 10192 3080 2972 10193 3094 2986 10194 3095 2987 10195 3082 2974 10196 3096 2988 10197 3093 2985 10198 3092 2984 10199 3094 2986 10200 3097 2989 10201 3095 2987 10202 3094 2986 10203 3082 2974 10204 3098 2990 10205 3036 2928 10206 3098 2990 10207 3082 2974 10208 1135 1126 10209 3086 2978 10210 3099 2991 10211 3100 2992 10212 3084 2976 10213 3083 2975 10214 3101 2993 10215 3102 2994 10216 3084 2976 10217 1137 1128 10218 3099 2991 10219 3103 2995 10220 3100 2992 10221 3101 2993 10222 3084 2976 10223 1137 1128 10224 1135 1126 10225 3099 2991 10226 3104 2996 10227 3083 2975 10228 3087 2979 10229 3104 2996 10230 3100 2992 10231 3083 2975 10232 3105 2997 10233 3087 2979 10234 3088 2980 10235 3105 2997 10236 3104 2996 10237 3087 2979 10238 3106 2998 10239 3088 2980 10240 3089 2981 10241 3106 2998 10242 3105 2997 10243 3088 2980 10244 3107 2999 10245 3089 2981 10246 3090 2982 10247 3107 2999 10248 3106 2998 10249 3089 2981 10250 3108 3000 10251 3090 2982 10252 3091 2983 10253 3108 3000 10254 3107 2999 10255 3090 2982 10256 3109 3001 10257 3091 2983 10258 3093 2985 10259 3110 3002 10260 3108 3000 10261 3091 2983 10262 3109 3001 10263 3110 3002 10264 3091 2983 10265 3111 3003 10266 3112 3004 10267 3113 3005 10268 3114 3006 10269 3109 3001 10270 3093 2985 10271 3111 3003 10272 3115 3007 10273 3112 3004 10274 3018 2910 10275 3116 3008 10276 3117 3009 10277 3018 2910 10278 3117 3009 10279 3024 2916 10280 1137 1128 10281 3103 2995 10282 3118 3010 10283 3119 3011 10284 3101 2993 10285 3100 2992 10286 3120 3012 10287 3121 3013 10288 3101 2993 10289 3122 3014 10290 3118 3010 10291 3123 3015 10292 3119 3011 10293 3120 3012 10294 3101 2993 10295 3122 3014 10296 1137 1128 10297 3118 3010 10298 3124 3016 10299 3100 2992 10300 3104 2996 10301 3124 3016 10302 3119 3011 10303 3100 2992 10304 3125 3017 10305 3104 2996 10306 3105 2997 10307 3125 3017 10308 3124 3016 10309 3104 2996 10310 3126 3018 10311 3105 2997 10312 3106 2998 10313 3126 3018 10314 3125 3017 10315 3105 2997 10316 3127 3019 10317 3106 2998 10318 3107 2999 10319 3127 3019 10320 3126 3018 10321 3106 2998 10322 3128 3020 10323 3107 2999 10324 3108 3000 10325 3128 3020 10326 3127 3019 10327 3107 2999 10328 3129 3021 10329 3108 3000 10330 3110 3002 10331 3129 3021 10332 3128 3020 10333 3108 3000 10334 3130 3022 10335 3131 3023 10336 3132 3024 10337 3133 3025 10338 3129 3021 10339 3110 3002 10340 3130 3022 10341 3134 3026 10342 3131 3023 10343 3130 3022 10344 3132 3024 10345 3115 3007 10346 3130 3022 10347 3115 3007 10348 3111 3003 10349 3122 3014 10350 3123 3015 10351 3135 3027 10352 3136 3028 10353 3120 3012 10354 3119 3011 10355 3137 3029 10356 3138 3030 10357 3120 3012 10358 3139 3031 10359 3135 3027 10360 3140 3032 10361 3136 3028 10362 3137 3029 10363 3120 3012 10364 3139 3031 10365 3122 3014 10366 3135 3027 10367 3141 3033 10368 3119 3011 10369 3124 3016 10370 3141 3033 10371 3136 3028 10372 3119 3011 10373 3142 3034 10374 3124 3016 10375 3125 3017 10376 3142 3034 10377 3141 3033 10378 3124 3016 10379 3143 3035 10380 3125 3017 10381 3126 3018 10382 3143 3035 10383 3142 3034 10384 3125 3017 10385 3144 3036 10386 3126 3018 10387 3127 3019 10388 3144 3036 10389 3143 3035 10390 3126 3018 10391 3145 3037 10392 3127 3019 10393 3128 3020 10394 3145 3037 10395 3144 3036 10396 3127 3019 10397 3146 3038 10398 3128 3020 10399 3129 3021 10400 3146 3038 10401 3145 3037 10402 3128 3020 10403 3147 3039 10404 3148 3040 10405 3134 3026 10406 3149 3041 10407 3146 3038 10408 3129 3021 10409 3147 3039 10410 3150 3042 10411 3148 3040 10412 3147 3039 10413 3134 3026 10414 3130 3022 10415 3137 3029 10416 3151 3043 10417 3138 3030 10418 3152 3044 10419 3140 3032 10420 3153 3045 10421 3152 3044 10422 3139 3031 10423 3140 3032 10424 3152 3044 10425 3153 3045 10426 3154 3046 10427 3155 3047 10428 3137 3029 10429 3136 3028 10430 3155 3047 10431 3156 3048 10432 3137 3029 10433 3152 3044 10434 3154 3046 10435 3157 3049 10436 3158 3050 10437 3136 3028 10438 3141 3033 10439 3158 3050 10440 3155 3047 10441 3136 3028 10442 3159 3051 10443 3141 3033 10444 3142 3034 10445 3159 3051 10446 3158 3050 10447 3141 3033 10448 3160 3052 10449 3142 3034 10450 3143 3035 10451 3161 3053 10452 3159 3051 10453 3142 3034 10454 3160 3052 10455 3161 3053 10456 3142 3034 10457 3162 3054 10458 3143 3035 10459 3144 3036 10460 3162 3054 10461 3160 3052 10462 3143 3035 10463 3163 3055 10464 3144 3036 10465 3145 3037 10466 3164 3056 10467 3162 3054 10468 3144 3036 10469 3163 3055 10470 3164 3056 10471 3144 3036 10472 3165 3057 10473 3145 3037 10474 3146 3038 10475 3166 3058 10476 3163 3055 10477 3145 3037 10478 3167 3059 10479 3166 3058 10480 3145 3037 10481 3165 3057 10482 3167 3059 10483 3145 3037 10484 3168 3060 10485 3169 3061 10486 3150 3042 10487 3168 3060 10488 3170 3062 10489 3169 3061 10490 3168 3060 10491 3150 3042 10492 3147 3039 10493 3171 3063 10494 3172 3064 10495 3173 3065 10496 3174 3066 10497 3152 3044 10498 3157 3049 10499 3175 3067 10500 3176 3068 10501 3177 3069 10502 3178 3070 10503 3172 3064 10504 3179 3071 10505 3171 3063 10506 3179 3071 10507 3172 3064 10508 3171 3063 10509 3173 3065 10510 3180 3072 10511 3181 3073 10512 3180 3072 10513 3182 3074 10514 3171 3063 10515 3180 3072 10516 3181 3073 10517 3183 3075 10518 3182 3074 10519 3184 3076 10520 3181 3073 10521 3182 3074 10522 3183 3075 10523 3183 3075 10524 3184 3076 10525 3185 3077 10526 3186 3078 10527 3185 3077 10528 3187 3079 10529 3183 3075 10530 3185 3077 10531 3186 3078 10532 3188 3080 10533 3187 3079 10534 3189 3081 10535 3186 3078 10536 3187 3079 10537 3188 3080 10538 3190 3082 10539 3189 3081 10540 3191 3083 10541 3188 3080 10542 3189 3081 10543 3190 3082 10544 3192 3084 10545 3191 3083 10546 3193 3085 10547 3190 3082 10548 3191 3083 10549 3192 3084 10550 3194 3086 10551 3195 3087 10552 3196 3088 10553 3197 3089 10554 3198 3090 10555 3199 3091 10556 3194 3086 10557 3200 3092 10558 3195 3087 10559 3168 3060 10560 3196 3088 10561 3170 3062 10562 3194 3086 10563 3196 3088 10564 3168 3060 10565 1123 1114 10566 1137 1128 10567 3122 3014 10568 3201 3093 10569 3122 3014 10570 3139 3031 10571 3201 3093 10572 1123 1114 10573 3122 3014 10574 3202 3094 10575 3139 3031 10576 3152 3044 10577 3202 3094 10578 3201 3093 10579 3139 3031 10580 3203 3095 10581 3152 3044 10582 3174 3066 10583 3203 3095 10584 3202 3094 10585 3152 3044 10586 3204 3096 10587 3203 3095 10588 3174 3066 10589 3175 3067 10590 3205 3097 10591 3176 3068 10592 1103 1094 10593 1123 1114 10594 3201 3093 10595 2305 2245 10596 3201 3093 10597 3202 3094 10598 2305 2245 10599 1103 1094 10600 3201 3093 10601 2302 2242 10602 3202 3094 10603 3203 3095 10604 2302 2242 10605 2305 2245 10606 3202 3094 10607 2300 2240 10608 3203 3095 10609 3204 3096 10610 2300 2240 10611 2302 2242 10612 3203 3095 10613 2296 2236 10614 2300 2240 10615 3204 3096 10616 2251 2194 10617 2299 2239 10618 3205 3097 10619 3175 3067 10620 2251 2194 10621 3205 3097 10622 3206 3098 10623 2248 2191 10624 2251 2194 10625 3175 3067 10626 3206 3098 10627 2251 2194 10628 3207 3099 10629 2242 2185 10630 2248 2191 10631 3208 3100 10632 3207 3099 10633 2248 2191 10634 3209 3101 10635 3208 3100 10636 2248 2191 10637 3206 3098 10638 3209 3101 10639 2248 2191 10640 3210 3102 10641 2238 2181 10642 2242 2185 10643 3207 3099 10644 3210 3102 10645 2242 2185 10646 3211 3103 10647 2235 2178 10648 2238 2181 10649 3210 3102 10650 3211 3103 10651 2238 2181 10652 3212 3104 10653 2231 2174 10654 2235 2178 10655 3213 3105 10656 3212 3104 10657 2235 2178 10658 3211 3103 10659 3213 3105 10660 2235 2178 10661 3214 3106 10662 2225 2168 10663 2231 2174 10664 3212 3104 10665 3214 3106 10666 2231 2174 10667 3215 3107 10668 2219 2162 10669 2225 2168 10670 3216 3108 10671 3215 3107 10672 2225 2168 10673 3217 3109 10674 3216 3108 10675 2225 2168 10676 3214 3106 10677 3217 3109 10678 2225 2168 10679 3218 3110 10680 2211 2154 10681 2219 2162 10682 3215 3107 10683 3218 3110 10684 2219 2162 10685 3218 3110 10686 2424 2362 10687 2211 2154 10688 2421 2359 10689 2425 2363 10690 3219 3111 10691 2421 2359 10692 3219 3111 10693 3220 3112 10694 2421 2359 10695 3220 3112 10696 3221 3113 10697 3222 3114 10698 3221 3113 10699 3223 3115 10700 3222 3114 10701 2421 2359 10702 3221 3113 10703 3222 3114 10704 3223 3115 10705 3224 3116 10706 3225 3117 10707 3224 3116 10708 3226 3118 10709 3222 3114 10710 3224 3116 10711 3225 3117 10712 3227 3119 10713 3225 3117 10714 3228 3120 10715 3229 3121 10716 3225 3117 10717 3227 3119 10718 3179 3071 10719 3225 3117 10720 3229 3121 10721 3222 3114 10722 3225 3117 10723 3179 3071 10724 3230 3122 10725 3179 3071 10726 3231 3123 10727 3178 3070 10728 3179 3071 10729 3230 3122 10730 3171 3063 10731 3222 3114 10732 3179 3071 10733 3232 3124 10734 2480 2418 10735 2486 2424 10736 2483 2421 10737 2485 2423 10738 3233 3125 10739 3234 3126 10740 2486 2424 10741 2488 2426 10742 3234 3126 10743 3232 3124 10744 2486 2424 10745 3235 3127 10746 2488 2426 10747 2490 2428 10748 3235 3127 10749 3234 3126 10750 2488 2426 10751 3236 3128 10752 2490 2428 10753 2493 2431 10754 3236 3128 10755 3235 3127 10756 2490 2428 10757 3237 3129 10758 2493 2431 10759 2495 2433 10760 3237 3129 10761 3236 3128 10762 2493 2431 10763 3238 3130 10764 2495 2433 10765 2421 2359 10766 3238 3130 10767 3237 3129 10768 2495 2433 10769 3222 3114 10770 3238 3130 10771 2421 2359 10772 3190 3082 10773 3232 3124 10774 3234 3126 10775 3190 3082 10776 3192 3084 10777 3232 3124 10778 3197 3089 10779 3233 3125 10780 3198 3090 10781 3239 3131 10782 3233 3125 10783 3197 3089 10784 2483 2421 10785 3233 3125 10786 3239 3131 10787 3188 3080 10788 3234 3126 10789 3235 3127 10790 3188 3080 10791 3190 3082 10792 3234 3126 10793 3186 3078 10794 3235 3127 10795 3236 3128 10796 3186 3078 10797 3188 3080 10798 3235 3127 10799 3183 3075 10800 3236 3128 10801 3237 3129 10802 3183 3075 10803 3186 3078 10804 3236 3128 10805 3181 3073 10806 3237 3129 10807 3238 3130 10808 3181 3073 10809 3183 3075 10810 3237 3129 10811 3171 3063 10812 3238 3130 10813 3222 3114 10814 3171 3063 10815 3181 3073 10816 3238 3130 10817 2964 2856 10818 3240 3132 10819 2967 2859 10820 3241 3133 10821 2962 2854 10822 3242 3134 10823 2959 2851 10824 2962 2854 10825 3241 3133 10826 3243 3135 10827 3244 3136 10828 3240 3132 10829 3245 3137 10830 3242 3134 10831 3246 3138 10832 3247 3139 10833 3243 3135 10834 3240 3132 10835 2964 2856 10836 3247 3139 10837 3240 3132 10838 3241 3133 10839 3242 3134 10840 3245 3137 10841 3248 3140 10842 3249 3141 10843 3244 3136 10844 3250 3142 10845 3246 3138 10846 3251 3143 10847 3243 3135 10848 3248 3140 10849 3244 3136 10850 3245 3137 10851 3246 3138 10852 3250 3142 10853 3239 3131 10854 3197 3089 10855 3249 3141 10856 3252 3144 10857 3251 3143 10858 3200 3092 10859 3248 3140 10860 3239 3131 10861 3249 3141 10862 3250 3142 10863 3251 3143 10864 3252 3144 10865 3252 3144 10866 3200 3092 10867 3194 3086 10868 3253 3145 10869 3239 3131 10870 3248 3140 10871 3253 3145 10872 2483 2421 10873 3239 3131 10874 3254 3146 10875 3248 3140 10876 3243 3135 10877 3254 3146 10878 3253 3145 10879 3248 3140 10880 3254 3146 10881 3243 3135 10882 3247 3139 10883 3255 3147 10884 3247 3139 10885 2964 2856 10886 3255 3147 10887 3254 3146 10888 3247 3139 10889 2968 2860 10890 3255 3147 10891 2964 2856 10892 3256 3148 10893 2478 2416 10894 3257 3149 10895 3256 3148 10896 2472 2410 10897 2478 2416 10898 3258 3150 10899 3257 3149 10900 3259 3151 10901 3258 3150 10902 3256 3148 10903 3257 3149 10904 3260 3152 10905 3259 3151 10906 3261 3153 10907 3260 3152 10908 3258 3150 10909 3259 3151 10910 3262 3154 10911 3261 3153 10912 2973 2865 10913 3262 3154 10914 3260 3152 10915 3261 3153 10916 2970 2862 10917 3262 3154 10918 2973 2865 10919 2949 2841 10920 3263 3155 10921 2952 2844 10922 2941 2833 10923 2947 2839 10924 3264 3156 10925 3265 3157 10926 3266 3158 10927 3263 3155 10928 2941 2833 10929 3264 3156 10930 3267 3159 10931 2949 2841 10932 3265 3157 10933 3263 3155 10934 3268 3160 10935 3269 3161 10936 3266 3158 10937 2994 2886 10938 3267 3159 10939 3270 3162 10940 3265 3157 10941 3268 3160 10942 3266 3158 10943 2941 2833 10944 3267 3159 10945 2994 2886 10946 3271 3163 10947 3272 3164 10948 3269 3161 10949 3008 2900 10950 3270 3162 10951 3273 3165 10952 3268 3160 10953 3271 3163 10954 3269 3161 10955 2994 2886 10956 3270 3162 10957 3008 2900 10958 3274 3166 10959 3275 3167 10960 3272 3164 10961 3008 2900 10962 3273 3165 10963 3276 3168 10964 3271 3163 10965 3274 3166 10966 3272 3164 10967 3130 3022 10968 3111 3003 10969 3275 3167 10970 3018 2910 10971 3276 3168 10972 3116 3008 10973 3274 3166 10974 3130 3022 10975 3275 3167 10976 3008 2900 10977 3276 3168 10978 3018 2910 10979 3147 3039 10980 3130 3022 10981 3274 3166 10982 3277 3169 10983 3274 3166 10984 3271 3163 10985 3277 3169 10986 3147 3039 10987 3274 3166 10988 3278 3170 10989 3271 3163 10990 3268 3160 10991 3278 3170 10992 3277 3169 10993 3271 3163 10994 3279 3171 10995 3268 3160 10996 3265 3157 10997 3279 3171 10998 3278 3170 10999 3268 3160 11000 3280 3172 11001 3265 3157 11002 2949 2841 11003 3280 3172 11004 3279 3171 11005 3265 3157 11006 2953 2845 11007 3280 3172 11008 2949 2841 11009 3168 3060 11010 3147 3039 11011 3277 3169 11012 3281 3173 11013 3277 3169 11014 3278 3170 11015 3281 3173 11016 3168 3060 11017 3277 3169 11018 3282 3174 11019 3278 3170 11020 3279 3171 11021 3282 3174 11022 3281 3173 11023 3278 3170 11024 3283 3175 11025 3279 3171 11026 3280 3172 11027 3283 3175 11028 3282 3174 11029 3279 3171 11030 3284 3176 11031 3280 3172 11032 2953 2845 11033 3284 3176 11034 3283 3175 11035 3280 3172 11036 2956 2848 11037 3284 3176 11038 2953 2845 11039 3194 3086 11040 3168 3060 11041 3281 3173 11042 3252 3144 11043 3281 3173 11044 3282 3174 11045 3252 3144 11046 3194 3086 11047 3281 3173 11048 3250 3142 11049 3282 3174 11050 3283 3175 11051 3250 3142 11052 3252 3144 11053 3282 3174 11054 3245 3137 11055 3283 3175 11056 3284 3176 11057 3245 3137 11058 3250 3142 11059 3283 3175 11060 3241 3133 11061 3284 3176 11062 2956 2848 11063 3241 3133 11064 3245 3137 11065 3284 3176 11066 2959 2851 11067 3241 3133 11068 2956 2848 11069 3036 2928 11070 3038 2930 11071 3098 2990 11072 2503 2441 11073 2472 2410 11074 3256 3148 11075 3285 3177 11076 3256 3148 11077 3258 3150 11078 3285 3177 11079 2503 2441 11080 3256 3148 11081 3286 3178 11082 3258 3150 11083 3260 3152 11084 3286 3178 11085 3285 3177 11086 3258 3150 11087 3287 3179 11088 3260 3152 11089 3262 3154 11090 3287 3179 11091 3286 3178 11092 3260 3152 11093 3288 3180 11094 3262 3154 11095 2970 2862 11096 3288 3180 11097 3287 3179 11098 3262 3154 11099 2974 2866 11100 3288 3180 11101 2970 2862 11102 2513 2451 11103 2503 2441 11104 3285 3177 11105 3289 3181 11106 3285 3177 11107 3286 3178 11108 3289 3181 11109 2513 2451 11110 3285 3177 11111 3290 3182 11112 3286 3178 11113 3287 3179 11114 3290 3182 11115 3289 3181 11116 3286 3178 11117 3291 3183 11118 3287 3179 11119 3288 3180 11120 3291 3183 11121 3290 3182 11122 3287 3179 11123 3292 3184 11124 3288 3180 11125 2974 2866 11126 3292 3184 11127 3291 3183 11128 3288 3180 11129 2977 2869 11130 3292 3184 11131 2974 2866 11132 2524 2462 11133 2513 2451 11134 3289 3181 11135 3293 3185 11136 3289 3181 11137 3290 3182 11138 3293 3185 11139 2524 2462 11140 3289 3181 11141 3294 3186 11142 3290 3182 11143 3291 3183 11144 3294 3186 11145 3293 3185 11146 3290 3182 11147 3295 3187 11148 3291 3183 11149 3292 3184 11150 3295 3187 11151 3294 3186 11152 3291 3183 11153 3296 3188 11154 3292 3184 11155 2977 2869 11156 3296 3188 11157 3295 3187 11158 3292 3184 11159 2980 2872 11160 3296 3188 11161 2977 2869 11162 3297 3189 11163 2524 2462 11164 3293 3185 11165 3297 3189 11166 2540 2478 11167 2524 2462 11168 3298 3190 11169 3293 3185 11170 3294 3186 11171 3298 3190 11172 3297 3189 11173 3293 3185 11174 3299 3191 11175 3294 3186 11176 3295 3187 11177 3299 3191 11178 3298 3190 11179 3294 3186 11180 3300 3192 11181 3295 3187 11182 3296 3188 11183 3300 3192 11184 3299 3191 11185 3295 3187 11186 3301 3193 11187 3296 3188 11188 2980 2872 11189 3301 3193 11190 3300 3192 11191 3296 3188 11192 2983 2875 11193 3301 3193 11194 2980 2872 11195 2543 2481 11196 2537 2475 11197 3302 3194 11198 2543 2481 11199 3302 3194 11200 3303 3195 11201 2555 2493 11202 3303 3195 11203 3304 3196 11204 2555 2493 11205 2543 2481 11206 3303 3195 11207 2562 2500 11208 3304 3196 11209 3305 3197 11210 2562 2500 11211 2555 2493 11212 3304 3196 11213 2562 2500 11214 3305 3197 11215 3306 3198 11216 2570 2508 11217 3306 3198 11218 2986 2878 11219 2570 2508 11220 2562 2500 11221 3306 3198 11222 3307 3199 11223 3308 3199 11224 3309 3199 11225 3307 3200 11226 3309 3200 11227 3310 3200 11228 3311 3201 11229 3310 3201 11230 3312 3201 11231 3307 2660 11232 3310 2660 11233 3311 2660 11234 3313 3202 11235 3312 3202 11236 3314 3202 11237 3311 3203 11238 3312 3203 11239 3313 3203 11240 3315 3204 11241 3314 3204 11242 3316 3204 11243 3313 2660 11244 3314 2660 11245 3315 2660 11246 3317 3205 11247 3316 3205 11248 3318 3205 11249 3315 3206 11250 3316 3206 11251 3317 3206 11252 3317 3207 11253 3318 3207 11254 3319 3207 11255 3320 3208 11256 3319 3208 11257 3321 3208 11258 3317 3209 11259 3319 3209 11260 3320 3209 11261 3322 3210 11262 3321 3210 11263 3323 3210 11264 3320 3211 11265 3321 3211 11266 3322 3211 11267 3324 3212 11268 3323 3212 11269 3325 3212 11270 3322 3213 11271 3323 3213 11272 3324 3213 11273 3326 3214 11274 3325 3214 11275 3327 3214 11276 3324 3215 11277 3325 3215 11278 3326 3215 11279 3328 3216 11280 3327 3216 11281 3329 3216 11282 3326 2660 11283 3327 2660 11284 3328 2660 11285 3330 3217 11286 3329 3217 11287 3331 3217 11288 3332 3218 11289 3329 3218 11290 3330 3218 11291 3328 2660 11292 3329 2660 11293 3332 2660 11294 3333 2660 11295 3331 2660 11296 3334 2660 11297 3330 2660 11298 3331 2660 11299 3333 2660 11300 3335 3219 11301 3334 3219 11302 3336 3219 11303 3333 3220 11304 3334 3220 11305 3335 3220 11306 3337 3221 11307 3336 3221 11308 3338 3221 11309 3335 3222 11310 3336 3222 11311 3337 3222 11312 3339 2660 11313 3338 2660 11314 3340 2660 11315 3337 3223 11316 3338 3223 11317 3339 3223 11318 3341 3224 11319 3342 3224 11320 3343 3224 11321 3344 3225 11322 3345 3225 11323 3342 3225 11324 3341 3226 11325 3344 3226 11326 3342 3226 11327 3346 3227 11328 3343 3227 11329 3347 3227 11330 3346 3228 11331 3341 3228 11332 3343 3228 11333 3348 3229 11334 3347 3229 11335 3349 3229 11336 3350 3230 11337 3346 3230 11338 3347 3230 11339 3348 3231 11340 3350 3231 11341 3347 3231 11342 3351 3232 11343 3349 3232 11344 3352 3232 11345 3351 3233 11346 3348 3233 11347 3349 3233 11348 3353 3234 11349 3352 3234 11350 3354 3234 11351 3353 3235 11352 3351 3235 11353 3352 3235 11354 3353 3236 11355 3354 3236 11356 3355 3236 11357 3356 3237 11358 3353 3237 11359 3355 3237 11360 3357 3238 11361 3356 3238 11362 3355 3238 11363 3358 3239 11364 3359 3239 11365 3345 3239 11366 3344 3240 11367 3358 3240 11368 3345 3240 11369 3358 3241 11370 3360 3241 11371 3359 3241 11372 3357 3242 11373 3361 3242 11374 3356 3242 11375 3362 3243 11376 3363 3243 11377 3361 3243 11378 3357 3244 11379 3362 3244 11380 3361 3244 11381 3364 3245 11382 3365 3245 11383 3363 3245 11384 3362 3246 11385 3364 3246 11386 3363 3246 11387 3366 3247 11388 3367 3247 11389 3365 3247 11390 3364 3248 11391 3366 3248 11392 3365 3248 11393 3368 3249 11394 3369 3249 11395 3367 3249 11396 3366 3250 11397 3368 3250 11398 3367 3250 11399 3370 3251 11400 3371 3251 11401 3369 3251 11402 3368 3252 11403 3370 3252 11404 3369 3252 11405 3372 3253 11406 3373 3253 11407 3371 3253 11408 3370 3254 11409 3372 3254 11410 3371 3254 11411 3374 3255 11412 3375 3255 11413 3373 3255 11414 3372 3256 11415 3374 3256 11416 3373 3256 11417 3374 3257 11418 3376 3257 11419 3375 3257 11420 3377 3258 11421 1290 1280 11422 1293 1283 11423 1296 1286 11424 3377 3258 11425 1293 1283 11426 3378 3259 11427 1287 1277 11428 1290 1280 11429 3377 3258 11430 3378 3259 11431 1290 1280 11432 3379 3260 11433 1285 1275 11434 1287 1277 11435 3378 3259 11436 3379 3260 11437 1287 1277 11438 3380 3261 11439 3381 3262 11440 1285 1275 11441 1043 1034 11442 1285 1275 11443 3381 3262 11444 3379 3260 11445 3380 3261 11446 1285 1275 11447 3382 3263 11448 3383 3264 11449 3381 3262 11450 1033 1024 11451 3381 3262 11452 3383 3264 11453 3380 3261 11454 3382 3263 11455 3381 3262 11456 1033 1024 11457 1043 1034 11458 3381 3262 11459 3384 3265 11460 3385 3266 11461 3383 3264 11462 1028 1019 11463 3383 3264 11464 3385 3266 11465 3382 3263 11466 3384 3265 11467 3383 3264 11468 1028 1019 11469 1033 1024 11470 3383 3264 11471 3386 3267 11472 3387 3268 11473 3385 3266 11474 772 763 11475 3385 3266 11476 3387 3268 11477 3384 3265 11478 3386 3267 11479 3385 3266 11480 772 763 11481 1028 1019 11482 3385 3266 11483 3388 3269 11484 3389 3270 11485 3387 3268 11486 797 788 11487 3387 3268 11488 3389 3270 11489 3386 3267 11490 3388 3269 11491 3387 3268 11492 797 788 11493 772 763 11494 3387 3268 11495 3390 3271 11496 3391 3272 11497 3389 3270 11498 794 785 11499 3389 3270 11500 3391 3272 11501 3388 3269 11502 3390 3271 11503 3389 3270 11504 794 785 11505 797 788 11506 3389 3270 11507 3392 3273 11508 3393 3274 11509 3391 3272 11510 792 783 11511 3391 3272 11512 3393 3274 11513 3390 3271 11514 3392 3273 11515 3391 3272 11516 792 783 11517 794 785 11518 3391 3272 11519 3394 3275 11520 1970 1916 11521 3393 3274 11522 789 780 11523 3393 3274 11524 1970 1916 11525 3392 3273 11526 3394 3275 11527 3393 3274 11528 789 780 11529 792 783 11530 3393 3274 11531 3394 3275 11532 1973 1919 11533 1970 1916 11534 787 778 11535 789 780 11536 1970 1916 11537 1737 1710 11538 1973 1919 11539 3394 3275 11540 1733 1706 11541 3394 3275 11542 3392 3273 11543 1737 1710 11544 3394 3275 11545 1733 1706 11546 1730 1703 11547 3392 3273 11548 3390 3271 11549 1733 1706 11550 3392 3273 11551 1730 1703 11552 1726 1699 11553 3390 3271 11554 3388 3269 11555 1730 1703 11556 3390 3271 11557 1726 1699 11558 1723 1696 11559 3388 3269 11560 3386 3267 11561 1726 1699 11562 3388 3269 11563 1723 1696 11564 1719 1692 11565 3386 3267 11566 3384 3265 11567 1723 1696 11568 3386 3267 11569 1719 1692 11570 1716 1689 11571 3384 3265 11572 3382 3263 11573 1719 1692 11574 3384 3265 11575 1716 1689 11576 1712 1685 11577 3382 3263 11578 3380 3261 11579 1716 1689 11580 3382 3263 11581 1712 1685 11582 1706 1679 11583 3380 3261 11584 3379 3260 11585 1712 1685 11586 3380 3261 11587 1706 1679 11588 1702 1675 11589 3379 3260 11590 3378 3259 11591 1706 1679 11592 3379 3260 11593 1702 1675 11594 1699 1672 11595 3378 3259 11596 3377 3258 11597 1702 1675 11598 3378 3259 11599 1699 1672 11600 1695 1668 11601 3377 3258 11602 1296 1286 11603 1699 1672 11604 3377 3258 11605 1695 1668 11606 1692 1665 11607 1296 1286 11608 1298 1288 11609 1695 1668 11610 1296 1286 11611 1692 1665 11612 1688 1661 11613 1298 1288 11614 1277 1268 11615 1692 1665 11616 1298 1288 11617 1688 1661 11618 1688 1661 11619 1277 1268 11620 1530 1520 11621 166 166 11622 537 533 11623 541 537 11624 134 134 11625 540 536 11626 159 159 11627 134 134 11628 534 530 11629 540 536 11630 163 163 11631 541 537 11632 543 539 11633 163 163 11634 166 166 11635 541 537 11636 2011 1957 11637 543 539 11638 546 542 11639 2011 1957 11640 163 163 11641 543 539 11642 2009 1955 11643 546 542 11644 549 545 11645 2009 1955 11646 2011 1957 11647 546 542 11648 2006 1952 11649 549 545 11650 424 421 11651 2006 1952 11652 2009 1955 11653 549 545 11654 748 739 11655 2006 1952 11656 424 421 11657 114 114 11658 526 522 11659 529 525 11660 103 103 11661 529 525 11662 532 528 11663 103 103 11664 114 114 11665 529 525 11666 98 98 11667 532 528 11668 534 530 11669 98 98 11670 103 103 11671 532 528 11672 134 134 11673 98 98 11674 534 530 11675 3395 3276 11676 3396 3276 11677 3397 3276 11678 3398 3277 11679 3396 3277 11680 3395 3277 11681 3399 3278 11682 3396 3278 11683 3398 3278 11684 3400 3279 11685 3397 3279 11686 3401 3279 11687 3395 3280 11688 3397 3280 11689 3400 3280 11690 3402 3281 11691 3401 3281 11692 3403 3281 11693 3400 3282 11694 3401 3282 11695 3402 3282 11696 3404 3283 11697 3403 3283 11698 3405 3283 11699 3402 3284 11700 3403 3284 11701 3404 3284 11702 3406 3285 11703 3405 3285 11704 3407 3285 11705 3404 3286 11706 3405 3286 11707 3406 3286 11708 3408 3287 11709 3407 3287 11710 3409 3287 11711 3406 1648 11712 3407 1648 11713 3408 1648 11714 3410 3288 11715 3409 3288 11716 3411 3288 11717 3408 3289 11718 3409 3289 11719 3410 3289 11720 3412 3290 11721 3411 3290 11722 3413 3290 11723 3414 3291 11724 3411 3291 11725 3412 3291 11726 3410 3292 11727 3411 3292 11728 3414 3292 11729 3415 3293 11730 3413 3293 11731 3416 3293 11732 3412 3294 11733 3413 3294 11734 3415 3294 11735 3417 3295 11736 3416 3295 11737 3418 3295 11738 3415 3296 11739 3416 3296 11740 3417 3296 11741 3399 3297 11742 3398 3297 11743 3419 3297 11744 3420 3298 11745 3419 3298 11746 3421 3298 11747 3399 3299 11748 3419 3299 11749 3420 3299 11750 3422 3300 11751 3421 3300 11752 3423 3300 11753 3420 3301 11754 3421 3301 11755 3422 3301 11756 3424 3302 11757 3423 3302 11758 3425 3302 11759 3422 3303 11760 3423 3303 11761 3424 3303 11762 3426 3304 11763 3425 3304 11764 3427 3304 11765 3424 1648 11766 3425 1648 11767 3426 1648 11768 3428 3305 11769 3427 3305 11770 3429 3305 11771 3426 3306 11772 3427 3306 11773 3428 3306 11774 3430 3307 11775 3429 3307 11776 3431 3307 11777 3432 3308 11778 3429 3308 11779 3430 3308 11780 3428 3309 11781 3429 3309 11782 3432 3309 11783 3433 3310 11784 3431 3310 11785 3434 3310 11786 3430 3311 11787 3431 3311 11788 3433 3311 11789 3435 3312 11790 3434 3312 11791 3436 3312 11792 3433 3313 11793 3434 3313 11794 3435 3313 11795 3437 3314 11796 3438 3314 11797 3439 3314 11798 3440 3315 11799 3441 3315 11800 3438 3315 11801 3437 3316 11802 3440 3316 11803 3438 3316 11804 3442 3317 11805 3439 3317 11806 3443 3317 11807 3442 3318 11808 3437 3318 11809 3439 3318 11810 3444 3319 11811 3443 3319 11812 3445 3319 11813 3444 3320 11814 3442 3320 11815 3443 3320 11816 3446 3321 11817 3445 3321 11818 3447 3321 11819 3446 3322 11820 3444 3322 11821 3445 3322 11822 3448 3323 11823 3447 3323 11824 3449 3323 11825 3448 3324 11826 3446 3324 11827 3447 3324 11828 3450 3325 11829 3449 3325 11830 3451 3325 11831 3450 3326 11832 3448 3326 11833 3449 3326 11834 3452 3327 11835 3450 3327 11836 3451 3327 11837 3453 3328 11838 3452 3328 11839 3451 3328 11840 3454 3329 11841 3455 3329 11842 3441 3329 11843 3440 3330 11844 3454 3330 11845 3441 3330 11846 3453 3331 11847 3456 3331 11848 3452 3331 11849 3457 3332 11850 3458 3332 11851 3456 3332 11852 3453 3333 11853 3457 3333 11854 3456 3333 11855 3457 3334 11856 3459 3334 11857 3458 3334 11858 3460 3335 11859 3461 3335 11860 3459 3335 11861 3457 3336 11862 3460 3336 11863 3459 3336 11864 3462 3337 11865 3463 3337 11866 3461 3337 11867 3460 3338 11868 3462 3338 11869 3461 3338 11870 3464 3339 11871 3465 3339 11872 3463 3339 11873 3462 3340 11874 3464 3340 11875 3463 3340 11876 3466 3341 11877 3467 3341 11878 3465 3341 11879 3468 3342 11880 3466 3342 11881 3465 3342 11882 3464 3343 11883 3468 3343 11884 3465 3343 11885 3469 3344 11886 3470 3344 11887 3467 3344 11888 3466 3345 11889 3469 3345 11890 3467 3345 11891 3471 3346 11892 3472 3347 11893 3473 3348 11894 238 3349 11895 3474 3349 11896 3475 3349 11897 3476 3350 11898 3477 3351 11899 3478 3352 11900 3479 3353 11901 3478 3353 11902 3477 3353 11903 3480 3354 11904 3477 3351 11905 3476 3350 11906 3481 3355 11907 3477 3351 11908 3480 3354 11909 3482 3356 11910 3477 3351 11911 3481 3355 11912 258 256 11913 3477 3351 11914 3482 3356 11915 3483 3357 11916 3484 3357 11917 3485 3357 11918 3471 3346 11919 3486 3358 11920 3472 3347 11921 238 3359 11922 3475 3359 11923 3487 3359 11924 3471 3346 11925 3488 3360 11926 3486 3358 11927 3479 3361 11928 3489 3361 11929 3478 3361 11930 3490 3362 11931 3489 3362 11932 3491 3362 11933 3479 3363 11934 3491 3363 11935 3489 3363 11936 238 3364 11937 3487 3364 11938 239 3364 11939 3471 3346 11940 3492 3365 11941 3488 3360 11942 3471 3346 11943 3493 3366 11944 3492 3365 11945 3471 3346 11946 3494 3367 11947 3493 3366 11948 3495 3368 11949 3496 3369 11950 3494 3367 11951 3471 3346 11952 3495 3368 11953 3494 3367 11954 258 256 11955 3482 3356 11956 3497 3370 11957 968 959 11958 3495 3368 11959 3471 3346 11960 967 958 11961 3495 3368 11962 968 959 11963 258 256 11964 3497 3370 11965 259 257 11966 3483 3371 11967 3498 3371 11968 3484 3371 11969

+
+ + + + +

3499 3372 11970 3500 3373 11971 3501 3374 11972 3502 3375 11973 3503 3375 11974 3504 3375 11975 3505 3376 11976 3499 3372 11977 3501 3374 11978 3506 3377 11979 3507 3377 11980 3508 3377 11981 3506 3378 11982 3508 3378 11983 3509 3378 11984 3510 3379 11985 3511 3380 11986 3500 3373 11987 3512 3381 11988 3504 3381 11989 3513 3381 11990 3499 3372 11991 3510 3379 11992 3500 3373 11993 3514 3382 11994 3502 3382 11995 3504 3382 11996 3515 3383 11997 3514 3383 11998 3504 3383 11999 3516 3384 12000 3515 3384 12001 3504 3384 12002 3512 3385 12003 3516 3385 12004 3504 3385 12005 3517 3386 12006 3518 3387 12007 3511 3380 12008 3519 3388 12009 3520 3389 12010 3521 3390 12011 3510 3379 12012 3517 3386 12013 3511 3380 12014 3522 3391 12015 3512 3391 12016 3513 3391 12017 3517 3386 12018 3523 3392 12019 3518 3387 12020 3524 3393 12021 3521 3390 12022 3525 3394 12023 3524 3393 12024 3519 3388 12025 3521 3390 12026 3526 3395 12027 3527 3396 12028 3523 3392 12029 3528 3397 12030 3525 3394 12031 3529 3398 12032 3517 3386 12033 3526 3395 12034 3523 3392 12035 3524 3393 12036 3525 3394 12037 3528 3397 12038 3526 3395 12039 3530 3399 12040 3527 3396 12041 3531 3400 12042 3529 3398 12043 3532 3401 12044 3533 3402 12045 3529 3398 12046 3531 3400 12047 3528 3397 12048 3529 3398 12049 3533 3402 12050 3526 3395 12051 3534 3403 12052 3530 3399 12053 3535 3404 12054 3532 3401 12055 3536 3405 12056 3531 3400 12057 3532 3401 12058 3535 3404 12059 3537 3406 12060 3538 3407 12061 3534 3403 12062 3535 3404 12063 3536 3405 12064 3539 3408 12065 3526 3395 12066 3537 3406 12067 3534 3403 12068 3537 3406 12069 3540 3409 12070 3538 3407 12071 3541 3410 12072 3542 3410 12073 3543 3410 12074 3535 3404 12075 3539 3408 12076 3544 3411 12077 3545 3412 12078 3546 3413 12079 3540 3409 12080 3547 3414 12081 3543 3414 12082 3548 3414 12083 3537 3406 12084 3545 3412 12085 3540 3409 12086 3541 3415 12087 3543 3415 12088 3547 3415 12089 3545 3412 12090 3549 3416 12091 3546 3413 12092 3550 3417 12093 3551 3417 12094 3552 3417 12095 3553 3418 12096 3547 3418 12097 3548 3418 12098 3554 3419 12099 3555 3420 12100 3549 3416 12101 3556 3421 12102 3552 3421 12103 3557 3421 12104 3545 3412 12105 3554 3419 12106 3549 3416 12107 3558 3422 12108 3550 3422 12109 3552 3422 12110 3556 3423 12111 3558 3423 12112 3552 3423 12113 3559 3424 12114 3560 3425 12115 3561 3426 12116 3562 3427 12117 3557 3427 12118 3563 3427 12119 3556 3428 12120 3557 3428 12121 3562 3428 12122 3564 3429 12123 3554 3419 12124 3545 3412 12125 3565 3430 12126 3566 3431 12127 3554 3419 12128 3567 3432 12129 3561 3426 12130 3568 3433 12131 3564 3429 12132 3565 3430 12133 3554 3419 12134 3569 3434 12135 3561 3426 12136 3567 3432 12137 3559 3424 12138 3561 3426 12139 3569 3434 12140 3570 3435 12141 3545 3412 12142 3537 3406 12143 3570 3435 12144 3564 3429 12145 3545 3412 12146 3571 3436 12147 3537 3406 12148 3526 3395 12149 3571 3436 12150 3570 3435 12151 3537 3406 12152 3572 3437 12153 3526 3395 12154 3517 3386 12155 3572 3437 12156 3571 3436 12157 3526 3395 12158 3573 3438 12159 3517 3386 12160 3510 3379 12161 3573 3438 12162 3572 3437 12163 3517 3386 12164 3574 3439 12165 3510 3379 12166 3499 3372 12167 3574 3439 12168 3573 3438 12169 3510 3379 12170 3575 3440 12171 3576 3441 12172 3499 3372 12173 3577 3442 12174 3499 3372 12175 3576 3441 12176 3505 3376 12177 3575 3440 12178 3499 3372 12179 3577 3442 12180 3574 3439 12181 3499 3372 12182 3578 3443 12183 3579 3444 12184 3580 3445 12185 3581 3446 12186 3577 3442 12187 3576 3441 12188 3582 3447 12189 3583 3448 12190 3579 3444 12191 3582 3447 12192 3579 3444 12193 3578 3443 12194 3506 3449 12195 3584 3449 12196 3507 3449 12197 3578 3443 12198 3580 3445 12199 3585 3450 12200 3565 3430 12201 3586 3451 12202 3566 3431 12203 3587 3452 12204 3568 3433 12205 3588 3453 12206 3567 3432 12207 3568 3433 12208 3587 3452 12209 3565 3430 12210 3589 3454 12211 3586 3451 12212 3590 3455 12213 3588 3453 12214 3591 3456 12215 3587 3452 12216 3588 3453 12217 3590 3455 12218 3565 3430 12219 3592 3457 12220 3589 3454 12221 3593 3458 12222 3591 3456 12223 3594 3459 12224 3590 3455 12225 3591 3456 12226 3593 3458 12227 3595 3460 12228 3596 3461 12229 3592 3457 12230 3597 3462 12231 3594 3459 12232 3598 3463 12233 3565 3430 12234 3595 3460 12235 3592 3457 12236 3593 3458 12237 3594 3459 12238 3597 3462 12239 3597 3462 12240 3598 3463 12241 3599 3464 12242 3600 3465 12243 3601 3465 12244 3602 3465 12245 3597 3462 12246 3599 3464 12247 3603 3466 12248 3604 3467 12249 3565 3430 12250 3564 3429 12251 3605 3468 12252 3602 3468 12253 3606 3468 12254 3600 3469 12255 3602 3469 12256 3605 3469 12257 3607 3470 12258 3564 3429 12259 3570 3435 12260 3608 3471 12261 3609 3472 12262 3564 3429 12263 3604 3467 12264 3564 3429 12265 3609 3472 12266 3610 3473 12267 3608 3471 12268 3564 3429 12269 3607 3470 12270 3610 3473 12271 3564 3429 12272 3611 3474 12273 3570 3435 12274 3571 3436 12275 3611 3474 12276 3607 3470 12277 3570 3435 12278 3612 3475 12279 3571 3436 12280 3572 3437 12281 3612 3475 12282 3611 3474 12283 3571 3436 12284 3613 3476 12285 3572 3437 12286 3573 3438 12287 3613 3476 12288 3612 3475 12289 3572 3437 12290 3614 3477 12291 3573 3438 12292 3574 3439 12293 3614 3477 12294 3613 3476 12295 3573 3438 12296 3615 3478 12297 3574 3439 12298 3577 3442 12299 3615 3478 12300 3614 3477 12301 3574 3439 12302 3616 3479 12303 3617 3480 12304 3577 3442 12305 3618 3481 12306 3577 3442 12307 3617 3480 12308 3619 3482 12309 3616 3479 12310 3577 3442 12311 3581 3446 12312 3619 3482 12313 3577 3442 12314 3618 3481 12315 3615 3478 12316 3577 3442 12317 3620 3483 12318 3621 3484 12319 3617 3480 12320 3622 3485 12321 3623 3485 12322 3624 3485 12323 3616 3479 12324 3620 3483 12325 3617 3480 12326 3625 3486 12327 3618 3481 12328 3617 3480 12329 3626 3487 12330 3625 3486 12331 3617 3480 12332 3622 3488 12333 3627 3488 12334 3623 3488 12335 3620 3483 12336 3628 3489 12337 3621 3484 12338 3629 3490 12339 3630 3491 12340 3631 3492 12341 3622 3493 12342 3624 3493 12343 3632 3493 12344 3633 3494 12345 3631 3492 12346 3634 3495 12347 3629 3490 12348 3631 3492 12349 3633 3494 12350 3635 3496 12351 3634 3495 12352 3636 3497 12353 3633 3494 12354 3634 3495 12355 3635 3496 12356 3637 3498 12357 3636 3497 12358 3638 3499 12359 3635 3496 12360 3636 3497 12361 3637 3498 12362 3639 3500 12363 3638 3499 12364 3583 3448 12365 3637 3498 12366 3638 3499 12367 3639 3500 12368 3639 3500 12369 3583 3448 12370 3582 3447 12371 3640 3501 12372 3641 3502 12373 3642 3503 12374 3605 3504 12375 3606 3504 12376 3643 3504 12377 3605 3505 12378 3643 3505 12379 3644 3505 12380 3645 3506 12381 3642 3503 12382 3646 3507 12383 3640 3501 12384 3642 3503 12385 3645 3506 12386 3647 3508 12387 3610 3473 12388 3607 3470 12389 3648 3509 12390 3646 3507 12391 3649 3510 12392 3648 3509 12393 3645 3506 12394 3646 3507 12395 3650 3511 12396 3607 3470 12397 3611 3474 12398 3651 3512 12399 3647 3508 12400 3607 3470 12401 3652 3513 12402 3651 3512 12403 3607 3470 12404 3653 3514 12405 3652 3513 12406 3607 3470 12407 3650 3511 12408 3653 3514 12409 3607 3470 12410 3654 3515 12411 3611 3474 12412 3612 3475 12413 3654 3515 12414 3650 3511 12415 3611 3474 12416 3655 3516 12417 3612 3475 12418 3613 3476 12419 3656 3517 12420 3654 3515 12421 3612 3475 12422 3655 3516 12423 3656 3517 12424 3612 3475 12425 3657 3518 12426 3613 3476 12427 3614 3477 12428 3657 3518 12429 3655 3516 12430 3613 3476 12431 3658 3519 12432 3614 3477 12433 3615 3478 12434 3659 3520 12435 3657 3518 12436 3614 3477 12437 3658 3519 12438 3659 3520 12439 3614 3477 12440 3660 3521 12441 3615 3478 12442 3618 3481 12443 3660 3521 12444 3658 3519 12445 3615 3478 12446 3661 3522 12447 3662 3523 12448 3663 3524 12449 3664 3525 12450 3660 3521 12451 3618 3481 12452 3665 3526 12453 3664 3525 12454 3618 3481 12455 3666 3527 12456 3667 3528 12457 3662 3523 12458 3661 3522 12459 3668 3529 12460 3662 3523 12461 3666 3527 12462 3662 3523 12463 3668 3529 12464 3626 3487 12465 3669 3530 12466 3625 3486 12467 3661 3522 12468 3663 3524 12469 3670 3531 12470 3671 3532 12471 3672 3532 12472 3627 3532 12473 3661 3522 12474 3670 3531 12475 3673 3533 12476 3671 3534 12477 3627 3534 12478 3622 3534 12479 3674 3535 12480 3649 3510 12481 3675 3536 12482 3674 3535 12483 3648 3509 12484 3649 3510 12485 3676 3537 12486 3677 3538 12487 3678 3539 12488 3679 3540 12489 3677 3540 12490 3676 3540 12491 3680 3541 12492 3675 3541 12493 3681 3541 12494 3674 3535 12495 3675 3536 12496 3680 3542 12497 3682 3543 12498 3678 3539 12499 3683 3544 12500 3676 3537 12501 3678 3539 12502 3682 3543 12503 3684 3545 12504 3683 3544 12505 3685 3546 12506 3682 3543 12507 3683 3544 12508 3684 3545 12509 3686 3547 12510 3685 3546 12511 3687 3548 12512 3684 3545 12513 3685 3546 12514 3686 3547 12515 3688 3549 12516 3687 3548 12517 3689 3550 12518 3690 3551 12519 3687 3548 12520 3688 3549 12521 3686 3547 12522 3687 3548 12523 3690 3551 12524 3691 3552 12525 3689 3550 12526 3692 3553 12527 3688 3549 12528 3689 3550 12529 3691 3552 12530 3693 3554 12531 3692 3553 12532 3694 3555 12533 3695 3556 12534 3692 3553 12535 3693 3554 12536 3691 3552 12537 3692 3553 12538 3695 3556 12539 3696 3557 12540 3694 3555 12541 3697 3558 12542 3693 3554 12543 3694 3555 12544 3696 3557 12545 3698 3559 12546 3697 3558 12547 3699 3560 12548 3700 3561 12549 3697 3558 12550 3698 3559 12551 3696 3557 12552 3697 3558 12553 3700 3561 12554 3701 3562 12555 3699 3560 12556 3702 3563 12557 3698 3559 12558 3699 3560 12559 3701 3562 12560 3703 3564 12561 3702 3563 12562 3704 3565 12563 3701 3562 12564 3702 3563 12565 3703 3564 12566 3705 3566 12567 3706 3567 12568 3667 3528 12569 3707 3568 12570 3703 3564 12571 3704 3565 12572 3708 3569 12573 3705 3566 12574 3667 3528 12575 3709 3570 12576 3708 3569 12577 3667 3528 12578 3710 3571 12579 3709 3570 12580 3667 3528 12581 3666 3527 12582 3710 3571 12583 3667 3528 12584 3711 3572 12585 3506 3572 12586 3509 3572 12587 3712 3573 12588 3713 3573 12589 3714 3573 12590 3715 3574 12591 3716 3574 12592 3717 3574 12593 3715 3575 12594 3718 3575 12595 3716 3575 12596 3719 3576 12597 3716 3576 12598 3718 3576 12599 3720 3577 12600 3713 3577 12601 3712 3577 12602 3721 3578 12603 3713 3578 12604 3720 3578 12605 3722 3579 12606 3717 3579 12607 3723 3579 12608 3722 3580 12609 3715 3580 12610 3717 3580 12611 3724 3581 12612 3723 3581 12613 3725 3581 12614 3724 3582 12615 3722 3582 12616 3723 3582 12617 3726 3583 12618 3725 3583 12619 3727 3583 12620 3726 3584 12621 3724 3584 12622 3725 3584 12623 3728 3585 12624 3726 3585 12625 3727 3585 12626 3729 3586 12627 3728 3586 12628 3727 3586 12629 3730 3587 12630 3731 3587 12631 3732 3587 12632 3733 3588 12633 3734 3589 12634 3735 3590 12635 3736 3591 12636 3730 3591 12637 3732 3591 12638 3737 3592 12639 3736 3592 12640 3732 3592 12641 3738 3593 12642 3734 3589 12643 3733 3588 12644 3739 3594 12645 3740 3594 12646 3731 3594 12647 3741 3595 12648 3735 3590 12649 3742 3596 12650 3730 3597 12651 3739 3597 12652 3731 3597 12653 3733 3588 12654 3735 3590 12655 3741 3595 12656 3743 3598 12657 3744 3598 12658 3740 3598 12659 3745 3599 12660 3746 3600 12661 3703 3564 12662 3739 3601 12663 3743 3601 12664 3740 3601 12665 3741 3595 12666 3742 3596 12667 3747 3602 12668 3748 3603 12669 3749 3603 12670 3744 3603 12671 3743 3604 12672 3748 3604 12673 3744 3604 12674 3745 3599 12675 3703 3564 12676 3707 3568 12677 3750 3605 12678 3751 3605 12679 3749 3605 12680 3748 3606 12681 3750 3606 12682 3749 3606 12683 3752 3607 12684 3753 3607 12685 3751 3607 12686 3750 3608 12687 3752 3608 12688 3751 3608 12689 3754 3609 12690 3755 3609 12691 3753 3609 12692 3752 3610 12693 3754 3610 12694 3753 3610 12695 3756 3611 12696 3757 3611 12697 3755 3611 12698 3754 3612 12699 3756 3612 12700 3755 3612 12701 3756 3613 12702 3758 3613 12703 3757 3613 12704 3759 3614 12705 3760 3615 12706 3761 3616 12707 3762 3617 12708 3679 3617 12709 3676 3617 12710 3759 3614 12711 3763 3618 12712 3760 3615 12713 3759 3614 12714 3761 3616 12715 3764 3619 12716 3737 3620 12717 3765 3620 12718 3736 3620 12719 3648 3509 12720 3766 3621 12721 3645 3506 12722 3759 3614 12723 3764 3619 12724 3767 3622 12725 3768 3623 12726 3769 3623 12727 3765 3623 12728 3737 3624 12729 3768 3624 12730 3765 3624 12731 3770 3625 12732 3771 3625 12733 3769 3625 12734 3768 3626 12735 3770 3626 12736 3769 3626 12737 3772 3627 12738 3773 3627 12739 3771 3627 12740 3770 3628 12741 3772 3628 12742 3771 3628 12743 3774 3629 12744 3775 3629 12745 3773 3629 12746 3772 3630 12747 3774 3630 12748 3773 3630 12749 3776 3631 12750 3777 3631 12751 3775 3631 12752 3774 3632 12753 3776 3632 12754 3775 3632 12755 3778 3633 12756 3779 3633 12757 3777 3633 12758 3776 3634 12759 3778 3634 12760 3777 3634 12761 3780 3635 12762 3781 3635 12763 3779 3635 12764 3778 3636 12765 3780 3636 12766 3779 3636 12767 3782 3637 12768 3783 3637 12769 3781 3637 12770 3780 3638 12771 3782 3638 12772 3781 3638 12773 3719 3639 12774 3718 3639 12775 3783 3639 12776 3782 3640 12777 3719 3640 12778 3783 3640 12779 3784 3641 12780 3785 3641 12781 3786 3641 12782 3553 3642 12783 3787 3642 12784 3547 3642 12785 3788 3643 12786 3786 3643 12787 3789 3643 12788 3784 3644 12789 3786 3644 12790 3788 3644 12791 3729 3645 12792 3790 3645 12793 3728 3645 12794 3791 3646 12795 3792 3646 12796 3790 3646 12797 3729 3647 12798 3791 3647 12799 3790 3647 12800 3791 3648 12801 3793 3648 12802 3792 3648 12803 3794 3649 12804 3795 3650 12805 3796 3651 12806 3797 3652 12807 3798 3653 12808 3799 3654 12809 3800 3655 12810 3794 3649 12811 3796 3651 12812 3801 3656 12813 3800 3655 12814 3796 3651 12815 3802 3657 12816 3803 3657 12817 3804 3657 12818 3805 3658 12819 3802 3658 12820 3804 3658 12821 3806 3659 12822 3805 3659 12823 3804 3659 12824 3794 3649 12825 3807 3660 12826 3795 3650 12827 3808 3661 12828 3799 3654 12829 3809 3662 12830 3810 3663 12831 3797 3652 12832 3799 3654 12833 3811 3664 12834 3810 3663 12835 3799 3654 12836 3808 3661 12837 3811 3664 12838 3799 3654 12839 3794 3649 12840 3812 3665 12841 3807 3660 12842 3813 3666 12843 3809 3662 12844 3814 3667 12845 3813 3666 12846 3808 3661 12847 3809 3662 12848 3794 3668 12849 3815 3668 12850 3812 3668 12851 3816 3669 12852 3814 3667 12853 3817 3670 12854 3818 3671 12855 3813 3666 12856 3814 3667 12857 3816 3669 12858 3818 3671 12859 3814 3667 12860 3819 3672 12861 3820 3672 12862 3821 3672 12863 3822 3673 12864 3816 3669 12865 3817 3670 12866 3823 3674 12867 3794 3649 12868 3800 3655 12869 3819 3675 12870 3821 3675 12871 3824 3675 12872 3801 3656 12873 3825 3676 12874 3800 3655 12875 3826 3677 12876 3800 3655 12877 3825 3676 12878 3827 3678 12879 3828 3679 12880 3800 3655 12881 3823 3674 12882 3800 3655 12883 3828 3679 12884 3829 3680 12885 3827 3678 12886 3800 3655 12887 3830 3681 12888 3829 3680 12889 3800 3655 12890 3831 3682 12891 3830 3681 12892 3800 3655 12893 3832 3683 12894 3831 3682 12895 3800 3655 12896 3826 3677 12897 3832 3683 12898 3800 3655 12899 3833 3684 12900 3834 3685 12901 3825 3676 12902 3835 3686 12903 3825 3676 12904 3834 3685 12905 3836 3687 12906 3833 3684 12907 3825 3676 12908 3801 3656 12909 3836 3687 12910 3825 3676 12911 3837 3688 12912 3826 3677 12913 3825 3676 12914 3838 3689 12915 3837 3688 12916 3825 3676 12917 3835 3686 12918 3838 3689 12919 3825 3676 12920 3839 3690 12921 3840 3691 12922 3834 3685 12923 3841 3692 12924 3834 3685 12925 3840 3691 12926 3842 3693 12927 3839 3690 12928 3834 3685 12929 3843 3694 12930 3842 3693 12931 3834 3685 12932 3844 3695 12933 3843 3694 12934 3834 3685 12935 3845 3696 12936 3844 3695 12937 3834 3685 12938 3833 3684 12939 3845 3696 12940 3834 3685 12941 3846 3697 12942 3835 3686 12943 3834 3685 12944 3841 3692 12945 3846 3697 12946 3834 3685 12947 3847 3698 12948 3848 3699 12949 3840 3691 12950 3849 3700 12951 3840 3691 12952 3848 3699 12953 3850 3701 12954 3847 3698 12955 3840 3691 12956 3839 3690 12957 3850 3701 12958 3840 3691 12959 3849 3700 12960 3841 3692 12961 3840 3691 12962 3851 3702 12963 3852 3703 12964 3848 3699 12965 3853 3704 12966 3848 3699 12967 3852 3703 12968 3847 3698 12969 3851 3702 12970 3848 3699 12971 3854 3705 12972 3849 3700 12973 3848 3699 12974 3853 3704 12975 3854 3705 12976 3848 3699 12977 3855 3706 12978 3856 3707 12979 3852 3703 12980 3857 3708 12981 3852 3703 12982 3856 3707 12983 3858 3709 12984 3855 3706 12985 3852 3703 12986 3859 3710 12987 3858 3709 12988 3852 3703 12989 3860 3711 12990 3859 3710 12991 3852 3703 12992 3851 3702 12993 3860 3711 12994 3852 3703 12995 3861 3712 12996 3853 3704 12997 3852 3703 12998 3862 3713 12999 3861 3712 13000 3852 3703 13001 3857 3708 13002 3862 3713 13003 3852 3703 13004 3855 3706 13005 3863 3714 13006 3856 3707 13007 3864 3715 13008 3865 3715 13009 3866 3715 13010 3867 3716 13011 3857 3708 13012 3856 3707 13013 3868 3717 13014 3867 3716 13015 3856 3707 13016 3869 3718 13017 3868 3717 13018 3856 3707 13019 3870 3719 13020 3869 3718 13021 3856 3707 13022 3870 3719 13023 3856 3707 13024 3871 3720 13025 3871 3720 13026 3872 3721 13027 3870 3719 13028 3864 3722 13029 3873 3722 13030 3865 3722 13031 3874 3723 13032 3875 3724 13033 3876 3725 13034 3864 3726 13035 3866 3726 13036 3877 3726 13037 3878 3727 13038 3876 3725 13039 3879 3728 13040 3880 3729 13041 3876 3725 13042 3878 3727 13043 3874 3723 13044 3876 3725 13045 3880 3729 13046 3881 3730 13047 3879 3728 13048 3882 3731 13049 3883 3732 13050 3879 3728 13051 3881 3730 13052 3878 3727 13053 3879 3728 13054 3883 3732 13055 3884 3733 13056 3882 3731 13057 3885 3734 13058 3881 3730 13059 3882 3731 13060 3884 3733 13061 3886 3735 13062 3887 3735 13063 3888 3735 13064 3884 3733 13065 3885 3734 13066 3889 3736 13067 3890 3737 13068 3889 3736 13069 3885 3734 13070 3891 3738 13071 3888 3738 13072 3892 3738 13073 3893 3739 13074 3888 3739 13075 3891 3739 13076 3894 3740 13077 3888 3740 13078 3893 3740 13079 3895 3741 13080 3888 3741 13081 3894 3741 13082 3886 3742 13083 3888 3742 13084 3895 3742 13085 3896 3743 13086 3897 3744 13087 3898 3745 13088 3899 3746 13089 3897 3744 13090 3896 3743 13091 3891 3747 13092 3892 3747 13093 3900 3747 13094 3901 3748 13095 3898 3745 13096 3902 3749 13097 3896 3743 13098 3898 3745 13099 3901 3748 13100 3903 3750 13101 3902 3749 13102 3904 3751 13103 3901 3748 13104 3902 3749 13105 3903 3750 13106 3905 3752 13107 3904 3751 13108 3906 3753 13109 3903 3750 13110 3904 3751 13111 3905 3752 13112 3905 3752 13113 3906 3753 13114 3907 3754 13115 3908 3755 13116 3907 3754 13117 3909 3756 13118 3905 3752 13119 3907 3754 13120 3908 3755 13121 3910 3757 13122 3909 3756 13123 3911 3758 13124 3908 3755 13125 3909 3756 13126 3910 3757 13127 3912 3759 13128 3911 3758 13129 3913 3760 13130 3910 3757 13131 3911 3758 13132 3912 3759 13133 3914 3761 13134 3915 3761 13135 3803 3761 13136 3912 3759 13137 3913 3760 13138 3916 3762 13139 3917 3763 13140 3803 3763 13141 3802 3763 13142 3917 3764 13143 3914 3764 13144 3803 3764 13145 3918 3765 13146 3919 3766 13147 3920 3767 13148 3819 3768 13149 3824 3768 13150 3921 3768 13151 3922 3769 13152 3819 3769 13153 3921 3769 13154 3923 3770 13155 3920 3767 13156 3924 3771 13157 3925 3772 13158 3920 3767 13159 3923 3770 13160 3918 3765 13161 3920 3767 13162 3925 3772 13163 3926 3773 13164 3924 3771 13165 3927 3774 13166 3923 3770 13167 3924 3771 13168 3926 3773 13169 3928 3775 13170 3927 3774 13171 3929 3776 13172 3926 3773 13173 3927 3774 13174 3928 3775 13175 3930 3777 13176 3929 3776 13177 3931 3778 13178 3932 3779 13179 3929 3776 13180 3930 3777 13181 3928 3775 13182 3929 3776 13183 3932 3779 13184 3933 3780 13185 3931 3778 13186 3934 3781 13187 3930 3777 13188 3931 3778 13189 3935 3782 13190 3933 3780 13191 3935 3782 13192 3931 3778 13193 3936 3783 13194 3934 3781 13195 3937 3784 13196 3936 3783 13197 3933 3780 13198 3934 3781 13199 3938 3785 13200 3939 3786 13201 3940 3787 13202 3936 3783 13203 3937 3784 13204 3941 3788 13205 3942 3789 13206 3940 3787 13207 3943 3790 13208 3944 3791 13209 3940 3787 13210 3942 3789 13211 3945 3792 13212 3938 3785 13213 3940 3787 13214 3944 3791 13215 3945 3792 13216 3940 3787 13217 3946 3793 13218 3943 3790 13219 3947 3794 13220 3942 3789 13221 3943 3790 13222 3946 3793 13223 3948 3795 13224 3947 3794 13225 3949 3796 13226 3946 3793 13227 3947 3794 13228 3948 3795 13229 3950 3797 13230 3949 3796 13231 3951 3798 13232 3952 3799 13233 3949 3796 13234 3950 3797 13235 3948 3795 13236 3949 3796 13237 3952 3799 13238 3953 3800 13239 3951 3798 13240 3954 3801 13241 3950 3797 13242 3951 3798 13243 3953 3800 13244 3953 3800 13245 3954 3801 13246 3955 3802 13247 3956 3803 13248 3955 3802 13249 3957 3804 13250 3956 3803 13251 3953 3800 13252 3955 3802 13253 3958 3805 13254 3959 3806 13255 3960 3807 13256 3958 3805 13257 3961 3808 13258 3959 3806 13259 3962 3809 13260 3957 3804 13261 3963 3810 13262 3962 3809 13263 3956 3803 13264 3957 3804 13265 3964 3811 13266 3960 3807 13267 3965 3812 13268 3964 3811 13269 3958 3805 13270 3960 3807 13271 3966 3813 13272 3965 3812 13273 3967 3814 13274 3966 3813 13275 3968 3815 13276 3965 3812 13277 3969 3816 13278 3965 3812 13279 3968 3815 13280 3970 3817 13281 3964 3811 13282 3965 3812 13283 3969 3816 13284 3970 3817 13285 3965 3812 13286 3971 3818 13287 3967 3814 13288 3972 3819 13289 3973 3820 13290 3967 3814 13291 3971 3818 13292 3966 3813 13293 3967 3814 13294 3973 3820 13295 3974 3821 13296 3972 3819 13297 3975 3822 13298 3976 3823 13299 3972 3819 13300 3974 3821 13301 3971 3818 13302 3972 3819 13303 3976 3823 13304 3977 3824 13305 3975 3822 13306 3978 3825 13307 3974 3821 13308 3975 3822 13309 3977 3824 13310 3979 3826 13311 3978 3825 13312 3980 3827 13313 3977 3824 13314 3978 3825 13315 3979 3826 13316 3864 3828 13317 3981 3828 13318 3873 3828 13319 3979 3826 13320 3980 3827 13321 3982 3829 13322 3983 3830 13323 3984 3831 13324 3985 3832 13325 3917 3833 13326 3802 3833 13327 3986 3833 13328 3797 3652 13329 3984 3831 13330 3983 3830 13331 3810 3663 13332 3984 3831 13333 3797 3652 13334 3987 3834 13335 3988 3834 13336 3989 3834 13337 3990 3835 13338 3989 3835 13339 3991 3835 13340 3990 3836 13341 3987 3836 13342 3989 3836 13343 3992 3837 13344 3993 3837 13345 3988 3837 13346 3994 3838 13347 3995 3838 13348 3993 3838 13349 3992 3839 13350 3994 3839 13351 3993 3839 13352 3996 3840 13353 3992 3840 13354 3988 3840 13355 3987 3841 13356 3996 3841 13357 3988 3841 13358 3997 3842 13359 3991 3842 13360 3998 3842 13361 3997 3843 13362 3990 3843 13363 3991 3843 13364 3999 3844 13365 3998 3844 13366 4000 3844 13367 3999 3845 13368 3997 3845 13369 3998 3845 13370 4001 3846 13371 4000 3846 13372 4002 3846 13373 4001 3847 13374 3999 3847 13375 4000 3847 13376 4003 3848 13377 4002 3848 13378 4004 3848 13379 4003 3849 13380 4001 3849 13381 4002 3849 13382 4005 3850 13383 4004 3850 13384 4006 3850 13385 4005 3851 13386 4003 3851 13387 4004 3851 13388 4005 3852 13389 4006 3852 13390 4007 3852 13391 4008 3853 13392 4007 3853 13393 4009 3853 13394 4008 3854 13395 4005 3854 13396 4007 3854 13397 4010 3855 13398 4011 3855 13399 4012 3855 13400 4013 3856 13401 4014 3857 13402 4015 3858 13403 4016 3859 13404 4010 3859 13405 4012 3859 13406 4017 3860 13407 4016 3860 13408 4012 3860 13409 4018 3861 13410 3969 3861 13411 3968 3861 13412 4019 3862 13413 4020 3862 13414 4011 3862 13415 4021 3863 13416 4015 3858 13417 4022 3864 13418 4010 3865 13419 4019 3865 13420 4011 3865 13421 4023 3866 13422 4015 3858 13423 4021 3863 13424 4024 3867 13425 4015 3858 13426 4023 3866 13427 4013 3856 13428 4015 3858 13429 4024 3867 13430 4025 3868 13431 4026 3868 13432 4020 3868 13433 4027 3869 13434 4022 3864 13435 4028 3870 13436 4019 3871 13437 4025 3871 13438 4020 3871 13439 4021 3863 13440 4022 3864 13441 4027 3869 13442 4029 3872 13443 4030 3872 13444 4026 3872 13445 3956 3803 13446 4031 3873 13447 3953 3800 13448 4025 3874 13449 4029 3874 13450 4026 3874 13451 4032 3875 13452 4027 3869 13453 4028 3870 13454 3956 3876 13455 4033 3876 13456 4031 3876 13457 4032 3875 13458 4028 3870 13459 4034 3877 13460 4029 3878 13461 4035 3878 13462 4030 3878 13463 4036 3879 13464 4037 3879 13465 4035 3879 13466 4029 3880 13467 4036 3880 13468 4035 3880 13469 4038 3881 13470 4039 3882 13471 4040 3883 13472 4041 3884 13473 3944 3884 13474 3942 3884 13475 4042 3885 13476 4040 3883 13477 4043 3886 13478 4044 3887 13479 4040 3883 13480 4042 3885 13481 4038 3881 13482 4040 3883 13483 4044 3887 13484 4045 3888 13485 4043 3886 13486 4046 3889 13487 4045 3888 13488 4042 3885 13489 4043 3886 13490 4017 3890 13491 4047 3890 13492 4016 3890 13493 3933 3780 13494 4048 3891 13495 3935 3782 13496 4049 3892 13497 4048 3892 13498 3933 3892 13499 4050 3893 13500 4045 3888 13501 4046 3889 13502 4051 3894 13503 4052 3894 13504 4047 3894 13505 4017 3895 13506 4051 3895 13507 4047 3895 13508 4053 3896 13509 4054 3896 13510 4052 3896 13511 4051 3897 13512 4053 3897 13513 4052 3897 13514 4055 3898 13515 4056 3898 13516 4054 3898 13517 4053 3899 13518 4055 3899 13519 4054 3899 13520 4057 3900 13521 4058 3900 13522 4056 3900 13523 4055 3901 13524 4057 3901 13525 4056 3901 13526 4059 3902 13527 4060 3902 13528 4058 3902 13529 4057 3903 13530 4059 3903 13531 4058 3903 13532 4061 3904 13533 4062 3904 13534 4060 3904 13535 4059 3905 13536 4061 3905 13537 4060 3905 13538 4063 3906 13539 4009 3906 13540 4062 3906 13541 4061 3907 13542 4063 3907 13543 4062 3907 13544 4063 3908 13545 4008 3908 13546 4009 3908 13547 4064 3909 13548 4065 3909 13549 3995 3909 13550 3994 3910 13551 4064 3910 13552 3995 3910 13553 4066 3911 13554 4067 3911 13555 4065 3911 13556 4064 3912 13557 4066 3912 13558 4065 3912 13559 4066 3913 13560 4068 3913 13561 4067 3913 13562 4069 3914 13563 4070 3915 13564 3889 3736 13565 4069 3914 13566 4071 3916 13567 4070 3915 13568 3890 3737 13569 4069 3914 13570 3889 3736 13571 4013 3856 13572 4024 3867 13573 4072 3917 13574 4038 3881 13575 4044 3887 13576 4073 3918 13577 4032 3919 13578 4034 3919 13579 4074 3919 13580 4050 3893 13581 4075 3920 13582 4045 3888 13583

+
+
+
+
+ + + + + -4.37108e-11 -1.62919e-10 -9.99987e-4 0 -9.99987e-4 -2.98019e-11 4.37108e-11 0 -2.98019e-11 9.99987e-4 -1.62919e-10 -0.6104 0 0 0 1 + + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl new file mode 100644 index 0000000000000000000000000000000000000000..130906df3bec23f23a958664684c702aa13b1102 GIT binary patch literal 6884 zcmb7I32;@_8UDebWoaB5StK9HpvR4(~fjrZasr@J` zU(SH(FHg>yGJagbgq+Ef68cUYpFM7T&Lb&Z9_^X%aPHJG3CSJl|N6|0P@lSxXE$+I zmv0}HRsLGx(9n^+heJC?W%W+~bXaJ_$qtsR_3uP;E>>F&*Jasn>|0fiJO4~+5qk4N zd}!Cw4wkGB@jp3<$S%&Z_ui71aEAR%N~UFfG`L)-60_#@ zZuMNEH92=eXctQ<2t@me)bH6x^^5DMzTh+eTsYJbDs?TK()ny7H}j!k)(4E#zZ3m5 zCC_$7{K>hudGd$b(q0HH%s#hmZS!7MA@iHle!r94<<|y3qE7X{aF_l)Nxgq5Ug23= za@Ut9Pi*2IIW*EbkkZ0oT|C}I4XtE#xU8xA>{lmU+?mVL6-IdcCU=6fJE9ZO%HRyu zoi(4yn&ZxVMkKHm;@Jx93#T|@H=@+yELFkQZM>w1c<;{6F_xkz;*X=e-gn0zODya-X_pi8NRG8Dw^Jx? z(Pihc9ltj$O?2^%%uuT?GgW?f%Zs1WnLl?crj52rR>Xz=(YJ}aXX^9T@-h2+f2(5M z4|-);?7`-f)q?C2_d>y2p^Ds2&e)X8&LBRQ`8k>&TAFA~{#vWwJ3*E4Nn0fmr+MJH zU*)dv{e8agO`=a`kFbrgIPn#2wyLxjoZ?7a zp(H3F(SY&|;brfYl)qS&XR{T{heYn3oU3n?SXbXiqU)~~u>M3prcSfv`-t7l4djf|BH zyRI)gM+bJWp9LXQpYr-@#zp7BOS70q6iswCb(#|SE13uHI3me5MzGHv z%}>@^LZYgepoh53dLY#vzJo#~I+=(iuNJsNXWSLO!ukl6ocl@*`yg86kx#xVSP~PE zcol@it4Jtokx=4I))H?%z5ajMQ|T!p$(I}cXklK#-~IFD|Kc&Pm!jr!?)9jx?(ieJ z%{HnR+at_ASDXWTS0%-|6AlfxBwj@l$v%?pWG&f_s9u9qC;ffSCu*?uE?coEsfoLr zZxLq#M@N3anEmAk`9^K=Zq#YE(bLCUgwL?eB>I|7Z|oL+^^$jMTi3IQ+()9t zi|!9(y!K1`z1ID0)DShtTR_A-l;$Cl2#VY$rp#bO{RTmWHoV59yU^DL? zXnEUuF)+$r_|SZ#_dzO*1)|{IO#Ac7d+eES-m2C6=&lAUD$$Tt)9pRWa;(mM_8Ywq zYKwgkQTwiqx=Zhq%DoTX53J7E2NAWKKPz015&dg)OPE(o1Xnft8?I`d7q!`nl3-k6 zO(gomhIieoY2DP```RnaIM@ea=S1{%^?G+~Qc(Sn)z;{*P$v^{nt5zy9`%~FSGa>W z7djj{Sih8O9RcW};quGu3wX`ES|h*pVR>_FY7u zwY=?4q+N5fQk9(T6=zlwPVQ z?qElbQE4J@2YrJ!G!f_zq(ZcbKwF^|kT=oB<0}J#6YHYpsFR5(Em>IVbILbj7o|ep zL>)$F+Z}0(n>J{%H~r{}jJF7DFwqL`sT0#Txrw&fQ)7RH{WZ~ovDx;jAIsbx2}L2? z!E=!xQO}(*R*QqvRb}cRqYFobR8ifL6SWzgtuk1TTLTw|@aEu+lC`e$MCVUstH2Yb z?t`uWYV_?`aj+6`<;=-edxn*{IWv~l;-SwKw4MNnW^tz<&z=5s?({LMVI-QJetc-X z^<8{7we?@^jMx>;wQo$s?DL;n_kEP4UTNG~;STb^h#_iZCEG`M9^A?EAnxFeGW~IG zN}f8yQ|j8J|DGnKr;?u9oGi{prip8HOcR2T zIRPgNou5VD=20L%a@SLsfy-h3k$5sW9^8_W6i4j1Ve)u0+19r9-M4 z5pUlc#2xIMWUYBedBiaS&y}^FYw;wWSRymd$2DdgmeA{WYtB1F7q}Nqd)_UrYsL{h zWO^|tmM6GF7TFHfG2;lrp8<(P554wu@n$LPaj~a1J7l4kyne0QfHK^{o*GZ`=>;Jx zv=#aWt>7ah=ia~R?lN=cj83dVg*wUKJ`dc%Nl*GxK}b{zjeL9r?$nf|Hjn+!E(}YS zksaw+aUMYZd=8?=nvB>W+5~M?8zEBdV;*Q9(+bgu@p%Yh?z2w@VfE}R4q!@ z1W|UBur8^5B=*tR0pi-Pn9p=w7FbQxfsW8vW+4*Y7g$|{BYimuydN!zy@MR*x z9a-xNAZzU>p9doFTs_y|Nkm8awhBUCDDX~TSB!OqHIE>EU6lgjgX z|BBl4xvpwhMTw3@vS=dTcZ?-j>xzt(nn=ImT&ZKC*ZIoyIU~Fq8^b)%ifCQ4o*#}N zBn#n=#F&0_z<4A2hNThf{=`U(K3VIRROzquq)+rx1aXTIxP$&cKM~#4z<=>N!Pyk; zj{d;6fhgj59j^x3x@dLpRn4;%zp5$J5H-hHgy;ZMiso^3yfbLc(IWgdcDAVWI=?e~ zUE`er>p4yqL_1%eRl1qq8U9k^odNp?^VT}&huf_N{LcFRXE%*ED~SwU`*70Zne$}2 zwV=4E{q(;dH{Kbr_L+#Ct!+>9!Td5Iv4rU54yP_ky; + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b + + 2019-01-16T08:12:43 + 2019-01-16T08:12:43 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.663 0.667 0.674 1 + + + 0.25 0.25 0.25 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + -62.67052 931.9716 14.69951 -60.852 935.2482 18.28853 -62.25659 935.7335 12 -58.87258 934.5645 12 -62.25659 935.7335 12 -60.852 935.2482 18.28853 -63.94472 931.9716 7.398792 -62.70845 937.0785 6.033858 -62.02388 936.506 12 -58.87258 934.5645 12 -62.02388 936.506 12 -62.25659 935.7335 12 -60.56562 931.9716 21.80539 -58.87258 934.5645 24.40083 -58.87258 934.5645 24.40083 -57.65792 931.9716 28.62224 -58.18949 934.4147 26.08606 -58.87258 934.5645 12 -58.87258 934.5645 24.40083 -58.18949 934.4147 26.08606 -57.54951 934.4197 27.46604 -58.06918 934.4053 12 -57.54951 934.4197 27.46604 -56.96586 934.5469 28.58106 -57.25921 934.4682 12 -56.96586 934.5469 28.58106 -53.98598 931.9716 35.05971 -56.44681 934.7716 29.46158 -56.49779 934.7449 12 -56.44681 934.7716 29.46158 -55.9966 935.0755 30.13236 -55.9966 935.0755 30.13236 -55.62137 935.4405 30.6073 -55.83888 935.2144 12 -55.62137 935.4405 30.6073 -55.32942 935.8418 30.8958 -55.32942 935.8418 30.8958 -55.12098 936.2529 31.02024 -55.32879 935.8438 12 -55.12098 936.2529 31.02024 -54.98164 936.6762 31.00728 -55.00495 936.5888 12 -54.98164 936.6762 31.00728 -53.2886 939.0808 32.3461 -54.90479 937.1342 30.85495 -54.90479 937.1342 30.85495 -54.90255 937.6392 30.53003 -54.893 937.4 12 -54.90255 937.6392 30.53003 -54.99153 938.1626 30.01408 -54.93143 937.8712 12 -54.99153 938.1626 30.01408 -55.17924 938.6789 29.29951 -55.03704 938.3184 12 -55.17924 938.6789 29.29951 -41.28906 964.9195 19.8271 -55.17924 938.6789 29.29951 -53.2886 939.0808 32.3461 -55.21226 938.7459 12 -55.48388 939.1878 27.92171 -42.72776 964.4782 17.71942 -55.48388 939.1878 27.92171 -49.37286 939.0809 38.05603 -51.19286 939.5262 35.29479 -39.66504 965.4011 21.8766 -51.19286 939.5262 35.29479 -49.59845 931.9716 41.03245 -44.8481 939.0809 43.29652 -48.33262 940.1342 38.77003 -44.5535 931.9716 46.46132 -39.77009 939.0809 48.00292 -42.72406 941.3276 44.25068 -45.21295 940.7973 42.00425 -38.91799 931.9716 51.27434 -34.20149 939.0809 52.11716 -37.3836 942.4613 48.27422 -40.11109 941.8822 46.34355 -32.76663 931.9716 55.40773 -28.211 939.0809 55.58849 -31.6243 943.6854 51.62348 -34.55152 943.0639 50.03557 -26.18095 931.9716 58.80668 -21.87248 939.0809 58.3741 -25.52735 944.9815 54.25511 -28.613 944.3261 53.03096 -19.24824 931.9716 61.42616 -15.26416 939.0809 60.43961 -14.5762 945.9179 57.70845 -22.37883 945.651 55.29077 -21.14233 945.9141 55.64122 -12.0604 931.9716 63.23143 -8.467541 939.0809 61.75955 -4.712694 931.9716 64.19858 -1.566466 939.0809 62.31763 -7.82003 945.9179 59.0049 2.697475 931.9716 64.31478 5.353932 939.0809 62.10697 -0.95939 945.9179 59.51311 10.07189 931.9717 63.57849 12.20828 939.0809 61.13018 5.914066 945.9179 59.2263 17.3128 931.9717 61.99946 18.91204 939.0809 59.39929 12.70852 945.9179 58.1483 24.32423 931.9717 59.59864 25.3825 939.0809 56.93566 19.3332 945.9179 56.2935 31.01324 931.9717 56.40785 31.53984 939.0809 53.76969 25.69961 945.9179 53.68669 37.25696 936.9123 50.86442 37.25696 939.0947 49.97259 31.72271 945.9179 50.36269 37.25696 931.9776 52.49203 87 934.5101 37.42399 37.25696 939.0947 49.97259 37.25696 936.9123 50.86442 37.25696 942.9152 48.13413 37.25696 942.9152 48.13413 87 931.8104 38.54377 37.25696 931.9776 52.49203 37.25696 930.6123 52.85218 87 929.0297 39.47208 37.25696 930.6123 52.85218 25.65672 924.6796 60.37168 37.25696 924.6832 53.98956 31.6264 924.6796 57.4698 19.42435 924.6796 62.65542 12.99309 924.6796 64.29765 6.439184 924.6938 65.27893 2.339567 926.6361 65.30867 4.570069 925.8533 65.2967 -6.444386 924.6898 65.27887 0 926.9 65.31265 -2.330073 926.6382 65.3087 -4.545989 925.8649 65.29688 -13.77441 924.6796 64.13481 -20.93515 924.6796 62.16693 -27.82758 924.6796 59.4023 -34.36336 924.6796 55.87635 -40.45874 924.6796 51.63428 -46.03558 924.6796 46.73044 -51.02241 924.6796 41.22768 -55.35532 924.6795 35.19654 -58.97878 924.6795 28.71431 -61.84635 924.6795 21.86407 -63.92127 924.6795 14.73361 -63.01863 937.0126 0 -64.37135 931.9716 0 -65.17697 924.6795 7.414317 -62.67754 937.0852 -6.326257 -64.37135 931.9716 0 -63.01863 937.0126 0 -64.79264 929.9664 0 -63.94465 931.9716 -7.399402 -64.79264 929.9664 0 -47.93976 962.7628 0 -63.01863 937.0126 0 -62.70845 937.0785 6.033858 -47.85824 962.791 -2.290539 -63.01863 937.0126 0 -47.93976 962.7628 0 -62.67754 937.0852 -6.326257 -61.78159 937.2755 12 -47.62354 962.8721 4.504169 -61.78159 937.2755 12 -47.86124 962.79 2.248175 -61.78159 937.2755 12 -60.62262 939.1965 12 -47.22624 963.0084 6.749334 -60.62262 939.1965 12 -44.76399 948.7677 33.95393 -51.19286 939.5262 35.29479 -48.33262 940.1342 38.77003 -39.55772 965.4002 22.04029 -47.27775 948.1519 30.93052 -47.27775 948.1519 30.93052 -42.10007 949.4152 36.84221 -45.21295 940.7973 42.00425 -42.10007 949.4152 36.84221 -45.21295 940.7973 42.00425 -42.72406 941.3276 44.25068 -38.28533 950.3464 40.37538 -40.11109 941.8822 46.34355 -37.3836 942.4613 48.27422 -34.13038 951.3438 43.51502 -34.55152 943.0639 50.03557 -31.6243 943.6854 51.62348 -29.6704 952.3931 46.23006 -28.613 944.3261 53.03096 -25.52735 944.9815 54.25511 -24.94227 953.4788 48.49188 -22.37883 945.651 55.29077 -21.14233 945.9141 55.64122 -15.93596 947.0202 56.78635 -19.98495 954.5836 50.2748 -15.93596 947.0202 56.78635 -12.66454 947.7163 57.24101 -6.076632 949.1165 57.55987 -9.373752 948.4148 57.49968 0.496272 950.5112 57.09117 -2.782607 949.8156 57.42374 7.012398 951.9006 55.82592 3.746744 951.2041 56.5619 15.48784 952.3969 53.77119 9.355464 952.3978 55.16907 21.42216 952.3969 51.69435 27.08605 952.3969 48.96489 37.25696 945.939 46.40523 32.40798 952.3969 45.61729 87 937.1297 36.1111 37.25696 945.939 46.40523 37.25696 948.5344 44.70538 87 939.6497 34.61606 37.25696 948.5344 44.70538 -14.83925 955.689 51.55542 -12.66454 947.7163 57.24101 -9.373752 948.4148 57.49968 -9.548305 956.7749 52.31264 -6.076632 949.1165 57.55987 -2.782607 949.8156 57.42374 -4.158053 957.82 52.52753 0.496272 950.5112 57.09117 1.281909 958.8028 52.18364 3.746744 951.2041 56.5619 7.012398 951.9006 55.82592 9.355464 952.3978 55.16907 10.22851 952.5828 54.89579 6.717409 959.7022 51.2677 10.22851 952.5828 54.89579 16.46084 953.9069 52.46221 13.38217 953.2515 53.77348 22.35687 955.1597 49.29885 19.45627 954.5428 50.96928 27.83622 956.3239 45.4541 25.15301 955.7545 47.45801 37.25696 952.4202 41.73136 32.82505 957.3839 40.98546 30.39585 956.8689 43.29315 87 942.0554 32.94503 37.25696 952.4202 41.73136 35.11503 957.8693 38.53786 37.25696 953.6942 40.62818 87 944.3442 31.10175 37.25696 953.6942 40.62818 13.38217 953.2515 53.77348 12.08885 960.4994 49.77082 16.46084 953.9069 52.46221 19.45627 954.5428 50.96928 17.33087 961.1805 47.69044 22.35687 955.1597 49.29885 25.15301 955.7545 47.45801 22.37288 961.7377 45.03258 27.83622 956.3239 45.4541 27.14096 962.1717 41.81409 30.39585 956.8689 43.29315 32.82505 957.3839 40.98546 31.5609 962.4909 38.06404 35.11503 957.8693 38.53786 37.25696 958.3267 35.95722 37.25696 958.3267 35.95722 87 946.4901 29.10347 37.25696 958.3267 35.95722 87 948.4984 26.94602 87 950.3364 24.66879 38.2222 960.8385 32.44842 35.5619 962.7105 33.82387 38.2222 960.8385 32.44842 87 926.2002 40.19765 37.25696 924.6832 53.98956 37.25696 924.1187 54.06272 87 923.3153 40.72205 37.25696 924.1187 54.06272 31.03131 917.2962 58.24987 37.25696 917.4836 54.47854 37.25696 917.2977 54.47851 24.42344 917.2962 61.31464 17.51809 917.2962 63.63258 6.569955 924.5906 65.27736 10.46113 917.3027 65.16557 10.24522 918.699 65.18701 9.47367 920.9277 65.2212 8.225384 922.9263 65.25186 6.546148 924.6096 48.7 6.439184 924.6938 65.27893 4.570069 925.8533 65.2967 6.569955 924.5906 65.27736 4.55936 925.8585 48.7 2.339567 926.6361 65.30867 2.340802 926.6358 48.7 0 926.9 65.31265 0 926.9 48.7 0 926.9 65.31265 -2.330073 926.6382 65.3087 0 926.9 48.7 -2.35033 926.6336 48.7 -4.545989 925.8649 65.29688 -4.583739 925.8466 48.7 -6.444386 924.6898 65.27887 -6.535737 924.6179 65.27778 -6.535737 924.6179 65.27778 -17.40695 917.2962 63.66307 -8.190952 922.9695 65.25251 -9.449559 920.9778 65.22197 -10.23418 918.7477 65.18776 -10.46117 917.3022 65.16556 -24.2082 917.2962 61.39994 -30.72391 917.2962 58.41259 -36.87723 917.2962 54.73627 -42.59559 917.2961 50.41433 -47.81153 917.2961 45.49776 -52.46354 917.2961 40.04455 -56.49674 917.2961 34.11901 -59.86357 917.2961 27.79104 -62.52431 917.2961 21.13528 -64.44758 917.2961 14.23022 -65.59733 924.6795 0 -65.61069 917.296 7.15732 -65.59733 924.6795 0 -65.78135 922.7679 0 -65.16783 924.6795 -7.494164 -65.78135 922.7679 0 87 920.4078 41.03981 37.25696 917.4836 54.47854 87 917.4786 41.14924 37.25696 917.2977 54.47851 31.95196 909.914 57.26283 37.25696 910.7951 54.07674 87 914.5473 41.05097 37.25696 910.7951 54.07674 26.33157 909.914 60.05504 20.47001 909.914 62.29718 14.42094 909.914 63.96871 10.49994 916.4249 48.7 10.46113 917.3027 65.16557 10.24522 918.699 65.18701 10.49991 916.3556 65.15105 10.49991 916.3556 65.15105 10.23089 918.7619 48.7 9.47367 920.9277 65.2212 9.447655 920.9816 48.7 8.225384 922.9263 65.25186 8.194878 922.9645 48.7 37.25696 909.912 53.96154 37.25696 909.912 53.96154 37.25696 904.174 52.84875 87 911.6337 40.74331 37.25696 904.174 52.84875 31.02474 902.6258 56.34881 37.25696 902.6129 52.43338 24.34045 902.6258 59.54213 17.33335 902.6258 61.94577 9.432517 911.7872 65.0809 8.250819 909.9058 65.052 10.09636 902.6258 63.52784 10.22493 914.0124 65.11508 8.230257 909.8798 48.7 8.250819 909.9058 65.052 9.432517 911.7872 65.0809 8.169685 909.8041 65.05044 8.169685 909.8041 65.05044 9.472749 911.8705 48.7 10.22493 914.0124 65.11508 10.24256 914.0894 48.7 87 908.7388 40.22796 37.25696 902.6129 52.43338 31.66401 895.5231 53.61708 37.25696 897.7628 50.81631 87 905.8959 39.50868 37.25696 897.7628 50.81631 25.63868 895.5231 56.74556 19.30857 895.5231 59.19949 12.74893 895.5231 60.94969 4.530846 906.9279 65.00622 2.725466 902.6258 64.26737 6.037742 895.5231 61.97537 6.515366 908.1659 65.02526 -4.554728 906.9393 65.0064 -4.681572 902.6258 64.15455 -0.74522 895.5231 62.26432 -2.332171 906.1623 64.99443 0 905.9 64.99038 2.322807 906.1602 64.9944 -8.253356 909.9091 65.05205 -12.02652 902.6258 63.19086 -7.519323 895.5231 61.81311 -8.204166 909.847 65.0511 -6.549449 908.193 65.02568 -15.41009 909.914 63.73765 -19.21197 902.6258 61.38911 -14.20404 895.5231 60.6271 -22.38371 909.914 61.63545 -26.14261 902.6258 58.77317 -20.71991 895.5231 58.7204 -29.08116 909.914 58.77283 -32.72653 902.6258 55.37776 -26.98948 895.5231 56.11567 -35.41983 909.914 55.1851 -38.87642 902.6258 51.24789 -32.9382 895.5231 52.84387 -41.3215 909.914 50.91653 -44.51071 902.6257 46.43833 -38.49539 895.5231 48.9439 -46.71338 909.914 46.01977 -49.55466 902.6257 41.01289 -43.59496 895.5231 44.46212 -51.52893 909.914 40.55525 -53.94139 902.6257 35.04351 -48.17631 895.5231 39.45179 -55.70875 909.914 34.59038 -57.61272 902.6257 28.60936 -55.34395 898.9819 30.88398 -52.18496 895.5231 33.97249 -54.98893 898.1526 31.01222 -55.13266 898.575 31.01631 -59.20126 909.914 28.19876 -60.51996 902.6257 21.79578 -57.56399 900.3819 27.43669 -55.63959 899.3804 30.58638 -56.01777 899.7417 30.10307 -56.46791 900.0399 29.4279 -56.98489 900.2593 28.54673 -61.96338 909.914 21.45923 -62.62454 902.6257 14.69312 -60.852 899.5518 18.28853 -58.19752 900.3845 26.06759 -58.87258 900.2355 24.40083 -63.96102 909.914 14.45495 -63.89856 902.6257 7.395605 -62.25659 899.0665 12 -65.36458 908.2637 0 -64.32512 902.6257 0 -61.97613 895.5231 6.029772 -65.57407 909.9139 0 -65.16957 909.9139 7.272337 -61.34257 896.2083 12 -61.10149 895.5229 12 -65.14486 909.9139 -7.490384 -64.32512 902.6257 0 -65.36458 908.2637 0 -63.96415 901.1339 0 -63.8987 902.6257 -7.394437 -63.96415 901.1339 0 -65.57407 909.9139 0 -65.97277 915.5043 0 -65.56958 917.296 -7.524658 -65.97277 915.5043 0 -65.99992 917.296 0 -9.456836 911.8373 65.08168 -10.5 916.4029 65.15177 -10.23619 914.0611 65.11582 -9.447655 911.8184 48.7 -8.253356 909.9091 65.05205 -8.204166 909.847 65.0511 -9.456836 911.8373 65.08168 -8.194878 909.8355 48.7 -6.549449 908.193 65.02568 -6.546148 908.1904 48.7 -4.554728 906.9393 65.0064 -2.340802 906.1643 48.7 -2.332171 906.1623 64.99443 -4.55936 906.9416 48.7 0 905.9 64.99038 0 905.9 48.7 0 905.9 64.99038 2.322807 906.1602 64.9944 0 905.9 48.7 2.35033 906.1665 48.7 4.530846 906.9279 65.00622 4.583739 906.9534 48.7 6.515366 908.1659 65.02526 6.581006 908.2183 48.7 37.25696 895.5 49.88296 87 903.0982 38.58416 37.25696 895.5 49.88296 31.89458 888.695 50.14735 37.25696 891.7093 48.04066 87 900.3798 37.46491 37.25696 891.7093 48.04066 26.06389 888.695 53.41061 19.90376 888.695 55.99875 13.49203 888.695 57.87905 6.909759 888.695 59.02774 0.240148 888.695 59.43031 -6.432498 888.695 59.08166 -13.02383 888.695 57.98619 -19.45055 888.695 56.15777 -25.6314 888.695 53.61949 -31.48826 888.695 50.40345 -36.9471 888.6949 46.55029 -41.93892 888.6949 42.10873 -46.40061 888.6949 37.13489 -55.41906 895.7031 28.53016 -55.55694 895.5178 28.11753 -50.27579 888.6949 31.69167 -55.14807 896.1895 29.40755 -54.97671 896.6962 30.08184 -54.89906 897.2094 30.56837 -54.90814 897.701 30.87141 -55.44979 895.6591 12 -55.55694 895.5178 28.11753 -55.41906 895.7031 28.53016 -55.79754 895.2531 27.42539 -55.74558 895.3057 12 -55.79754 895.2531 27.42539 -55.21226 896.0541 12 -55.14807 896.1895 29.40755 -55.03704 896.4816 12 -54.97671 896.6962 30.08184 -54.93143 896.9288 12 -54.89906 897.2094 30.56837 -54.893 897.4 12 -54.90814 897.701 30.87141 -54.98893 898.1526 31.01222 -55.00498 898.2113 12 -55.13266 898.575 31.01631 -55.32887 898.9564 12 -55.34395 898.9819 30.88398 -55.63959 899.3804 30.58638 -55.83901 899.5857 12 -56.01777 899.7417 30.10307 -56.46791 900.0399 29.4279 -56.49795 900.0552 12 -56.98489 900.2593 28.54673 -57.25935 900.3318 12 -57.56399 900.3819 27.43669 -58.06927 900.3947 12 -58.19752 900.3845 26.06759 -58.87258 900.2355 24.40083 -62.25659 899.0665 12 -58.87258 900.2355 24.40083 -60.852 899.5518 18.28853 -58.87258 900.2355 12 -58.87258 900.2355 12 -61.10149 895.5229 12 -62.25659 899.0665 12 -61.34257 896.2083 12 -60.29742 893.3954 12 -58.87258 900.2355 12 -59.05516 888.6949 6.671181 -60.29742 893.3954 12 -62.26875 895.523 0 -62.26875 895.523 0 -61.78846 894.2012 0 -61.88791 895.523 -6.876325 -61.78846 894.2012 0 37.25696 888.6637 46.2833 87 897.7401 36.14891 37.25696 888.6637 46.2833 32.28773 882.2271 45.56723 37.25696 886.1171 44.60159 87 895.1998 34.6478 37.25696 886.1171 44.60159 26.83996 882.2271 48.97434 21.0369 882.2271 51.73314 14.95536 882.2271 53.80712 8.675845 882.2271 55.16882 2.281482 882.2271 55.80021 -4.143081 882.2271 55.69293 -10.5128 882.2271 54.84842 -16.74335 882.2271 53.27784 -22.75226 882.2271 51.00198 -28.45998 882.2271 48.05098 -33.79096 882.2271 44.4639 -38.67463 882.2271 40.28821 -43.04633 882.2271 35.57921 -46.8482 882.2271 30.39922 -53.51547 888.6949 25.84785 -50.02991 882.2271 24.81682 -56.91341 894.5645 24.40083 -56.0787 888.6949 19.67731 -52.54934 882.2271 18.9059 -56.29208 894.8629 26.06296 -58.893 893.8806 18.28789 -57.93308 888.6949 13.25804 -54.37314 882.2271 12.74471 -55.47716 882.2271 6.414815 -59.43077 888.6949 0 -59.43077 888.6949 0 -58.86388 887.5496 0 -59.05517 888.6949 -6.671046 -58.86388 887.5496 0 -56.91341 894.5645 12 -60.29742 893.3954 12 -58.893 893.8806 18.28789 -56.91341 894.5645 12 -56.91341 894.5645 24.40083 -56.91341 894.5645 12 -56.91341 894.5645 24.40083 -56.29208 894.8629 26.06296 -56.0924 895.0005 12 -56.4806 894.7546 12 37.25696 882.1956 41.576 87 892.7752 32.9677 37.25696 882.1956 41.576 33.03694 876.2008 39.58773 37.25696 881.1212 40.64189 87 890.4689 31.1129 37.25696 881.1212 40.64189 28.34891 876.2008 43.06932 23.29728 876.2008 45.99852 17.94684 876.2008 48.33774 12.36622 876.2008 50.057 6.626997 876.2008 51.13423 0.802775 876.2008 51.55562 -5.031743 876.2008 51.31576 -10.80173 876.2008 50.41774 -16.43317 876.2008 48.87306 -21.85383 876.2008 46.70156 -26.99421 876.2008 43.93106 -31.78836 876.2008 40.59711 -36.1748 876.2008 36.74246 -40.09726 876.2008 32.41657 -43.50545 876.2008 27.6749 -46.35564 876.2008 22.57828 -48.61128 876.2008 17.19208 -50.24344 876.2008 11.58537 -55.8468 882.2271 0 -51.23118 876.2008 5.830074 -55.8468 882.2271 0 -55.22585 881.2599 0 -55.47709 882.2271 -6.415464 -55.22585 881.2599 0 37.25696 876.791 36.31565 87 888.3088 29.10226 37.25696 876.791 36.31565 37.25696 876.1665 35.60494 87 886.2891 26.93124 37.25696 876.1665 35.60494 30.21151 870.6917 35.51892 33.96576 870.6917 31.94771 37.25696 873.1555 31.78582 87 884.4432 24.64163 37.25696 873.1555 31.78582 26.08421 870.6917 38.65156 21.63483 870.6917 41.30694 16.91831 870.6917 43.45227 11.99288 870.6917 45.06106 6.919378 870.6917 46.11346 1.760431 870.6917 46.59646 -3.420252 870.6917 46.5041 -8.558705 870.6917 45.83751 -13.59147 870.6917 44.60494 -18.45642 870.6917 42.8216 -23.09347 870.6917 40.50951 -27.44537 870.6917 37.69722 -31.45839 870.6917 34.41946 -35.07554 870.7 30.73776 -36.89781 870.7085 28.53865 -35.30246 870.7638 30.57442 -35.81478 870.8403 30.09145 -36.35129 870.8254 29.41745 -39.82493 870.6917 24.25496 -36.93766 870.6957 28.46606 -42.23521 870.6917 19.76146 -44.14042 870.6917 15.03165 -45.5178 870.6916 10.12209 -51.56184 876.2008 0 -46.35086 870.6916 5.091485 -51.56184 876.2008 0 -50.91846 875.4082 0 -51.23134 876.2008 -5.82867 -50.91846 875.4082 0 37.25696 870.6586 27.98499 74.12786 880.8034 25.49057 37.25696 870.6586 27.98499 36.44896 870.4472 28.6867 36.86367 870.354 27.99563 37.25696 870.205 27.21301 72.0554 878.5068 22.93998 37.25696 870.205 27.21301 73.6902 880.632 25.44933 73.2704 880.3842 25.28748 72.8708 880.0464 24.97885 72.51555 879.6145 24.49606 72.23542 879.098 23.82264 27.24083 865.7687 30.79207 36.01498 870.481 29.28399 35.56452 870.4492 29.77947 35.10453 870.3442 30.15667 34.65559 870.1629 30.39118 34.24197 869.9119 30.46931 33.87297 869.5966 30.38783 33.55815 869.2238 30.1476 30.53138 865.7687 27.5327 23.60455 865.7687 33.66065 19.6687 865.7687 36.10203 15.48323 865.7687 38.08522 11.10125 865.7687 39.58506 6.578382 865.7687 40.5825 1.972024 865.7687 41.06489 -2.659361 865.7687 41.02611 -7.256996 865.7687 40.46665 -11.76253 865.7687 39.39362 -16.11878 865.7687 37.82062 -20.27046 865.7687 35.76762 -24.16488 865.7687 33.26068 -34.83491 870.6105 30.87515 -27.75261 865.7687 30.33162 -34.06479 870.1384 31.01503 -34.4251 870.3994 31.01386 -34.68685 870.5426 12 -35.07554 870.7 30.73776 -35.30246 870.7638 30.57442 -34.83491 870.6105 30.87515 -35.47725 870.7994 12 -35.81478 870.8403 30.09145 -36.30836 870.8296 12 -36.35129 870.8254 29.41745 -36.89781 870.7085 28.53865 -36.93766 870.6957 28.46606 -37.44038 870.4776 27.43188 -37.11742 870.6298 12 -37.44038 870.4776 27.43188 -39.09337 868.6921 21.33566 -37.9595 870.1176 26.06632 -38.42712 869.6093 24.40084 -39.66579 867.9042 18.24251 -40.53142 866.7127 12 -40.14495 867.2447 15.12831 -40.31156 865.7687 8.074136 -39.32033 865.7675 12 -46.62966 870.6916 0 -40.91154 865.7687 4.056867 -46.62966 870.6916 0 -45.99393 870.0655 0 -46.32926 870.6916 -5.28439 -45.99393 870.0655 0 37.28482 870.1914 12 37.25696 870.205 27.21301 36.86367 870.354 27.99563 37.68489 869.9631 26.55007 37.68489 869.9631 26.55007 36.46509 870.444 12 36.44896 870.4472 28.6867 36.01498 870.481 29.28399 35.60842 870.4546 12 35.56452 870.4492 29.77947 35.10453 870.3442 30.15667 34.78369 870.2227 12 34.65559 870.1629 30.39118 34.24197 869.9119 30.46931 34.05735 869.7664 12 33.87297 869.5966 30.38783 33.55815 869.2238 30.1476 33.31307 868.8153 29.76242 33.48864 869.1214 12 33.31307 868.8153 29.76242 33.14242 868.3944 29.25851 33.14242 868.3944 29.25851 33.03994 867.9689 28.65232 33.12548 868.3392 12 33.03994 867.9689 28.65232 33.00065 867.5433 27.95144 33.00065 867.5433 27.95144 33.02167 867.121 27.1588 33 867.481 12 33.02167 867.121 27.1588 33.10222 866.7045 26.27191 33.02567 867.0894 12 33.10222 866.7045 26.27191 33.36269 865.7324 23.94181 33.99432 863.3752 16.7841 33.10222 866.7045 26.27191 33.36269 865.7324 23.94181 34.15203 862.7866 14.39387 34.28388 862.2945 12 33.10222 866.7045 12 33.10222 866.7045 12 27.42559 861.494 21.87118 33.60139 864.8416 21.55367 29.70194 861.494 18.66297 33.60139 864.8416 21.55367 24.80435 861.494 24.80435 21.87118 861.494 27.42559 18.66297 861.494 29.70194 15.22006 861.494 31.60477 11.58574 861.494 33.11015 7.805734 861.494 34.19915 3.927563 861.494 34.85808 0 861.494 35.07865 -3.927563 861.494 34.85808 -7.805734 861.494 34.19915 -11.58574 861.494 33.11015 -15.22006 861.494 31.60477 -18.66297 861.494 29.70194 -21.87118 861.494 27.42559 -33.06299 868.4575 29.4529 -30.98812 865.7687 27.01761 -24.80435 861.494 24.80435 -33.21776 868.9682 30.11537 -33.44975 869.426 30.58758 -33.73841 869.8171 30.88021 -33.57287 866.0828 24.40084 -33.80931 865.7573 23.36403 -27.42559 861.494 21.87118 -33.22749 866.7001 26.10452 -33.04761 867.3137 27.48123 -33.00055 867.9036 28.5843 -33.57287 866.0828 12 -33.80931 865.7573 23.36403 -33.57287 866.0828 24.40084 -29.70194 861.494 18.66297 -34.24095 865.1632 21.32634 -34.24095 865.1632 21.32634 -33.57287 866.0828 12 -33.57287 866.0828 24.40084 -33.22749 866.7001 26.10452 -33.06555 867.2224 12 -33.04761 867.3137 27.48123 -33.25934 866.6259 12 -33 867.846 12 -33.00055 867.9036 28.5843 -33.06299 868.4575 29.4529 -33.11797 868.6786 12 -33.21776 868.9682 30.11537 -33.44975 869.426 30.58758 -33.45975 869.4413 12 -33.73841 869.8171 30.88021 -33.9968 870.0785 12 -34.06479 870.1384 31.01503 -34.4251 870.3994 31.01386 33.99432 863.3752 16.7841 31.60477 861.494 15.22006 34.15203 862.7866 14.39387 33.11015 861.494 11.58574 34.28388 862.2945 12 37.25696 864.2595 12 34.28388 862.2945 12 35.78392 863.2566 12 35.78392 863.2566 12 33.10222 866.7045 12 34.19915 861.494 7.805734 37.25696 864.2595 12 37.25696 863.6765 9.038722 87 877.1889 8.736272 37.25696 864.2595 12 37.25696 863.6765 9.038722 38.51999 864.6065 12 38.51999 864.6065 12 39.78305 864.9536 12 37.25696 863.2579 6.0454 87 876.668 5.851431 37.25696 863.2579 6.0454 34.85808 861.494 3.927563 37.25696 863.0057 3.029343 87 876.3556 2.941395 37.25696 863.0057 3.029343 35.07865 861.494 0 37.25696 862.9214 0 37.25696 862.9214 0 34.85808 861.494 -3.927563 37.25696 862.9214 0 35.07865 861.494 0 37.25696 862.9683 -2.260576 87 876.25 0 37.25696 862.9214 0 37.25696 862.9683 -2.260576 87 876.25 0 31.63372 859.475 0 28.42494 857.9209 -3.202722 31.63372 859.475 0 28.4181 857.9209 3.262946 28.60481 857.9209 0 27.8604 857.9209 6.483296 26.939 857.9209 9.61901 25.66593 857.9209 12.62915 24.0578 857.9209 15.47443 22.1356 857.9209 18.11769 19.92444 857.9209 20.52444 17.45316 857.9209 22.66325 14.75405 857.9209 24.5062 11.86233 857.9209 26.02924 8.815751 857.9209 27.21248 5.654085 857.9209 28.04047 2.419688 857.9235 28.50759 -0.238821 859.1405 31.0125 2.403126 857.9458 28.55565 2.026692 858.3619 29.43459 1.598386 858.6887 30.10704 1.13654 858.9264 30.58659 0.667092 859.0749 30.88267 0.2093909 859.1427 31.01688 -5.655437 857.9209 28.04019 -0.695256 859.0683 30.86961 -1.162168 858.9158 30.5653 -1.619158 858.6755 30.08017 -2.041546 858.3482 29.40608 -2.412744 857.9329 28.52787 2.35033 906.1665 48.7 -2.340802 906.1643 48.7 0 905.9 48.7 -8.816952 857.9209 27.21209 -11.86337 857.9209 26.02876 -14.75494 857.9209 24.50567 -17.45389 857.9209 22.66269 -19.92501 857.9209 20.52388 -22.13604 857.9209 18.11716 -24.05811 857.9209 15.47394 -34.81368 864.3748 18.22994 -31.60477 861.494 15.22006 -25.66613 857.9209 12.62874 -35.29208 863.7163 15.11877 -33.11015 861.494 11.58574 -26.93912 857.9209 9.618685 -34.19915 861.494 7.805734 -27.86046 857.9209 6.483072 -38.14508 864.8933 12 -35.67718 863.1862 12 -34.85808 861.494 3.927563 -28.41811 857.9209 3.262832 -40.51194 865.2965 0 -35.07865 861.494 0 -41.11218 865.7687 0 -40.85104 865.7687 -4.626395 -35.07865 861.494 0 -40.51194 865.2965 0 -34.53894 861.1589 0 -34.85808 861.494 -3.927563 -34.53894 861.1589 0 -41.11218 865.7687 0 -33.57287 866.0828 12 -39.32033 865.7675 12 -38.14508 864.8933 12 -33.25934 866.6259 12 -40.53142 866.7127 12 -35.67718 863.1862 12 -35.67718 863.1862 12 -35.29208 863.7163 15.11877 -34.81368 864.3748 18.22994 28.60481 857.9209 0 25.69459 856.607 0 21.63501 855.0944 -2.43768 25.69459 856.607 0 21.24769 855.0944 4.748893 21.77191 855.0944 0 21.64046 855.0944 2.38887 20.59834 855.0944 7.051571 19.70026 855.0944 9.2691 18.56428 855.0944 11.3747 17.20414 855.0944 13.34294 15.63624 855.0944 15.15006 13.87953 855.0944 16.77424 11.95522 855.0944 18.19586 9.886541 855.0944 19.39776 7.698476 855.0944 20.36542 5.417449 855.0944 21.08716 2.70908 857.4388 27.44651 3 855.0659 21.47125 2.919602 856.8399 26.07576 2.510289 857.7917 12 2.419688 857.9235 28.50759 2.403126 857.9458 28.55565 2.70908 857.4388 27.44651 2.026692 858.3619 29.43459 1.946467 858.4323 12 1.598386 858.6887 30.10704 1.230266 858.8858 12 1.13654 858.9264 30.58659 0.667092 859.0749 30.88267 0.413992 859.1205 12 0.2093909 859.1427 31.01688 -0.238821 859.1405 31.0125 -0.437745 859.117 12 -0.695256 859.0683 30.86961 -1.162168 858.9158 30.5653 -1.251954 858.8759 12 -1.619158 858.6755 30.08017 -1.961929 858.4193 12 -2.041546 858.3482 29.40608 -2.412744 857.9329 28.52787 4.583739 906.9534 48.7 -4.55936 906.9416 48.7 -2.714106 857.4282 27.42281 -2.516978 857.7816 12 -2.714106 857.4282 27.42281 -5.417449 855.0944 21.08716 -2.921121 856.8334 26.06059 -3 856.15 24.40159 -3 855.0659 21.47125 -7.698476 855.0944 20.36542 -9.886541 855.0944 19.39776 -11.95522 855.0944 18.19586 -13.87953 855.0944 16.77424 -15.63624 855.0944 15.15006 -17.20414 855.0944 13.34294 -18.56428 855.0944 11.3747 -19.70026 855.0944 9.2691 -20.59834 855.0944 7.051571 -21.24769 855.0944 4.748893 -28.60481 857.9209 0 -21.64046 855.0944 2.38887 -28.60481 857.9209 0 -28.14731 857.703 0 -28.42494 857.9209 -3.202722 -28.14731 857.703 0 21.77191 855.0944 0 19.49887 854.3461 0 14.57351 853.0501 -1.64204 19.49887 854.3461 0 14.57206 853.0501 1.654893 14.66573 853.0501 0 14.29225 853.0501 3.288647 13.82987 853.0501 4.880392 13.19084 853.0501 6.409797 12.3833 853.0501 7.857324 11.41758 853.0501 9.204483 10.30602 853.0501 10.43406 9.062809 853.0501 11.53036 7.70383 853.0501 12.47938 6.246443 853.0501 13.26898 4.709266 853.0501 13.88909 3 853.0252 14.25964 3 856.15 24.40159 3 856.15 12 3 855.0659 21.47125 3 856.15 24.40159 3 853.9539 17.93332 3 853.9539 17.93332 3 856.15 12 3 856.15 24.40159 2.919602 856.8399 26.07576 2.874678 857.0078 12 14.66573 853.0501 0 13.10844 852.7149 0 7.329081 851.8134 -0.825789 13.10844 852.7149 0 7.190538 851.8134 1.641193 7.375456 851.8134 0 7.329081 851.8134 0.825789 6.96157 851.8134 2.435959 6.645057 851.8134 3.200091 6.244977 851.8134 3.923979 5.766364 851.8134 4.598522 5.215235 851.8134 5.215235 4.598522 851.8134 5.766364 3.923979 851.8134 6.244977 3.200091 851.8134 6.645057 2.435959 851.8134 6.96157 3 852.5695 12 3 853.0252 14.25964 3 852.5695 12 7.375456 851.8134 0 6.587109 851.7296 0 0 851.4 0 6.587109 851.7296 0 0 851.4 0 1.641193 851.8134 7.190538 2.000279 852.5309 12 0.825789 851.8134 7.329081 0 852.5001 12 0 851.8134 7.375456 1.000319 852.5078 12 -1.000319 852.5078 12 -0.825789 851.8134 7.329081 -2.000279 852.5309 12 -1.641193 851.8134 7.190538 -4.709266 853.0501 13.88909 -2.435959 851.8134 6.96157 -3 852.5695 12 -6.246443 853.0501 13.26898 -3.200091 851.8134 6.645057 -7.70383 853.0501 12.47938 -3.923979 851.8134 6.244977 -9.062809 853.0501 11.53036 -4.598522 851.8134 5.766364 -10.30602 853.0501 10.43406 -5.215235 851.8134 5.215235 -11.41758 853.0501 9.204483 -5.766364 851.8134 4.598522 -12.3833 853.0501 7.857324 -6.244977 851.8134 3.923979 -13.19084 853.0501 6.409797 -6.645057 851.8134 3.200091 -13.82987 853.0501 4.880392 -6.96157 851.8134 2.435959 -14.29225 853.0501 3.288647 -7.190538 851.8134 1.641193 -14.57206 853.0501 1.654893 -7.329081 851.8134 0.825789 -14.4222 852.9951 0 -7.375456 851.8134 0 -14.66573 853.0501 0 -14.57351 853.0501 -1.64204 -7.375456 851.8134 0 -14.4222 852.9951 0 -7.255066 851.8 0 -7.329081 851.8134 -0.825789 -7.255066 851.8 0 -14.66573 853.0501 0 -21.41453 854.9707 0 -21.63501 855.0944 -2.43768 -21.41453 854.9707 0 -21.77191 855.0944 0 -3 853.0252 14.25964 -3 856.15 24.40159 -3 853.0252 14.25964 -3 852.5695 12 -3 855.0659 21.47125 -3 853.9539 17.93332 -3 853.9539 17.93332 3 852.5695 12 -3 852.5695 12 -2.000279 852.5309 12 3 856.15 12 -3 856.15 12 -3 856.15 12 2.000279 852.5309 12 -1.000319 852.5078 12 1.000319 852.5078 12 0 852.5001 12 -7.190538 851.8134 -1.641193 -6.96157 851.8134 -2.435959 -6.645057 851.8134 -3.200091 -6.244977 851.8134 -3.923979 -5.766364 851.8134 -4.598522 -5.215235 851.8134 -5.215235 -4.598522 851.8134 -5.766364 -3.923979 851.8134 -6.244977 -3.200091 851.8134 -6.645057 -2.435959 851.8134 -6.96157 -1.641193 851.8134 -7.190538 -0.825789 851.8134 -7.329081 0 851.8134 -7.375456 0.825789 851.8134 -7.329081 1.641193 851.8134 -7.190538 2.435959 851.8134 -6.96157 3.200091 851.8134 -6.645057 3.923979 851.8134 -6.244977 4.598522 851.8134 -5.766364 5.215235 851.8134 -5.215235 5.766364 851.8134 -4.598522 6.244977 851.8134 -3.923979 6.645057 851.8134 -3.200091 6.96157 851.8134 -2.435959 7.190538 851.8134 -1.641193 -65.99992 917.296 0 -6.581006 924.5817 48.7 -8.190952 922.9695 65.25251 -8.230257 922.9202 48.7 -9.449559 920.9778 65.22197 -9.472749 920.9295 48.7 -10.23418 918.7477 65.18776 -10.24256 918.7107 48.7 -10.46117 917.3022 65.16556 -10.5 916.4029 65.15177 -10.49994 916.3751 48.7 -10.23619 914.0611 65.11582 -10.23089 914.0382 48.7 -37.84226 870.2136 12 -37.9595 870.1176 26.06632 -38.42712 869.6093 24.40084 -39.66579 867.9042 18.24251 -38.42712 869.6093 24.40084 -39.09337 868.6921 21.33566 -40.14495 867.2447 15.12831 -40.53142 866.7127 12 -38.42712 869.6093 12 -38.42712 869.6093 12 -33.45975 869.4413 12 -38.42712 869.6093 12 -33.11797 868.6786 12 -33 867.846 12 -33.06555 867.2224 12 -21.77191 855.0944 0 -2.875674 857.0042 12 -2.921121 856.8334 26.06059 -3 856.15 24.40159 -3 856.15 12 -59.46238 941.1162 12 -59.46238 941.1162 12 -57.25921 934.4682 12 -56.91341 940.2355 12 -56.91341 940.2355 22.88183 -59.46238 941.1162 12 -56.91341 940.2355 12 -58.06918 934.4053 12 -46.66674 963.1986 8.983836 -58.39623 940.7478 17.41578 -58.39623 940.7478 17.41578 -56.49779 934.7449 12 -56.4806 940.0454 12 -56.91341 940.2355 22.88183 -56.91341 940.2355 12 -56.4806 940.0454 12 -55.83888 935.2144 12 -56.0924 939.7995 12 -56.35051 939.9731 24.74449 -56.0924 939.7995 12 -55.74558 939.4943 12 -55.87509 939.6199 26.41399 -55.74558 939.4943 12 -55.32879 935.8438 12 -55.44979 939.1409 12 -55.44979 939.1409 12 -55.21226 938.7459 12 -55.00495 936.5888 12 -55.03704 938.3184 12 -54.93143 937.8712 12 -54.893 937.4 12 -44.50112 977.3314 0 -47.93976 962.7628 0 -47.86124 962.79 2.248175 -44.29661 977.3762 -3.791381 -47.85824 962.791 -2.290539 -47.93976 962.7628 0 -44.50112 977.3314 0 -44.29661 977.3762 3.791381 -47.62354 962.8721 4.504169 -47.22624 963.0084 6.749334 -43.68806 977.5079 7.53378 -46.66674 963.1986 8.983836 -45.94218 963.4418 11.20084 -45.94218 963.4418 11.20084 -45.04833 963.737 13.399 -45.04456 966.1377 12 -45.04833 963.737 13.399 -42.68884 977.7186 11.18026 -56.91341 940.2355 22.88183 -43.97847 964.0832 15.57508 -44.04953 965.9978 14.5243 -43.97847 964.0832 15.57508 -55.87509 939.6199 26.41399 -42.87273 965.8325 16.9462 -42.72776 964.4782 17.71942 -56.35051 939.9731 24.74449 -41.52141 965.6425 19.25525 -41.28906 964.9195 19.8271 -39.83607 965.4105 21.65902 -39.66504 965.4011 21.8766 -40.00352 965.4292 21.44097 -40.00352 965.4292 12 -39.66504 965.4011 21.8766 -39.55772 965.4002 22.04029 -39.83607 965.4105 21.65902 -43.36265 956.7775 26.56626 -39.44754 965.4032 22.20199 -39.44754 965.4032 22.20199 -38.84014 965.4942 23.02524 -39.44754 965.4032 22.20199 -43.36265 956.7775 26.56626 -39.14841 965.4321 12 -38.84014 965.4942 23.02524 -41.19537 957.4013 29.13781 -53.35694 939.0655 -32.24349 -41.09028 964.9794 -20.09465 -39.41567 965.4735 -22.16646 -37.60331 978.6867 -21.14724 -39.41567 965.4735 -22.16646 -41.09028 964.9794 -20.09465 -43.3414 956.8244 -26.54257 -41.19536 957.4013 -29.1378 -43.3414 956.8244 -26.54257 -39.41567 965.4735 -22.16646 -37.6587 966.0241 -24.28212 -39.41567 965.4735 -22.16646 -37.60331 978.6867 -21.14724 -37.6587 966.0241 -24.28212 -54.71067 938.7782 -30.09512 -42.57107 964.5269 -17.96529 -39.61511 978.324 -18.02054 -42.57107 964.5269 -17.96529 -57.65056 938.1535 -24.52965 -43.85488 964.1227 -15.80338 -43.85488 964.1227 -15.80338 -44.9534 963.768 -13.60892 -41.32167 977.9957 -14.6882 -44.9534 963.768 -13.60892 -59.97632 937.6593 -18.66554 -45.87407 963.4645 -11.38519 -42.68884 977.7186 -11.18026 -45.87407 963.4645 -11.38519 -61.65904 937.3016 -12.57327 -46.62189 963.2138 -9.138074 -46.62189 963.2138 -9.138074 -47.20038 963.0173 -6.869502 -43.68806 977.5079 -7.53378 -47.20038 963.0173 -6.869502 -47.61177 962.8761 -4.586817 -47.61177 962.8761 -4.586817 -61.65904 937.3016 -12.57327 -62.67024 931.9716 -14.70071 -59.97632 937.6593 -18.66554 -60.565 931.9716 -21.80713 -57.65056 938.1535 -24.52965 -57.65684 931.9716 -28.62444 -54.71067 938.7782 -30.09512 -53.35694 939.0655 -32.24349 -47.26713 948.1753 -30.91868 -51.19286 939.5262 -35.29479 -49.44237 939.0808 -37.96575 -51.19286 939.5262 -35.29479 -53.98431 931.9716 -35.06228 -48.3326 940.1342 -38.77006 -51.19286 939.5262 -35.29479 -47.26713 948.1753 -30.91868 -48.3326 940.1342 -38.77006 -44.76398 948.7677 -33.95392 -35.79095 991.9 -20.12801 -34.4468 979.276 -25.4637 -35.79095 991.9 -20.12801 -37.62725 966.0346 -24.32106 -35.87351 966.6519 -26.51835 -38.06859 991.9 -15.39189 -37.00771 991.9 -17.79149 -38.97531 991.9 -12.92409 -39.72275 991.9 -10.40343 -40.7262 991.9 -5.244555 -40.30683 991.9 -7.84 -40.97774 991.9 -2.632987 -41.0625 991.9 0 -41.0625 991.9 0 35.92845 991.9 -19.88127 -35.79095 991.9 -20.12801 -37.00771 991.9 -17.79149 -34.47204 991.9 -22.31159 34.42625 991.9 -22.38125 -34.47204 991.9 -22.31159 37.25172 991.9 -17.27391 -38.06859 991.9 -15.39189 38.38709 991.9 -14.57941 -38.97531 991.9 -12.92409 39.3263 991.9 -11.81151 -39.72275 991.9 -10.40343 40.06954 991.9 -8.974722 -40.30683 991.9 -7.84 40.60614 991.9 -6.098397 -40.7262 991.9 -5.244555 40.93793 991.9 -3.175976 -40.97774 991.9 -2.632987 41.06209 991.9 -0.258373 -41.0625 991.9 0 -40.97774 991.9 2.632987 -40.97774 991.9 2.632987 -37.62725 966.0346 -24.32106 -38.98367 958.0422 -31.6751 -35.87351 966.6519 -26.51835 -31.19065 991.9 -26.70669 -35.87351 966.6519 -26.51835 -34.4468 979.276 -25.4637 -33.97824 967.3474 -28.75585 -38.98367 958.0422 -31.6751 -35.87351 966.6519 -26.51835 -33.97824 967.3474 -28.75585 -33.0201 991.9 -24.40905 -33.0201 991.9 -24.40905 -33.0201 991.9 -24.40905 32.74561 991.9 -24.77552 -31.19065 991.9 -26.70669 -45.21324 940.7972 -42.00397 -45.21324 940.7972 -42.00397 -42.10005 949.4153 -36.84218 -38.03607 950.4067 -40.58281 -45.21324 940.7972 -42.00397 -42.10005 949.4153 -36.84218 -44.92121 939.0808 -43.22072 -42.7242 941.3276 -44.25056 -42.7242 941.3276 -44.25056 -35.62234 959.0133 -35.07421 37.25696 863.1083 -4.509339 87 876.3579 -2.962667 37.25696 863.1083 -4.509339 34.19915 861.494 -7.805734 37.25696 863.6609 -8.945619 87 876.6737 -5.888951 37.25696 863.6609 -8.945619 33.11015 861.494 -11.58574 37.25696 864.5828 -13.35143 87 877.1993 -8.784898 37.25696 864.5828 -13.35143 31.60477 861.494 -15.22006 37.25696 865.7534 -17.33643 87 877.9334 -11.64655 37.25696 865.7534 -17.33643 35.0945 865.7687 -21.41466 37.25696 865.9014 -17.77122 37.25696 865.9014 -17.77122 29.70194 861.494 -18.66297 32.46177 865.7687 -25.22786 37.25696 869.9598 -26.78343 37.25696 867.6675 -22.23947 27.42559 861.494 -21.87118 29.41667 865.7687 -28.72057 33.90768 870.6916 -32.00929 37.25696 870.6448 -27.962 24.80435 861.494 -24.80435 25.99786 865.7687 -31.84843 30.06173 870.6916 -35.64572 21.87118 861.494 -27.42559 22.2488 865.7687 -34.5717 25.82845 870.6916 -38.82289 18.66297 861.494 -29.70194 18.21709 865.7687 -36.85578 21.26239 870.6916 -41.49983 15.22006 861.494 -31.60477 13.95396 865.7687 -38.67167 16.42236 870.6916 -43.64208 11.58574 861.494 -33.11015 9.513563 865.7687 -39.99629 11.37075 870.6916 -45.22202 7.805734 861.494 -34.19915 4.952311 865.7687 -40.81282 6.172631 870.6916 -46.2193 3.927563 861.494 -34.85808 0.328148 865.7687 -41.11087 0.89498 870.6916 -46.62107 0 861.494 -35.07865 -4.300184 865.7687 -40.88667 -4.394202 870.6916 -46.42215 -3.927563 861.494 -34.85808 -8.873888 865.7687 -40.14306 -9.626768 870.6916 -45.62511 -7.805734 861.494 -34.19915 -13.33486 865.7687 -38.88949 -14.7353 870.6916 -44.24021 -11.58574 861.494 -33.11015 -17.62644 865.7687 -37.14189 -19.65397 870.6916 -42.2853 -15.22006 861.494 -31.60477 -21.69409 865.7687 -34.92245 -24.31941 870.6916 -39.78557 -18.66297 861.494 -29.70194 -25.48616 865.7687 -32.25938 -28.67151 870.6916 -36.77322 -21.87118 861.494 -27.42559 -28.95445 865.7687 -29.18649 -32.65419 870.6916 -33.28707 -24.80435 861.494 -24.80435 -32.05492 865.7687 -25.74283 -36.21614 870.6916 -29.37203 -27.42559 861.494 -21.87118 -34.74818 865.7687 -21.97214 -39.31147 870.6916 -25.07855 -29.70194 861.494 -18.66297 -37.00002 865.7687 -17.92233 -41.90029 870.6916 -20.46195 -31.60477 861.494 -15.22006 -38.78182 865.7687 -13.64484 -43.94924 870.6916 -15.5817 -33.11015 861.494 -11.58574 -40.07095 865.7687 -9.194019 -45.43194 870.6916 -10.50069 -34.19915 861.494 -7.805734 -27.88762 857.9209 -6.365168 -26.9996 857.9209 -9.447568 -25.77204 857.9209 -12.41116 -24.22038 857.9209 -15.21867 -22.36414 857.9209 -17.83481 -20.22665 857.9209 -20.22665 -17.83481 857.9209 -22.36414 -15.21867 857.9209 -24.22038 -12.41116 857.9209 -25.77204 -9.447568 857.9209 -26.9996 -6.365168 857.9209 -27.88762 -3.202722 857.9209 -28.42494 0 857.9209 -28.60481 3.202722 857.9209 -28.42494 6.365168 857.9209 -27.88762 9.447568 857.9209 -26.9996 12.41116 857.9209 -25.77204 15.21867 857.9209 -24.22038 17.83481 857.9209 -22.36414 20.22665 857.9209 -20.22665 22.36414 857.9209 -17.83481 24.22038 857.9209 -15.21867 25.77204 857.9209 -12.41116 26.9996 857.9209 -9.447568 27.88762 857.9209 -6.365168 87 878.8644 -14.43332 37.25696 867.6675 -22.23947 87 879.9959 -17.15091 37.25696 869.9598 -26.78343 87 881.3097 -19.76913 37.25696 870.6448 -27.962 37.25696 872.8857 -31.40689 87 882.799 -22.27482 37.25696 872.8857 -31.40689 37.25696 876.1842 -35.6255 33.01521 876.2008 -39.6058 28.32646 876.2008 -43.08404 23.27457 876.2008 -46.00997 17.92431 876.2008 -48.34607 12.34427 876.2008 -50.06238 6.605977 876.2008 -51.13692 0.782998 876.2008 -51.5559 -5.050019 876.2008 -51.31394 -10.8183 876.2008 -50.41416 -16.44789 876.2008 -48.86809 -21.86662 876.2008 -46.69555 -27.00503 876.2008 -43.92438 -31.79725 876.2008 -40.59012 -36.18183 876.2008 -36.73551 -40.10258 876.2008 -32.40997 -43.50923 876.2008 -27.66894 -46.35811 876.2008 -22.5732 -48.61268 876.2008 -17.18808 -50.24407 876.2008 -11.58262 87 884.4636 -24.66879 37.25696 876.1842 -35.6255 37.25696 876.47 -35.95347 87 886.3017 -26.94602 37.25696 876.47 -35.95347 32.29783 882.2271 -45.56002 37.25696 880.7156 -40.27622 37.25696 882.1907 -41.5719 26.85026 882.2271 -48.96866 21.04718 882.2271 -51.72893 14.96542 882.2271 -53.80429 8.68552 882.2271 -55.16727 2.290619 882.2271 -55.79981 -4.134611 882.2271 -55.69354 -10.5051 882.2271 -54.84987 -16.73649 882.2271 -53.27997 -22.74629 882.2271 -51.00463 -28.45492 882.2271 -48.05396 -33.78679 882.2271 -44.46705 -38.67132 882.2271 -40.29137 -43.04382 882.2271 -35.58222 -46.84642 882.2271 -30.40196 -50.02874 882.2271 -24.81916 -52.54867 882.2271 -18.90774 -54.37284 882.2271 -12.74598 87 888.31 -29.10347 37.25696 880.7156 -40.27622 87 890.4558 -31.10175 37.25696 882.1907 -41.5719 37.25696 885.5974 -44.23245 87 892.7446 -32.94503 37.25696 885.5974 -44.23245 31.89239 888.6949 -50.1487 37.25696 888.6608 -46.28148 26.06169 888.6949 -53.41165 19.90157 888.6949 -55.9995 13.48991 888.6949 -57.87952 6.907735 888.6949 -59.02796 0.238249 888.6949 -59.43029 -6.434249 888.6949 -59.08144 -13.02542 888.6949 -57.98582 -19.45195 888.6949 -56.15726 -25.63261 888.6949 -53.61889 -31.48929 888.6949 -50.40279 -36.94794 888.6949 -46.54961 -41.93958 888.6949 -42.10805 -46.40111 888.6949 -37.13425 -50.27615 888.6949 -31.69109 -53.5157 888.6949 -25.84736 -56.07883 888.6949 -19.67692 -57.93313 888.6949 -13.25777 87 895.1503 -34.61606 37.25696 888.6608 -46.28148 37.25696 891.0592 -47.68733 37.25696 891.0592 -47.68733 31.56795 895.523 -53.67366 37.25696 895.5014 -49.88356 25.44771 895.523 -56.83143 19.01618 895.523 -59.29403 12.35205 895.523 -61.03134 5.536825 895.523 -62.0221 -1.346126 895.523 -62.25419 -8.212612 895.523 -61.72479 -14.97864 895.523 -60.44036 -21.56144 895.523 -58.41662 -27.88051 895.523 -55.67831 -33.85853 895.523 -52.25894 -39.42239 895.523 -48.20033 -44.50403 895.523 -43.55213 -49.0413 895.523 -38.37119 -52.97868 895.523 -32.72089 -56.26802 895.523 -26.67034 -58.86908 895.523 -20.29356 -60.75004 895.523 -13.66854 87 897.6704 -36.1111 37.25696 895.5014 -49.88356 37.25696 897.0153 -50.52113 87 900.2899 -37.42399 37.25696 897.0153 -50.52113 31.00619 902.6257 -56.359 37.25696 902.6172 -52.43459 24.32194 902.6257 -59.54967 17.31523 902.6257 -61.95082 10.07894 902.6257 -63.53059 2.709023 902.6257 -64.26805 -4.696812 902.6257 -64.15342 -12.04037 902.6257 -63.18821 -19.2243 902.6257 -61.38523 -26.15335 902.6257 -58.76839 -32.73564 902.6257 -55.37237 -38.88391 902.6257 -51.24219 -44.51664 902.6257 -46.43264 -49.55915 902.6257 -41.00745 -53.94459 902.6257 -35.03858 -57.61481 902.6257 -28.60515 -60.52115 902.6257 -21.79246 -62.62508 902.6257 -14.69084 87 902.9897 -38.54377 37.25696 902.6172 -52.43459 37.25696 903.3555 -52.63717 87 905.7703 -39.47208 37.25696 903.3555 -52.63717 30.84943 909.9139 -57.86425 37.25696 909.914 -53.96183 24.0378 909.9139 -61.00936 16.91149 909.9139 -63.35582 9.563803 909.9139 -64.8729 2.090914 909.9139 -65.54073 -5.409347 909.9139 -65.35057 -12.83879 909.9139 -64.30493 -20.10017 909.9139 -62.41748 -27.09842 909.9139 -59.71293 -33.74193 909.9139 -56.22669 -39.94373 909.9139 -52.00439 -45.62263 909.9139 -47.10132 -50.70429 909.9139 -41.58164 -55.12219 909.9139 -35.51763 -58.8185 909.9139 -28.98867 -61.74481 909.9139 -22.08021 -63.86285 909.9139 -14.88271 87 908.5998 -40.19765 37.25696 909.914 -53.96183 37.25696 916.6749 -54.47378 87 914.3922 -41.03981 37.25696 916.6749 -54.47378 87 911.4847 -40.72205 30.81978 917.296 -58.36206 37.25696 917.2969 -54.47851 23.96496 917.296 -61.49528 16.79761 917.296 -63.82656 9.411213 917.296 -65.32548 1.902083 917.296 -65.97251 -5.631852 917.296 -65.7592 -13.09234 917.296 -64.68833 -20.3821 917.296 -62.77387 -27.40606 917.296 -60.0408 -34.07262 917.296 -56.52474 -40.29484 917.296 -52.27155 -45.99158 917.296 -47.3367 -51.08856 917.296 -41.78454 -55.5193 917.296 -35.68747 -59.22603 917.296 -29.12502 -62.1604 917.296 -22.18274 -64.28414 917.296 -14.95119 87 917.3215 -41.14924 37.25696 917.2969 -54.47851 30.87833 924.6795 -57.87519 37.25696 923.4138 -54.14566 87 920.2527 -41.05097 37.25696 923.4138 -54.14566 24.06421 924.6795 -61.02395 16.93498 924.6795 -63.37362 9.583977 924.6795 -64.89343 2.10748 924.6795 -65.56346 -5.396614 924.6795 -65.37496 -12.83004 924.6795 -64.33039 -20.09546 924.6795 -62.44343 -27.09774 924.6795 -59.73878 -33.74517 924.6795 -56.25186 -39.95072 924.6795 -52.02835 -45.63312 924.6795 -47.12353 -50.71797 924.6795 -41.60164 -55.13868 924.6795 -35.53498 -58.83736 924.6795 -29.00301 -61.76557 924.6795 -22.09124 -63.88498 924.6795 -14.89019 37.25696 924.6824 -53.98967 37.25696 924.6824 -53.98967 31.02293 931.9716 -56.40255 37.25696 930.0737 -52.98391 87 923.1663 -40.74331 37.25696 930.0737 -52.98391 24.3339 931.9716 -59.59473 17.32226 931.9716 -61.99684 10.08098 931.9716 -63.57707 2.706058 931.9716 -64.31444 -4.70474 931.9716 -64.19918 -12.05317 931.9716 -63.23283 -19.2418 931.9716 -61.42819 -26.17535 931.9716 -58.80919 -32.76188 931.9716 -55.41055 -38.91409 931.9716 -51.27732 -44.5504 931.9716 -46.4643 -49.59611 931.9716 -41.0353 37.25696 931.9782 -52.49187 87 926.0612 -40.22796 37.25696 931.9782 -52.49187 31.5382 939.0808 -53.7707 37.25696 936.5443 -51.00407 87 928.9041 -39.50868 37.25696 936.5443 -51.00407 25.37289 939.0808 -56.93999 18.8938 939.0808 -59.40514 12.18106 939.0808 -61.13565 5.317684 939.0808 -62.11013 -1.611454 939.0808 -62.31653 -8.520665 939.0808 -61.75228 -15.3245 939.0808 -60.42438 -21.93883 939.0808 -58.34924 -28.28185 939.0808 -55.55252 -34.27513 939.0808 -52.06882 -39.84454 939.0808 -47.9412 37.25696 939.0963 -49.97189 87 931.7018 -38.58416 37.25696 939.0963 -49.97189 31.72589 945.9177 -50.36076 37.25696 942.7074 -48.2437 87 934.4202 -37.46491 37.25696 942.7074 -48.2437 25.7025 945.9177 -53.68537 19.33571 945.9177 -56.2927 12.71057 945.9177 -58.14791 5.915605 945.9177 -59.22621 -0.958396 945.9177 -59.51319 -7.819593 945.9177 -59.00502 -14.57631 945.9177 -57.70848 -21.14295 945.914 -55.64105 -28.613 944.3261 -53.03096 -22.37883 945.651 -55.29077 -25.52735 944.9815 -54.25511 -34.55152 943.0639 -50.03557 -31.6243 943.6854 -51.62348 -40.11112 941.8822 -46.34352 -37.38358 942.4613 -48.27424 37.25696 945.9406 -46.40425 87 937.06 -36.14891 37.25696 945.9406 -46.40425 32.40855 952.3968 -45.61698 37.25696 948.4624 -44.75544 87 939.6003 -34.6478 37.25696 948.4624 -44.75544 27.08649 952.3968 -48.96473 21.42247 952.3968 -51.6943 15.48798 952.3968 -53.77123 9.355441 952.3977 -55.16915 3.746761 951.204 -56.56193 7.012432 951.9005 -55.82597 -2.782607 949.8156 -57.42374 0.496278 950.5112 -57.09118 -9.373754 948.4149 -57.49968 -6.076634 949.1165 -57.55986 -15.93596 947.0202 -56.78635 -12.66454 947.7163 -57.24101 -18.40032 954.9287 -50.72861 -21.14295 945.914 -55.64105 -22.37883 945.651 -55.29077 -15.93596 947.0202 -56.78635 -23.72681 953.7529 -48.98193 -25.52735 944.9815 -54.25511 -28.613 944.3261 -53.03096 -28.80595 952.5937 -46.68803 -31.6243 943.6854 -51.62348 -34.55152 943.0639 -50.03557 -33.59058 951.4719 -43.87709 -37.38358 942.4613 -48.27424 -40.11112 941.8822 -46.34352 37.25696 952.4295 -41.72359 87 942.0249 -32.9677 37.25696 952.4295 -41.72359 32.82512 957.3837 -40.98553 35.11508 957.8692 -38.53794 37.25696 953.7031 -40.62019 87 944.3311 -31.1129 37.25696 953.7031 -40.62019 30.39594 956.8688 -43.29321 25.15309 955.7543 -47.45808 27.8363 956.3238 -45.45416 19.45633 954.5427 -50.96934 22.35694 955.1596 -49.29891 13.38223 953.2514 -53.77355 16.46091 953.9068 -52.46228 10.07531 960.2118 -50.4037 9.355441 952.3977 -55.16915 7.012432 951.9005 -55.82597 10.22856 952.5827 -54.89586 10.22856 952.5827 -54.89586 4.333768 959.3186 -51.74123 3.746761 951.204 -56.56193 -1.449783 958.319 -52.4269 0.496278 950.5112 -57.09118 -2.782607 949.8156 -57.42374 -7.207044 957.2369 -52.47407 -6.076634 949.1165 -57.55986 -9.373754 948.4149 -57.49968 -12.87613 956.0983 -51.90079 -12.66454 947.7163 -57.24101 37.25696 958.3267 -35.95722 87 946.4913 -29.10226 37.25696 958.3267 -35.95722 35.31389 962.6988 -34.1157 37.25696 958.3267 -35.95722 35.11508 957.8692 -38.53794 87 948.5109 -26.93124 38.4441 961.3686 -31.62472 38.4441 961.3686 -31.62472 31.01789 962.4559 -38.57167 32.82512 957.3837 -40.98553 30.39594 956.8688 -43.29321 26.25904 962.0984 -42.46797 27.8363 956.3238 -45.45416 25.15309 955.7543 -47.45808 21.12311 961.6089 -45.75723 22.35694 955.1596 -49.29891 19.45633 954.5427 -50.96934 15.69929 960.9793 -48.4079 16.46091 953.9068 -52.46228 13.38223 953.2514 -53.77355 -21.22604 855.0944 -4.844705 -20.55014 855.0944 -7.190805 -19.61581 855.0944 -9.446477 -18.4348 855.0944 -11.58335 -17.02196 855.0944 -13.57456 -15.39506 855.0944 -15.39506 -13.57456 855.0944 -17.02196 -11.58335 855.0944 -18.4348 -9.446477 855.0944 -19.61581 -7.190805 855.0944 -20.55014 -4.844705 855.0944 -21.22604 -2.43768 855.0944 -21.63501 0 855.0944 -21.77191 2.43768 855.0944 -21.63501 4.844705 855.0944 -21.22604 7.190805 855.0944 -20.55014 9.446477 855.0944 -19.61581 11.58335 855.0944 -18.4348 13.57456 855.0944 -17.02196 15.39506 855.0944 -15.39506 17.02196 855.0944 -13.57456 18.4348 855.0944 -11.58335 19.61581 855.0944 -9.446477 20.55014 855.0944 -7.190805 21.22604 855.0944 -4.844705 -14.29802 853.0501 -3.263431 -13.84273 853.0501 -4.843782 -13.21336 853.0501 -6.36322 -12.41782 853.0501 -7.802636 -11.46613 853.0501 -9.143931 -10.37023 853.0501 -10.37023 -9.143931 853.0501 -11.46613 -7.802636 853.0501 -12.41782 -6.36322 853.0501 -13.21336 -4.843782 853.0501 -13.84273 -3.263431 853.0501 -14.29802 -1.64204 853.0501 -14.57351 0 853.0501 -14.66573 1.64204 853.0501 -14.57351 3.263431 853.0501 -14.29802 4.843782 853.0501 -13.84273 6.36322 853.0501 -13.21336 7.802636 853.0501 -12.41782 9.143931 853.0501 -11.46613 10.37023 853.0501 -10.37023 11.46613 853.0501 -9.143931 12.41782 853.0501 -7.802636 13.21336 853.0501 -6.36322 13.84273 853.0501 -4.843782 14.29802 853.0501 -3.263431 87 882.5017 -2.656713 87 876.25 0 87 876.3579 -2.962667 87 882.4942 2.555263 87 876.3556 2.941395 87 876.6737 -5.888951 87 883.2821 -7.806154 87 877.1993 -8.784898 87 877.9334 -11.64655 87 884.8183 -12.78341 87 878.8644 -14.43332 87 879.9959 -17.15091 87 887.0791 -17.48244 87 881.3097 -19.76913 87 890.018 -21.79955 87 882.799 -22.27482 87 884.4636 -24.66879 87 893.5777 -25.6398 87 886.3017 -26.94602 87 897.6411 -28.8901 87 888.31 -29.10347 87 890.4558 -31.10175 87 902.1492 -31.50128 87 892.7446 -32.94503 87 907.0262 -33.42635 87 895.1503 -34.61606 87 914.7573 -34.89903 87 897.6704 -36.1111 87 909.5718 -34.11265 87 912.1499 -34.60385 87 937.06 -36.14891 87 900.2899 -37.42399 87 939.6003 -34.6478 87 917.4 -35 87 934.4202 -37.46491 87 902.9897 -38.54377 87 931.7018 -38.58416 87 905.7703 -39.47208 87 928.9041 -39.50868 87 908.5998 -40.19765 87 926.0612 -40.22796 87 911.4847 -40.72205 87 923.1663 -40.74331 87 914.3922 -41.03981 87 920.2527 -41.05097 87 917.3215 -41.14924 87 922.618 -34.60894 87 942.0249 -32.9677 87 932.6004 -31.52566 87 944.3311 -31.1129 87 927.7251 -33.44159 87 946.4913 -29.10226 87 937.1191 -28.91718 87 948.5109 -26.93124 87 950.3569 -24.64163 87 941.2013 -25.65904 87 950.3569 -24.64163 39.06637 962.8107 -29.20958 87 952.0256 -22.23638 87 943.069 -23.79108 87 952.0256 -22.23638 39.65026 964.1392 -26.71894 87 953.5162 -19.72166 87 944.7825 -21.79878 87 953.5162 -19.72166 40.43379 965.9984 -22.67359 87 954.8287 -17.09739 87 947.7385 -17.45213 87 954.8287 -17.09739 40.59867 966.4183 -21.64164 87 955.9565 -14.37693 87 955.9565 -14.37693 41.20526 968.2026 -16.51845 87 956.8829 -11.59188 87 950.0059 -12.72118 87 956.8829 -11.59188 42.80348 969.1866 -11.24027 87 957.6112 -8.736272 87 957.6112 -8.736272 87 958.132 -5.851431 87 951.5377 -7.718456 87 958.132 -5.851431 43.78722 969.8113 -5.778301 87 958.4445 -2.941395 87 958.4445 -2.941395 44.13534 970.0355 0 87 958.55 0 87 952.3059 -2.555263 87 958.55 0 43.97042 969.9291 3.981252 87 958.55 0 44.13534 970.0355 0 87 958.4421 2.962667 87 952.2984 2.656713 87 958.4421 2.962667 41.06209 991.9 -0.258373 44.13534 970.0355 0 43.78722 969.8113 -5.778301 40.97778 991.9 2.65007 43.97042 969.9291 3.981252 40.60614 991.9 -6.098397 42.80348 969.1866 -11.24027 40.93793 991.9 -3.175976 39.3263 991.9 -11.81151 41.20526 968.2026 -16.51845 40.06954 991.9 -8.974722 38.63683 969.0092 -21.63046 41.20526 968.2026 -16.51845 40.59867 966.4183 -21.64164 38.38709 991.9 -14.57941 37.25172 991.9 -17.27391 38.63683 969.0092 -21.63046 40.43379 965.9984 -22.67359 37.12499 966.4744 -27.86741 39.65026 964.1392 -26.71894 35.32812 969.9661 -26.47102 39.06637 962.8107 -29.20958 33.18815 966.9323 -32.59121 45.40438 968.3001 12 42.61396 969.068 12 40.62145 965.5022 12 87 957.6007 8.784898 45.40438 968.3001 12 48.19501 967.5316 12 48.19501 967.5316 12 72.91872 960.6907 12 46.08581 966.9664 16.09131 48.19501 967.5316 12 40.62145 965.5022 23.59409 40.62145 965.5022 12 46.08581 966.9664 16.09131 42.61396 969.068 12 43.46034 969.6022 8.031613 40.1878 991.9 8.424599 42.61396 969.068 12 43.46034 969.6022 8.031613 42.39053 970.598 12 42.16701 972.128 12 39.48369 991.9 11.2765 42.39053 970.598 12 87 958.1263 5.888951 40.68656 991.9 5.544225 87 958.1263 5.888951 87 951.5179 7.806154 87 957.6007 8.784898 78.69912 959.0812 12 87 956.8666 11.64655 87 956.8666 11.64655 75.80873 959.8865 12 78.34936 957.7759 16.10123 87 955.9356 14.43332 87 949.9818 12.78341 87 955.9356 14.43332 87 954.8042 17.15091 87 954.8042 17.15091 77.89778 956.0905 20.07578 87 953.4903 19.76913 87 947.721 17.48244 87 953.4903 19.76913 76.79188 954.4609 23.50334 87 952.001 22.27482 87 944.7821 21.79955 87 952.001 22.27482 77.24806 954.8805 22.5923 77.62958 955.4229 21.45973 74.77876 953.8752 25.35962 87 950.3364 24.66879 75.26214 953.8785 25.12731 75.7737 953.9685 24.75247 76.29214 954.1596 24.21613 87 941.2223 25.6398 87 948.4984 26.94602 74.32845 953.9431 25.47337 87 937.1589 28.8901 87 946.4901 29.10347 87 944.3442 31.10175 87 932.6508 31.50128 87 942.0554 32.94503 87 927.7739 33.42635 87 939.6497 34.61606 87 920.0427 34.89903 87 937.1297 36.1111 87 925.2282 34.11265 87 922.6502 34.60385 87 897.7401 36.14891 87 934.5101 37.42399 87 895.1998 34.6478 87 917.4 35 87 900.3798 37.46491 87 931.8104 38.54377 87 903.0982 38.58416 87 929.0297 39.47208 87 905.8959 39.50868 87 926.2002 40.19765 87 908.7388 40.22796 87 923.3153 40.72205 87 911.6337 40.74331 87 920.4078 41.03981 87 914.5473 41.05097 87 917.4786 41.14924 87 912.182 34.60894 87 892.7752 32.9677 87 902.1997 31.52566 87 890.4689 31.1129 87 907.0749 33.44159 87 888.3088 29.10226 87 897.6809 28.91718 87 886.2891 26.93124 87 893.5987 25.65904 87 884.4432 24.64163 76.17849 880.6918 24.34911 87 882.7744 22.23638 87 891.731 23.79108 87 882.7744 22.23638 75.6296 880.8662 24.87218 75.09415 880.9315 25.22103 74.59309 880.9053 25.4188 77.61096 879.4105 21.52891 87 881.2838 19.72166 87 890.0175 21.79878 87 881.2838 19.72166 77.20108 879.9714 22.7026 76.71192 880.3966 23.63356 77.89778 878.7095 20.07578 87 879.9713 17.09739 87 887.0616 17.45213 87 879.9713 17.09739 78.34936 877.0242 16.10123 87 878.8435 14.37693 87 878.8435 14.37693 78.69912 875.7188 12 87 877.9171 11.59188 87 884.7941 12.72118 87 877.9171 11.59188 39.78305 864.9536 12 87 877.1889 8.736272 72.91872 874.1093 12 75.80873 874.9135 12 87 883.2623 7.718456 87 876.668 5.851431 39.40809 866.353 17.31022 38.89778 868.2575 12 39.78305 864.9536 12 39.40809 866.353 17.31022 38.89778 868.2575 12 72.56317 875.4363 16.30158 38.89778 868.2575 22.47707 38.89778 868.2575 22.47707 72.10223 877.1566 20.45118 38.56658 869.0343 24.30115 38.89778 868.2575 12 38.89778 868.2575 22.47707 38.56658 869.0343 24.30115 38.03735 869.6831 25.85385 38.55442 869.054 12 38.03735 869.6831 25.85385 72.00103 877.8545 21.82633 38.00112 869.7156 12 72.43317 955.3142 24.33727 39.07763 962.8289 29.17572 39.07763 962.8289 29.17572 72.7469 954.8862 24.83962 73.11013 954.5371 25.1856 73.49979 954.2691 25.39266 73.90462 954.0741 25.48388 72.19092 955.8139 23.66468 39.26716 963.265 28.38879 33.96085 966.8505 31.7571 39.26716 963.265 28.38879 72.10223 957.6434 20.45118 40.1983 965.4209 24.0138 39.64611 965.4066 25.0559 40.1983 965.4209 24.0138 72.00254 956.9905 21.7437 72.04038 956.3765 22.80603 39.12027 965.4888 25.86855 38.63216 965.6561 26.47516 38.19573 965.8941 26.89 37.83159 966.176 27.12593 37.60157 966.4083 27.20705 72.56317 959.3637 16.30158 40.4129 965.4542 23.81777 40.16407 965.4179 12 40.1983 965.4209 24.0138 40.4129 965.4542 23.81777 39.71076 965.403 12 39.64611 965.4066 25.0559 40.62145 965.5022 23.59409 40.62145 965.5022 23.59409 43.58931 966.2975 19.87369 43.58931 966.2975 19.87369 40.62145 965.5022 12 72.10223 957.6434 12 78.69912 959.0812 12 75.80873 959.8865 12 78.34936 957.7759 16.10123 78.69912 959.0812 12 77.89778 956.0905 20.07578 77.89778 956.0905 12 72 956.867 12 77.89778 956.0905 12 72.02568 957.2586 12 72.91872 960.6907 12 72.10223 957.6434 12 72.91872 960.6907 12 72.56317 959.3637 16.30158 72.10223 957.6434 20.45118 72.10223 957.6434 12 72.10223 957.6434 20.45118 72.00254 956.9905 21.7437 72 956.867 12 72.04038 956.3765 22.80603 72.02568 957.2586 12 72.1255 956.0087 12 72.19092 955.8139 23.66468 72.43317 955.3142 24.33727 72.48872 955.2265 12 72.7469 954.8862 24.83962 73.05747 954.5816 12 73.11013 954.5371 25.1856 73.49979 954.2691 25.39266 73.78386 954.1253 12 73.90462 954.0741 25.48388 74.32845 953.9431 25.47337 74.60861 953.8934 12 74.77876 953.8752 25.35962 75.26214 953.8785 25.12731 75.46528 953.904 12 75.7737 953.9685 24.75247 76.28497 954.1567 12 76.29214 954.1596 24.21613 76.79188 954.4609 23.50334 77.00121 954.6325 12 77.24806 954.8805 22.5923 77.55447 955.2941 12 77.62958 955.4229 21.45973 77.89778 956.0905 20.07578 77.89778 956.0905 12 77.89778 878.7095 12 78.69912 875.7188 12 78.34936 877.0242 16.10123 75.80873 874.9135 12 78.69912 875.7188 12 72.10223 877.1566 12 72.91872 874.1093 12 77.89778 878.7095 12 77.89778 878.7095 20.07578 77.89778 878.7095 12 77.89778 878.7095 20.07578 77.61096 879.4105 21.52891 77.55443 879.506 12 77.20108 879.9714 22.7026 77.00112 880.1676 12 76.71192 880.3966 23.63356 76.28482 880.6434 12 76.17849 880.6918 24.34911 75.6296 880.8662 24.87218 75.4651 880.8961 12 75.09415 880.9315 25.22103 74.60842 880.9066 12 74.59309 880.9053 25.4188 74.12786 880.8034 25.49057 73.78369 880.6746 12 73.6902 880.632 25.44933 73.2704 880.3842 25.28748 73.05735 880.2183 12 72.8708 880.0464 24.97885 72.51555 879.6145 24.49606 72.48865 879.5734 12 72.23542 879.098 23.82264 72.12548 878.7912 12 72.0554 878.5068 22.93998 72 877.933 12 72.00103 877.8545 21.82633 72.02568 877.5415 12 72.10223 877.1566 20.45118 72.91872 874.1093 12 72.10223 877.1566 20.45118 72.56317 875.4363 16.30158 72.10223 877.1566 12 72.10223 877.1566 12 39.06854 971.2978 12 40.16407 965.4179 12 39.71076 965.403 12 39.25651 965.4589 12 39.25651 965.4589 12 38.81638 965.5819 12 39.12027 965.4888 25.86855 38.81638 965.5819 12 38.34349 970.9972 12 38.40104 965.771 12 38.63216 965.6561 26.47516 38.40104 965.771 12 38.0188 966.0199 12 38.19573 965.8941 26.89 38.0188 966.0199 12 37.72311 970.5208 12 37.67942 966.3247 12 37.83159 966.176 27.12593 37.67942 966.3247 12 37.24739 969.9008 12 37.38921 966.677 12 37.60157 966.4083 27.20705 37.38921 966.677 12 37.15645 967.0703 12 37.27371 966.8546 27.18171 37.15645 967.0703 12 37.53168 966.4899 27.21825 36.9477 969.1782 12 36.9849 967.4946 12 37.05631 967.294 26.98994 36.9849 967.4946 12 36.8819 967.9364 12 36.90527 967.8017 26.60538 36.8819 967.9364 12 36.845 968.4 12 36.84543 968.3491 26.01167 36.845 968.4 12 36.88938 968.9141 25.19555 36.9477 969.1782 12 37.04524 969.4777 24.13514 37.24739 969.9008 12 37.34121 970.0526 23.52346 37.72311 970.5208 12 37.77733 970.5737 22.67448 38.34349 970.9972 12 38.35449 971.0036 21.56083 39.06854 971.2978 12 40.81229 971.765 16.15338 39.06854 971.2978 12 42.16701 972.128 12 39.06854 971.2978 20.1482 39.06854 971.2978 20.1482 42.16701 972.128 12 38.57771 991.9 14.06498 40.81229 971.765 16.15338 34.69087 991.9 21.96774 37.04524 969.4777 24.13514 37.34121 970.0526 23.52346 36.29096 969.6942 25.20181 36.88938 968.9141 25.19555 37.04524 969.4777 24.13514 33.0201 991.9 24.40905 36.29096 969.6942 25.20181 37.77733 970.5737 22.67448 38.35449 971.0036 21.56083 36.17323 991.9 19.43227 39.06854 971.2978 20.1482 37.46931 991.9 16.79673 37.53168 966.4899 27.21825 37.27371 966.8546 27.18171 31.49897 970.9649 30.72834 37.05631 967.294 26.98994 35.50472 969.9151 26.24573 36.90527 967.8017 26.60538 36.84543 968.3491 26.01167 29.80633 967.2426 35.82531 26.93832 971.9911 34.61316 25.23004 967.537 39.3393 21.95622 972.9058 37.82074 20.32981 967.6899 42.25598 13.9872 973.9084 41.28605 15.20743 967.6693 44.55268 16.69553 973.632 40.30915 8.322786 974.2595 42.73888 9.961332 967.4597 46.22696 11.18933 974.117 42.10017 2.550839 974.3063 43.46033 4.680271 967.0615 47.29352 5.437526 974.3227 43.19189 -0.346035 974.21 43.54728 -0.560375 966.4893 47.77937 -6.14689 973.7741 43.17455 -5.699526 965.7671 47.71856 -3.248987 974.0318 43.45241 -11.92163 973.0198 42.05897 -10.6891 964.9245 47.14784 -9.04347 973.4364 42.71045 -14.70831 972.5491 41.23756 -15.49154 963.9923 46.10362 -19.9874 971.4492 39.12716 -20.0771 963.0009 44.62049 -17.37807 972.0241 40.26586 -22.55959 970.822 37.80541 -24.42127 961.9781 42.73046 -27.4672 969.4639 34.64938 -28.50292 960.9494 40.46336 -25.05984 970.1538 36.31069 -29.77198 968.7487 32.82612 -32.3026 959.9373 37.847 -31.94721 968.0413 30.85648 -35.80223 958.9622 34.90878 -35.87351 966.6519 26.51835 -38.98368 958.0422 31.67511 -33.983 967.3439 28.75098 -38.98368 958.0422 31.67511 -35.87351 966.6519 26.51835 -34.4468 979.276 25.4637 -35.87351 966.6519 26.51835 -33.983 967.3439 28.75098 -36.85497 966.299 25.28302 -34.4468 979.276 25.4637 -36.85497 966.299 25.28302 -35.87351 966.6519 26.51835 -31.17197 991.9 26.72777 -31.94721 968.0413 30.85648 -33.0201 991.9 24.40905 -29.1757 991.9 28.89469 -29.77198 968.7487 32.82612 -27.02589 991.9 30.91426 -27.4672 969.4639 34.64938 -24.73221 991.9 32.77852 -25.05984 970.1538 36.31069 -22.3177 991.9 34.46762 -22.55959 970.822 37.80541 -19.78125 991.9 35.9834 -19.9874 971.4492 39.12716 -17.15159 991.9 37.30857 -17.37807 972.0241 40.26586 -14.42535 991.9 38.4448 -14.70831 972.5491 41.23756 -11.63374 991.9 39.37984 -11.92163 973.0198 42.05897 -8.774662 991.9 40.11348 -9.04347 973.4364 42.71045 -5.877292 991.9 40.63964 -6.14689 973.7741 43.17455 -3.248987 974.0318 43.45241 -2.944813 991.9 40.95619 -0.346035 974.21 43.54728 1.71e-4 991.9 41.06247 2.550839 974.3063 43.46033 2.945151 991.9 40.95617 5.437526 974.3227 43.19189 5.877622 991.9 40.6396 8.322786 974.2595 42.73888 8.774976 991.9 40.11341 11.18933 974.117 42.10017 11.63403 991.9 39.37976 13.9872 973.9084 41.28605 14.42562 991.9 38.44469 16.69553 973.632 40.30915 17.15183 991.9 37.30846 21.95622 972.9058 37.82074 22.31788 991.9 34.46751 26.93832 971.9911 34.61316 19.78146 991.9 35.98328 27.02599 991.9 30.91416 31.49897 970.9649 30.72834 24.73235 991.9 32.77841 31.172 991.9 26.72773 35.50472 969.9151 26.24573 29.17577 991.9 28.89462 -38.30104 965.6892 23.64666 -38.33186 965.6748 12 -38.30104 965.6892 23.64666 -37.62747 966.0345 24.32079 -37.83117 965.9668 24.06906 -37.83117 965.9668 24.06906 -37.41783 966.3266 24.52818 -37.83117 965.9668 24.06906 -37.62747 966.0345 24.32079 -37.61779 966.1359 12 -37.41783 966.3266 24.52818 -37.10533 966.7129 24.8512 -36.71862 967.5179 25.17703 -36.61995 967.95 25.20676 -36.87744 967.1102 25.06113 -40.00352 965.4292 21.44097 -41.52141 965.6425 19.25525 -40.00352 965.4292 21.44097 -40.00352 965.4292 12 -39.16848 971.3708 12 -40.00352 965.4292 12 -39.14841 965.4321 12 -43.70859 972.0089 12 -44.37454 969.0775 12 -45.04456 966.1377 12 -44.04953 965.9978 14.5243 -45.04456 966.1377 12 -42.87273 965.8325 16.9462 -38.34454 971.1311 12 -38.33186 965.6748 12 -37.62484 970.6702 12 -37.61779 966.1359 12 -37.06489 970.026 12 -37.06174 966.7789 12 -37.10533 966.7129 24.8512 -37.06174 966.7789 12 -36.70871 969.2492 12 -36.70785 967.5537 12 -36.71862 967.5179 25.17703 -36.70785 967.5537 12 -36.87744 967.1102 25.06113 -36.586 968.4 12 -36.61995 967.95 25.20676 -36.586 968.4 12 -36.62918 968.9072 24.96719 -36.70871 969.2492 12 -36.58603 968.4136 25.14241 -37.01671 969.9488 24.19589 -37.06489 970.026 12 -36.76635 969.4245 24.65905 -37.3964 970.4508 23.56185 -37.62484 970.6702 12 -37.92157 970.8959 22.74364 -38.34454 971.1311 12 -39.16848 971.3708 20.95294 -39.16848 971.3708 12 -38.89677 971.3198 21.33886 -38.62448 971.2418 21.72152 -43.70859 972.0089 12 -39.16848 971.3708 12 -39.16848 971.3708 20.95294 -39.61511 978.324 18.02054 -39.16848 971.3708 20.95294 -38.89677 971.3198 21.33886 -42.80307 971.8816 14.37518 -40.52716 971.5618 18.86025 -41.74071 971.7323 16.6648 -40.52716 971.5618 18.86025 -38.62448 971.2418 21.72152 -38.62448 971.2418 21.72152 -37.92157 970.8959 22.74364 -37.60331 978.6867 21.14724 -37.60331 978.6867 21.14724 -37.3964 970.4508 23.56185 -37.01671 969.9488 24.19589 -36.76635 969.4245 24.65905 -36.62918 968.9072 24.96719 -36.58603 968.4136 25.14241 -44.37454 969.0775 12 -43.70859 972.0089 12 -42.80307 971.8816 14.37518 -40.7262 991.9 5.244555 -40.30683 991.9 7.84 -41.32168 977.9957 14.6882 -39.72275 991.9 10.40343 -41.74071 971.7323 16.6648 -38.06859 991.9 15.39189 -38.97531 991.9 12.92409 -37.00771 991.9 17.79149 -35.79095 991.9 20.12801 -34.47204 991.9 22.31159 -35.79095 991.9 20.12801 -33.0201 991.9 24.40905 40.97778 991.9 2.65007 -40.7262 991.9 5.244555 40.68656 991.9 5.544225 -40.30683 991.9 7.84 40.1878 991.9 8.424599 -39.72275 991.9 10.40343 39.48369 991.9 11.2765 -38.97531 991.9 12.92409 38.57771 991.9 14.06498 -38.06859 991.9 15.39189 37.46931 991.9 16.79673 -37.00771 991.9 17.79149 36.17323 991.9 19.43227 -35.79095 991.9 20.12801 34.69087 991.9 21.96774 -34.47204 991.9 22.31159 30.90552 991.9 -27.03609 -29.21377 991.9 -28.85643 -31.92681 968.05 -30.87584 -29.21377 991.9 -28.85643 28.90163 991.9 -29.16811 -27.08464 991.9 -30.86237 -29.72438 968.7633 -32.86647 -27.08464 991.9 -30.86237 26.75707 991.9 -31.14769 -24.8064 991.9 -32.72183 -27.37714 969.4906 -34.71581 -24.8064 991.9 -32.72183 24.47146 991.9 -32.97302 -22.41103 991.9 -34.40716 -24.90498 970.1979 -36.40958 -22.41103 991.9 -34.40716 22.06106 991.9 -34.63287 -19.89231 991.9 -35.92117 -22.30995 970.8833 -37.94326 -19.89231 991.9 -35.92117 19.54064 991.9 -36.11423 -17.28246 991.9 -37.24848 -19.62304 971.5346 -39.29775 -17.28246 991.9 -37.24848 16.91199 991.9 -37.41786 -14.59464 991.9 -38.38217 -16.90075 972.1209 -40.4538 -14.59464 991.9 -38.38217 14.2041 991.9 -38.52701 -11.82884 991.9 -39.32237 -14.14937 972.65 -41.41769 -11.82884 991.9 -39.32237 11.41075 991.9 -39.44465 -8.989476 991.9 -40.06464 -11.32973 973.1133 -42.20866 -8.989476 991.9 -40.06464 8.565549 991.9 -40.15898 -6.081171 991.9 -40.60873 -8.424906 973.5129 -42.8258 -6.081171 991.9 -40.60873 5.66666 991.9 -40.66884 -3.155215 991.9 -40.9408 -5.48893 973.84 -43.25378 -3.155215 991.9 -40.9408 2.737826 991.9 -40.97111 -0.2043319 991.9 -41.06113 -2.575804 974.0803 -43.49068 -0.2043319 991.9 -41.06113 0.316042 974.2382 -43.54356 2.737826 991.9 -40.97111 3.183427 974.3176 -43.41699 5.66666 991.9 -40.66884 6.011004 974.3167 -43.11668 8.565549 991.9 -40.15898 11.56782 974.0953 -42.0009 11.41075 991.9 -39.44465 8.804798 974.2412 -42.64482 14.2041 991.9 -38.52701 16.97285 973.6011 -40.19788 16.91199 991.9 -37.41786 19.54064 991.9 -36.11423 22.19472 972.866 -37.68777 22.06106 991.9 -34.63287 24.47146 991.9 -32.97302 27.01438 971.9717 -34.5573 26.75707 991.9 -31.14769 28.90163 991.9 -29.16811 31.41175 970.9822 -30.81403 30.90552 991.9 -27.03609 32.74561 991.9 -24.77552 35.32812 969.9661 -26.47102 34.42625 991.9 -22.38125 35.92845 991.9 -19.88127 -33.0201 991.9 24.40905 33.0201 991.9 24.40905 -31.17197 991.9 26.72777 31.172 991.9 26.72773 -29.1757 991.9 28.89469 29.17577 991.9 28.89462 -27.02589 991.9 30.91426 27.02599 991.9 30.91416 24.73235 991.9 32.77841 -24.73221 991.9 32.77852 22.31788 991.9 34.46751 -22.3177 991.9 34.46762 19.78146 991.9 35.98328 -19.78125 991.9 35.9834 17.15183 991.9 37.30846 -17.15159 991.9 37.30857 14.42562 991.9 38.44469 -14.42535 991.9 38.4448 11.63403 991.9 39.37976 -8.774662 991.9 40.11348 8.774976 991.9 40.11341 -11.63374 991.9 39.37984 -5.877292 991.9 40.63964 5.877622 991.9 40.6396 -2.944813 991.9 40.95619 2.945151 991.9 40.95617 1.71e-4 991.9 41.06247 -31.92681 968.05 -30.87584 -31.90884 960.0444 -38.14375 -29.72438 968.7633 -32.86647 -27.37714 969.4906 -34.71581 -27.86432 961.1144 -40.85266 -24.90498 970.1979 -36.40958 -23.51016 962.1989 -43.16897 -22.30995 970.8833 -37.94326 -19.62304 971.5346 -39.29775 -18.86938 963.2711 -45.05971 -16.90075 972.1209 -40.4538 -13.96751 964.3004 -46.48941 -14.14937 972.65 -41.41769 -11.32973 973.1133 -42.20866 -8.834792 965.2532 -47.4197 -8.424906 973.5129 -42.8258 -3.508899 966.0937 -47.80931 -5.48893 973.84 -43.25378 -2.575804 974.0803 -43.49068 1.961654 966.786 -47.61517 0.316042 974.2382 -43.54356 3.183427 974.3176 -43.41699 7.51393 967.298 -46.79527 6.011004 974.3167 -43.11668 8.804798 974.2412 -42.64482 13.06797 967.6066 -45.31334 11.56782 974.0953 -42.0009 18.52649 967.7036 -43.14523 16.97285 973.6011 -40.19788 23.77808 967.5999 -40.28555 22.19472 972.866 -37.68777 28.70412 967.3267 -36.75288 27.01438 971.9717 -34.5573 31.41175 970.9822 -30.81403 113.5 917.4 35 87 917.4 35 87 912.182 34.60894 113.5 922.618 34.60894 87 920.0427 34.89903 87 917.4 35 113.5 917.4 35 113.5 912.1499 34.60385 87 907.0749 33.44159 113.5 914.7573 34.89903 113.5 907.0262 33.42635 87 902.1997 31.52566 113.5 909.5718 34.11265 113.5 902.1492 31.50128 87 897.6809 28.91718 113.5 897.6411 28.8901 87 893.5987 25.65904 113.5 893.5777 25.6398 87 891.731 23.79108 113.5 890.018 21.79955 87 890.0175 21.79878 113.5 887.0791 17.48244 87 887.0616 17.45213 113.5 884.8183 12.78341 87 884.7941 12.72118 113.5 883.2821 7.806154 87 883.2623 7.718456 113.5 882.5017 2.656713 87 882.4942 2.555263 113.5 882.4942 -2.555263 87 882.5017 -2.656713 113.5 883.2623 -7.718456 87 883.2821 -7.806154 113.5 884.7941 -12.72118 87 884.8183 -12.78341 113.5 887.0616 -17.45213 87 887.0791 -17.48244 113.5 890.0175 -21.79878 87 890.018 -21.79955 113.5 891.731 -23.79108 87 893.5777 -25.6398 113.5 893.5987 -25.65904 87 897.6411 -28.8901 113.5 897.6809 -28.91718 87 902.1492 -31.50128 113.5 902.1997 -31.52566 87 907.0262 -33.42635 113.5 907.0749 -33.44159 87 909.5718 -34.11265 87 912.1499 -34.60385 113.5 912.182 -34.60894 87 914.7573 -34.89903 87 917.4 -35 113.5 917.4 -35 87 917.4 -35 87 922.618 -34.60894 113.5 917.4 -35 113.5 922.6502 -34.60385 87 927.7251 -33.44159 113.5 920.0427 -34.89903 113.5 927.7739 -33.42635 87 932.6004 -31.52566 113.5 925.2282 -34.11265 113.5 932.6508 -31.50128 87 937.1191 -28.91718 113.5 937.1589 -28.8901 87 941.2013 -25.65904 113.5 941.2223 -25.6398 87 943.069 -23.79108 113.5 944.7821 -21.79955 87 944.7825 -21.79878 113.5 947.721 -17.48244 87 947.7385 -17.45213 113.5 949.9818 -12.78341 87 950.0059 -12.72118 113.5 951.5179 -7.806154 87 951.5377 -7.718456 113.5 952.2984 -2.656713 87 952.3059 -2.555263 113.5 952.3059 2.555263 87 952.2984 2.656713 113.5 951.5377 7.718456 87 951.5179 7.806154 113.5 950.0059 12.72118 87 949.9818 12.78341 113.5 947.7385 17.45213 87 947.721 17.48244 113.5 944.7825 21.79878 87 944.7821 21.79955 113.5 943.069 23.79108 87 941.2223 25.6398 113.5 941.2013 25.65904 87 937.1589 28.8901 113.5 937.1191 28.91718 87 932.6508 31.50128 113.5 932.6004 31.52566 87 927.7739 33.42635 113.5 927.7251 33.44159 87 925.2282 34.11265 87 922.6502 34.60385 113.5 922.618 34.60894 113.5 917.4 35 113.5 914.7573 34.89903 113.5 912.1499 34.60385 113.5 909.5718 34.11265 113.5 927.7251 33.44159 113.5 907.0262 33.42635 113.5 932.6004 31.52566 113.5 902.1492 31.50128 113.5 937.1191 28.91718 113.5 897.6411 28.8901 113.5 941.2013 25.65904 113.5 893.5777 25.6398 113.5 943.069 23.79108 113.5 890.018 21.79955 113.5 944.7825 21.79878 113.5 887.0791 17.48244 113.5 947.7385 17.45213 113.5 884.8183 12.78341 113.5 950.0059 12.72118 113.5 883.2821 7.806154 113.5 951.5377 7.718456 113.5 882.5017 2.656713 113.5 952.3059 2.555263 113.5 882.4942 -2.555263 113.5 952.2984 -2.656713 113.5 883.2623 -7.718456 113.5 951.5179 -7.806154 113.5 884.7941 -12.72118 113.5 949.9818 -12.78341 113.5 887.0616 -17.45213 113.5 947.721 -17.48244 113.5 890.0175 -21.79878 113.5 944.7821 -21.79955 113.5 891.731 -23.79108 113.5 941.2223 -25.6398 113.5 893.5987 -25.65904 113.5 937.1589 -28.8901 113.5 897.6809 -28.91718 113.5 932.6508 -31.50128 113.5 902.1997 -31.52566 113.5 927.7739 -33.42635 113.5 907.0749 -33.44159 113.5 925.2282 -34.11265 113.5 912.182 -34.60894 113.5 920.0427 -34.89903 113.5 917.4 -35 113.5 922.6502 -34.60385 33.02567 867.0894 12 33 867.481 12 33.12548 868.3392 12 38.55442 869.054 12 33.48864 869.1214 12 38.00112 869.7156 12 34.05735 869.7664 12 37.28482 870.1914 12 34.78369 870.2227 12 36.46509 870.444 12 35.60842 870.4546 12 72.1255 956.0087 12 77.55447 955.2941 12 72.48872 955.2265 12 77.00121 954.6325 12 73.05747 954.5816 12 76.28497 954.1567 12 73.78386 954.1253 12 75.46528 953.904 12 74.60861 953.8934 12 72.02568 877.5415 12 72 877.933 12 72.12548 878.7912 12 77.55443 879.506 12 72.48865 879.5734 12 77.00112 880.1676 12 73.05735 880.2183 12 76.28482 880.6434 12 73.78369 880.6746 12 75.4651 880.8961 12 74.60842 880.9066 12 -58.06927 900.3947 12 -57.25935 900.3318 12 -56.49795 900.0552 12 -56.0924 895.0005 12 -55.83901 899.5857 12 -56.4806 894.7546 12 -55.44979 895.6591 12 -55.32887 898.9564 12 -55.74558 895.3057 12 -55.03704 896.4816 12 -55.00498 898.2113 12 -55.21226 896.0541 12 -54.93143 896.9288 12 -54.893 897.4 12 -33.9968 870.0785 12 -37.84226 870.2136 12 -34.68685 870.5426 12 -37.11742 870.6298 12 -35.47725 870.7994 12 -36.30836 870.8296 12 2.874678 857.0078 12 -2.875674 857.0042 12 -2.516978 857.7816 12 2.510289 857.7917 12 -1.961929 858.4193 12 1.946467 858.4323 12 -1.251954 858.8759 12 1.230266 858.8858 12 -0.437745 859.117 12 0.413992 859.1205 12 2.340802 926.6358 48.7 0 926.9 48.7 -2.35033 926.6336 48.7 4.55936 925.8585 48.7 -4.583739 925.8466 48.7 6.546148 924.6096 48.7 -6.581006 924.5817 48.7 8.194878 922.9645 48.7 -8.230257 922.9202 48.7 9.447655 920.9816 48.7 -9.472749 920.9295 48.7 10.23089 918.7619 48.7 -10.24256 918.7107 48.7 10.49994 916.4249 48.7 -10.49994 916.3751 48.7 10.24256 914.0894 48.7 -10.23089 914.0382 48.7 9.472749 911.8705 48.7 -9.447655 911.8184 48.7 8.230257 909.8798 48.7 -8.194878 909.8355 48.7 6.581006 908.2183 48.7 -6.546148 908.1904 48.7 + + + + + + + + + + -0.9495562 0.220768 0.2227204 -0.9219927 0.2704532 0.2771006 -0.9432824 0.2777786 0.1818174 0.3265271 0.9451879 8.6245e-6 0.3265313 0.9451864 1.08437e-5 0.3265143 0.9451923 1.9721e-6 -0.9688675 0.2207496 0.1120958 -0.9501317 0.2981482 0.09141945 -0.939753 0.2894846 0.1818323 0 0 1 -0.9176561 0.2208017 0.3303846 -0.8920102 0.2600632 0.3697093 0.3265106 0.9451935 0 -0.8736072 0.2207638 0.4336748 -0.8816531 0.2578144 0.3952463 0.3265468 0.945181 5.54474e-6 0.326529 0.9451872 -4.06057e-6 0.09881579 0.9951058 1.6354e-6 -0.871958 0.2578913 0.4161506 0.05946958 0.9982301 1.71316e-5 -0.1145178 0.9934212 -2.57231e-6 -0.8631189 0.2597908 0.4330527 -0.2108436 0.9775199 -2.66747e-5 -0.3090484 0.9510463 3.83705e-7 -0.8179647 0.2207679 0.5312205 -0.8552578 0.2631921 0.4463901 -0.4650145 0.885303 2.17105e-5 -0.4820525 0.8761423 -1.71922e-6 -0.8484326 0.2678231 0.4565449 -0.6321207 0.7748699 -1.70432e-6 -0.8427505 0.2733606 0.4637302 -0.6849763 0.7285653 -3.57839e-5 -0.7572231 0.6531563 1.30944e-6 -0.8383286 0.2794311 0.4681062 -0.8545264 0.5194082 6.90576e-7 -0.8351585 0.2856447 0.4700187 -0.8550952 0.5184711 2.68948e-5 -0.9240216 0.3823406 -1.0652e-6 -0.833064 0.2920654 0.4697898 -0.9629376 0.2697244 5.19217e-5 -0.9704481 0.2413098 3.01981e-7 -0.8074049 0.3285163 0.4900762 -0.8319028 0.2989984 0.4674802 -0.9960677 0.08859634 6.06291e-7 -0.8318439 0.3066685 0.4625908 -1 -8.36604e-6 -1.32562e-6 -0.9968162 -0.07973533 -2.73809e-7 -0.8332081 0.3145795 0.4547573 -0.9878597 -0.1553485 1.44753e-5 -0.9671517 -0.2542001 -2.00793e-6 -0.8360397 0.3224189 0.4439411 -0.9520583 -0.3059167 1.35667e-4 -0.9045794 -0.4263052 1.53668e-6 -0.7304491 0.5406853 0.4172574 -0.7586318 0.5340774 0.3731477 -0.7338224 0.5405681 0.4114498 -0.8936485 -0.4487677 -1.24319e-5 -0.8030444 -0.5959194 -3.28384e-6 -0.7586362 0.533374 0.3741435 -0.7667465 0.531914 0.3593987 -0.7480809 0.3284786 0.5766081 -0.7756435 0.3352659 0.5347654 -0.698704 0.5488461 0.4588909 -0.7066811 0.5475046 0.4481523 -0.7514927 0.220751 0.6217136 -0.6795122 0.3285162 0.6560033 -0.7323107 0.3444555 0.5874279 -0.6750534 0.2207865 0.7039576 -0.6025787 0.3284844 0.7273218 -0.6473343 0.3625195 0.670476 -0.6850411 0.354511 0.6364281 -0.5896676 0.2207941 0.7768797 -0.5182068 0.3284846 0.789658 -0.5664176 0.3797129 0.7314296 -0.6077476 0.3709295 0.7021782 -0.4964585 0.2207252 0.8395293 -0.4274386 0.3284776 0.8422582 -0.479156 0.3982447 0.7821833 -0.523507 0.3888441 0.7581166 -0.3966855 0.2208148 0.8910003 -0.3313854 0.3284909 0.8844645 -0.3867765 0.4178791 0.822059 -0.4335316 0.4079844 0.8034919 -0.2916317 0.220731 0.9307141 -0.2312772 0.3284747 0.9157595 -0.2208526 0.4320882 0.8743707 -0.3390771 0.4280278 0.8377464 -0.3202652 0.4320827 0.843051 -0.182716 0.2206868 0.9580774 -0.1282967 0.3285077 0.9357472 -0.07141047 0.2207954 0.9727025 -0.02374941 0.3286057 0.9441686 -0.1184837 0.4320904 0.8940132 0.0408737 0.2208245 0.9744567 0.08111971 0.3284988 0.9410144 -0.01453751 0.4321002 0.9017085 0.1524618 0.2211509 0.9632486 0.1849594 0.3285529 0.9261983 0.08960723 0.4320864 0.8973696 0.2622245 0.220808 0.9394053 0.286531 0.3285293 0.8999825 0.1925569 0.4320784 0.8810393 0.3685594 0.2207422 0.9030154 0.3846768 0.3281927 0.862736 0.2929493 0.4320198 0.8529593 0.4698172 0.2207278 0.8547228 0.4778465 0.3285012 0.8147084 0.3893924 0.4320769 0.813439 0.5644477 0.2956604 0.7707034 0.5652564 0.3285046 0.7566836 0.480615 0.4320932 0.7630891 0.5650259 0.2207814 0.7949852 0.2591238 0.4016193 0.8783831 0.2588849 0.3846183 0.886029 0.2588188 0.345943 0.9018516 0.5644804 0.3866093 0.7293115 0.2588201 0.4524024 0.8534309 0.2588638 0.3382853 0.904739 0.2588738 0.2584511 0.9306919 0.5644979 0.2001988 0.8007887 0.2587735 0.2734761 0.9264163 0.2588195 0.2342485 0.9370913 0.3887405 0.1102981 0.9147214 0.5647315 0.1102945 0.8178713 0.4791803 0.1105659 0.8707247 0.2943584 0.1103082 0.9493078 0.1968819 0.1103081 0.9742021 0.0974192 0.1103154 0.9891108 0.03544515 0.139922 0.989528 0.06923282 0.1280607 0.989347 -0.09753417 0.1102989 0.9891013 -3.58559e-6 0.1439404 0.9895864 -0.03530037 0.1399582 0.9895281 -0.06887811 0.1282547 0.9893466 -0.2086839 0.1102815 0.9717454 -0.3171977 0.1102923 0.9419243 -0.4216499 0.1103908 0.9000141 -0.520668 0.1103764 0.8465943 -0.6130105 0.1102908 0.7823389 -0.6975098 0.110328 0.708031 -0.7730659 0.1104344 0.6246386 -0.8387151 0.1103601 0.5332707 -0.893618 0.1102985 0.4350647 -0.9370598 0.1104413 0.3312427 -0.968506 0.1102544 0.223249 -0.9548281 0.2971589 -3.06219e-6 -0.975323 0.2207832 2.24039e-5 -0.9875323 0.1102957 0.1123157 -0.9496544 0.298277 -0.09585088 -0.975324 0.220779 2.05226e-5 -0.954832 0.2971462 -1.19205e-5 -0.9817069 0.1903988 -9.53674e-6 -0.9688587 0.22078 -0.1121123 -0.9817074 0.1903962 -6.92904e-7 -0.8629323 0.5053197 -1.08164e-5 -0.862933 0.5053185 -5.48381e-6 -0.8588203 0.5063906 0.07743597 -0.8611707 0.5059608 -0.04887419 -0.8629317 0.5053209 -6.01634e-6 -0.8629328 0.5053188 -1.64169e-5 -0.8583728 0.5065545 -0.0812329 -0.9360839 0.3011447 0.1818208 -0.8564817 0.5070798 0.09648466 -0.8462511 0.5100923 0.1538348 -0.8613677 0.5057147 0.04794162 -0.8484491 0.5093981 0.1436934 -0.8452318 0.5103718 0.158442 -0.6834444 0.5500845 0.479907 -0.706669 0.5475069 0.4481686 -0.67135 0.5528474 0.4936082 -0.6962986 0.5495819 0.461658 -0.7036405 0.5481427 0.4521392 -0.7036716 0.5481359 0.4520987 -0.6607872 0.5467203 0.5142542 -0.6347849 0.5527154 0.5399573 -0.6607884 0.546719 0.514254 -0.6347713 0.5527195 0.5399691 -0.6056596 0.5506933 0.5743809 -0.6128407 0.5419063 0.5751208 -0.5742642 0.548654 0.6076179 -0.5408124 0.5464178 0.6394916 -0.5579115 0.5368813 0.6328454 -0.5051883 0.544142 0.6698467 -0.4674666 0.541808 0.6985121 -0.4957332 0.5317846 0.686625 -0.427718 0.5394111 0.7253227 -0.3860123 0.5368921 0.7501611 -0.426566 0.5264854 0.7354283 -0.3424389 0.534334 0.772802 -0.3250493 0.533297 0.7809849 -0.2414615 0.4487769 0.8604045 -0.3504094 0.5212009 0.7781793 -0.2501032 0.5289501 0.8109626 -0.1918876 0.4593375 0.8672878 -0.092076 0.4805678 0.8721104 -0.1420285 0.4699071 0.8712149 0.007515907 0.5016878 0.8650162 -0.04215902 0.4911254 0.8700681 0.1062411 0.5227526 0.8458384 0.05677253 0.5121787 0.8570006 0.234667 0.5302495 0.814719 0.1417932 0.5302476 0.8359021 0.3245785 0.5302548 0.7832489 0.410389 0.5302692 0.7418864 0.5654982 0.4320853 0.7025056 0.4910296 0.5302588 0.6911697 0.2589131 0.4630957 0.8476477 0.2588126 0.5059472 0.8228206 0.5645 0.4717296 0.6773557 0.2593727 0.5221738 0.8124409 0.2588189 0.5520294 0.7926388 -0.2676975 0.5160288 0.8136661 -0.2016173 0.5261827 0.826125 -0.1518244 0.5233535 0.8384811 -0.1790007 0.5110428 0.8407104 -0.1008414 0.5205069 0.8478819 -0.04894191 0.5176694 0.8541797 -0.08518809 0.5063478 0.8581113 0.003673076 0.5148749 0.8572575 0.01260459 0.5022963 0.8646038 0.05695414 0.512236 0.8569543 0.1109406 0.5096101 0.8532232 0.150276 0.5078645 0.848228 0.1549834 0.5330776 0.8317502 0.1127794 0.4990893 0.8591803 0.1649995 0.5072461 0.8458586 0.2494158 0.5531257 0.7948861 0.20276 0.543214 0.8147435 0.3387347 0.5721235 0.7469495 0.2947925 0.5627667 0.7722637 0.4217714 0.589739 0.6887066 0.3811137 0.5811137 0.7190684 0.5654754 0.5302537 0.6317188 0.497359 0.6058015 0.6209981 0.4605343 0.5980277 0.6559506 0.2588447 0.5787839 0.7733103 0.2588191 0.620924 0.7399096 0.5320541 0.613158 0.5839142 0.5646027 0.549854 0.615536 0.2587721 0.6324237 0.7301214 0.2588176 0.6435198 0.7203442 0.2186825 0.5052356 0.8348144 0.2135955 0.4971886 0.8409402 0.2715724 0.5036633 0.8201048 0.3233835 0.5026016 0.8017573 0.3126414 0.4969081 0.8095294 0.3738261 0.5022056 0.7797715 0.4224656 0.5026136 0.7542563 0.4074292 0.4988584 0.7649457 0.4690648 0.5039247 0.7252849 0.4953488 0.5036565 0.7077851 0.513219 0.5063275 0.6929928 0.5546125 0.5099101 0.6575688 0.5738915 0.5117962 0.639307 0.5929602 0.5148261 0.6191546 0.5645015 0.6201002 0.5448062 0.6279612 0.5211536 0.5779825 0.2588495 0.6829236 0.6830904 0.258818 0.7256363 0.6375463 0.2588263 0.7298815 0.6326785 0.2587986 0.7731748 0.5789856 0.2588191 0.7738566 0.5780646 0.6407372 0.5240082 0.5611339 0.6633518 0.5300769 0.5281884 0.2588827 0.2061337 0.9436571 0.2588195 0.1290998 0.9572595 0.5645141 0.101794 0.8191226 0.2588798 0.1392375 0.9558213 0.2588189 0.1191218 0.9585524 0.4702364 -0.001429498 0.8825395 0.5644975 0.001255452 0.8254339 0.5645757 -0.001569271 0.8253799 0.3700547 -0.001544296 0.9290087 0.2654733 -0.001319229 0.9641174 0.09955245 0.108959 0.9890487 0.1575673 -0.001574933 0.9875071 0.1552457 0.01968562 0.9876798 0.1435549 0.05345392 0.9881978 0.1246435 0.08374905 0.9886608 -0.6234641 -0.781852 -1.01386e-5 -0.6132088 -0.7899209 6.9238e-7 -0.4352132 -0.9003274 3.48891e-6 -0.6257228 -0.7800455 1.48185e-6 -0.4341101 -0.9008599 3.76018e-5 -0.2227778 -0.9748693 -3.41255e-5 -0.2228246 -0.9748587 0 4.93228e-6 -1 4.22266e-6 1.49682e-5 -1 -5.78561e-6 1.70469e-5 -1 -1.87829e-4 0.2216944 -0.9751163 -5.66385e-5 -1.093e-5 -1 0 0.2238715 -0.9746187 1.91298e-4 0.4328971 -0.9014433 -3.14318e-6 0.4364352 -0.8997356 3.41484e-4 0.6137369 -0.7895106 -9.96515e-7 -0.09903693 0.109375 0.9890546 0.62244 -0.7826676 -2.47266e-6 -0.2637587 -0.001571476 0.9645875 -0.1240863 0.08437079 0.988678 -0.1431661 0.05420666 0.9882132 -0.1550549 0.02041894 0.9876948 -0.1575985 -0.001567125 0.987502 -0.366909 -0.001661002 0.9302554 -0.4657301 -0.001737296 0.8849252 -0.5587563 -0.001581966 0.8293305 -0.6453582 -0.001549661 0.7638786 -0.7243965 -0.001555621 0.6893819 -0.7948934 -0.001565635 0.6067473 -0.8560399 -0.001606225 0.5169073 -0.9070241 -0.001574993 0.4210761 -0.9473356 -0.001571297 0.3202389 -0.9764955 -0.001602351 0.2155321 -0.9938991 0.1102932 -1.86563e-5 -0.9940991 -0.001640141 0.1084629 -0.9938993 0.1102924 1.86153e-5 -0.9966872 0.08132988 2.68221e-6 -0.9873847 0.1103056 -0.1135967 -0.9966871 0.0813325 -5.7295e-6 0.2590067 0.07037025 0.9633088 0.2588199 0.00149101 0.9659245 0.2588916 0.001895189 0.9659046 0.2588186 -0.001826882 0.9659242 0.4841144 -0.1133707 0.8676292 0.5645074 -0.1000837 0.819338 0.2588766 -0.0669502 0.9635874 0.2589297 -0.1170825 0.9587737 0.3989819 -0.1134297 0.909916 0.3103157 -0.113475 0.9438366 0.2185181 -0.113439 0.969217 -0.9999971 -0.002402186 2.58428e-4 -0.9962972 -0.08597558 3.319e-6 -0.975735 -0.2189553 9.28063e-7 0.1591113 -0.01582312 0.9871339 -0.9999911 0.004235327 0 -0.9743626 -0.224983 3.78545e-4 -0.9022349 -0.431245 -1.77414e-5 -0.8998546 -0.4361899 3.32584e-4 -0.7832929 -0.6216529 -6.13487e-5 -0.7806906 -0.6249178 2.42361e-4 0.5648325 -0.1134298 0.8173727 0.2588194 -0.1327791 0.9567562 0.5645104 -0.2003859 0.8007332 0.2587873 -0.1354284 0.9563934 0.2588197 -0.2344931 0.9370301 0.4700734 -0.2238479 0.8537699 0.5651305 -0.2238477 0.7940527 0.3689507 -0.2238863 0.9020812 0.2625351 -0.224298 0.9384912 0.1429007 -0.0850352 0.9860774 0.1248562 -0.1134321 0.9856694 0.1529776 -0.223855 0.9625419 0.1549175 -0.05132895 0.9865931 -0.7838514 0.6209485 1.07879e-4 -0.785818 0.6184579 -7.27072e-7 -0.8983554 0.4392696 -2.10021e-6 0.1237708 -0.1150795 0.9856154 -0.7780577 0.6281929 2.34519e-6 -0.9021703 0.4313801 1.37848e-5 -0.9738299 0.2272785 -5.89155e-5 -0.9754886 0.2200503 1.2868e-4 0.2587932 -0.2032176 0.944314 0.2588193 -0.2621225 0.9296798 0.4796878 -0.3314717 0.8124198 0.5645137 -0.2975212 0.7699386 0.2588037 -0.2701452 0.9273847 0.2589037 -0.348174 0.9009683 0.3884363 -0.3315412 0.8597661 0.2925653 -0.3312695 0.8970319 0.193001 -0.3315143 0.9234982 0.06864297 -0.1586628 0.9849439 0.04129576 -0.2238555 0.9737471 0.09115129 -0.3317341 0.9389591 0.09872412 -0.1399204 0.9852289 -0.06900721 -0.1584821 0.9849475 -0.07093364 -0.2238546 0.9720379 -0.01128357 -0.3314607 0.9434016 -0.03533053 -0.1702615 0.9847654 6.60168e-6 -0.1742249 0.984706 0.03519052 -0.1702864 0.9847661 -0.1249579 -0.1134336 0.9856564 -0.182052 -0.2235189 0.9575471 -0.1140063 -0.3315551 0.9365222 -0.1242995 -0.1144304 0.9856243 -0.09924066 -0.139503 0.9852361 -0.2334933 -0.1134291 0.9657199 -0.2908431 -0.2236045 0.9302749 -0.2151993 -0.3314505 0.9186022 -0.3391421 -0.1135286 0.9338598 -0.3962249 -0.2238977 0.8904358 -0.3139805 -0.3315316 0.8896646 -0.4407138 -0.1131373 0.8904894 -0.4955545 -0.2239348 0.8392133 -0.4089541 -0.3315092 0.8502107 -0.5366711 -0.1134107 0.8361353 -0.5890671 -0.223818 0.77647 -0.4990797 -0.3315399 0.8006252 -0.6260444 -0.1134892 0.7714848 -0.6742809 -0.2241548 0.7036334 -0.5835081 -0.3317398 0.7412605 -0.7080203 -0.1130722 0.697081 -0.7508234 -0.2238752 0.6214051 -0.6608452 -0.3310248 0.6735772 -0.7806906 -0.1134952 0.6145252 -0.8172856 -0.2238364 0.5309818 -0.7299823 -0.3313602 0.5977678 -0.8440783 -0.1134166 0.5240885 -0.8729193 -0.223858 0.4334738 -0.8385468 -0.2790794 0.4679251 -0.7906644 -0.3314809 0.5147526 -0.833172 -0.2916276 0.4698701 -0.8353454 -0.285228 0.4699395 -0.8971999 -0.1131527 0.4268825 -0.9169662 -0.2238634 0.3302397 -0.8721871 -0.2578368 0.415704 -0.8430255 -0.2730036 0.4634406 -0.8487538 -0.2675671 0.4560973 -0.8555746 -0.2630177 0.4458854 -0.8634076 -0.2597053 0.4325283 -0.9388357 -0.1134291 0.3251484 -0.9488584 -0.2238457 0.2226226 -0.9220001 -0.2704291 0.2770991 -0.881775 -0.2578299 0.3949641 -0.8920133 -0.2600519 0.3697097 -0.9692159 -0.1133205 0.2185841 -0.9681528 -0.2238752 0.1120721 -0.943284 -0.2777787 0.1818083 -0.9903728 -0.138426 9.72301e-6 -0.9746231 -0.2238522 -3.33041e-6 -0.9390284 -0.3314943 0.09130853 -0.9935466 -0.113425 -8.25524e-6 -0.9874135 -0.1134565 0.1101918 -0.9294295 -0.3210895 0.1818311 -0.9257743 -0.3314667 0.1818567 -0.9870386 -0.1133649 -0.1135925 -0.9746244 -0.2238468 -1.7181e-5 -0.9903718 -0.1384332 -1.57803e-5 -0.9691532 -0.246459 1.36793e-5 -0.9681721 -0.223791 -0.1120736 -0.9691532 -0.2464593 -6.57141e-6 -0.9935463 -0.1134276 1.16192e-5 -0.9995873 -0.02872717 1.97962e-5 -0.9934753 -0.001564443 -0.1140367 -0.9995874 -0.02872568 -1.53407e-5 -0.9999988 -0.001576483 -2.10702e-5 -0.1432704 -0.08427399 0.9860891 -0.159102 -0.01510822 0.9871466 -0.1551128 -0.05059385 0.9866004 0.8998628 0.4361732 1.39718e-4 0.7860404 0.6181752 1.00862e-6 0.7813356 0.6241112 3.3332e-6 0.9006572 0.4345305 -5.78795e-7 0.780701 0.6249048 6.44583e-5 0.623575 0.7817636 5.49684e-5 0.6234937 0.7818284 0 0.4337078 0.9010537 7.10228e-6 0.2228108 0.9748618 1.70833e-5 0.2224862 0.9749358 0 0.4341564 0.9008376 2.73115e-6 -1.02744e-5 1 -1.89424e-6 -5.31226e-6 1 -1.54732e-6 -2.11075e-5 1 1.91051e-4 -0.2213979 0.9751836 -8.86598e-5 -1.47894e-5 1 0 -0.2238398 0.974626 2.65759e-4 -0.4316483 0.9020421 -9.57908e-5 -0.4364217 0.8997422 4.40697e-4 -0.6207911 0.783976 -4.24465e-4 -0.6267833 0.7791937 -2.33398e-5 0.5653599 -0.3314626 0.7553151 0.2587229 -0.3353558 0.9058693 0.258819 -0.3881506 0.8845066 0.4832127 -0.4349356 0.7598267 0.5644715 -0.3892676 0.727903 0.2588049 -0.399563 0.8794144 0.2588173 -0.4554854 0.8517903 0.3948989 -0.4349523 0.8092412 0.3015857 -0.4348565 0.8484963 0.204421 -0.4349673 0.8769354 0.1046929 -0.4349268 0.8943591 0.003637671 -0.4349128 0.9004653 -0.09746134 -0.4349281 0.8951753 -0.1973563 -0.434834 0.8786182 -0.2947317 -0.4348506 0.8509044 -0.3883656 -0.4349011 0.8124243 -0.4771028 -0.4349008 0.7636976 -0.5598 -0.4349372 0.7053039 -0.6354527 -0.4348997 0.6380143 -0.7029315 -0.4350711 0.5626726 -0.8396831 -0.3287428 0.4322736 -0.8420247 -0.3314558 0.4255956 -0.7618491 -0.4348573 0.4800888 -0.8355807 -0.321362 0.4455687 -0.8329828 -0.3136906 0.4557829 -0.8318125 -0.3059109 0.4631486 -0.8319473 -0.2984677 0.4677399 -0.8144575 0.5802232 3.717e-4 -0.7777863 0.6285289 9.03383e-7 -0.8246519 0.5656407 -2.40654e-6 -0.8454077 -0.3355797 0.4155386 -0.7157822 0.6983236 4.2578e-4 -0.698498 0.7156119 2.32831e-7 -0.8936859 0.4486933 6.69601e-6 -0.9149684 0.4035255 0 -0.9521088 0.3057594 2.87126e-4 -0.9720917 0.2346016 1.34297e-6 -0.9878618 0.1553362 6.09038e-6 -0.9979808 0.06351792 -8.2422e-7 -1 1.85067e-5 -1.63596e-6 -0.994955 -0.1003232 -4.23286e-7 -0.9680278 -0.2508431 -2.53494e-6 -0.9629344 -0.2697359 -1.18442e-5 -0.9201161 -0.3916459 -3.11644e-7 -0.8550874 -0.5184841 3.03786e-6 -0.8496759 -0.5273055 0 -0.7511329 -0.6601511 1.46218e-6 -0.6848759 -0.7286598 1.40674e-4 -0.6250813 -0.7805598 -3.18512e-7 -0.4750286 -0.8799704 -1.05053e-6 -0.4650105 -0.8853052 9.73216e-5 -0.3026989 -0.9530863 -2.86847e-7 -0.2108476 -0.977519 1.15715e-4 -0.1096688 -0.9939682 -2.69711e-6 0.0595079 -0.9982278 7.2987e-5 0.1015108 -0.9948344 0 0.3265163 -0.9451916 -3.81264e-7 0.3265148 -0.9451922 2.18754e-6 0.3265109 -0.9451935 8.87261e-6 0.3264808 -0.9452039 5.97474e-5 0.3265161 -0.9451918 0 0.3265509 -0.9451797 0 -0.8947659 -0.4349528 0.101046 -0.9135964 -0.363698 0.1818393 -0.9434661 -0.331469 -1.74418e-5 -0.9434688 -0.3314616 -2.20612e-5 -0.9361881 -0.3514996 2.00123e-5 -0.9376958 -0.331469 -0.1041871 -0.936187 -0.3515024 -1.28224e-5 0.5655012 -0.4349204 0.7007515 0.2591213 -0.4613755 0.8485216 0.2588195 -0.5093013 0.8207466 0.4892047 -0.5329234 0.690414 0.5644769 -0.474003 0.6757862 0.2593165 -0.5209733 0.8132293 0.2588179 -0.5546677 0.7907953 0.4067408 -0.5328413 0.7420526 0.3190603 -0.5326082 0.783919 0.2265673 -0.5329486 0.8152504 0.1317871 -0.5326367 0.8360206 0.03465253 -0.5328508 0.8454994 -0.06279087 -0.5329369 0.8438221 -0.1592963 -0.5329326 0.8310279 -0.2536113 -0.5328407 0.807318 -0.344734 -0.5329271 0.7727531 -0.4312109 -0.5329208 0.7280471 -0.5119534 -0.5328098 0.6738082 -0.5859733 -0.5327898 0.6105493 -0.652199 -0.533032 0.538993 -0.7098481 -0.5328442 0.4606441 -0.8108228 -0.4349511 0.3916429 -0.75805 -0.5328794 0.3760321 -0.8623221 -0.3460023 0.3697067 -0.8496868 -0.4349073 0.298141 -0.7962148 -0.5329008 0.2864593 -0.8529196 -0.3414521 0.3948907 -0.8923192 -0.3563532 0.2770898 -0.8777841 -0.4349052 0.2008795 -0.8238975 -0.5328236 0.1931112 -0.8406701 -0.5327129 0.0974214 -0.9004661 -0.4349263 -4.18723e-6 -0.9004656 -0.4349274 8.21426e-6 -0.8918773 -0.4522775 2.87592e-6 -0.8948007 -0.4348598 -0.1011382 -0.8918782 -0.4522757 1.07475e-5 -0.3265332 0.9451857 8.62498e-6 -0.326532 0.9451861 1.08448e-5 -0.3265369 0.9451845 1.97249e-6 -0.326538 0.9451842 0 -0.3265435 0.9451822 -1.27055e-6 -0.3265282 0.9451875 1.94833e-6 -0.5336409 0.8457113 -4.41447e-7 -0.6000312 0.7999767 1.83722e-4 -0.4693807 0.882996 6.83643e-6 0.5652776 -0.5329194 0.6296492 0.2589491 -0.578087 0.7737964 0.2588183 -0.6239264 0.7373798 0.5005583 -0.6242311 0.5998142 0.5645274 -0.5496705 0.6157688 0.2591986 -0.6320528 0.7302913 0.2588182 -0.6432453 0.7205892 0.4293242 -0.6241421 0.6527845 0.3527908 -0.6240009 0.6972529 0.2719277 -0.6242401 0.7323794 0.1872363 -0.6239588 0.758695 0.1003885 -0.6241853 0.7747999 0.01213479 -0.6241694 0.7811949 -0.07625526 -0.6241967 0.7775369 -0.1637068 -0.6241441 0.7639661 -0.249001 -0.6242051 0.7405177 -0.3311648 -0.6241532 0.7076458 -0.4090119 -0.6242164 0.6656299 -0.4816354 -0.6242402 0.615103 -0.5480974 -0.6242387 0.5567005 -0.6075254 -0.6242424 0.4911561 -0.6591977 -0.6241978 0.4193276 -0.7023896 -0.6241903 0.3421044 -0.7365862 -0.624166 0.260495 -0.761263 -0.6242324 0.1755358 -0.846166 -0.5329194 1.56201e-5 -0.7762368 -0.6242215 0.08834081 -0.8461584 -0.5329317 1.87308e-5 -0.8367578 -0.5475732 -1.54749e-5 -0.8405533 -0.5329395 -0.09718906 -0.8367536 -0.5475797 -2.09734e-6 0.5645473 -0.6152673 0.5502113 0.2591929 -0.6830161 0.6828675 0.2588186 -0.7200191 0.6438832 0.5651529 -0.6242451 0.5393704 0.2590844 -0.7300692 0.6323561 0.2588185 -0.7308027 0.6316173 0.4577361 -0.7077242 0.5381489 0.5146345 -0.7077021 0.4840549 0.5644975 -0.6703552 0.4816289 0.2588056 -0.7736442 0.5783549 0.2587997 -0.784446 0.5636199 0.3952382 -0.7076658 0.5856586 0.327861 -0.7075955 0.6259521 0.2563942 -0.7075912 0.6584656 0.1817032 -0.7077184 0.6827289 0.1048233 -0.7077417 0.6986514 0.02670311 -0.7076216 0.7060868 -0.05169928 -0.7074069 0.7049133 -0.1295656 -0.7075277 0.6947067 -0.2058089 -0.7076495 0.6759253 -0.2794867 -0.7077625 0.6488139 -0.3496927 -0.7078765 0.6136986 -0.4158768 -0.7076621 0.5711926 -0.4766439 -0.7077038 0.5215036 -0.5315621 -0.7077032 0.465401 -0.5590615 -0.7074416 0.4324078 -0.5348868 -0.7066084 0.4632502 -0.5426531 -0.7054425 0.455937 -0.5507791 -0.7056756 0.4457178 -0.6034097 -0.7077001 0.3675017 -0.5596769 -0.707698 0.4311908 -0.6399515 -0.7076782 0.2994224 -0.66878 -0.7077165 0.2277511 -0.6896638 -0.7077027 0.1533649 -0.7812388 -0.6242324 -1.6138e-5 -0.7023249 -0.7076622 0.0771622 -0.7812418 -0.6242287 -6.47456e-6 -0.7714896 -0.636242 2.30297e-5 -0.7762172 -0.6242521 -0.08829736 -0.7714931 -0.6362378 0 0.5651604 -0.707701 0.423973 0.2588185 -0.7926026 0.5520817 0.2588182 -0.8284961 0.4965957 0.5522477 -0.711415 0.4346394 0.5585418 -0.7128146 0.4241774 0.5644994 -0.7150766 0.4123178 0.2588701 -0.8321642 0.4903968 0.2588195 -0.8367801 0.4825055 0.2588244 -0.7942403 0.5497202 0.258807 -0.797567 0.5448908 0.2588257 -0.8029446 0.5369259 0.2587899 -0.8104842 0.5254933 0.258811 -0.8202081 0.5101721 0.4127357 -0.7822962 0.4665426 0.545691 -0.7109098 0.443654 0.5388413 -0.7113886 0.4511945 0.5318772 -0.7129808 0.4569082 0.5250803 -0.7157326 0.4604538 0.518809 -0.7195091 0.4616752 0.5132141 -0.7242967 0.4604408 0.5084692 -0.7299398 0.456779 0.4626134 -0.7822834 0.4171589 0.3576274 -0.7823142 0.5099875 0.298025 -0.7822704 0.547023 0.2346118 -0.7822573 0.5770881 0.1681972 -0.7823017 0.5997617 0.09968185 -0.782252 0.6149353 0.02987945 -0.7822887 0.6221992 -0.04029417 -0.7822664 0.6216396 -0.1099581 -0.7822718 0.613156 -0.1782246 -0.782278 0.5968896 -0.2442296 -0.7822802 0.573053 -0.3071368 -0.7822774 0.5419493 -0.3661298 -0.7822973 0.5039444 -0.5277992 -0.7089428 0.4677907 -0.4204858 -0.782292 0.459577 -0.516144 -0.7160851 0.4699122 -0.5215899 -0.7121188 0.4699265 -0.4379281 -0.89901 3.37579e-5 -0.3068333 -0.9517633 1.29454e-7 -0.2325361 -0.9725878 5.22239e-6 -0.3883581 -0.9215086 -1.45659e-6 -0.1741825 -0.9847134 1.29164e-4 -0.06175351 -0.9980915 1.52923e-6 0.103156 -0.9946652 1.0057e-4 0.1170746 -0.9931232 1.09151e-6 0.2992727 -0.9541677 -3.59863e-6 0.31291 -0.9497828 -9.57795e-6 -0.5672683 -0.7109533 0.4156348 0.3729808 -0.9278391 -1.62524e-5 0.4801377 -0.8771931 4.30271e-7 -0.5923394 -0.7379935 0.3232643 -0.575134 -0.7164098 0.3949404 -0.5822498 -0.7240893 0.3697026 -0.6010051 -0.7499317 0.2763972 -0.6141107 -0.7679864 0.1818383 -0.608251 -0.7599248 0.2292271 -0.6108231 -0.7822614 0.122321 -0.5957311 -0.7822927 0.1819959 -0.7065124 -0.7077007 7.87154e-6 -0.6201834 -0.7820513 0.06138747 -0.7065122 -0.7077009 -9.75654e-6 -0.6968812 -0.7171866 -1.37761e-5 -0.7019681 -0.7076925 -0.08007675 -0.6968805 -0.7171874 1.01812e-5 -0.4287733 -0.9034122 -6.17078e-5 -0.4189707 -0.9079998 -1.49384e-6 -0.2878997 -0.9576606 1.66334e-6 0.258826 -0.8428509 0.4718174 -0.5616466 -0.8273772 6.57514e-7 -0.1553178 -0.9878646 1.32899e-5 -0.1496313 -0.9887419 1.21444e-6 -0.004980623 -0.9999877 -8.41916e-7 0.1305574 -0.9914408 -2.83018e-5 0.1451766 -0.9894058 -2.06754e-7 0.2984965 -0.9544108 -1.41375e-6 0.4057524 -0.9139831 8.25311e-5 0.4481547 -0.8939561 2.70316e-7 0.5861158 -0.8102273 -5.60172e-5 0.6480212 -0.7616224 -4.65348e-5 0.7089932 -0.7052153 8.91276e-7 0.8139457 -0.5809411 -7.00355e-7 0.5047613 -0.7361221 0.4509329 0.8375094 -0.546423 -2.45585e-5 0.8956446 -0.4447706 -9.574e-7 0.5021536 -0.7425077 0.4433104 0.9525285 -0.3044497 -3.59491e-7 0.5006156 -0.7489476 0.4341217 0.9583736 -0.2855173 -4.89524e-5 0.9866837 -0.1626507 2.22586e-6 0.5000215 -0.755397 0.423502 0.9997845 -0.0207625 -2.47918e-6 0.5003309 -0.7618004 0.4114964 1 -4.06429e-6 3.22328e-4 0.9927726 0.1200113 2.01538e-6 0.5015336 -0.7681256 0.3980545 0.9914394 0.1305682 6.17879e-5 0.9659312 0.2587992 2.49856e-7 0.5065935 -0.7822857 0.3624808 0.9659316 0.2587978 0 0.9659258 0.2588194 5.8463e-6 0.9659245 0.2588244 3.92044e-5 0.9659186 0.2588461 0 0.9659255 0.2588204 0 0.9659261 0.2588182 0 0.9659318 0.2587967 0 0.4155701 -0.847035 0.3314111 0.9659106 0.2588762 -3.94749e-5 0.45002 -0.8470664 0.2827734 0.509092 -0.7963504 0.3265753 0.3761689 -0.84677 0.3761351 0.33172 -0.8467383 0.4159281 0.282854 -0.8469703 0.4501501 0.2305791 -0.8470998 0.4788062 0.1755949 -0.8469672 0.5018098 0.1183146 -0.8469422 0.5183538 0.05949604 -0.8471228 0.5280561 -2.80642e-6 -0.8470653 0.5314888 -0.05949181 -0.8470739 0.5281352 -0.1182685 -0.8470624 0.5181677 -0.1756537 -0.846901 0.5019009 -0.2306818 -0.8469752 0.478977 -0.2828897 -0.8469475 0.4501704 -0.3314848 -0.846975 0.4156336 -0.5009735 -0.7415449 0.4462474 -0.4695328 -0.7822796 0.4093626 -0.3759047 -0.8469998 0.3758819 -0.5033123 -0.7338128 0.4562847 -0.5068249 -0.7268794 0.4634383 -0.5111906 -0.7209482 0.4678868 -0.5086708 -0.7775401 0.3697098 -0.5125944 -0.7822826 0.3539506 -0.4156785 -0.8469617 0.3314626 -0.5034373 -0.7681887 0.3955212 -0.5007316 -0.7588794 0.4163775 -0.5000028 -0.7499482 0.4330993 -0.8090445 0.5877473 -2.57145e-6 -0.8090716 0.5877102 -8.14535e-7 -0.8090772 0.5877025 0 -0.4500062 -0.8470729 0.2827758 -0.5187993 -0.7914787 0.3231235 -0.8090344 0.5877615 -5.07879e-6 -0.8090358 0.5877593 8.77481e-7 -0.809045 0.5877467 2.80887e-6 -0.9241668 0.3819894 3.18699e-6 -0.9781528 0.2078874 -8.57836e-5 -0.9841347 0.1774227 -2.94857e-6 -0.9134027 0.4070571 -7.8757e-5 -1 -1.53623e-5 2.21247e-7 -0.9998162 -0.01917368 -4.71249e-7 -0.9790001 -0.2038602 9.20147e-7 -0.9608814 -0.2769604 -3.51464e-5 -0.9274097 -0.3740475 -5.04777e-7 -0.8500822 -0.5266501 -2.17929e-7 -0.8471061 -0.5314238 1.59907e-4 -0.7538526 -0.6570438 -3.553e-7 -0.6681302 -0.7440445 1.89913e-5 -0.6450763 -0.7641182 0 -0.5249647 -0.8511241 0 0.515056 -0.8185625 0.2543088 0.4788559 -0.8470647 0.2306043 0.5174645 -0.8274357 0.2181303 0.5016566 -0.8470703 0.1755348 0.5194526 -0.834928 0.1818355 0.5421839 -0.8203558 0.1818047 0.5181707 -0.8470606 0.1182688 0.5645039 -0.8051556 0.1818245 0.5644971 -0.8140041 0.1368955 0.2592653 -0.9437314 0.2053114 0.2588179 -0.9422003 0.2127722 0.2586226 -0.9525821 0.1603178 0.2588189 -0.9418991 0.2141003 0.5645032 -0.8203338 0.09158945 0.2589507 -0.9560827 0.1372973 0.2585753 -0.9600288 0.1071623 0.5281383 -0.8470706 0.05951064 0.5644887 -0.8241602 0.04596233 0.2591231 -0.9633979 0.06870126 0.2587766 -0.9644379 0.0538004 0.5314915 -0.8470637 1.14646e-5 0.5644884 -0.8254411 1.79936e-5 0.2588201 -0.9659256 -7.63126e-6 0.5281606 -0.8470567 -0.05950933 0.5645098 -0.8254265 1.08909e-5 0.531499 -0.847059 9.61125e-6 0.5645314 -0.8246903 -0.03449994 0.2588193 -0.9659259 2.07238e-5 0.2588189 -0.9659259 -5.23802e-6 0.2587772 -0.965107 -0.04003566 0.2588196 -0.9659258 -1.43638e-5 0.4792957 -0.8776535 1.95354e-5 0.4306799 -0.9011991 -0.04853194 0.4793007 -0.8776508 -6.95139e-6 0.4305821 -0.9011961 0.04944378 0.4334083 -0.9011977 1.24834e-5 0.4221888 -0.9011686 0.09824419 0.4081801 -0.9011919 0.1457473 0.3889244 -0.9011739 0.1913725 0.3645442 -0.9011806 0.2344806 0.335403 -0.9011892 0.274523 0.3018866 -0.9011977 0.3109776 0.2644846 -0.9011649 0.3434382 0.2235664 -0.9011798 0.3713398 0.1797555 -0.9011713 0.3944342 0.1335773 -0.9011902 0.4123266 0.08565473 -0.9012047 0.4248454 0.03665369 -0.901194 0.4318634 -0.003618836 -0.8827193 0.4698866 0.03643345 -0.9008258 0.4326496 0.0307132 -0.8945267 0.4459582 0.02424055 -0.8895613 0.4561723 0.0172134 -0.8859679 0.4634269 0.01009589 -0.8837219 0.4679037 0.003174483 -0.8826825 0.4699591 -0.08568954 -0.9011977 0.4248531 -0.01052904 -0.8838194 0.4677101 -0.01760631 -0.8861256 0.4631106 -0.02454853 -0.8897614 0.4557656 -0.03094565 -0.8947232 0.4455478 -0.03657603 -0.90101 0.4322536 -0.1336101 -0.9011669 0.4123671 -0.1797901 -0.9011493 0.3944687 -0.2235823 -0.9011778 0.371335 -0.2644699 -0.9011853 0.343396 -0.3019314 -0.901173 0.3110061 -0.3354193 -0.9011836 0.2745217 -0.364516 -0.9011991 0.2344532 -0.5275054 -0.8033989 0.2762033 -0.4788722 -0.8470539 0.2306107 -0.3888868 -0.9011955 0.1913476 -0.5347134 -0.8133887 0.2290865 -0.5016518 -0.8470758 0.1755222 -0.4081839 -0.9011909 0.1457433 -0.51845 -0.8469034 0.1181707 -0.4221467 -0.9011897 0.09823179 -0.577982 -0.7955388 0.1818104 -0.540574 -0.8214133 0.1818246 -0.5282609 -0.8469914 0.05954986 -0.4305819 -0.9011964 0.04943972 -0.6138173 -0.7894481 5.96046e-7 -0.5314983 -0.8470594 1.96621e-5 -0.6229141 -0.7822903 5.96419e-6 -0.6190038 -0.7822477 -0.07016289 -0.5314848 -0.8470679 1.23531e-5 -0.6138157 -0.7894495 -5.23403e-6 -0.5233161 -0.8521387 1.4022e-5 -0.5281378 -0.8470718 -0.05949693 -0.5233182 -0.8521373 4.92483e-6 -0.6229232 -0.7822831 -2.0884e-5 -0.809045 0.5877467 -1.09323e-5 -0.809042 0.5877509 3.83622e-6 -0.8090488 0.5877414 5.90492e-6 0.4334049 -0.9011994 5.36442e-7 0.3893135 -0.9211053 2.61143e-6 0.3278023 -0.9440241 -0.03693783 0.389316 -0.9211044 4.02331e-6 0.3219771 -0.9440088 0.07196038 0.3298856 -0.9440209 1.42232e-5 0.3278684 -0.9440305 0.03617918 0.312066 -0.9440346 0.1068334 0.29853 -0.9440082 0.1404579 0.2812674 -0.9440277 0.1723386 0.2607017 -0.9440097 0.2021895 0.2369094 -0.9440255 0.2295429 0.2103024 -0.9440204 0.2541621 0.1811818 -0.9439983 0.2757542 0.1498427 -0.9439899 0.2939903 0.1166463 -0.9440215 0.308573 0.08207875 -0.944018 0.3195201 0.04105234 -0.9085032 0.4158567 0.04653918 -0.9440237 0.3265783 0.04424184 -0.9175785 0.3950853 -0.8371854 -0.5469194 -2.72781e-5 -0.806713 -0.5909436 0 -0.8010377 -0.5986139 -2.77534e-6 -0.9030292 -0.4295794 -2.10106e-6 -0.6755712 -0.7372948 -1.41002e-6 -0.6492435 -0.7605807 2.09652e-5 -0.5328124 -0.8462336 -1.66521e-6 -0.4104282 -0.911893 1.63839e-5 -0.3788649 -0.925452 -1.13249e-6 -0.2223406 -0.9749692 4.54485e-7 -0.1381683 -0.9904088 -1.57382e-5 -0.06981068 -0.9975603 -9.40752e-7 0.0795837 -0.9968282 1.69291e-6 0.1460611 -0.9892756 6.06706e-5 0.2317348 -0.972779 0 0.3873735 -0.9219229 8.28877e-7 0.4176835 -0.9085927 -4.05475e-7 0.5397147 -0.841848 3.55765e-7 0.6543536 -0.7561888 2.18695e-5 0.6805031 -0.7327452 -1.17347e-6 0.8042611 -0.5942762 1.64844e-6 3.64349e-7 0 1 -5.89537e-7 0 1 -0.04110503 -0.9086665 0.4154946 0.839381 -0.5435435 2.00598e-5 0.9046995 -0.4260505 -2.99327e-6 -0.08206915 -0.9440307 0.3194853 -0.04425859 -0.9176763 0.3948561 -0.04543143 -0.9280312 0.369722 -0.04651594 -0.9440263 0.3265742 -0.1166597 -0.9440091 0.3086057 -0.1498408 -0.9439915 0.293986 -0.1812093 -0.9439817 0.2757933 -0.2103071 -0.944018 0.2541677 -0.2369105 -0.9440249 0.2295438 -0.2606583 -0.9440282 0.2021585 -0.2812638 -0.944029 0.1723369 -0.2985275 -0.9440092 0.1404567 -0.3120667 -0.9440345 0.1068335 -0.3219776 -0.9440085 0.07196056 -0.4334059 -0.9011989 -1.37389e-5 -0.3279568 -0.9439977 0.03623193 -0.4334071 -0.9011983 1.00769e-6 -0.4264762 -0.9044989 8.09133e-6 -0.4307079 -0.9011848 -0.04854702 -0.4264848 -0.9044948 1.30776e-5 0.3298764 -0.9440242 -7.55675e-6 0.2954413 -0.9553609 -1.80788e-5 0.2207925 -0.9750021 -0.02493149 0.2954441 -0.9553601 -1.12802e-5 0.2207869 -0.9749998 0.02507227 0.2222152 -0.9749977 7.61263e-6 0.2165554 -0.9749979 0.04982924 0.2095901 -0.9749882 0.0739597 0.1998304 -0.975007 0.09710389 0.1876501 -0.9749928 0.1190652 0.1730652 -0.9749785 0.139519 0.1562232 -0.9749764 0.1581629 0.1373281 -0.9749947 0.1747182 0.1167479 -0.9749895 0.1891175 0.09465342 -0.9749938 0.2010668 0.07136768 -0.9749953 0.2104542 0.04714363 -0.9750004 0.2171447 0.04551792 -0.9280282 0.3697184 -1 0 0 0.04542982 -0.961313 0.2716863 -1 8.70228e-6 9.21963e-6 -1 -1.55345e-5 4.34369e-6 -0.9732041 -0.2299431 1.35787e-6 -0.9583827 -0.2854868 2.54898e-5 0.2222062 -0.9749998 -4.84847e-6 0.1986177 -0.980077 -6.08712e-6 0.111046 -0.9937365 -0.01251626 0.19863 -0.9800747 -6.52671e-6 0.1089448 -0.9937368 0.02486616 0.1117542 -0.9937359 2.01073e-6 0.1110502 -0.9937361 0.01251566 0.1054752 -0.9937368 0.03690701 0.1007103 -0.993733 0.04849934 0.09468948 -0.9937273 0.05949807 0.08741647 -0.9937297 0.06971251 0.07902723 -0.9937351 0.07902723 0.06968671 -0.9937343 0.08738398 0.05948293 -0.9937303 0.09466749 0.04848241 -0.9937373 0.1006753 0.03689998 -0.9937357 0.1054885 0.04547351 -0.982283 0.181803 0.1117444 -0.9937371 -2.704e-5 0.09979444 -0.9950081 1.64062e-5 1.61387e-6 -1 -1.73226e-5 0.09982073 -0.9950055 0 -1.14418e-6 -1 -1.85072e-5 0.02486491 -0.993738 0.1089335 0.03020697 -0.982865 0.1818351 0.01251101 -0.9937376 0.1110372 9.63431e-7 -0.9833271 0.181846 7.05157e-7 -0.9937356 0.1117578 0.01515763 -0.9832157 0.1818163 -0.01515704 -0.9832133 0.1818291 -0.01251202 -0.9937359 0.111052 -0.03020888 -0.9828642 0.181839 -0.02485638 -0.9937345 0.1089679 -0.07134628 -0.9750007 0.2104366 -0.03690552 -0.9937373 0.1054711 -0.04547321 -0.9822826 0.1818057 -0.09467166 -0.9749929 0.2010629 -0.04848426 -0.9937369 0.1006795 -0.1167459 -0.9749904 0.1891143 -0.05948644 -0.9937295 0.09467333 -0.1372637 -0.975018 0.1746385 -0.06971055 -0.99373 0.08741384 -0.1562522 -0.9749671 0.1581909 -0.07901751 -0.9937367 0.07901769 -0.1730001 -0.9750015 0.1394383 -0.0873816 -0.9937347 0.06968492 -0.18766 -0.9749923 0.1190539 -0.09464401 -0.9937334 0.05946868 -0.199887 -0.9749944 0.09711468 -0.1007528 -0.9937277 0.04851996 -0.2095966 -0.9749867 0.0739625 -0.1054337 -0.9937419 0.03689128 -0.2165547 -0.9749981 0.04982912 -0.1089406 -0.9937372 0.02486532 -0.2208202 -0.9749919 0.02508658 -0.1110959 -0.9937308 0.01252591 -0.2185311 -0.97583 2.15173e-5 -0.1117492 -0.9937365 -8.97981e-6 -0.2222095 -0.974999 7.12462e-6 -0.2208035 -0.9750011 -0.02487343 -0.1117622 -0.993735 -3.23262e-6 -0.2185378 -0.9758285 1.26474e-5 -0.1099311 -0.9939392 0 -0.1111006 -0.99373 -0.01254916 -0.1099432 -0.9939379 7.09016e-6 -0.222218 -0.9749971 -5.07757e-6 -0.3244678 -0.9458968 -6.95884e-6 -0.3278304 -0.9440136 -0.03695487 -0.3244632 -0.9458984 1.47522e-6 -0.3298765 -0.9440241 -8.27387e-6 -0.04716134 -0.974997 0.2171558 1 0 0 1 7.68894e-7 0 1 0 0 1 0 0 -0.04539698 -0.9613059 0.2717171 -0.1089974 -0.9937307 -0.02488005 -0.1055269 -0.9937315 -0.03690314 -0.100729 -0.9937322 -0.04847735 -0.09462279 -0.9937354 -0.05947005 -0.08737134 -0.9937372 -0.06966155 -0.07905501 -0.9937299 -0.07906508 -0.06964564 -0.993739 -0.087363 -0.05945569 -0.9937374 -0.09460985 -0.04848742 -0.9937369 -0.1006779 -0.03689318 -0.993741 -0.1054404 -0.02486705 -0.9937345 -0.1089649 -0.01250666 -0.9937407 -0.1110092 0 -0.9937418 -0.1117018 0.0125122 -0.9937368 -0.1110435 0.02486699 -0.9937344 -0.1089656 0.03689289 -0.9937387 -0.1054633 0.04848712 -0.9937349 -0.1006973 0.05942964 -0.9937428 -0.09456938 0.06964528 -0.9937378 -0.08737683 0.07905477 -0.9937294 -0.07907164 0.08735358 -0.9937387 -0.06966322 0.09462285 -0.9937354 -0.05946934 0.1007287 -0.9937304 -0.04851555 0.1054806 -0.9937357 -0.03692179 0.1089499 -0.9937362 -0.02486735 -0.9999988 -0.001577854 1.65552e-5 0.6267751 -0.7792003 -9.30994e-6 0.7800811 -0.6256785 -1.4549e-5 0.7839291 -0.6208503 3.57291e-4 0.8998935 -0.4361099 -6.72252e-5 0.9022052 -0.4313071 2.84356e-4 0.9746849 -0.2235829 -8.12055e-7 0.9754933 -0.220029 3.76315e-4 0.9962981 -0.08596599 -1.37836e-7 1 -2.70344e-4 -7.83475e-7 0.999997 0.002446472 1.60583e-4 0.9748681 0.2227829 4.51446e-6 0.9743645 0.2249751 1.40496e-4 0.6145632 -0.7888677 9.55269e-6 0.6531702 -0.7572112 -8.62405e-7 0.8090373 -0.5877574 -4.51657e-6 0.8090729 -0.5877083 -1.55134e-4 0.8090482 -0.5877424 5.3097e-6 0.8089766 -0.5878409 -1.22039e-4 0.8090168 -0.5877856 -2.5233e-6 0.8090375 -0.5877571 0 0.8090388 -0.5877554 0 0.8090298 -0.5877678 0 -0.3298724 -0.9440255 5.3905e-6 0.9587491 -0.2842542 9.80069e-5 0.9737111 -0.2277867 2.26684e-6 1 -2.1264e-5 -3.37767e-6 1 2.08616e-7 0 -0.8440774 0.510686 0.1635027 -0.3265329 -0.9451859 0 -0.3265393 -0.9451837 0 -0.326541 -0.9451831 0 -0.8372098 0.5123373 0.1912859 -0.8237057 0.5164061 0.234166 -0.3264795 -0.9452043 0 -0.3265262 -0.9451882 2.57569e-7 -0.3265256 -0.9451884 0 -0.4694653 -0.882951 6.3902e-5 -0.5141535 -0.8576983 3.4906e-6 -0.6001458 -0.7998907 6.91207e-5 -0.6726436 -0.7399668 5.90458e-7 -0.7159122 -0.6981904 8.7332e-5 -0.8145034 -0.5801588 -3.61004e-5 -0.9732576 0.2297165 -5.60656e-6 -0.9732577 0.2297163 -6.90338e-6 -0.9714106 0.2290595 0.06239539 -0.9687033 0.2275213 -0.09923762 -0.9713317 0.2290739 -0.06355971 -0.9732576 0.2297167 1.76393e-5 -0.9732573 0.2297176 1.84625e-5 -0.9686602 0.2276872 0.09927701 -0.9658057 0.2271095 0.1250628 -0.956408 0.2238308 0.1875731 -0.9548975 0.2214962 0.1977635 -0.9430108 0.2190666 0.2504805 -0.8226039 0.5163189 0.2381966 -0.9256183 0.2129348 0.3128733 -0.8048 0.5210767 0.2842112 -0.9193862 0.2099546 0.3326385 -0.9039921 0.2051703 0.3751047 -0.9320811 0.2111343 0.2943589 -0.7963154 0.5239464 0.3022617 -0.7833636 0.5268362 0.3298261 -0.8924883 0.2001082 0.404254 -0.877847 0.1957119 0.4371287 -0.7757607 0.5295094 0.3432425 -0.8601164 0.188333 0.4740576 -0.8469692 0.1843602 0.4986526 -0.7856101 0.5268459 0.3244225 -0.8226207 0.1745483 0.541136 -0.8112726 0.1709803 0.5591088 -0.7755411 0.1572956 0.611387 -0.7708393 0.15558 0.6177392 -0.7802041 0.1590433 0.6049685 0.1391568 0.9902704 -9.33697e-6 0.02636015 0.9996526 -3.13902e-6 -0.009431421 0.9999555 7.27363e-7 0.0833587 0.9965196 -4.41447e-7 -0.6996052 0.5489601 0.4573788 -0.6939585 0.5500536 0.4646103 -0.04617351 0.9989335 3.4906e-6 -0.7062728 0.5474606 0.4488493 -0.6939212 0.5500629 0.4646549 -0.6996083 0.5489706 0.4573615 -0.1458604 0.9893053 4.36758e-5 -0.2486175 0.9686018 7.6741e-7 -0.6989313 0.5463641 0.461499 -0.7348136 0.5403012 -0.4100289 -0.7264298 0.5417506 -0.4228548 -0.6938614 0.5500736 -0.4647316 -0.8131321 0.1548181 -0.5611129 -0.764609 0.1531672 -0.6260294 -0.8063234 0.1691308 -0.5667783 -0.6995934 0.5489642 -0.457392 -0.6989347 0.5463423 -0.4615198 -0.6995865 0.548955 -0.4574137 -0.6938837 0.5500655 -0.4647079 -0.7883099 0.1428522 -0.5984655 -0.7646082 0.1531639 -0.6260312 -0.8131135 0.1548073 -0.5611428 -0.7196418 0.5407022 -0.4356111 -0.7524868 0.5356947 -0.3831381 -0.7556273 0.5339511 -0.3793728 -0.8606554 0.1776643 -0.4771875 -0.843102 0.1829236 -0.5056856 -0.7911808 0.5254071 -0.3130182 -0.7808783 0.5274821 -0.3346518 -0.8747797 0.1945987 -0.4437249 -0.8028764 0.5216208 -0.2886198 -0.9005669 0.1965912 -0.3877257 -0.9016796 0.2043418 -0.3810753 -0.8220873 0.5168538 -0.2388193 -0.8212471 0.5166818 -0.2420605 -0.9321451 0.2108611 -0.2943519 -0.9239795 0.2123433 -0.3180758 -0.8446102 0.5105269 -0.1612334 -0.8362841 0.5126146 -0.1945645 -0.9419324 0.2187351 -0.2547909 -0.8479959 0.5093941 -0.1463578 -0.9548708 0.2215052 -0.1978823 -0.9557797 0.2236066 -0.1910117 -0.8562841 0.5071415 -0.09790366 -0.9655289 0.2270139 -0.1273524 -0.9342323 0.3015261 -0.1905049 -0.9495455 0.220798 -0.2227366 -0.9087288 0.3069698 -0.2828105 -0.9176505 0.220788 -0.3304094 -0.8734943 0.3144435 -0.3716627 -0.8735916 0.2207377 -0.4337196 -0.8289483 0.3239159 -0.4559859 -0.8083628 0.3285166 -0.4884942 -0.7036471 0.5481414 -0.4521303 -0.7066938 0.5475012 -0.4481366 -0.7491198 0.3285138 -0.5752376 -0.7756474 0.3352662 -0.5347595 -0.8179432 0.2207858 -0.5312462 -0.6713458 0.5528517 -0.4936091 -0.7066896 0.5475018 -0.4481424 -0.7036382 0.5481415 -0.4521441 -0.7323128 0.3444396 -0.5874346 -0.683332 0.5501649 -0.479975 -0.8610243 0.1554479 -0.4842243 -0.796317 0.1391732 -0.5886512 -0.8610334 0.1554582 -0.4842048 -0.7885075 0.1427309 -0.5982339 -0.7963173 0.1391863 -0.5886477 -0.9105402 0.1880673 -0.3681674 -0.8876335 0.1728836 -0.4268703 -0.9298219 0.2008933 -0.3083394 -0.9455238 0.2113302 -0.2476375 -0.966337 0.2251597 -0.1244823 -0.9576765 0.2194326 -0.1862931 -0.9714707 0.2287981 -0.06242001 -0.973257 0.2297193 -1.72881e-5 -0.9732571 0.2297187 -1.26995e-5 0 1 -8.07237e-5 0 1 1.09815e-4 0 1 7.96261e-5 -0.830869 0.1430487 -0.5377674 0 1 -5.90105e-5 0 1 1.94128e-5 0 1 -2.8374e-5 0 1 1.74459e-5 0 1 0 0 1 -2.7068e-5 0 1 -4.75244e-7 0 1 7.69607e-6 0 1 4.7738e-7 0 1 3.75122e-5 0 1 3.32231e-7 0 1 1.26673e-5 0 1 0 0 1 7.35298e-6 0 1 0 0 1 0 -0.9715374 0.2285524 0.06228101 0 1 -4.22867e-5 -0.7199542 0.5404784 -0.4353724 -0.6937782 0.5376367 -0.4791855 -0.7363095 0.5230745 -0.4292336 -0.7523728 0.1394424 -0.6438099 -0.7963129 0.1391734 -0.5886566 -0.7963088 0.1391731 -0.5886623 -0.7106264 0.5160703 -0.4782068 -0.6937801 0.5376342 -0.4791856 -0.7363118 0.5230726 -0.4292321 -0.7559378 0.1391742 -0.6396787 -0.7963098 0.1391713 -0.5886614 -0.7963194 0.1391738 -0.5886477 0 1 -2.87778e-5 0 1 -1.58715e-5 0 1 -1.24126e-5 -0.634787 0.5527211 -0.5399489 -0.6850383 0.3545197 -0.6364263 -0.6607794 0.5467206 -0.5142639 -0.6096285 0.541606 -0.5788057 -0.6347762 0.5527191 -0.5399636 -0.6607769 0.5467211 -0.5142666 -0.6806221 0.3285029 -0.6548584 -0.6473363 0.362527 -0.6704699 -0.6056502 0.5506677 -0.5744155 -0.649126 0.5306887 -0.5449816 0.5645319 -0.8225697 -0.06843215 0.259001 -0.9633843 -0.06934839 0.2588192 -0.9626112 -0.0799517 0.5181489 -0.8470745 -0.1182658 0.5644917 -0.8142315 -0.1355596 0.2589135 -0.9559757 -0.1381101 0.2587558 -0.9528292 -0.1586254 0.5016418 -0.8470784 -0.175539 0.5645089 -0.8002609 -0.2022681 0.2590433 -0.9435794 -0.2062877 0.2588173 -0.9364703 -0.2367218 0.4788365 -0.8470695 -0.2306275 0.5648882 -0.782279 -0.262566 0.2587547 -0.9264615 -0.273341 0.2589095 -0.9156502 -0.3074909 0.531741 -0.782288 -0.3244642 0.5644813 -0.7803056 -0.2692289 0.2588194 -0.9130858 -0.3150984 0.4501234 -0.8469882 -0.2828429 0.4918299 -0.7822979 -0.3822478 0.5644612 -0.7188066 -0.4058334 0.5645292 -0.7535169 -0.3369257 0.4155488 -0.8470534 -0.3313911 0.4457073 -0.7822918 -0.4351606 0.5137388 -0.7077098 -0.4849942 0.5653991 -0.7077076 -0.4236437 0.3758732 -0.847014 -0.3758813 0.3938927 -0.7823134 -0.4825293 0.4555693 -0.7075753 -0.5401795 0.3313899 -0.8470529 -0.4155504 0.3370973 -0.7823022 -0.5238023 0.3913886 -0.7076253 -0.5882868 0.28283 -0.8469851 -0.4501373 0.2760686 -0.7821707 -0.5585652 0.3221557 -0.7077058 -0.6287832 0.2306126 -0.8470523 -0.4788739 0.2114269 -0.7822827 -0.585946 0.2488489 -0.7076438 -0.6612976 0.1755645 -0.8470095 -0.5017491 0.1441587 -0.7822084 -0.6061092 0.1723098 -0.7076218 -0.6852596 0.1182867 -0.8469945 -0.5182747 0.07503658 -0.7822253 -0.6184603 0.0935319 -0.70767 -0.7003249 0.05950921 -0.8470587 -0.5281576 0.004973351 -0.782305 -0.6228759 0.0135616 -0.7076838 -0.7063992 7.3883e-7 -0.8470706 -0.5314804 -0.06515336 -0.782295 -0.6194915 -0.06658017 -0.7076622 -0.703407 -0.05949795 -0.8471049 -0.5280848 -0.1344805 -0.78222 -0.6083149 -0.1458638 -0.707678 -0.6913145 -0.1182796 -0.8470365 -0.5182078 -0.202086 -0.7822077 -0.5893321 -0.2232744 -0.7076576 -0.6703501 -0.1755799 -0.8469974 -0.5017642 -0.2671101 -0.782224 -0.5628303 -0.2978135 -0.7076338 -0.6407508 -0.2306092 -0.8470589 -0.4788641 -0.3287143 -0.7822705 -0.5291502 -0.368519 -0.707615 -0.6028888 -0.2828359 -0.8469905 -0.4501234 -0.3861855 -0.7822554 -0.4888122 -0.4344601 -0.7076299 -0.5572292 -0.3314183 -0.8470264 -0.415582 -0.4387247 -0.7822699 -0.4422383 -0.4947992 -0.7076464 -0.504391 -0.3758512 -0.8470378 -0.3758494 -0.485751 -0.7822237 -0.3900924 -0.5487866 -0.7076281 -0.4450795 -0.4155573 -0.8470472 -0.3313959 -0.5265119 -0.7822704 -0.3329242 -0.5956189 -0.7077143 -0.3799719 -0.4500748 -0.8470284 -0.2827996 -0.5606526 -0.7822524 -0.2715696 -0.6348899 -0.7076622 -0.3100472 -0.4788564 -0.8470643 -0.2306053 -0.5876708 -0.7822361 -0.2067603 -0.6659202 -0.7076793 -0.2360939 -0.5017296 -0.8470217 -0.1755618 -0.6071122 -0.7823112 -0.1392986 -0.688402 -0.707663 -0.1591096 -0.5182181 -0.8470302 -0.1182795 -0.4226042 -0.901167 -0.0964564 -0.4091466 -0.9011674 -0.1431664 -0.3905458 -0.9011666 -0.1880769 -0.3669564 -0.9012092 -0.2305753 -0.3389003 -0.9011684 -0.270263 -0.3065415 -0.9011464 -0.3065415 -0.2702361 -0.9011894 -0.3388661 -0.230642 -0.9011487 -0.3670631 -0.1880189 -0.9012314 -0.3904241 -0.1431665 -0.901167 -0.4091473 -0.09645712 -0.9011667 -0.4226046 -0.04852879 -0.901188 -0.4307033 -1.89572e-7 -0.9011685 -0.433469 0.04852843 -0.9011909 -0.4306972 0.09644669 -0.901188 -0.4225615 0.1431537 -0.901186 -0.4091098 0.1880372 -0.9012109 -0.3904628 0.2305952 -0.9011905 -0.36699 0.2702357 -0.9011898 -0.3388655 0.3065132 -0.9011656 -0.3065134 0.3389385 -0.9011449 -0.2702937 0.3669939 -0.9011883 -0.2305976 0.3905069 -0.9011873 -0.1880586 0.4091475 -0.9011669 -0.1431668 0.4226041 -0.901167 -0.09645617 0.258921 -0.9044999 -0.3388806 0.2587964 -0.881752 -0.394383 0.2587034 -0.8779866 -0.4027557 0.258819 -0.8411333 -0.4748764 0.258828 -0.8472766 -0.4638218 0.2588183 -0.8286398 -0.4963561 0.5645476 -0.6744317 -0.4758445 0.25892 -0.8121564 -0.5228409 0.2588168 -0.7892445 -0.5568726 0.5648758 -0.6242181 -0.5396918 0.5002124 -0.624242 -0.6000913 0.4291812 -0.6242365 -0.6527881 0.3526549 -0.6242237 -0.6971221 0.2711962 -0.6244753 -0.7324502 0.1869592 -0.6242732 -0.7585047 0.09972816 -0.6243958 -0.7747156 0.0115118 -0.6243489 -0.7810609 -0.07652884 -0.6242337 -0.7774804 -0.1639164 -0.624231 -0.7638502 -0.2495476 -0.6241872 -0.7403488 -0.3311868 -0.6242726 -0.7075303 -0.4089913 -0.6243198 -0.6655456 -0.4818606 -0.6241741 -0.6149936 -0.5482257 -0.6242175 -0.556598 -0.6076895 -0.6241593 -0.4910588 -0.6592314 -0.6242305 -0.419226 -0.7025336 -0.6240753 -0.3420186 -0.7367032 -0.6240575 -0.260424 -0.7612795 -0.6242241 -0.1754938 0.2588069 -0.7731709 -0.5789868 0.2588188 -0.7306613 -0.6317807 0.564516 -0.6201409 -0.5447449 0.2589808 -0.7297968 -0.6327129 0.25882 -0.7256966 -0.6374768 0.4893326 -0.5329362 -0.6903135 0.5644904 -0.5558385 -0.6102411 0.5654379 -0.5329157 -0.6295086 0.4069052 -0.5328273 -0.7419726 0.3189802 -0.5328361 -0.7837967 0.2267297 -0.5329411 -0.8152101 0.1316873 -0.5328429 -0.8359048 0.03503865 -0.532626 -0.8456252 -0.06265264 -0.532929 -0.8438373 -0.1588675 -0.5326228 -0.8313087 -0.2533171 -0.5326165 -0.8075581 -0.3446373 -0.5329177 -0.7728027 -0.4311292 -0.5329107 -0.7281029 -0.5118908 -0.5328003 -0.6738633 -0.5859283 -0.5328906 -0.6105045 -0.6521885 -0.5328686 -0.5391672 -0.7099628 -0.5324297 -0.4609465 -0.7582725 -0.5323716 -0.3763022 -0.7962086 -0.5328942 -0.286489 -0.8239489 -0.5327343 -0.1931388 0.258938 -0.6829729 -0.6830075 0.2588185 -0.6504268 -0.7141134 0.2592736 -0.632345 -0.7300117 0.2588193 -0.623997 -0.7373197 0.5644731 -0.4818785 -0.6701965 0.2592173 -0.5788151 -0.7731621 0.2588228 -0.563848 -0.7842745 0.4831246 -0.4349457 -0.7598768 0.565472 -0.434916 -0.700778 0.3948588 -0.4349678 -0.8092525 0.301558 -0.4348573 -0.8485059 0.2044098 -0.4348365 -0.8770028 0.1046825 -0.4347295 -0.8944563 0.003609955 -0.4349349 -0.9004546 -0.09748923 -0.4349224 -0.895175 -0.1973785 -0.4347801 -0.8786399 -0.2947318 -0.4349052 -0.8508764 -0.3884229 -0.4347668 -0.8124688 -0.4771705 -0.4347646 -0.7637331 -0.5598222 -0.4348996 -0.7053096 -0.6355206 -0.4347742 -0.6380321 -0.7030515 -0.4349179 -0.5626412 -0.7617328 -0.434976 -0.4801657 -0.8108302 -0.4349507 -0.3916279 -0.8496761 -0.4349316 -0.2981357 -0.8777562 -0.4349601 -0.2008823 0.2588232 -0.5222486 -0.8125683 0.2588191 -0.509301 -0.8207467 0.5645176 -0.3991018 -0.7225218 0.2588193 -0.4670161 -0.8455228 0.4783024 -0.3314702 -0.813237 0.5651956 -0.3314647 -0.755437 0.3855863 -0.3314333 -0.8610895 0.2880996 -0.3315413 -0.8983758 0.1871288 -0.3316287 -0.924665 0.08381468 -0.3313047 -0.9397937 -0.02059078 -0.3314263 -0.9432564 -0.1247375 -0.3315331 -0.9351611 -0.2273467 -0.3316207 -0.9156097 -0.3267538 -0.3315002 -0.8850647 -0.4224272 -0.3314675 -0.8436141 -0.5130653 -0.331502 -0.7917515 -0.5974039 -0.3315253 -0.7302052 -0.6743528 -0.3314989 -0.6598159 -0.7430742 -0.3314837 -0.5813427 -0.8027406 -0.3314861 -0.495706 -0.8526741 -0.3315012 -0.4037994 -0.8919419 -0.3314734 -0.3075147 -0.9205259 -0.3313924 -0.2069086 0.2587949 -0.463097 -0.847683 0.2589329 -0.3881056 -0.8844929 0.564525 -0.3088428 -0.7654592 0.2587776 -0.4020617 -0.8782828 0.2588187 -0.3614241 -0.8957598 0.4697642 -0.2237729 -0.8539598 0.5648441 -0.2238524 -0.7942551 0.3685261 -0.2237668 -0.9022843 0.262357 -0.2238084 -0.9386579 0.1527127 -0.2238341 -0.9625889 0.04104304 -0.2238903 -0.9737498 -0.0711627 -0.2238295 -0.972027 -0.1824299 -0.2238451 -0.957399 -0.2912753 -0.2237937 -0.9300942 -0.3962622 -0.223773 -0.8904505 -0.4959952 -0.2238284 -0.8389814 -0.589151 -0.2238209 -0.7764054 -0.6744982 -0.2237984 -0.7035387 -0.7508952 -0.2238638 -0.6213223 -0.8173518 -0.2237776 -0.5309046 -0.872963 -0.2237846 -0.4334236 -0.9170089 -0.2237414 -0.3302038 -0.9488669 -0.2238442 -0.2225884 0.2588437 -0.3378533 -0.9049062 0.2585379 -0.2620772 -0.9297708 0.5645089 -0.2127904 -0.7975274 0.2588672 -0.2734127 -0.9264088 0.258818 -0.2490231 -0.9332742 0.4673277 -0.113292 -0.8767952 0.5644844 -0.1134271 -0.8176135 0.3642053 -0.113405 -0.9243884 0.2562379 -0.11344 -0.9599342 0.1448845 -0.1133317 -0.9829366 0.03167909 -0.1134182 -0.9930422 -0.08198922 -0.1133146 -0.9901705 -0.1945858 -0.1132118 -0.9743304 -0.3045695 -0.1133508 -0.9457215 -0.4105909 -0.1133953 -0.9047412 -0.5112919 -0.1132491 -0.8519128 -0.6052864 -0.1131528 -0.7879245 -0.6914051 -0.1128665 -0.7135967 -0.7682549 -0.1133956 -0.6300206 -0.8352972 -0.1129697 -0.5380674 -0.8911724 -0.1135002 -0.4392375 -0.935501 -0.1135549 -0.3345792 -0.9676113 -0.113468 -0.2255074 0.2589154 -0.2061957 -0.9436346 0.2588173 -0.1327276 -0.9567638 0.5644934 -0.0109964 -0.8253644 0.2590204 -0.07058709 -0.9632891 0.2588196 -0.01286149 -0.9658402 0.2588048 -0.139081 -0.9558644 0.4666469 -0.001606822 -0.8844423 0.5647197 -0.001572608 -0.8252814 0.3631698 -0.00156784 -0.9317218 0.2542536 -0.001601755 -0.9671363 0.142346 -0.001600086 -0.9898157 0.02858215 -0.001598536 -0.9995902 -0.08555388 -0.001596927 -0.9963323 -0.1985743 -0.001595556 -0.9800845 -0.3090063 -0.00159353 -0.9510587 -0.4154064 -0.001591086 -0.9096346 -0.5159686 -0.001546144 -0.8566062 -0.6106482 -0.00158751 -0.7919006 -0.696939 -0.001585602 -0.7171287 -0.7741473 -0.001583576 -0.6330036 -0.8412596 -0.001581668 -0.5406292 -0.8974044 -0.001579344 -0.4412061 -0.9418492 -0.001577556 -0.3360324 -0.9740155 -0.001575291 -0.2264759 0.2590082 -0.001737236 -0.9658735 0.2588175 -0.0018031 -0.9659246 0.4677795 0.1102546 -0.8769414 0.5645064 0.09111022 -0.8203849 0.2588917 0.06687051 -0.9635889 0.258847 0.1066257 -0.9600152 0.3645915 0.1101989 -0.9246239 0.2565577 0.1101351 -0.9602336 0.145183 0.1101691 -0.9832521 0.03189748 0.1101568 -0.9934023 -0.08181923 0.1100974 -0.9905475 -0.1944654 0.1100396 -0.9747177 -0.3044837 0.1102709 -0.9461131 -0.4106227 0.1101196 -0.9051314 -0.5113011 0.1102575 -0.8522996 -0.6053399 0.1102052 -0.7883011 -0.6915561 0.1097723 -0.7139329 -0.7684537 0.1102964 -0.6303282 -0.8355417 0.109867 -0.5383302 -0.8914527 0.1103928 -0.4394605 -0.9358114 0.1104419 -0.3347535 -0.9680038 0.1100203 -0.2255311 0.5649868 0.1102871 -0.817696 0.2588195 0.129127 -0.9572558 0.4699882 0.220739 -0.8546258 0.5644676 0.1920354 -0.8028069 0.2587293 0.1355074 -0.956398 0.2588194 0.2246999 -0.9394267 0.3686969 0.2207676 -0.9029532 0.2624641 0.2207183 -0.9393594 0.1527449 0.2207422 -0.9632974 0.04100316 0.2207401 -0.9744705 -0.07128316 0.2207627 -0.9727193 -0.1826233 0.2207557 -0.9580792 -0.2915419 0.2207203 -0.9307448 -0.3965964 0.2207558 -0.8910546 -0.4963927 0.2207632 -0.8395581 -0.5896093 0.2207449 -0.776938 -0.6750087 0.2207459 -0.7040133 -0.7514521 0.2208207 -0.621738 0.565144 0.2207885 -0.7948992 0.258665 0.2030432 -0.9443865 0.2588192 0.2585104 -0.9306906 0.4778273 0.3284991 -0.8147205 0.5644723 0.2900852 -0.7728011 0.2589268 0.2703382 -0.927294 0.2587526 0.3394099 -0.9043496 0.3845391 0.3281708 -0.8628057 0.2862655 0.3284962 -0.9000791 0.1845582 0.3285105 -0.9262933 0.08054441 0.3286301 -0.941018 -0.02444779 0.3287249 -0.9441093 -0.1291024 0.3285166 -0.9356333 -0.2321874 0.3285298 -0.9155093 -0.3323997 0.3285227 -0.8840721 -0.4285061 0.3284668 -0.8417196 -0.5193184 0.3285186 -0.7889133 -0.6037066 0.3284868 -0.7263847 0.56537 0.3284921 -0.7566042 0.2589712 0.3354303 -0.9057706 0.2588192 0.3846386 -0.8860394 0.4806604 0.432092 -0.7630611 0.5644794 0.3834558 -0.7309753 0.2586888 0.3995634 -0.8794483 0.2588293 0.4487444 -0.8553572 0.3894015 0.4321642 -0.8133883 0.2929557 0.432115 -0.8529089 0.1925836 0.4320892 -0.8810282 0.08963835 0.4320644 -0.897377 -0.01452213 0.4320977 -0.9017099 -0.1184785 0.4321066 -0.8940061 -0.2208534 0.4320893 -0.8743699 -0.3202782 0.4321047 -0.8430347 -0.4335285 0.4079837 -0.8034939 -0.3390754 0.4280629 -0.8377291 -0.3867825 0.4179118 -0.8220396 -0.5235083 0.3888423 -0.7581166 -0.4791535 0.3982619 -0.782176 -0.6077418 0.3709445 -0.7021753 -0.5664169 0.3797 -0.7314369 0.5655421 0.4320828 -0.7024717 0.2592653 0.4614101 -0.8484588 0.2588117 0.5059283 -0.8228324 0.4910319 0.5302298 -0.6911903 0.5645344 0.4706259 -0.6780945 0.2588992 0.5210751 -0.813297 0.2588192 0.5507463 -0.7935309 0.4104028 0.5302491 -0.7418932 0.3245925 0.5302286 -0.7832608 0.2346623 0.5302742 -0.8147043 0.141782 0.5302695 -0.8358902 0.05676561 0.5121974 -0.8569898 0.1062494 0.5227301 -0.8458513 -0.04216295 0.491162 -0.8700473 0.007519006 0.5016851 -0.8650178 -0.1420274 0.4699197 -0.8712083 -0.09207469 0.4805632 -0.8721132 -0.2414624 0.4487732 -0.8604061 -0.1918855 0.4593356 -0.8672893 -0.3253259 0.5196118 -0.7900422 -0.3250508 0.5332954 -0.7809854 -0.3424164 0.5343255 -0.7728179 -0.250092 0.5289543 -0.8109633 -0.4082206 0.5251665 -0.7466968 -0.3860193 0.5368883 -0.75016 -0.4277459 0.5393757 -0.7253326 -0.483371 0.5307669 -0.6961602 -0.4674727 0.5418067 -0.698509 -0.5051971 0.5441402 -0.6698413 -0.550563 0.536251 -0.6397776 -0.5407945 0.5464317 -0.639495 -0.5743097 0.5485804 -0.6076414 0.5654847 0.5302511 -0.6317127 0.2593063 0.5781002 -0.7736669 0.2588195 0.6209418 -0.7398946 0.4973607 0.6057959 -0.6210022 0.5320526 0.6131611 -0.5839123 0.5645745 0.5500016 -0.6154298 0.2592533 0.6320653 -0.7302611 0.2588191 0.6436654 -0.7202136 0.4605451 0.5980073 -0.6559615 0.3811039 0.5811333 -0.7190577 0.4217679 0.5897504 -0.6886991 0.2947961 0.5627518 -0.7722731 0.3387385 0.5721201 -0.7469504 0.2027596 0.5431942 -0.8147568 0.2494093 0.5531347 -0.7948818 0.1756833 0.4977145 -0.849362 0.1502329 0.5078623 -0.848237 0.1109226 0.5095877 -0.8532389 0.1549676 0.533077 -0.8317536 0.1650035 0.5072635 -0.8458474 0.06860786 0.5003833 -0.8630815 0.05676722 0.5121808 -0.8569997 -0.0368635 0.5042313 -0.8627815 0.003678202 0.5148518 -0.8572714 -0.04895025 0.5176639 -0.8541827 -0.1386675 0.5089443 -0.8495571 -0.1008372 0.5205234 -0.8478723 -0.1518432 0.523333 -0.8384906 -0.2352154 0.5140891 -0.8248552 -0.2016164 0.5261811 -0.8261262 0.5644985 0.6201008 -0.5448087 0.2588682 0.6829642 -0.6830428 0.2588179 0.7256404 -0.6375417 0.6366906 0.5231356 -0.5665284 0.627961 0.5211558 -0.5779806 0.5929494 0.5148655 -0.6191322 0.2585272 0.7303484 -0.6322619 0.2588192 0.7841593 -0.5640096 0.6712974 0.5325363 -0.515524 0.5644319 0.5105916 -0.648624 0.5546336 0.5099043 -0.6575556 0.5131997 0.5063617 -0.692982 0.4792926 0.5024909 -0.7195703 0.4690563 0.5039223 -0.725292 0.4224346 0.5026468 -0.7542515 0.3840483 0.4981281 -0.7774158 0.3738076 0.5021891 -0.779791 0.323388 0.5025855 -0.8017656 0.2818105 0.496734 -0.8208765 0.2715564 0.5036304 -0.8201302 0.2186715 0.5052467 -0.8348106 -0.3216171 -0.9440201 -0.07340735 -0.3113768 -0.9440198 -0.1089557 -0.2972609 -0.9440039 -0.1431528 -0.2793264 -0.9440191 -0.1755129 -0.2579195 -0.944019 -0.2056834 -0.2332985 -0.9440042 -0.2332982 -0.2057096 -0.9440044 -0.2579521 -0.1755126 -0.9440189 -0.2793274 -0.1431343 -0.9440188 -0.2972222 -0.1089562 -0.9440191 -0.3113784 -0.07340759 -0.9440199 -0.3216174 -0.03693628 -0.9440196 -0.3278151 7.35795e-7 -0.9440197 -0.3298894 0.03694087 -0.9440043 -0.3278586 0.07341766 -0.9440041 -0.3216616 0.1089379 -0.9440386 -0.3113258 0.1431289 -0.9440233 -0.297211 0.1755112 -0.9440199 -0.2793249 0.2056829 -0.9440193 -0.2579193 0.2333368 -0.943985 -0.2333373 0.2579557 -0.9440028 -0.2057128 0.2793201 -0.9440219 -0.1755081 0.2972179 -0.9440206 -0.1431323 0.3113797 -0.9440187 -0.1089568 0.3216193 -0.9440193 -0.07340794 -0.2167097 -0.9749823 -0.04946285 -0.2097648 -0.9749929 -0.07340025 -0.2003255 -0.974968 -0.09647381 -0.1881447 -0.9750005 -0.1182191 -0.1737524 -0.9749926 -0.1385625 -0.1571764 -0.9749827 -0.1571763 -0.1385615 -0.9749932 -0.1737501 -0.1182343 -0.9749941 -0.1881684 -0.09646427 -0.974972 -0.200311 -0.07338583 -0.975003 -0.2097235 -0.04944247 -0.9750035 -0.2166189 -0.02488642 -0.9749825 -0.2208847 -1.80024e-7 -0.974983 -0.2222795 0.02488636 -0.974983 -0.2208821 0.0494647 -0.9749799 -0.2167197 0.07338684 -0.9750023 -0.209726 0.09646141 -0.9749737 -0.2003036 0.1182575 -0.9749841 -0.1882054 0.1385192 -0.9750083 -0.1736986 0.1571654 -0.9749863 -0.1571649 0.1737165 -0.9750031 -0.1385338 0.1881878 -0.9749886 -0.1182475 0.2002772 -0.9749804 -0.09644901 0.2097603 -0.974994 -0.07339882 0.2167088 -0.9749825 -0.04946225 1 2.34291e-7 0 1 8.31991e-7 0 1 4.58711e-7 0 1 6.44607e-7 0 1 7.11485e-7 0 1 4.80669e-7 0 1 1.39462e-7 0 1 7.96937e-7 0 1 1.98802e-7 0 1 -1.13834e-6 0 1 -1.90575e-7 0 1 -2.18119e-7 0 1 4.11638e-7 0 1 -2.27895e-7 0 1 1.0259e-6 0 1 -2.14664e-7 0 1 -4.02025e-7 0 1 -7.7914e-7 0 1 -3.98123e-7 0 1 1.07614e-6 0 1 0 0 1 0 0 1 -1.56599e-7 0 1 0 0 1 8.58967e-7 0 1 -3.23112e-7 0 1 0 0 1 -2.44847e-7 0 1 0 0 1 -3.26183e-7 0 1 0 0 1 1.44475e-7 0 1 -4.83404e-7 0 1 0 0 0.258751 0.7735609 -0.5784907 1 -1.08145e-6 0 0.2588202 0.8125216 -0.5223227 0.2590712 0.8126417 -0.5220111 1 -1.44228e-7 0 1 -4.15679e-7 0 0.2588173 0.8385871 -0.4793595 0.2588997 0.8477897 -0.462843 1 -2.18069e-7 0 1 -1.09952e-6 0 0.2588186 0.8752824 -0.4085264 0.2588387 0.8786085 -0.40131 1 -7.39368e-7 0 1 -5.79068e-7 0 0.2588191 0.8836377 -0.3901247 0.2589749 0.9049751 -0.337568 1 -8.89765e-7 0 0.2588169 0.9185829 -0.2986958 0.2591037 0.9268388 -0.2717264 1 -2.22317e-7 0 1 -5.96689e-7 0 0.2588165 0.9439439 -0.2048999 0.2588331 0.9438501 -0.2053107 0.2588471 0.9561111 -0.1372945 1 -1.64064e-7 0 1 -1.04379e-6 0 0.2588064 0.9601086 -0.1058808 0.259093 0.9634078 -0.06867593 1 -4.58711e-7 0 0.2588204 0.9659255 -1.23791e-5 0.2588193 0.9659259 1.87977e-5 0.2588183 0.9631626 0.0730139 0.258819 0.9659259 -7.95349e-6 0.2588211 0.9659253 -2.01225e-5 0.258835 0.9634304 0.06932806 1 -2.34292e-7 0 1 -8.31991e-7 0 0.990249 0.139172 -0.006174147 0.9902681 0.1391727 -7.53766e-6 0.981756 0.1392049 -0.1295264 0.9882203 0.1390467 0.06392806 0.9862347 0.1391485 0.08932489 0.9792965 0.1392012 -0.1469751 0.9577962 0.1391776 -0.2515077 0.9873009 0.1391527 -0.0766381 0.9483786 0.1391031 -0.2850062 0.9191601 0.1391631 -0.368481 0.9663156 0.1391606 -0.2164914 0.7493825 0.5683273 -0.3397499 0.7685599 0.59165 -0.243446 0.7479477 0.5698338 -0.3403876 0.9257564 0.1391543 -0.351584 0.8984056 0.139178 -0.4165298 0.8640754 0.1391715 -0.4837406 0.7421875 0.5655323 -0.3596261 0.7018631 0.5430084 -0.4610099 0.7142503 0.549341 -0.4336715 0.7117556 0.5462044 -0.4416613 0.6939215 0.5404976 -0.4757473 0.6427515 0.5244941 -0.5583695 0.259036 0.9435946 0.2062271 0.2588201 0.9401591 0.2216151 0.2588192 0.9393844 0.2248774 0.2588706 0.9308267 0.2579685 -0.2587968 0.9659318 -3.74207e-6 -0.2588198 0.9659256 0 -0.2588321 0.9659224 -1.56057e-5 -0.2588226 0.965925 0 0.2588194 0.9187276 0.2982486 0.2588203 0.9408795 0.2185359 0.2588159 0.9546875 0.1469222 0.9691728 0.139256 0.2032532 0.9531907 0.139176 0.2684357 0.9737789 0.1391711 0.1799614 0.9521836 0.139259 0.2719437 0.9528485 0.1391744 0.2696486 0.258575 0.9560592 0.138166 0.9811899 0.1392344 0.1337171 1 -6.44607e-7 0 1 -7.11486e-7 0 0.2588468 0.9282277 0.2671924 0.2588419 0.9264505 0.2732954 1 -4.80673e-7 0 0.2588179 0.9295582 0.2625545 0.2588336 0.8972146 0.3577864 0.2587979 0.904555 0.3388273 1 -1.39473e-7 0 1 -7.96956e-7 0 0.2588409 0.8780312 0.4025702 1 -1.98804e-7 0 0.2588192 0.8573762 0.4448806 0.2588839 0.8471327 0.4640533 1 1.13834e-6 0 1 1.90577e-7 0 0.2588332 0.8157124 0.517319 0.2588765 0.8121716 0.5228388 1 2.1812e-7 0 0.2588076 0.8272693 0.4986425 0.258845 0.8411474 0.4748373 0.2588199 0.7930749 0.5514024 1 -4.11638e-7 0 0.258823 0.7954624 0.5479509 0.2588412 0.7998678 0.5414915 0.258825 0.8065829 0.5314447 1 2.27895e-7 0 1 -1.02589e-6 0 0.2588194 0.7924039 0.5523664 1 2.14663e-7 0 1 4.02017e-7 0 1 7.79136e-7 0 1 3.98125e-7 0 1 -1.07614e-6 0 1 0 0 1 0 0 1 1.56599e-7 0 1 0 0 1 -8.58973e-7 0 1 3.23112e-7 0 1 0 0 1 2.44847e-7 0 1 0 0 1 3.26183e-7 0 1 0 0 1 -1.44473e-7 0 1 4.83405e-7 0 1 0 0 1 1.08145e-6 0 0.2588175 -0.8049442 0.5339274 0.2588655 -0.8127419 0.5219572 1 1.44229e-7 0 1 4.15674e-7 0 0.2588199 -0.7984525 0.5435861 0.2588223 -0.7944393 0.5494335 0.2588184 -0.7926136 0.5520659 0.2588453 -0.8403336 0.4762757 0.258868 -0.8477497 0.4629339 1 2.1807e-7 0 1 1.09951e-6 0 0.2588483 -0.8258546 0.5009608 0.2588207 -0.8140724 0.519902 0.2588187 -0.8573783 0.444877 0.2588043 -0.8786155 0.4013169 1 7.39365e-7 0 1 5.79063e-7 0 0.2588016 -0.8972162 0.3578055 0.2588385 -0.9050551 0.3374584 1 8.89765e-7 0 0.2588213 -0.9282279 0.2672164 0.2585712 -0.9268057 0.2723456 1 2.22316e-7 0 1 5.96693e-7 0 0.2588185 -0.9415953 0.2154334 0.2588204 -0.9308308 0.2580041 0.2588211 -0.9295689 0.2625135 1 1.64064e-7 0 1 1.04379e-6 0 0.2588141 -0.9147606 0.3102072 -0.9659257 -0.2588195 0 -0.9659258 -0.2588196 0 -0.9659258 -0.2588194 0 0.258834 -0.9003812 0.3497411 0.2588181 -0.8784154 0.4017457 -0.9659259 -0.2588193 0 0.2587481 -0.8611315 0.4376096 0.2588194 -0.8630999 0.4336717 -0.9659307 -0.2588011 -1.00581e-5 -0.9659269 -0.2588149 4.95464e-6 -0.8555176 -0.5177738 6.51926e-7 0.2588194 -0.8492742 0.4601584 -0.8518016 -0.5238646 -3.19784e-5 -0.6791215 -0.7340259 -4.65661e-7 0.2588253 -0.8457099 0.4666736 -0.6675041 -0.7446061 3.67052e-5 0.2588179 0.8128673 0.5217856 0.2588192 0.812913 0.5217138 0.6940779 0.540552 0.4754571 0.2588449 0.8052039 0.5335223 0.2588459 0.7994506 0.5421048 0.2588108 0.7954962 0.5479079 0.2588192 0.7932235 0.5511889 0.2588261 0.8224576 0.5065301 0.2588186 0.8213272 0.5083646 0.6550946 0.5275638 0.5408582 0.7006111 0.5432144 0.4626688 0.2588218 0.8610979 0.437632 0.258821 0.8639218 0.4320311 0.7265864 0.555477 0.4043732 0.7337588 0.5599772 0.3847386 0.2588083 0.846648 0.4649791 0.2588099 0.8337047 0.4878052 0.7204076 0.551968 0.4199337 0.7153798 0.5493004 0.4318575 0.7116273 0.5474365 0.4403406 0.7092747 0.5462579 0.4455689 0.7084137 0.5457872 0.4475115 0.2588242 0.9003773 0.3497583 0.2588144 0.8654567 0.428952 -0.1080248 0.9941482 -1.02053e-5 -0.1177768 0.9930401 3.48315e-7 -0.1892862 0.981922 -3.25032e-7 0.04463887 0.9990032 7.26225e-5 0.06627684 0.9978013 1.88686e-6 0.25881 0.8672219 0.4253746 -0.2588374 0.9659209 -1.43587e-6 -0.2588036 0.9659301 2.03e-5 0.2588193 0.8948414 0.3636915 -0.258823 0.9659248 0 -0.9659501 0.2587288 0 -0.9659262 0.258818 0 -0.965928 0.2588109 0 -0.9659252 0.2588216 0 0.9659276 -0.2588124 0 0.965928 -0.2588109 0 0.9659268 -0.2588157 0 0.9659264 -0.258817 0 0.9659314 -0.2587981 -2.13735e-7 0.9659241 -0.2588258 -2.8871e-6 0.9991516 -0.04118353 -1.41934e-6 1 -5.37979e-6 1.01456e-6 0.9865415 0.1635112 1.63913e-6 0.9914488 -0.1304965 3.25335e-5 0.9583525 0.285588 3.22616e-5 0.9363541 0.3510574 1.00769e-6 0.8556045 0.5176301 1.84029e-6 0.8374752 0.5464754 6.35543e-5 0.7510439 0.6602524 3.31551e-7 0.6479616 0.761673 5.03028e-5 0.6299554 0.7766314 -3.15718e-7 0.5000621 0.8659896 -4.20259e-7 0.4057026 0.9140052 1.89678e-5 0.3651459 0.9309504 -1.52782e-6 0.2238481 0.974624 0 0.1304954 0.991449 -2.76221e-5 0.07377052 0.9972752 1.37836e-7 -0.08737534 0.9961755 6.35162e-7 -0.155372 0.9878561 4.15142e-5 -0.2578955 0.9661729 9.70438e-7 -0.4288032 0.903398 2.46801e-5 -0.4307065 0.9024922 1.17905e-6 -0.597297 0.8020203 1.29268e-6 -0.6675415 0.7445726 -3.0057e-5 -0.7493414 0.6621839 -1.61678e-6 -0.8518065 0.5238566 2.22581e-5 -0.8765288 0.4813497 1.16043e-6 -0.9659312 0.2587991 3.79351e-6 -0.9659197 0.258842 0 -0.9659254 -0.2588206 3.57583e-6 -0.9659258 -0.2588192 4.80666e-6 -0.9659247 -0.2588235 1.13693e-6 -0.9659243 -0.2588248 0 -0.9659275 -0.258813 5.88061e-6 -0.9659209 -0.2588375 3.83705e-6 -0.8703269 -0.4924744 3.17022e-6 -0.8517896 -0.523884 -3.41246e-5 -0.7337058 -0.6794673 -2.03401e-6 -0.6675028 -0.7446073 1.20385e-5 -0.5706441 -0.8211975 -1.99676e-6 -0.4287735 -0.9034121 -4.06154e-5 -0.3928326 -0.9196101 2.12342e-6 -0.2098896 -0.9777251 1.40257e-6 -0.1553206 -0.9878641 -4.10752e-5 -0.03137135 -0.9995078 8.97795e-7 0.130558 -0.9914407 1.33107e-5 0.1356238 -0.9907605 2.23517e-7 0.2908751 -0.9567611 -1.5287e-5 0.4057605 -0.9139795 1.88625e-5 0.4366201 -0.8996461 0 0.5765201 -0.817083 9.5088e-7 0.648012 -0.7616302 -6.75349e-5 0.7097425 -0.7044613 3.63216e-7 0.8281542 -0.5605005 -1.28895e-6 0.8374884 -0.5464553 2.88442e-5 0.9215177 -0.3883365 1.38395e-6 0.9583631 -0.2855525 8.28109e-6 0.9815385 -0.1912649 1.21444e-6 1 -8.98289e-6 1.39151e-6 0.9996577 0.0261619 -3.81842e-7 0.9914278 0.1306555 1.48872e-4 0.9659317 0.2587972 -3.68734e-6 0.9659273 0.2588137 -1.18806e-6 0.965927 0.2588148 -3.69732e-6 0.965924 0.2588261 -3.11351e-5 0.9659275 0.2588133 0 0.9659202 0.2588403 0 0.1961669 0.9805706 1.29517e-4 0.2415586 0.9703863 -9.33185e-7 0.3428416 0.9393932 2.51256e-4 0.4042649 0.914642 -7.71135e-7 0.4814151 0.8764928 1.21733e-4 0.5497421 0.8353345 6.83591e-7 0.6087446 0.7933663 1.16505e-4 0.6711277 0.7413418 7.63103e-7 0.7220527 0.691838 5.25522e-4 0.7476463 0.6640973 1.42679e-6 0.8186034 0.5743591 5.14066e-5 0.8570887 0.515169 -1.36014e-6 0.8963515 0.4433444 1.16093e-4 0.7711027 0.6367109 -1.37067e-6 0.9295564 0.3686801 -4.44241e-7 0.9533672 0.301813 8.49836e-5 0.9799138 0.1994214 2.14204e-7 0.9882481 0.1528593 -1.55382e-6 0.9998567 0.01693379 -9.72301e-7 1 -1.79986e-5 -3.3644e-7 0.9852066 -0.1713711 -2.40654e-6 0.9657701 -0.2593998 6.90855e-6 0.9332426 -0.3592471 1.60001e-6 0.8658705 -0.5002682 5.43473e-5 0.8346048 -0.5508494 -1.8049e-6 0.7072985 -0.7069151 7.17468e-6 0.6892237 -0.7245486 -4.13507e-7 0.5004225 -0.8657813 1.0742e-4 0.4968233 -0.8678517 -2.02283e-6 0.2588295 -0.965923 -8.79968e-7 0.2588127 -0.9659276 0 0.2588108 -0.9659281 0 0.2588098 -0.9659283 0 0.2588037 -0.9659301 1.10269e-6 0.2588136 -0.9659273 0 0.9524565 0.1391732 0.2710306 0.9303497 0.1392568 0.3392008 0.9207616 0.139151 0.3644658 0.8364807 0.1391116 0.5300455 0.8297148 0.1391723 0.5405594 0.8378703 0.1391731 0.5278298 0.7238698 0.5519316 0.4139859 0.7243641 0.5525013 0.4123581 0.7327634 0.5567814 0.3912191 0.7961313 0.1395621 0.5888101 0.8133975 0.1391875 0.5648109 0.8490258 0.1392039 0.5096838 0.8632385 0.1391616 0.4852355 0.8722919 0.1393792 0.4687007 0.8801225 0.1391727 0.4538893 0.903622 0.1394104 0.4050087 0.7081257 0.5456368 0.44815 0.7081022 0.5455185 0.4483311 0.6558899 0.527691 0.5397692 0.7094832 0.5459997 0.4455536 0.714049 0.5472071 0.4366905 0.7125995 0.5472363 0.4390153 0.7175804 0.5493683 0.4281039 0.5854251 0.5133393 0.6275032 0.5772331 0.5118003 0.6362881 0.5013248 0.5027684 0.7041998 0.4804435 0.4992125 0.7210832 0.4054358 0.4953251 0.7682934 0.3094261 0.4852784 0.8177778 0.3012477 0.4906461 0.8176286 0.369349 0.4893302 0.7900236 0.1800532 0.478608 0.8593692 0.1921709 0.4882346 0.8512915 0.2460202 0.4816808 0.8411051 0.0447852 0.4741471 0.879306 0.08192729 0.4878149 0.8690943 0.1126265 0.4760987 0.8721498 -0.02347207 0.472789 0.880863 -0.02667796 0.4890197 0.8718647 -0.1592735 0.4719476 0.8671203 -0.1310226 0.4915248 0.8609508 -0.09175097 0.4720214 0.8767997 -0.2911437 0.4739294 0.8310393 -0.2292109 0.495324 0.837924 -0.2260605 0.4725455 0.8518201 -0.3526687 0.4759965 0.8056377 -0.320249 0.4999994 0.8046373 -0.4642382 0.4821811 0.7429565 -0.4032016 0.505429 0.7628696 -0.4099969 0.4787604 0.7763319 -0.5156781 0.4863738 0.7053486 -0.4778513 0.5113814 0.7142459 -0.6069 0.4967712 0.6203958 -0.5439821 0.5177768 0.660296 -0.5633571 0.4912645 0.664295 -0.6462265 0.5028068 0.5740876 -0.6018576 0.5243387 0.6023592 -0.6806825 0.5093316 0.526548 -0.6515965 0.5310403 0.5416811 -0.7363097 0.5230768 0.4292304 -0.6937692 0.5376338 0.4792017 -0.7107056 0.5160874 0.4780705 -0.6937711 0.537634 0.4791988 -0.7362897 0.5230925 0.4292457 -0.7963223 0.1391741 0.5886438 -0.7963232 0.1391726 0.588643 -0.7559825 0.1391736 0.639626 -0.7270767 0.5339473 0.4315784 -0.796319 0.1391741 0.5886482 -0.7923218 0.1403036 0.5937517 -0.7962918 0.1391728 0.5886853 -0.7519119 0.1392 0.6444005 -0.7122812 0.1391726 0.6879583 -0.796323 0.1391711 0.5886434 -0.7036285 0.1394379 0.6967526 -0.6652782 0.1391717 0.7335096 -0.6517329 0.1392989 0.7455469 -0.6151438 0.139177 0.7760335 -0.5964931 0.1391562 0.7904629 -0.562468 0.139176 0.8150213 -0.538176 0.1392043 0.8312574 -0.5074897 0.1391621 0.8503459 -0.4771018 0.1391929 0.8677553 -0.4504919 0.1391671 0.8818671 -0.41358 0.1391504 0.8997716 -0.3924569 0.1391596 0.9091822 -0.3479413 0.1391017 0.9271394 -0.332691 0.1391691 0.9327104 -0.2805014 0.139221 0.9497035 -0.2700842 0.1391674 0.9527261 -0.2116454 0.139186 0.9673849 -0.2051491 0.139171 0.9687855 -0.1416104 0.1395304 0.9800397 -0.1395989 0.1391729 0.9803791 -0.07381165 0.1391728 0.9875135 -0.07114607 0.1395699 0.9876531 -0.00800985 0.139135 0.9902411 1.92707e-5 0.1390731 0.9902821 0.05798351 0.1391258 0.9885757 0.07103711 0.139185 0.9877153 0.1237025 0.1391304 0.9825175 0.141712 0.1391279 0.9800822 0.1893206 0.1391291 0.9720087 0.2116529 0.1392025 0.967381 0.2543742 0.1391609 0.9570413 0.2805148 0.139178 0.9497058 0.3177943 0.1391407 0.9378948 0.34794 0.1392042 0.9271246 0.3789201 0.1391757 0.9149042 0.4136458 0.1391344 0.8997437 0.4971579 0.1391872 0.8564234 0.5383975 0.1390432 0.8311408 0.6082235 0.1391593 0.7814723 0.4770744 0.139151 0.8677771 0.6517904 0.1391388 0.7455264 0.7088366 0.1391772 0.6915059 0.5964292 0.1391429 0.7905135 0.7519549 0.1389975 0.644394 0.7963258 0.1391748 0.5886389 0.7037129 0.13919 0.6967169 -0.7133412 0.544572 0.4411189 -0.4180479 0.9084251 1.34632e-5 -0.4283112 0.9036313 0 -0.7199516 0.5404919 0.4353599 -0.7179018 0.5419366 0.4369459 -0.584941 0.8110759 -2.73809e-7 -0.7898978 0.1420378 0.5965625 -0.7871636 0.1436006 0.5997936 -0.7885041 0.142691 0.5982479 -0.6560821 0.7546896 2.80492e-5 -0.7227277 0.6911329 1.41561e-6 -0.7916135 0.1411313 0.5944999 -0.7933775 0.1403322 0.5923336 -0.7938959 0.1402226 0.5916646 -0.7926712 0.1403307 0.5932788 0.1391688 0.9902687 0 0.1391723 0.9902682 -8.79845e-6 0.1391679 0.9902689 0 0.1391724 0.9902682 -7.44046e-6 0.1391678 0.9902689 0 0.1391775 0.9902675 0 0.1391776 0.9902675 -2.46389e-5 -0.826892 0.5623608 9.53674e-7 -0.8414629 0.540315 1.59618e-4 -0.9557902 0.2940495 -1.46707e-6 -0.95938 0.2821174 5.18166e-5 -0.9028514 0.4299528 -7.37142e-7 -0.9886856 0.1500024 -8.08916e-5 -1 -3.40403e-6 2.98109e-5 -0.9856054 -0.1690626 2.7474e-7 -0.9590995 -0.2830694 1.51654e-5 -0.9999898 -0.004523873 -2.52388e-7 -0.8564253 -0.5162711 0 -0.8403855 -0.5419891 6.59103e-5 -0.9398812 -0.3415017 -1.3411e-7 -0.7298734 -0.6835824 -2.34507e-6 -0.6537241 -0.756733 7.37538e-6 -0.5548085 -0.8319781 2.5034e-6 -0.4137959 -0.9103698 3.4087e-5 -0.1391525 -0.990271 -4.74229e-6 -0.1391753 -0.9902678 0 -0.2297447 -0.9732511 4.82425e-7 -0.320507 -0.9472462 2.83867e-6 -0.1391718 -0.9902684 0 -0.1391711 -0.9902684 0 -0.1391889 -0.9902659 4.47909e-5 -0.8606266 0.1776646 0.4772393 -0.8009316 0.1600303 0.576974 -0.7934461 0.1570274 0.5880356 -0.1391797 -0.9902672 -8.3555e-6 -0.8376706 0.1749271 0.5174055 -0.1391751 -0.9902679 -1.40363e-5 -0.1392047 -0.9902637 1.5229e-4 -0.7857225 0.15398 0.599108 -0.7857156 0.1539954 0.5991131 -0.793422 0.1479172 0.5904255 -0.8131204 0.1548147 0.5611308 -0.8131194 0.1548104 0.5611334 -0.7949035 0.1443489 0.5893149 -0.7950195 0.1422632 0.5896654 -0.7948276 0.1411146 0.5901997 -0.7945609 0.1405194 0.5907008 -0.794269 0.1402739 0.5911516 -0.9207823 0.2095289 0.3290254 -0.9222754 0.2090782 0.3251069 -0.898553 0.1994855 0.3909067 -0.9663361 0.225161 0.1244875 -0.9576835 0.2194071 0.1862874 -0.9005351 0.1964809 0.3878555 -0.9455261 0.2113072 0.2476481 -0.8702692 0.1880724 0.4552587 -0.9105413 0.188067 0.3681648 -0.9298335 0.2008633 0.3083239 -0.8876264 0.1728879 0.4268831 -0.8610293 0.1554513 0.4842143 -0.83086 0.1430695 0.5377759 -0.861019 0.1554526 0.4842323 -0.7963277 0.1391769 0.5886358 0 1 3.03398e-5 0 1 -5.07418e-5 0 1 6.57209e-5 0 1 -3.66678e-5 0 1 6.68413e-5 0 1 -3.91293e-5 0 1 4.01484e-5 0 1 -2.00333e-5 0 1 0 0 1 -1.74408e-5 0 1 2.82405e-5 0 1 -4.72328e-5 0 1 5.1791e-5 0 1 -3.54449e-5 0 1 -1.78115e-5 0 1 3.38203e-5 0 1 -5.60948e-5 0 1 4.51184e-5 -0.7118498 0.1391725 -0.6884046 -0.7045952 0.1391565 -0.6958312 0 1 -6.38832e-5 0 1 3.90764e-5 -0.664231 0.1391738 -0.7344576 -0.653111 0.1393358 -0.744333 0 1 -5.6356e-5 0 1 2.36405e-5 -0.6132097 0.1391714 -0.7775636 -0.598299 0.1392312 -0.7890837 0 1 -1.97927e-5 0 1 -1.18453e-5 -0.5590937 0.1391712 -0.8173406 -0.5404062 0.1392385 -0.8298035 0 1 -8.64477e-5 0 1 1.55037e-5 -0.5019479 0.1391679 -0.853628 -0.4797677 0.1393283 -0.8662624 0 1 -2.18962e-7 0 1 -2.11105e-5 -0.442413 0.1391689 -0.8859474 -0.416787 0.1392347 -0.8982775 0 1 -1.45369e-5 0 1 -1.97862e-5 -0.3817504 0.1391698 -0.9137277 -0.3519464 0.139294 -0.9255977 0 1 -1.23269e-4 0 1 1.4246e-4 -0.3201244 0.1391769 -0.9370967 -0.2853038 0.1392043 -0.9482741 0 1 -1.63854e-4 0 1 1.46621e-4 -0.2567489 0.1391625 -0.9564067 -0.2167429 0.1391806 -0.9662563 0 1 2.47371e-6 0 1 2.00675e-4 -0.1911395 0.1391758 -0.971646 -0.1467498 0.139308 -0.979315 0 1 0 -0.124715 0.1391521 -0.9823863 -0.07602041 0.139154 -0.9873486 -0.05849432 0.1392002 -0.9885352 -0.004966437 0.1392976 -0.9902382 0.007156789 0.1391555 -0.9902447 0.06606459 0.1392444 -0.9880519 0.07242375 0.1391793 -0.9876154 0.1368258 0.1394277 -0.9807338 0.1367201 0.139164 -0.980786 0.2064749 0.1392324 -0.968495 0.262968 0.1391696 -0.9547144 0.2752284 0.1391758 -0.9512516 0.2004014 0.1391901 -0.969776 0.3423442 0.1391115 -0.9292193 0.3851826 0.139182 -0.9122844 0.4079211 0.1391718 -0.9023478 0.4711592 0.1391328 -0.8710058 0.5025278 0.1391646 -0.8532872 0.5320677 0.1391679 -0.8351864 0.5901545 0.1391588 -0.795206 0.6099007 0.1391665 -0.7801628 0.6452636 0.1391527 -0.7511801 0.69703 0.1391591 -0.7034089 0.7069153 0.1391736 -0.6934707 0.7452924 0.1391531 -0.652055 0.7897449 0.1391702 -0.5974401 0.7924858 0.1391721 -0.5937992 0.830196 0.1391192 -0.5398337 0.8665921 0.1391524 -0.4792231 0 1 5.91018e-5 0 1 -3.83559e-5 0 1 -3.64284e-5 0 1 1.95261e-5 0 1 -1.6131e-5 0 1 1.0466e-5 0 1 -5.01034e-5 0 1 1.53287e-5 0 1 5.36995e-5 0 1 -1.87125e-5 0 1 4.12271e-5 0 1 -8.57777e-5 0 1 -7.14494e-6 0 1 1.30582e-6 0 1 7.99638e-5 0 1 -1.46786e-6 0 1 -9.15627e-5 0 1 2.11454e-6 0 1 1.7469e-4 0 1 -2.10545e-4 0 1 -1.79222e-4 0 1 -1.87254e-5 0 1 1.28485e-5 0 1 3.45608e-5 0 1 -6.88008e-5 0 1 -8.59343e-5 0 1 -1.29825e-5 -0.6803683 0.5092606 -0.5270225 -0.5960555 0.523621 -0.608719 -0.6454441 0.5026895 -0.5750699 -0.60531 0.4965474 -0.6221259 -0.5338955 0.5167321 -0.669286 -0.5604712 0.4909305 -0.6669778 -0.4625308 0.5100876 -0.7251731 -0.5108038 0.4859337 -0.7091883 -0.4568282 0.4816452 -0.747881 -0.3817608 0.5039099 -0.7748119 -0.3998728 0.4782106 -0.7819311 -0.2917929 0.4984269 -0.8163502 -0.3404489 0.4755166 -0.8111587 -0.2778201 0.4735818 -0.8357849 -0.1931328 0.4938153 -0.8478479 -0.2119119 0.4723631 -0.8555505 -0.08685213 0.4903209 -0.8672036 -0.1440827 0.4719091 -0.8697944 -0.07591348 0.4721325 -0.8782529 0.0253691 0.4882456 -0.8723375 -0.007916271 0.4730188 -0.8810169 0.05972993 0.4745374 -0.8782065 0.1410545 0.4878422 -0.8614603 0.1260877 0.4765409 -0.8700636 0.1911588 0.4791072 -0.8566882 0.2569521 0.4894369 -0.833323 0.25476 0.4821514 -0.8382287 0.3691493 0.4934131 -0.7875738 0.3754033 0.4897936 -0.7868766 0.4734492 0.5001936 -0.7250189 0.4852477 0.4997264 -0.7175014 0.565778 0.5103644 -0.6476291 0.5785816 0.5120246 -0.6348813 0.6544631 0.527332 -0.5418478 6.39817e-7 -8.95932e-6 1 3.56918e-6 -1.76281e-5 1 -8.8696e-6 -0.1489707 0.9888416 7.86551e-6 0.1489698 0.9888418 1.28902e-5 0.07515704 0.9971717 -4.624e-7 1.1038e-5 1 -3.56918e-6 1.9826e-5 1 -3.48699e-5 -0.1499056 0.9887004 -3.26424e-4 -0.2951248 0.9554587 -1.31903e-5 -0.07515668 0.9971718 9.88873e-5 -0.2963385 0.955083 2.05279e-5 -0.4343236 0.900757 -4.3489e-5 -0.2237197 0.9746536 1.26803e-4 -0.4354089 0.9002329 -1.29228e-4 -0.5634481 0.8261514 8.88993e-5 -0.5645377 0.8254074 -7.9893e-5 -0.6801153 0.7331052 1.30854e-5 -0.6807149 0.7325485 2.07544e-4 -0.7331687 0.6800468 5.87549e-5 -0.7824113 0.622762 -3.37765e-7 -0.7824109 0.6227627 4.32387e-5 -0.8662775 0.4995632 1.69811e-4 -0.8668631 0.4985464 1.2183e-4 -0.9309042 0.3652634 -1.96491e-4 -0.9315804 0.3635354 1.84878e-4 -0.9748135 0.2230215 -2.37474e-4 -0.9753692 0.2205784 2.279e-4 -0.9971165 0.0758863 -2.46783e-4 -0.9973298 0.0730291 2.46784e-4 -0.9973298 -0.07302916 1.07483e-4 -0.9971106 -0.07596391 -1.0445e-4 -0.9753603 -0.2206181 -1.84877e-4 -0.9748135 -0.2230215 1.9648e-4 -0.9315804 -0.3635354 -1.21823e-4 -0.9309043 -0.3652635 1.2693e-4 -0.8667759 -0.4986979 -4.32278e-5 -0.8662775 -0.4995633 3.49362e-7 -0.7824107 -0.6227629 -5.87524e-5 -0.7824113 -0.622762 -2.0754e-4 -0.7331686 -0.6800469 3.06716e-5 -0.6807312 -0.7325333 7.9893e-5 -0.6801154 -0.7331051 -8.88993e-5 -0.5645374 -0.8254076 1.29228e-4 -0.5634482 -0.8261514 -1.06511e-5 -0.4357002 -0.9000919 1.27799e-4 -0.4340435 -0.9008919 -9.89967e-5 -0.2963383 -0.9550831 3.26417e-4 -0.2951248 -0.9554587 4.33859e-5 -0.2237198 -0.9746536 3.49938e-5 -0.1499055 -0.9887004 8.89142e-6 -0.1489707 -0.9888416 1.31903e-5 -0.07515668 -0.9971718 -6.39817e-7 -8.96305e-6 -1 6.52856e-7 1.10343e-5 -1 3.56918e-6 1.97738e-5 -1 -7.85876e-6 0.1489698 -0.9888418 -3.56918e-6 -1.76877e-5 -1 2.00816e-6 0.1498785 -0.9887045 9.25548e-5 0.2948806 -0.9555342 -1.27743e-5 0.0751571 -0.9971717 9.89013e-5 0.2963316 -0.9550852 -1.27486e-4 0.4340565 -0.9008857 -4.44043e-5 0.2237194 -0.9746537 1.27211e-4 0.4353992 -0.9002376 -1.28652e-4 0.5634716 -0.8261355 8.88943e-5 0.564515 -0.8254229 -7.98968e-5 0.6801395 -0.7330828 -2.0221e-5 0.6807277 -0.7325367 2.06667e-4 0.7331939 -0.6800196 5.44187e-5 0.7824098 -0.622764 1.14743e-6 0.7824178 -0.622754 4.23964e-5 0.8662768 -0.4995644 -1.27825e-4 0.8667757 -0.4986982 1.20616e-4 0.9309048 -0.3652619 -1.97643e-4 0.931585 -0.3635236 1.83923e-4 0.9748167 -0.2230079 1.07736e-4 0.9753625 -0.2206084 -1.03291e-4 0.9971104 -0.07596677 -2.4652e-4 0.9973278 -0.07305687 -9.68676e-5 0.9973297 0.07303196 -2.29169e-4 0.9971172 0.07587754 2.36491e-4 0.9753642 0.2206008 -1.83923e-4 0.9748166 0.2230078 1.97631e-4 0.931585 0.3635237 -1.2061e-4 0.9309048 0.365262 1.27823e-4 0.8667756 0.4986983 -4.23803e-5 0.8662767 0.4995645 -1.12341e-6 0.7824176 0.6227542 -5.43835e-5 0.7824098 0.622764 -2.06648e-4 0.7331939 0.6800197 2.01575e-5 0.6807277 0.7325366 7.98967e-5 0.6801038 0.7331159 -8.88943e-5 0.5645146 0.8254231 1.28652e-4 0.5634714 0.8261355 -1.37988e-5 0.4356914 0.9000962 1.27486e-4 0.4340564 0.9008858 -9.89013e-5 0.2963314 0.9550853 3.26889e-4 0.295122 0.9554596 2.00304e-6 0.2237428 0.9746482 3.69495e-5 0.1499073 0.9887002 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.38346e-7 0 1 0 0 1 1.48459e-7 0 1 0 0 1 -1.78357e-7 0 1 0 0 1 -1.61632e-7 0 1 0 0 1 0 0 1 -1.45574e-7 0 1 0 0 1 -1.91671e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.04641e-7 0 5.89603e-7 0 1 -3.64282e-7 0 1 0 0 1 0 0 1 -2.37317e-7 0 1 0 0 1 -1.39627e-7 0 1 -1.47166e-7 0 1 0 0 1 -1.83958e-7 0 1 0 0 1 0 0 1 + + + + + + + + + + 0.573463 0.614479 0.596785 0.641817 0.600238 0.593917 0.591918 0.593917 0.600238 0.593917 0.596785 0.641817 0.573463 0.55887 0.573463 0.614479 0.600238 0.593917 0.609811 0.548473 0.573463 0.55887 0.600238 0.593917 0.605736 0.593917 0.609811 0.548473 0.600238 0.593917 0.591918 0.593917 0.605736 0.593917 0.600238 0.593917 0.573463 0.668605 0.591918 0.688374 0.596785 0.641817 0.591918 0.593917 0.596785 0.641817 0.591918 0.688374 0.573463 0.614479 0.573463 0.668605 0.596785 0.641817 0.573463 0.720529 0.590852 0.701211 0.591918 0.688374 0.591918 0.593917 0.591918 0.688374 0.590852 0.701211 0.573463 0.668605 0.573463 0.720529 0.591918 0.688374 0.573463 0.720529 0.590888 0.711722 0.590852 0.701211 0.590785 0.593917 0.590852 0.701211 0.590888 0.711722 0.591918 0.593917 0.590852 0.701211 0.590785 0.593917 0.573463 0.720529 0.591793 0.720215 0.590888 0.711722 0.591233 0.593917 0.590888 0.711722 0.591793 0.720215 0.590785 0.593917 0.590888 0.711722 0.591233 0.593917 0.573463 0.769563 0.593392 0.726922 0.591793 0.720215 0.593202 0.593917 0.591793 0.720215 0.593392 0.726922 0.573463 0.720529 0.573463 0.769563 0.591793 0.720215 0.591233 0.593917 0.591793 0.720215 0.593202 0.593917 0.573463 0.769563 0.595555 0.732032 0.593392 0.726922 0.593202 0.593917 0.593392 0.726922 0.595555 0.732032 0.573463 0.769563 0.598153 0.735649 0.595555 0.732032 0.596544 0.593917 0.595555 0.732032 0.598153 0.735649 0.593202 0.593917 0.595555 0.732032 0.596544 0.593917 0.573463 0.769563 0.601009 0.737847 0.598153 0.735649 0.596544 0.593917 0.598153 0.735649 0.601009 0.737847 0.573463 0.769563 0.603935 0.738794 0.601009 0.737847 0.601023 0.593917 0.601009 0.737847 0.603935 0.738794 0.596544 0.593917 0.601009 0.737847 0.601023 0.593917 0.573463 0.769563 0.606948 0.738696 0.603935 0.738794 0.606326 0.593917 0.603935 0.738794 0.606948 0.738696 0.601023 0.593917 0.603935 0.738794 0.606326 0.593917 0.624062 0.748894 0.610208 0.737535 0.606948 0.738696 0.606326 0.593917 0.606948 0.738696 0.610208 0.737535 0.573463 0.769563 0.624062 0.748894 0.606948 0.738696 0.624062 0.748894 0.613802 0.735061 0.610208 0.737535 0.6121 0.593917 0.610208 0.737535 0.613802 0.735061 0.606326 0.593917 0.610208 0.737535 0.6121 0.593917 0.624062 0.748894 0.617527 0.731131 0.613802 0.735061 0.615453 0.593917 0.613802 0.735061 0.617527 0.731131 0.6121 0.593917 0.613802 0.735061 0.615453 0.593917 0.624062 0.748894 0.621202 0.725688 0.617527 0.731131 0.618636 0.593917 0.617527 0.731131 0.621202 0.725688 0.615453 0.593917 0.617527 0.731131 0.618636 0.593917 0.807968 0.653536 0.621202 0.725688 0.624062 0.748894 0.618636 0.593917 0.621202 0.725688 0.621679 0.593917 0.624824 0.715193 0.621679 0.593917 0.621202 0.725688 0.807968 0.653536 0.804827 0.637482 0.621202 0.725688 0.624824 0.715193 0.621202 0.725688 0.804827 0.637482 0.573463 0.769563 0.624063 0.792386 0.624062 0.748894 0.627233 0.771354 0.624062 0.748894 0.624063 0.792386 0.811395 0.669147 0.624062 0.748894 0.627233 0.771354 0.811395 0.669147 0.807968 0.653536 0.624062 0.748894 0.573463 0.815058 0.624063 0.832303 0.624063 0.792386 0.63156 0.797825 0.624063 0.792386 0.624063 0.832303 0.573463 0.769563 0.573463 0.815058 0.624063 0.792386 0.63156 0.797825 0.627233 0.771354 0.624063 0.792386 0.573463 0.856409 0.624063 0.868152 0.624063 0.832303 0.640054 0.839571 0.624063 0.832303 0.624063 0.868152 0.573463 0.815058 0.573463 0.856409 0.624063 0.832303 0.636279 0.82246 0.63156 0.797825 0.624063 0.832303 0.640054 0.839571 0.636279 0.82246 0.624063 0.832303 0.573463 0.89307 0.624063 0.89949 0.624063 0.868152 0.648123 0.870218 0.624063 0.868152 0.624063 0.89949 0.573463 0.856409 0.573463 0.89307 0.624063 0.868152 0.644001 0.855512 0.640054 0.839571 0.624063 0.868152 0.648123 0.870218 0.644001 0.855512 0.624063 0.868152 0.573463 0.924554 0.624063 0.925931 0.624063 0.89949 0.656835 0.89573 0.624063 0.89949 0.624063 0.925931 0.573463 0.89307 0.573463 0.924554 0.624063 0.89949 0.652412 0.883634 0.648123 0.870218 0.624063 0.89949 0.656835 0.89573 0.652412 0.883634 0.624063 0.89949 0.573463 0.950444 0.624063 0.947149 0.624063 0.925931 0.66606 0.915775 0.624063 0.925931 0.624063 0.947149 0.573463 0.924554 0.573463 0.950444 0.624063 0.925931 0.661396 0.90645 0.656835 0.89573 0.624063 0.925931 0.66606 0.915775 0.661396 0.90645 0.624063 0.925931 0.573464 0.970397 0.624063 0.962882 0.624063 0.947149 0.672725 0.942079 0.624063 0.947149 0.624063 0.962882 0.573463 0.950444 0.573464 0.970397 0.624063 0.947149 0.670825 0.923663 0.66606 0.915775 0.624063 0.947149 0.672698 0.926333 0.670825 0.923663 0.624063 0.947149 0.672725 0.942079 0.672698 0.926333 0.624063 0.947149 0.573464 0.984147 0.624063 0.972936 0.624063 0.962882 0.672725 0.942079 0.624063 0.962882 0.624063 0.972936 0.573464 0.970397 0.573464 0.984147 0.624063 0.962882 0.573464 0.991514 0.624063 0.977187 0.624063 0.972936 0.672725 0.951954 0.624063 0.972936 0.624063 0.977187 0.573464 0.984147 0.573464 0.991514 0.624063 0.972936 0.672725 0.951954 0.672725 0.942079 0.624063 0.972936 0.573464 0.992399 0.624063 0.975582 0.624063 0.977187 0.672725 0.955825 0.624063 0.977187 0.624063 0.975582 0.573464 0.991514 0.573464 0.992399 0.624063 0.977187 0.672725 0.955825 0.672725 0.951954 0.624063 0.977187 0.573464 0.986791 0.624063 0.968142 0.624063 0.975582 0.672725 0.95364 0.624063 0.975582 0.624063 0.968142 0.573464 0.992399 0.573464 0.986791 0.624063 0.975582 0.672725 0.95364 0.672725 0.955825 0.624063 0.975582 0.573464 0.974763 0.624063 0.954958 0.624063 0.968142 0.672725 0.945429 0.624063 0.968142 0.624063 0.954958 0.573464 0.986791 0.573464 0.974763 0.624063 0.968142 0.672725 0.945429 0.672725 0.95364 0.624063 0.968142 0.573464 0.956476 0.624063 0.936192 0.624063 0.954958 0.672725 0.931301 0.624063 0.954958 0.624063 0.936192 0.573464 0.974763 0.573464 0.956476 0.624063 0.954958 0.672725 0.931301 0.672725 0.945429 0.624063 0.954958 0.573464 0.932172 0.624063 0.912077 0.624063 0.936192 0.672725 0.911445 0.624063 0.936192 0.624063 0.912077 0.573464 0.956476 0.573464 0.932172 0.624063 0.936192 0.672725 0.911445 0.672725 0.931301 0.624063 0.936192 0.608628 0.889948 0.624161 0.883155 0.624063 0.912077 0.672725 0.886126 0.624063 0.912077 0.624161 0.883155 0.573506 0.902345 0.608628 0.889948 0.624063 0.912077 0.573464 0.932172 0.573506 0.902345 0.624063 0.912077 0.672725 0.886126 0.672725 0.911445 0.624063 0.912077 0.591531 0.787572 0.624161 0.883155 0.608628 0.889948 0.651354 0.869151 0.672725 0.886126 0.624161 0.883155 0.591531 0.787572 0.651354 0.869151 0.624161 0.883155 0.572316 0.796101 0.608628 0.889948 0.573506 0.902345 0.572316 0.796101 0.591531 0.787572 0.608628 0.889948 0.563789 0.905089 0.573506 0.902345 0.573464 0.932172 0.552525 0.803172 0.573506 0.902345 0.563789 0.905089 0.552525 0.803172 0.572316 0.796101 0.573506 0.902345 0.521563 0.962365 0.573464 0.932172 0.573464 0.956476 0.521589 0.913752 0.563789 0.905089 0.573464 0.932172 0.521563 0.940261 0.521589 0.913752 0.573464 0.932172 0.521563 0.962365 0.521563 0.940261 0.573464 0.932172 0.521563 0.97976 0.573464 0.956476 0.573464 0.974763 0.521563 0.97976 0.521563 0.962365 0.573464 0.956476 0.521563 0.992269 0.573464 0.974763 0.573464 0.986791 0.521563 0.992269 0.521563 0.97976 0.573464 0.974763 0.521664 0.999743 0.573464 0.986791 0.573464 0.992399 0.521664 0.999743 0.521563 0.992269 0.573464 0.986791 0.535488 0.99997 0.573464 0.992399 0.573464 0.991514 0.529917 0.999879 0.521664 0.999743 0.573464 0.992399 0.535488 0.99997 0.529917 0.999879 0.573464 0.992399 0.521635 0.999743 0.573464 0.991514 0.573464 0.984147 0.537367 1 0.535488 0.99997 0.573464 0.991514 0.535503 0.99997 0.537367 1 0.573464 0.991514 0.529999 0.99988 0.535503 0.99997 0.573464 0.991514 0.521635 0.999743 0.529999 0.99988 0.573464 0.991514 0.521563 0.991028 0.573464 0.984147 0.573464 0.970397 0.521563 0.991028 0.521635 0.999743 0.573464 0.984147 0.521563 0.976039 0.573464 0.970397 0.573463 0.950444 0.521563 0.976039 0.521563 0.991028 0.573464 0.970397 0.521563 0.954981 0.573463 0.950444 0.573463 0.924554 0.521563 0.954981 0.521563 0.976039 0.573463 0.950444 0.521563 0.928124 0.573463 0.924554 0.573463 0.89307 0.521563 0.928124 0.521563 0.954981 0.573463 0.924554 0.521563 0.895812 0.573463 0.89307 0.573463 0.856409 0.521563 0.895812 0.521563 0.928124 0.573463 0.89307 0.521563 0.858459 0.573463 0.856409 0.573463 0.815058 0.521563 0.858459 0.521563 0.895812 0.573463 0.856409 0.521563 0.816545 0.573463 0.815058 0.573463 0.769563 0.521563 0.816545 0.521563 0.858459 0.573463 0.815058 0.521562 0.770605 0.573463 0.769563 0.573463 0.720529 0.521562 0.770605 0.521563 0.816545 0.573463 0.769563 0.521562 0.72123 0.573463 0.720529 0.573463 0.668605 0.521562 0.72123 0.521562 0.770605 0.573463 0.720529 0.521562 0.669052 0.573463 0.668605 0.573463 0.614479 0.521562 0.669052 0.521562 0.72123 0.573463 0.668605 0.521562 0.614739 0.573463 0.614479 0.573463 0.55887 0.521562 0.614739 0.521562 0.669052 0.573463 0.614479 0.609342 0.502513 0.573463 0.502513 0.573463 0.55887 0.521562 0.558988 0.573463 0.55887 0.573463 0.502513 0.609811 0.548473 0.609342 0.502513 0.573463 0.55887 0.521562 0.558988 0.521562 0.614739 0.573463 0.55887 0.609859 0.454326 0.573463 0.502513 0.609342 0.502513 0.559191 0.502513 0.521562 0.558988 0.573463 0.502513 0.573463 0.446152 0.559191 0.502513 0.573463 0.502513 0.573463 0.446152 0.573463 0.502513 0.609859 0.454326 0.792617 0.502513 0.609342 0.502513 0.609811 0.548473 0.792819 0.485066 0.609342 0.502513 0.792617 0.502513 0.609859 0.454326 0.609342 0.502513 0.792819 0.485066 0.605736 0.593917 0.611214 0.593917 0.609811 0.548473 0.793395 0.536821 0.609811 0.548473 0.611214 0.593917 0.792811 0.519637 0.792617 0.502513 0.609811 0.548473 0.793395 0.536821 0.792811 0.519637 0.609811 0.548473 0.591918 0.593917 0.611214 0.593917 0.605736 0.593917 0.591918 0.593917 0.624886 0.593917 0.611214 0.593917 0.794366 0.553923 0.611214 0.593917 0.624886 0.593917 0.794366 0.553923 0.793395 0.536821 0.611214 0.593917 0.693008 0.76114 0.627233 0.771354 0.63156 0.797825 0.811389 0.670394 0.811395 0.669147 0.627233 0.771354 0.688625 0.738111 0.811389 0.670394 0.627233 0.771354 0.693008 0.76114 0.688625 0.738111 0.627233 0.771354 0.697617 0.78314 0.63156 0.797825 0.636279 0.82246 0.693008 0.76114 0.63156 0.797825 0.697617 0.78314 0.697617 0.78314 0.636279 0.82246 0.640054 0.839571 0.704244 0.810053 0.640054 0.839571 0.644001 0.855512 0.697617 0.78314 0.640054 0.839571 0.704244 0.810053 0.704244 0.810053 0.644001 0.855512 0.648123 0.870218 0.711343 0.833967 0.648123 0.870218 0.652412 0.883634 0.704244 0.810053 0.648123 0.870218 0.711343 0.833967 0.711343 0.833967 0.652412 0.883634 0.656835 0.89573 0.718812 0.854648 0.656835 0.89573 0.661396 0.90645 0.711343 0.833967 0.656835 0.89573 0.718812 0.854648 0.718812 0.854648 0.661396 0.90645 0.66606 0.915775 0.726539 0.871876 0.66606 0.915775 0.670825 0.923663 0.718812 0.854648 0.66606 0.915775 0.726539 0.871876 0.726539 0.871876 0.670825 0.923663 0.672698 0.926333 0.680571 0.935055 0.672698 0.926333 0.672725 0.942079 0.734403 0.885457 0.672698 0.926333 0.680571 0.935055 0.726539 0.871876 0.672698 0.926333 0.734403 0.885457 0.685525 0.938518 0.672725 0.942079 0.672725 0.951954 0.685525 0.938518 0.680571 0.935055 0.672725 0.942079 0.695491 0.940947 0.672725 0.951954 0.672725 0.955825 0.690497 0.940489 0.685525 0.938518 0.672725 0.951954 0.695491 0.940947 0.690497 0.940489 0.672725 0.951954 0.705418 0.937377 0.672725 0.955825 0.672725 0.95364 0.700467 0.93991 0.695491 0.940947 0.672725 0.955825 0.705418 0.937377 0.700467 0.93991 0.672725 0.955825 0.715307 0.92774 0.672725 0.95364 0.672725 0.945429 0.710349 0.933345 0.705418 0.937377 0.672725 0.95364 0.715307 0.92774 0.710349 0.933345 0.672725 0.95364 0.718839 0.912089 0.672725 0.945429 0.672725 0.931301 0.718846 0.922736 0.715307 0.92774 0.672725 0.945429 0.718839 0.912089 0.718846 0.922736 0.672725 0.945429 0.718839 0.896269 0.672725 0.931301 0.672725 0.911445 0.718839 0.896269 0.718839 0.912089 0.672725 0.931301 0.718839 0.875479 0.672725 0.911445 0.672725 0.886126 0.718839 0.875479 0.718839 0.896269 0.672725 0.911445 0.651354 0.869151 0.672875 0.855982 0.672725 0.886126 0.718839 0.84998 0.672725 0.886126 0.672875 0.855982 0.718839 0.84998 0.718839 0.875479 0.672725 0.886126 0.610176 0.777572 0.672875 0.855982 0.651354 0.869151 0.691348 0.843034 0.718839 0.84998 0.672875 0.855982 0.628112 0.766184 0.691348 0.843034 0.672875 0.855982 0.610176 0.777572 0.628112 0.766184 0.672875 0.855982 0.591531 0.787572 0.610176 0.777572 0.651354 0.869151 0.74227 0.895211 0.680571 0.935055 0.685525 0.938518 0.734403 0.885457 0.680571 0.935055 0.74227 0.895211 0.74227 0.895211 0.685525 0.938518 0.690497 0.940489 0.749999 0.900979 0.690497 0.940489 0.695491 0.940947 0.74227 0.895211 0.690497 0.940489 0.749999 0.900979 0.749999 0.900979 0.695491 0.940947 0.700467 0.93991 0.757438 0.902616 0.700467 0.93991 0.705418 0.937377 0.749999 0.900979 0.700467 0.93991 0.757438 0.902616 0.764433 0.899996 0.705418 0.937377 0.710349 0.933345 0.757438 0.902616 0.705418 0.937377 0.764433 0.899996 0.764433 0.899996 0.710349 0.933345 0.715307 0.92774 0.764433 0.899996 0.715307 0.92774 0.718846 0.922736 0.720162 0.920655 0.718846 0.922736 0.718839 0.912089 0.770834 0.89302 0.718846 0.922736 0.720162 0.920655 0.764433 0.899996 0.718846 0.922736 0.770834 0.89302 0.729587 0.902118 0.718839 0.912089 0.718839 0.896269 0.724922 0.912106 0.720162 0.920655 0.718839 0.912089 0.729587 0.902118 0.724922 0.912106 0.718839 0.912089 0.738503 0.878023 0.718839 0.896269 0.718839 0.875479 0.734112 0.890746 0.729587 0.902118 0.718839 0.896269 0.738503 0.878023 0.734112 0.890746 0.718839 0.896269 0.746789 0.848737 0.718839 0.875479 0.718839 0.84998 0.742736 0.864001 0.738503 0.878023 0.718839 0.875479 0.746789 0.848737 0.742736 0.864001 0.718839 0.875479 0.691348 0.843034 0.719005 0.820381 0.718839 0.84998 0.754333 0.8147 0.718839 0.84998 0.719005 0.820381 0.750668 0.832277 0.746789 0.848737 0.718839 0.84998 0.754333 0.8147 0.750668 0.832277 0.718839 0.84998 0.645234 0.753456 0.719005 0.820381 0.691348 0.843034 0.757789 0.796056 0.754333 0.8147 0.719005 0.820381 0.728073 0.811978 0.757789 0.796056 0.719005 0.820381 0.661524 0.739415 0.728073 0.811978 0.719005 0.820381 0.645234 0.753456 0.661524 0.739415 0.719005 0.820381 0.628112 0.766184 0.645234 0.753456 0.691348 0.843034 0.770834 0.89302 0.720162 0.920655 0.724922 0.912106 0.776508 0.881618 0.724922 0.912106 0.729587 0.902118 0.770834 0.89302 0.724922 0.912106 0.776508 0.881618 0.776508 0.881618 0.729587 0.902118 0.734112 0.890746 0.781356 0.865771 0.734112 0.890746 0.738503 0.878023 0.776508 0.881618 0.734112 0.890746 0.781356 0.865771 0.781356 0.865771 0.738503 0.878023 0.742736 0.864001 0.785322 0.845527 0.742736 0.864001 0.746789 0.848737 0.781356 0.865771 0.742736 0.864001 0.785322 0.845527 0.78841 0.821011 0.746789 0.848737 0.750668 0.832277 0.785322 0.845527 0.746789 0.848737 0.78841 0.821011 0.78841 0.821011 0.750668 0.832277 0.754333 0.8147 0.790682 0.792447 0.754333 0.8147 0.757789 0.796056 0.78841 0.821011 0.754333 0.8147 0.790682 0.792447 0.728073 0.811978 0.761044 0.776399 0.757789 0.796056 0.790682 0.792447 0.757789 0.796056 0.761044 0.776399 0.676797 0.724194 0.761044 0.776399 0.728073 0.811978 0.691091 0.707761 0.704174 0.690415 0.761044 0.776399 0.778922 0.749673 0.761044 0.776399 0.704174 0.690415 0.676797 0.724194 0.691091 0.707761 0.761044 0.776399 0.792246 0.76015 0.761044 0.776399 0.778922 0.749673 0.790682 0.792447 0.761044 0.776399 0.792246 0.76015 0.661524 0.739415 0.676797 0.724194 0.728073 0.811978 0.532386 0.808699 0.563789 0.905089 0.521589 0.913752 0.532386 0.808699 0.552525 0.803172 0.563789 0.905089 0.517571 0.914309 0.521589 0.913752 0.521563 0.940261 0.511853 0.812693 0.521589 0.913752 0.517571 0.914309 0.511853 0.812693 0.532386 0.808699 0.521589 0.913752 0.469012 0.946203 0.521563 0.940261 0.521563 0.962365 0.470346 0.917477 0.517571 0.914309 0.521563 0.940261 0.469022 0.917476 0.470346 0.917477 0.521563 0.940261 0.469012 0.946203 0.469022 0.917476 0.521563 0.940261 0.469012 0.969547 0.521563 0.962365 0.521563 0.97976 0.469012 0.969547 0.469012 0.946203 0.521563 0.962365 0.469012 0.987203 0.521563 0.97976 0.521563 0.992269 0.469012 0.987203 0.469012 0.969547 0.521563 0.97976 0.520929 0.999731 0.521563 0.992269 0.521664 0.999743 0.469058 0.99888 0.469012 0.987203 0.521563 0.992269 0.478996 0.999043 0.469058 0.99888 0.521563 0.992269 0.494859 0.999303 0.478996 0.999043 0.521563 0.992269 0.509084 0.999537 0.494859 0.999303 0.521563 0.992269 0.520929 0.999731 0.509084 0.999537 0.521563 0.992269 0.521065 0.873461 0.521664 0.999743 0.529917 0.999879 0.521065 0.873461 0.520929 0.999731 0.521664 0.999743 0.529953 0.873461 0.529917 0.999879 0.535488 0.99997 0.529953 0.873461 0.521065 0.873461 0.529917 0.999879 0.535486 0.873461 0.535488 0.99997 0.537367 1 0.535486 0.873461 0.529953 0.873461 0.535488 0.99997 0.537367 0.873461 0.537367 1 0.535503 0.99997 0.535486 0.873461 0.537367 1 0.537367 0.873461 0.53547 0.873461 0.535503 0.99997 0.529999 0.99988 0.53547 0.873461 0.537367 0.873461 0.535503 0.99997 0.529869 0.873461 0.529999 0.99988 0.521635 0.999743 0.529869 0.873461 0.53547 0.873461 0.529999 0.99988 0.521124 0.999734 0.521635 0.999743 0.521563 0.991028 0.529869 0.873461 0.521635 0.999743 0.521124 0.999734 0.469012 0.987435 0.521563 0.991028 0.521563 0.976039 0.509391 0.999542 0.521124 0.999734 0.521563 0.991028 0.495215 0.999309 0.509391 0.999542 0.521563 0.991028 0.479343 0.999049 0.495215 0.999309 0.521563 0.991028 0.469055 0.99888 0.479343 0.999049 0.521563 0.991028 0.469012 0.987435 0.469055 0.99888 0.521563 0.991028 0.469012 0.970197 0.521563 0.976039 0.521563 0.954981 0.469012 0.970197 0.469012 0.987435 0.521563 0.976039 0.469012 0.947442 0.521563 0.954981 0.521563 0.928124 0.469012 0.947442 0.469012 0.970197 0.521563 0.954981 0.469011 0.91944 0.521563 0.928124 0.521563 0.895812 0.469011 0.91944 0.469012 0.947442 0.521563 0.928124 0.469011 0.886519 0.521563 0.895812 0.521563 0.858459 0.469011 0.886519 0.469011 0.91944 0.521563 0.895812 0.469011 0.84907 0.521563 0.858459 0.521563 0.816545 0.469011 0.84907 0.469011 0.886519 0.521563 0.858459 0.469011 0.807533 0.521563 0.816545 0.521562 0.770605 0.469011 0.807533 0.469011 0.84907 0.521563 0.816545 0.469011 0.762398 0.521562 0.770605 0.521562 0.72123 0.469011 0.762398 0.469011 0.807533 0.521562 0.770605 0.469011 0.714198 0.521562 0.72123 0.521562 0.669052 0.469011 0.714198 0.469011 0.762398 0.521562 0.72123 0.469011 0.663501 0.521562 0.669052 0.521562 0.614739 0.469011 0.663501 0.469011 0.714198 0.521562 0.669052 0.469011 0.610905 0.521562 0.614739 0.521562 0.558988 0.469011 0.610905 0.469011 0.663501 0.521562 0.614739 0.559191 0.502513 0.521562 0.502513 0.521562 0.558988 0.469011 0.55703 0.521562 0.558988 0.521562 0.502513 0.469011 0.55703 0.469011 0.610905 0.521562 0.558988 0.573463 0.446152 0.521562 0.502513 0.559191 0.502513 0.469011 0.55703 0.521562 0.502513 0.507956 0.502513 0.521562 0.44543 0.507956 0.502513 0.521562 0.502513 0.573463 0.446152 0.521562 0.44543 0.521562 0.502513 0.491159 0.815114 0.517571 0.914309 0.470346 0.917477 0.491159 0.815114 0.511853 0.812693 0.517571 0.914309 0.47031 0.815947 0.470346 0.917477 0.469022 0.917476 0.47031 0.815947 0.491159 0.815114 0.470346 0.917477 0.41647 0.938685 0.469022 0.917476 0.469012 0.946203 0.41647 0.938685 0.422741 0.914416 0.469022 0.917476 0.449447 0.815199 0.469022 0.917476 0.422741 0.914416 0.449447 0.815199 0.47031 0.815947 0.469022 0.917476 0.41647 0.959953 0.469012 0.946203 0.469012 0.969547 0.41647 0.959953 0.41647 0.938685 0.469012 0.946203 0.41647 0.977031 0.469012 0.969547 0.469012 0.987203 0.41647 0.977031 0.41647 0.959953 0.469012 0.969547 0.41647 0.989763 0.469012 0.987203 0.469058 0.99888 0.41647 0.989763 0.41647 0.977031 0.469012 0.987203 0.462811 0.873461 0.469058 0.99888 0.478996 0.999043 0.462317 0.998769 0.41647 0.989763 0.469058 0.99888 0.462811 0.873461 0.462317 0.998769 0.469058 0.99888 0.479444 0.873461 0.478996 0.999043 0.494859 0.999303 0.479444 0.873461 0.462811 0.873461 0.478996 0.999043 0.495243 0.873461 0.494859 0.999303 0.509084 0.999537 0.495243 0.873461 0.479444 0.873461 0.494859 0.999303 0.509356 0.873461 0.509084 0.999537 0.520929 0.999731 0.509356 0.873461 0.495243 0.873461 0.509084 0.999537 0.521065 0.873461 0.509356 0.873461 0.520929 0.999731 0.41647 0.938685 0.416455 0.913539 0.422741 0.914416 0.449447 0.815199 0.422741 0.914416 0.416455 0.913539 0.375615 0.905062 0.416455 0.913539 0.41647 0.938685 0.42871 0.812855 0.416455 0.913539 0.375615 0.905062 0.42871 0.812855 0.449447 0.815199 0.416455 0.913539 0.364597 0.931722 0.41647 0.938685 0.41647 0.959953 0.364504 0.901899 0.375615 0.905062 0.41647 0.938685 0.364597 0.931722 0.364504 0.901899 0.41647 0.938685 0.364597 0.956046 0.41647 0.959953 0.41647 0.977031 0.364597 0.956046 0.364597 0.931722 0.41647 0.959953 0.364596 0.974354 0.41647 0.977031 0.41647 0.989763 0.364596 0.974354 0.364597 0.956046 0.41647 0.977031 0.429802 0.998235 0.416412 0.998015 0.41647 0.989763 0.364596 0.986405 0.41647 0.989763 0.416412 0.998015 0.44564 0.998495 0.429802 0.998235 0.41647 0.989763 0.462317 0.998769 0.44564 0.998495 0.41647 0.989763 0.364596 0.986405 0.364596 0.974354 0.41647 0.989763 0.416227 0.873461 0.416412 0.998015 0.429802 0.998235 0.415687 0.998003 0.364596 0.986405 0.416412 0.998015 0.416227 0.873461 0.415687 0.998003 0.416412 0.998015 0.430395 0.873461 0.429802 0.998235 0.44564 0.998495 0.430395 0.873461 0.416227 0.873461 0.429802 0.998235 0.446187 0.873461 0.44564 0.998495 0.462317 0.998769 0.446187 0.873461 0.430395 0.873461 0.44564 0.998495 0.462811 0.873461 0.446187 0.873461 0.462317 0.998769 0.408105 0.80893 0.375615 0.905062 0.364504 0.901899 0.408105 0.80893 0.42871 0.812855 0.375615 0.905062 0.314043 0.910915 0.364504 0.901899 0.364597 0.931722 0.314043 0.910915 0.329984 0.889581 0.364504 0.901899 0.387871 0.803451 0.364504 0.901899 0.329984 0.889581 0.387871 0.803451 0.408105 0.80893 0.364504 0.901899 0.314043 0.934744 0.364597 0.931722 0.364597 0.956046 0.314043 0.934744 0.314043 0.910915 0.364597 0.931722 0.314043 0.953436 0.364597 0.956046 0.364596 0.974354 0.314043 0.953436 0.314043 0.934744 0.364597 0.956046 0.314043 0.966767 0.364596 0.974354 0.364596 0.986405 0.314043 0.966767 0.314043 0.953436 0.364596 0.974354 0.395216 0.997666 0.364596 0.992038 0.364596 0.986405 0.314043 0.97458 0.364596 0.986405 0.364596 0.992038 0.404028 0.997811 0.395216 0.997666 0.364596 0.986405 0.415687 0.998003 0.404028 0.997811 0.364596 0.986405 0.314043 0.97458 0.314043 0.966767 0.364596 0.986405 0.395298 0.997667 0.364596 0.991179 0.364596 0.992038 0.314043 0.976781 0.364596 0.992038 0.364596 0.991179 0.389767 0.997576 0.395298 0.997667 0.364596 0.992038 0.3879 0.997545 0.389767 0.997576 0.364596 0.992038 0.389752 0.997576 0.3879 0.997545 0.364596 0.992038 0.395216 0.997666 0.389752 0.997576 0.364596 0.992038 0.314043 0.976781 0.314043 0.97458 0.364596 0.992038 0.416435 0.998015 0.364596 0.983838 0.364596 0.991179 0.314043 0.973344 0.364596 0.991179 0.364596 0.983838 0.415993 0.998008 0.416435 0.998015 0.364596 0.991179 0.404221 0.997814 0.415993 0.998008 0.364596 0.991179 0.395298 0.997667 0.404221 0.997814 0.364596 0.991179 0.314043 0.973344 0.314043 0.976781 0.364596 0.991179 0.41647 0.988003 0.364596 0.970114 0.364596 0.983838 0.314043 0.96431 0.364596 0.983838 0.364596 0.970114 0.416435 0.998015 0.41647 0.988003 0.364596 0.983838 0.314043 0.96431 0.314043 0.973344 0.364596 0.983838 0.41647 0.971991 0.364596 0.950189 0.364596 0.970114 0.314043 0.949787 0.364596 0.970114 0.364596 0.950189 0.41647 0.988003 0.41647 0.971991 0.364596 0.970114 0.314043 0.949787 0.314043 0.96431 0.364596 0.970114 0.41647 0.950186 0.364596 0.924326 0.364596 0.950189 0.314043 0.929947 0.364596 0.950189 0.364596 0.924326 0.41647 0.971991 0.41647 0.950186 0.364596 0.950189 0.314043 0.929947 0.314043 0.949787 0.364596 0.950189 0.41647 0.922858 0.364596 0.892869 0.364596 0.924326 0.314043 0.905025 0.364596 0.924326 0.364596 0.892869 0.41647 0.950186 0.41647 0.922858 0.364596 0.924326 0.314043 0.905025 0.314043 0.929947 0.364596 0.924326 0.416469 0.890345 0.364596 0.856234 0.364596 0.892869 0.314043 0.875319 0.364596 0.892869 0.364596 0.856234 0.41647 0.922858 0.416469 0.890345 0.364596 0.892869 0.314043 0.875319 0.314043 0.905025 0.364596 0.892869 0.416469 0.853046 0.364596 0.814909 0.364596 0.856234 0.314043 0.841181 0.364596 0.856234 0.364596 0.814909 0.416469 0.890345 0.416469 0.853046 0.364596 0.856234 0.314043 0.841181 0.314043 0.875319 0.364596 0.856234 0.416469 0.811423 0.364596 0.76944 0.364596 0.814909 0.314043 0.803018 0.364596 0.814909 0.364596 0.76944 0.416469 0.853046 0.416469 0.811423 0.364596 0.814909 0.314043 0.803018 0.314043 0.841181 0.364596 0.814909 0.416469 0.765988 0.364596 0.720431 0.364596 0.76944 0.338661 0.737757 0.364596 0.76944 0.364596 0.720431 0.416469 0.811423 0.416469 0.765988 0.364596 0.76944 0.314043 0.761282 0.314043 0.803018 0.364596 0.76944 0.332759 0.738733 0.314043 0.761282 0.364596 0.76944 0.335765 0.738765 0.332759 0.738733 0.364596 0.76944 0.338661 0.737757 0.335765 0.738765 0.364596 0.76944 0.416469 0.717303 0.364596 0.668532 0.364596 0.720431 0.348626 0.711499 0.364596 0.720431 0.364596 0.668532 0.416469 0.765988 0.416469 0.717303 0.364596 0.720431 0.341498 0.73549 0.338661 0.737757 0.364596 0.720431 0.344069 0.731808 0.341498 0.73549 0.364596 0.720431 0.346192 0.726666 0.344069 0.731808 0.364596 0.720431 0.347753 0.719954 0.346192 0.726666 0.364596 0.720431 0.348626 0.711499 0.347753 0.719954 0.364596 0.720431 0.416469 0.665968 0.364596 0.614431 0.364596 0.668532 0.342717 0.641817 0.364596 0.668532 0.364596 0.614431 0.416469 0.717303 0.416469 0.665968 0.364596 0.668532 0.348644 0.70107 0.348626 0.711499 0.364596 0.668532 0.347584 0.688374 0.348644 0.70107 0.364596 0.668532 0.342717 0.641817 0.347584 0.688374 0.364596 0.668532 0.416469 0.612617 0.364596 0.558845 0.364596 0.614431 0.339263 0.593917 0.364596 0.614431 0.364596 0.558845 0.416469 0.665968 0.416469 0.612617 0.364596 0.614431 0.339263 0.593917 0.342717 0.641817 0.364596 0.614431 0.404724 0.502513 0.364596 0.502513 0.364596 0.558845 0.314043 0.548442 0.364596 0.558845 0.364596 0.502513 0.416469 0.502513 0.404724 0.502513 0.364596 0.558845 0.416469 0.557907 0.416469 0.502513 0.364596 0.558845 0.416469 0.612617 0.416469 0.557907 0.364596 0.558845 0.31892 0.593917 0.339263 0.593917 0.364596 0.558845 0.314042 0.593917 0.31892 0.593917 0.364596 0.558845 0.314043 0.548442 0.314042 0.593917 0.364596 0.558845 0.416469 0.445459 0.364596 0.502513 0.404724 0.502513 0.353978 0.502513 0.314043 0.548442 0.364596 0.502513 0.364596 0.44619 0.353978 0.502513 0.364596 0.502513 0.416469 0.445459 0.364596 0.44619 0.364596 0.502513 0.416469 0.445459 0.404724 0.502513 0.416469 0.502513 0.456258 0.502513 0.416469 0.502513 0.416469 0.557907 0.469011 0.445198 0.416469 0.502513 0.456258 0.502513 0.469011 0.445198 0.416469 0.445459 0.416469 0.502513 0.469011 0.610905 0.416469 0.557907 0.416469 0.612617 0.469011 0.55703 0.416469 0.557907 0.469011 0.610905 0.469011 0.502513 0.416469 0.557907 0.469011 0.55703 0.456258 0.502513 0.416469 0.557907 0.469011 0.502513 0.469011 0.663501 0.416469 0.612617 0.416469 0.665968 0.469011 0.610905 0.416469 0.612617 0.469011 0.663501 0.469011 0.714198 0.416469 0.665968 0.416469 0.717303 0.469011 0.663501 0.416469 0.665968 0.469011 0.714198 0.469011 0.762398 0.416469 0.717303 0.416469 0.765988 0.469011 0.714198 0.416469 0.717303 0.469011 0.762398 0.469011 0.807533 0.416469 0.765988 0.416469 0.811423 0.469011 0.762398 0.416469 0.765988 0.469011 0.807533 0.469011 0.84907 0.416469 0.811423 0.416469 0.853046 0.469011 0.807533 0.416469 0.811423 0.469011 0.84907 0.469011 0.886519 0.416469 0.853046 0.416469 0.890345 0.469011 0.84907 0.416469 0.853046 0.469011 0.886519 0.469011 0.91944 0.416469 0.890345 0.41647 0.922858 0.469011 0.886519 0.416469 0.890345 0.469011 0.91944 0.469012 0.947442 0.41647 0.922858 0.41647 0.950186 0.469011 0.91944 0.41647 0.922858 0.469012 0.947442 0.469012 0.970197 0.41647 0.950186 0.41647 0.971991 0.469012 0.947442 0.41647 0.950186 0.469012 0.970197 0.469012 0.987435 0.41647 0.971991 0.41647 0.988003 0.469012 0.970197 0.41647 0.971991 0.469012 0.987435 0.430159 0.998241 0.41647 0.988003 0.416435 0.998015 0.462654 0.998775 0.469012 0.987435 0.41647 0.988003 0.445986 0.998501 0.462654 0.998775 0.41647 0.988003 0.430159 0.998241 0.445986 0.998501 0.41647 0.988003 0.430024 0.873461 0.416435 0.998015 0.415993 0.998008 0.430024 0.873461 0.430159 0.998241 0.416435 0.998015 0.415911 0.873461 0.415993 0.998008 0.404221 0.997814 0.415911 0.873461 0.430024 0.873461 0.415993 0.998008 0.404202 0.873461 0.404221 0.997814 0.395298 0.997667 0.404202 0.873461 0.415911 0.873461 0.404221 0.997814 0.389781 0.873461 0.395298 0.997667 0.389767 0.997576 0.395314 0.873461 0.404202 0.873461 0.395298 0.997667 0.389781 0.873461 0.395314 0.873461 0.395298 0.997667 0.389781 0.873461 0.389767 0.997576 0.3879 0.997545 0.3879 0.873461 0.3879 0.997545 0.389752 0.997576 0.3879 0.873461 0.389781 0.873461 0.3879 0.997545 0.389797 0.873461 0.389752 0.997576 0.395216 0.997666 0.389797 0.873461 0.3879 0.873461 0.389752 0.997576 0.395398 0.873461 0.395216 0.997666 0.404028 0.997811 0.395398 0.873461 0.389797 0.873461 0.395216 0.997666 0.404401 0.873461 0.404028 0.997811 0.415687 0.998003 0.404401 0.873461 0.395398 0.873461 0.404028 0.997811 0.416227 0.873461 0.404401 0.873461 0.415687 0.998003 0.314043 0.910915 0.313879 0.882472 0.329984 0.889581 0.367959 0.796409 0.329984 0.889581 0.313879 0.882472 0.367959 0.796409 0.387871 0.803451 0.329984 0.889581 0.265445 0.884486 0.313879 0.882472 0.314043 0.910915 0.265445 0.884486 0.286899 0.868439 0.313879 0.882472 0.348611 0.787884 0.313879 0.882472 0.286899 0.868439 0.348611 0.787884 0.367959 0.796409 0.313879 0.882472 0.265444 0.909342 0.314043 0.910915 0.314043 0.934744 0.265444 0.909342 0.265445 0.884486 0.314043 0.910915 0.265444 0.929056 0.314043 0.934744 0.314043 0.953436 0.265444 0.929056 0.265444 0.909342 0.314043 0.934744 0.265444 0.943378 0.314043 0.953436 0.314043 0.966767 0.265444 0.943378 0.265444 0.929056 0.314043 0.953436 0.265444 0.952128 0.314043 0.966767 0.314043 0.97458 0.265444 0.952128 0.265444 0.943378 0.314043 0.966767 0.265444 0.955194 0.314043 0.97458 0.314043 0.976781 0.265444 0.955194 0.265444 0.952128 0.314043 0.97458 0.265444 0.952539 0.314043 0.976781 0.314043 0.973344 0.265444 0.952539 0.265444 0.955194 0.314043 0.976781 0.265444 0.944194 0.314043 0.973344 0.314043 0.96431 0.265444 0.944194 0.265444 0.952539 0.314043 0.973344 0.265444 0.930267 0.314043 0.96431 0.314043 0.949787 0.265444 0.930267 0.265444 0.944194 0.314043 0.96431 0.265444 0.910933 0.314043 0.949787 0.314043 0.929947 0.265444 0.910933 0.265444 0.930267 0.314043 0.949787 0.265444 0.910933 0.314043 0.929947 0.314043 0.905025 0.265444 0.886437 0.314043 0.905025 0.314043 0.875319 0.265444 0.886437 0.265444 0.910933 0.314043 0.905025 0.265444 0.857087 0.314043 0.875319 0.314043 0.841181 0.265444 0.857087 0.265444 0.886437 0.314043 0.875319 0.265444 0.823256 0.314043 0.841181 0.314043 0.803018 0.265444 0.823256 0.265444 0.857087 0.314043 0.841181 0.265444 0.78537 0.314043 0.803018 0.314043 0.761282 0.265444 0.78537 0.265444 0.823256 0.314043 0.803018 0.315324 0.719827 0.314005 0.716685 0.314043 0.761282 0.265444 0.743909 0.314043 0.761282 0.314005 0.716685 0.318786 0.726511 0.315324 0.719827 0.314043 0.761282 0.322393 0.731647 0.318786 0.726511 0.314043 0.761282 0.326045 0.735353 0.322393 0.731647 0.314043 0.761282 0.329544 0.737661 0.326045 0.735353 0.314043 0.761282 0.332759 0.738733 0.329544 0.737661 0.314043 0.761282 0.265444 0.743909 0.265444 0.78537 0.314043 0.761282 0.315012 0.593917 0.314005 0.716685 0.315324 0.719827 0.312122 0.711412 0.265444 0.743909 0.314005 0.716685 0.312496 0.593917 0.312122 0.711412 0.314005 0.716685 0.312496 0.593917 0.314005 0.716685 0.315012 0.593917 0.317823 0.593917 0.315324 0.719827 0.318786 0.726511 0.315012 0.593917 0.315324 0.719827 0.317823 0.593917 0.320866 0.593917 0.318786 0.726511 0.322393 0.731647 0.317823 0.593917 0.318786 0.726511 0.320866 0.593917 0.324049 0.593917 0.322393 0.731647 0.326045 0.735353 0.320866 0.593917 0.322393 0.731647 0.324049 0.593917 0.327402 0.593917 0.326045 0.735353 0.329544 0.737661 0.324049 0.593917 0.326045 0.735353 0.327402 0.593917 0.327402 0.593917 0.329544 0.737661 0.332759 0.738733 0.333177 0.593917 0.332759 0.738733 0.335765 0.738765 0.327402 0.593917 0.332759 0.738733 0.333177 0.593917 0.338479 0.593917 0.335765 0.738765 0.338661 0.737757 0.333177 0.593917 0.335765 0.738765 0.338479 0.593917 0.338479 0.593917 0.338661 0.737757 0.341498 0.73549 0.342959 0.593917 0.341498 0.73549 0.344069 0.731808 0.338479 0.593917 0.341498 0.73549 0.342959 0.593917 0.342959 0.593917 0.344069 0.731808 0.346192 0.726666 0.3463 0.593917 0.346192 0.726666 0.347753 0.719954 0.342959 0.593917 0.346192 0.726666 0.3463 0.593917 0.348269 0.593917 0.347753 0.719954 0.348626 0.711499 0.3463 0.593917 0.347753 0.719954 0.348269 0.593917 0.348716 0.593917 0.348626 0.711499 0.348644 0.70107 0.348269 0.593917 0.348626 0.711499 0.348716 0.593917 0.348716 0.593917 0.348644 0.70107 0.347584 0.688374 0.339263 0.593917 0.347584 0.688374 0.342717 0.641817 0.347584 0.593917 0.347584 0.688374 0.339263 0.593917 0.348716 0.593917 0.347584 0.688374 0.347584 0.593917 0.314042 0.593917 0.339263 0.593917 0.31892 0.593917 0.2989 0.593917 0.339263 0.593917 0.314042 0.593917 0.347584 0.593917 0.339263 0.593917 0.2989 0.593917 0.265444 0.553328 0.314042 0.593917 0.314043 0.548442 0.2989 0.593917 0.314042 0.593917 0.265444 0.553328 0.353978 0.502513 0.314043 0.502513 0.314043 0.548442 0.265444 0.553328 0.314043 0.548442 0.314043 0.502513 0.364596 0.44619 0.314043 0.502513 0.353978 0.502513 0.304635 0.502513 0.265444 0.553328 0.314043 0.502513 0.314043 0.450136 0.304635 0.502513 0.314043 0.502513 0.364596 0.44619 0.314043 0.450136 0.314043 0.502513 0.265445 0.884486 0.265222 0.855053 0.286899 0.868439 0.329822 0.77786 0.286899 0.868439 0.265222 0.855053 0.329822 0.77786 0.348611 0.787884 0.286899 0.868439 0.21941 0.849599 0.265222 0.855053 0.265445 0.884486 0.21941 0.849599 0.247097 0.842244 0.265222 0.855053 0.311742 0.766426 0.265222 0.855053 0.247097 0.842244 0.311742 0.766426 0.329822 0.77786 0.265222 0.855053 0.21941 0.875551 0.265445 0.884486 0.265444 0.909342 0.21941 0.875551 0.21941 0.849599 0.265445 0.884486 0.21941 0.896565 0.265444 0.909342 0.265444 0.929056 0.21941 0.896565 0.21941 0.875551 0.265444 0.909342 0.21941 0.912362 0.265444 0.929056 0.265444 0.943378 0.21941 0.912362 0.21941 0.896565 0.265444 0.929056 0.21941 0.922734 0.265444 0.943378 0.265444 0.952128 0.21941 0.922734 0.21941 0.912362 0.265444 0.943378 0.21941 0.927544 0.265444 0.952128 0.265444 0.955194 0.21941 0.927544 0.21941 0.922734 0.265444 0.952128 0.21941 0.926727 0.265444 0.955194 0.265444 0.952539 0.21941 0.926727 0.21941 0.927544 0.265444 0.955194 0.21941 0.920294 0.265444 0.952539 0.265444 0.944194 0.21941 0.920294 0.21941 0.926727 0.265444 0.952539 0.21941 0.908331 0.265444 0.944194 0.265444 0.930267 0.21941 0.908331 0.21941 0.920294 0.265444 0.944194 0.21941 0.890996 0.265444 0.930267 0.265444 0.910933 0.21941 0.890996 0.21941 0.908331 0.265444 0.930267 0.21941 0.868518 0.265444 0.910933 0.265444 0.886437 0.21941 0.868518 0.21941 0.890996 0.265444 0.910933 0.21941 0.841195 0.265444 0.886437 0.265444 0.857087 0.21941 0.841195 0.21941 0.868518 0.265444 0.886437 0.21941 0.809389 0.265444 0.857087 0.265444 0.823256 0.21941 0.809389 0.21941 0.841195 0.265444 0.857087 0.21941 0.77352 0.265444 0.823256 0.265444 0.78537 0.21941 0.77352 0.21941 0.809389 0.265444 0.823256 0.21941 0.734064 0.265444 0.78537 0.265444 0.743909 0.21941 0.734064 0.21941 0.77352 0.265444 0.78537 0.312122 0.711412 0.265444 0.699396 0.265444 0.743909 0.21941 0.691543 0.265444 0.743909 0.265444 0.699396 0.21941 0.691543 0.21941 0.734064 0.265444 0.743909 0.30722 0.688374 0.265444 0.652395 0.265444 0.699396 0.21941 0.646519 0.265444 0.699396 0.265444 0.652395 0.309344 0.701035 0.30722 0.688374 0.265444 0.699396 0.312122 0.711412 0.309344 0.701035 0.265444 0.699396 0.21941 0.646519 0.21941 0.691543 0.265444 0.699396 0.302353 0.641812 0.265444 0.6035 0.265444 0.652395 0.21941 0.59959 0.265444 0.652395 0.265444 0.6035 0.30722 0.688374 0.302353 0.641812 0.265444 0.652395 0.21941 0.59959 0.21941 0.646519 0.265444 0.652395 0.2989 0.593917 0.265444 0.553328 0.265444 0.6035 0.21941 0.551375 0.265444 0.6035 0.265444 0.553328 0.302353 0.641812 0.2989 0.593917 0.265444 0.6035 0.21941 0.551375 0.21941 0.59959 0.265444 0.6035 0.304635 0.502513 0.265444 0.502513 0.265444 0.553328 0.21941 0.551375 0.265444 0.553328 0.265444 0.502513 0.314043 0.450136 0.265444 0.502513 0.304635 0.502513 0.257293 0.502513 0.21941 0.551375 0.265444 0.502513 0.265444 0.4517 0.257293 0.502513 0.265444 0.502513 0.314043 0.450136 0.265444 0.4517 0.265444 0.502513 0.30722 0.593917 0.2989 0.593917 0.302353 0.641812 0.30722 0.593917 0.347584 0.593917 0.2989 0.593917 0.30722 0.593917 0.302353 0.641812 0.30722 0.688374 0.30722 0.593917 0.30722 0.688374 0.309344 0.701035 0.310324 0.593917 0.309344 0.701035 0.312122 0.711412 0.308574 0.593917 0.309344 0.701035 0.310324 0.593917 0.30722 0.593917 0.309344 0.701035 0.308574 0.593917 0.310324 0.593917 0.312122 0.711412 0.312496 0.593917 0.21941 0.849599 0.2191849 0.819198 0.247097 0.842244 0.294485 0.753628 0.247097 0.842244 0.2191849 0.819198 0.294485 0.753628 0.311742 0.766426 0.247097 0.842244 0.176518 0.804053 0.2191849 0.819198 0.21941 0.849599 0.176518 0.804053 0.211538 0.812083 0.2191849 0.819198 0.27807 0.7395 0.2191849 0.819198 0.211538 0.812083 0.27807 0.7395 0.294485 0.753628 0.2191849 0.819198 0.176518 0.830572 0.21941 0.849599 0.21941 0.875551 0.176518 0.830572 0.176518 0.804053 0.21941 0.849599 0.176518 0.852884 0.21941 0.875551 0.21941 0.896565 0.176518 0.852884 0.176518 0.830572 0.21941 0.875551 0.176518 0.870702 0.21941 0.896565 0.21941 0.912362 0.176518 0.870702 0.176518 0.852884 0.21941 0.896565 0.176518 0.883798 0.21941 0.912362 0.21941 0.922734 0.176518 0.883798 0.176518 0.870702 0.21941 0.912362 0.176518 0.892003 0.21941 0.922734 0.21941 0.927544 0.176518 0.892003 0.176518 0.883798 0.21941 0.922734 0.176518 0.895213 0.21941 0.927544 0.21941 0.926727 0.176518 0.895213 0.176518 0.892003 0.21941 0.927544 0.176518 0.893386 0.21941 0.926727 0.21941 0.920294 0.176518 0.893386 0.176518 0.895213 0.21941 0.926727 0.176518 0.886545 0.21941 0.920294 0.21941 0.908331 0.176518 0.886545 0.176518 0.893386 0.21941 0.920294 0.176518 0.87478 0.21941 0.908331 0.21941 0.890996 0.176518 0.87478 0.176518 0.886545 0.21941 0.908331 0.176518 0.858239 0.21941 0.890996 0.21941 0.868518 0.176518 0.858239 0.176518 0.87478 0.21941 0.890996 0.176518 0.837136 0.21941 0.868518 0.21941 0.841195 0.176518 0.837136 0.176518 0.858239 0.21941 0.868518 0.176518 0.811742 0.21941 0.841195 0.21941 0.809389 0.176518 0.811742 0.176518 0.837136 0.21941 0.841195 0.176518 0.782381 0.21941 0.809389 0.21941 0.77352 0.176518 0.782381 0.176518 0.811742 0.21941 0.809389 0.176518 0.74943 0.21941 0.77352 0.21941 0.734064 0.176518 0.74943 0.176518 0.782381 0.21941 0.77352 0.176518 0.713313 0.21941 0.734064 0.21941 0.691543 0.176518 0.713313 0.176518 0.74943 0.21941 0.734064 0.176518 0.674492 0.21941 0.691543 0.21941 0.646519 0.176518 0.674492 0.176518 0.713313 0.21941 0.691543 0.176518 0.633465 0.21941 0.646519 0.21941 0.59959 0.176518 0.633465 0.176518 0.674492 0.21941 0.646519 0.176518 0.590759 0.21941 0.59959 0.21941 0.551375 0.176518 0.590759 0.176518 0.633465 0.21941 0.59959 0.257293 0.502513 0.21941 0.502513 0.21941 0.551375 0.176518 0.546921 0.21941 0.551375 0.21941 0.502513 0.176518 0.546921 0.176518 0.590759 0.21941 0.551375 0.265444 0.4517 0.21941 0.502513 0.257293 0.502513 0.212526 0.502513 0.176518 0.546921 0.21941 0.502513 0.21941 0.453646 0.212526 0.502513 0.21941 0.502513 0.265444 0.4517 0.21941 0.453646 0.21941 0.502513 0.176518 0.804053 0.180719 0.77913 0.211538 0.812083 0.262696 0.724185 0.211538 0.812083 0.180719 0.77913 0.262696 0.724185 0.27807 0.7395 0.211538 0.812083 0.176518 0.804053 0.176274 0.773716 0.180719 0.77913 0.2483209 0.707649 0.180719 0.77913 0.176274 0.773716 0.2483209 0.707649 0.262696 0.724185 0.180719 0.77913 0.137307 0.773061 0.176274 0.773716 0.176518 0.804053 0.137307 0.745859 0.154843 0.744626 0.176274 0.773716 0.235183 0.690209 0.176274 0.773716 0.154843 0.744626 0.137307 0.773061 0.137307 0.745859 0.176274 0.773716 0.235183 0.690209 0.2483209 0.707649 0.176274 0.773716 0.137307 0.796922 0.176518 0.804053 0.176518 0.830572 0.137307 0.796922 0.137307 0.773061 0.176518 0.804053 0.137307 0.817148 0.176518 0.830572 0.176518 0.852884 0.137307 0.817148 0.137307 0.796922 0.176518 0.830572 0.137307 0.833489 0.176518 0.852884 0.176518 0.870702 0.137307 0.833489 0.137307 0.817148 0.176518 0.852884 0.137307 0.845744 0.176518 0.870702 0.176518 0.883798 0.137307 0.845744 0.137307 0.833489 0.176518 0.870702 0.137307 0.85376 0.176518 0.883798 0.176518 0.892003 0.137307 0.85376 0.137307 0.845744 0.176518 0.883798 0.137307 0.857439 0.176518 0.892003 0.176518 0.895213 0.137307 0.857439 0.137307 0.85376 0.176518 0.892003 0.137307 0.856735 0.176518 0.895213 0.176518 0.893386 0.137307 0.856735 0.137307 0.857439 0.176518 0.895213 0.137307 0.851658 0.176518 0.893386 0.176518 0.886545 0.137307 0.851658 0.137307 0.856735 0.176518 0.893386 0.137307 0.842269 0.176518 0.886545 0.176518 0.87478 0.137307 0.842269 0.137307 0.851658 0.176518 0.886545 0.137307 0.828686 0.176518 0.87478 0.176518 0.858239 0.137307 0.828686 0.137307 0.842269 0.176518 0.87478 0.137307 0.811074 0.176518 0.858239 0.176518 0.837136 0.137307 0.811074 0.137307 0.828686 0.176518 0.858239 0.137307 0.789653 0.176518 0.837136 0.176518 0.811742 0.137307 0.789653 0.137307 0.811074 0.176518 0.837136 0.137307 0.764686 0.176518 0.811742 0.176518 0.782381 0.137307 0.764686 0.137307 0.789653 0.176518 0.811742 0.137367 0.736643 0.176518 0.782381 0.176518 0.74943 0.137367 0.736643 0.137307 0.764686 0.176518 0.782381 0.137427 0.719892 0.176518 0.74943 0.176518 0.713313 0.13782 0.735399 0.137367 0.736643 0.176518 0.74943 0.138365 0.73172 0.13782 0.735399 0.176518 0.74943 0.1382589 0.726586 0.138365 0.73172 0.176518 0.74943 0.137427 0.719892 0.1382589 0.726586 0.176518 0.74943 0.137307 0.687263 0.176518 0.713313 0.176518 0.674492 0.137336 0.719339 0.137427 0.719892 0.176518 0.713313 0.137307 0.687263 0.137336 0.719339 0.176518 0.713313 0.137307 0.653036 0.176518 0.674492 0.176518 0.633465 0.137307 0.653036 0.137307 0.687263 0.176518 0.674492 0.137307 0.617009 0.176518 0.633465 0.176518 0.590759 0.137307 0.617009 0.137307 0.653036 0.176518 0.633465 0.137307 0.579613 0.176518 0.590759 0.176518 0.546921 0.137307 0.579613 0.137307 0.617009 0.176518 0.590759 0.212526 0.502513 0.176518 0.502513 0.176518 0.546921 0.137307 0.541295 0.176518 0.546921 0.176518 0.502513 0.137307 0.541295 0.137307 0.579613 0.176518 0.546921 0.21941 0.453646 0.176518 0.502513 0.212526 0.502513 0.170877 0.502513 0.137307 0.541295 0.176518 0.502513 0.176518 0.458116 0.170877 0.502513 0.176518 0.502513 0.21941 0.453646 0.176518 0.458116 0.176518 0.502513 0.137307 0.745859 0.137072 0.715675 0.154843 0.744626 0.209277 0.696675 0.154843 0.744626 0.137072 0.715675 0.209277 0.696675 0.235183 0.690209 0.154843 0.744626 0.135567 0.72102 0.137072 0.715675 0.137307 0.745859 0.134904 0.715756 0.133843 0.709795 0.137072 0.715675 0.1929309 0.677247 0.137072 0.715675 0.133843 0.709795 0.135567 0.72102 0.134904 0.715756 0.137072 0.715675 0.208057 0.696361 0.209277 0.696675 0.137072 0.715675 0.206293 0.695128 0.208057 0.696361 0.137072 0.715675 0.203889 0.692777 0.206293 0.695128 0.137072 0.715675 0.200815 0.6891 0.203889 0.692777 0.137072 0.715675 0.197138 0.68397 0.200815 0.6891 0.137072 0.715675 0.1929309 0.677247 0.197138 0.68397 0.137072 0.715675 0.102269 0.737057 0.137307 0.745859 0.137307 0.773061 0.135808 0.725569 0.135567 0.72102 0.137307 0.745859 0.135582 0.729344 0.135808 0.725569 0.137307 0.745859 0.134834 0.732217 0.135582 0.729344 0.137307 0.745859 0.133544 0.734003 0.134834 0.732217 0.137307 0.745859 0.131757 0.734598 0.133544 0.734003 0.137307 0.745859 0.129513 0.733977 0.131757 0.734598 0.137307 0.745859 0.12686 0.732148 0.129513 0.733977 0.137307 0.745859 0.102269 0.71223 0.12686 0.732148 0.137307 0.745859 0.102269 0.737057 0.102269 0.71223 0.137307 0.745859 0.102269 0.758907 0.137307 0.773061 0.137307 0.796922 0.102269 0.758907 0.102269 0.737057 0.137307 0.773061 0.102269 0.777503 0.137307 0.796922 0.137307 0.817148 0.102269 0.777503 0.102269 0.758907 0.137307 0.796922 0.102269 0.792608 0.137307 0.817148 0.137307 0.833489 0.102269 0.792608 0.102269 0.777503 0.137307 0.817148 0.102269 0.804033 0.137307 0.833489 0.137307 0.845744 0.102269 0.804033 0.102269 0.792608 0.137307 0.833489 0.102269 0.81163 0.137307 0.845744 0.137307 0.85376 0.102269 0.81163 0.102269 0.804033 0.137307 0.845744 0.102269 0.815305 0.137307 0.85376 0.137307 0.857439 0.102269 0.815305 0.102269 0.81163 0.137307 0.85376 0.102269 0.815009 0.137307 0.857439 0.137307 0.856735 0.102269 0.815009 0.102269 0.815305 0.137307 0.857439 0.102269 0.810748 0.137307 0.856735 0.137307 0.851658 0.102269 0.810748 0.102269 0.815009 0.137307 0.856735 0.102269 0.802575 0.137307 0.851658 0.137307 0.842269 0.102269 0.802575 0.102269 0.810748 0.137307 0.851658 0.102269 0.790593 0.137307 0.842269 0.137307 0.828686 0.102269 0.790593 0.102269 0.802575 0.137307 0.842269 0.102269 0.774955 0.137307 0.828686 0.137307 0.811074 0.102269 0.774955 0.102269 0.790593 0.137307 0.828686 0.102269 0.75586 0.137307 0.811074 0.137307 0.789653 0.102269 0.75586 0.102269 0.774955 0.137307 0.811074 0.102269 0.75586 0.137307 0.789653 0.137307 0.764686 0.13673 0.737689 0.137307 0.764686 0.137367 0.736643 0.102269 0.733549 0.102269 0.75586 0.137307 0.764686 0.133369 0.738755 0.102269 0.733549 0.137307 0.764686 0.135227 0.738746 0.133369 0.738755 0.137307 0.764686 0.13673 0.737689 0.135227 0.738746 0.137307 0.764686 0.136246 0.593917 0.137367 0.736643 0.13782 0.735399 0.136246 0.593917 0.13673 0.737689 0.137367 0.736643 0.138074 0.593917 0.13782 0.735399 0.138365 0.73172 0.136246 0.593917 0.13782 0.735399 0.138074 0.593917 0.138289 0.593917 0.138365 0.73172 0.1382589 0.726586 0.138074 0.593917 0.138365 0.73172 0.138289 0.593917 0.138289 0.593917 0.1382589 0.726586 0.137427 0.719892 0.138289 0.593917 0.137427 0.719892 0.137336 0.719339 0.135784 0.711462 0.137336 0.719339 0.137307 0.687263 0.136866 0.593917 0.137336 0.719339 0.135784 0.711462 0.138289 0.593917 0.137336 0.719339 0.136866 0.593917 0.123076 0.665027 0.137307 0.687263 0.137307 0.653036 0.133222 0.70106 0.135784 0.711462 0.137307 0.687263 0.129603 0.688374 0.133222 0.70106 0.137307 0.687263 0.123076 0.665027 0.129603 0.688374 0.137307 0.687263 0.1174679 0.641466 0.137307 0.653036 0.137307 0.617009 0.1174679 0.641466 0.123076 0.665027 0.137307 0.653036 0.108987 0.593917 0.137307 0.617009 0.137307 0.579613 0.112773 0.617746 0.1174679 0.641466 0.137307 0.617009 0.108987 0.593917 0.112773 0.617746 0.137307 0.617009 0.102269 0.564014 0.137307 0.579613 0.137307 0.541295 0.10226 0.593917 0.137307 0.579613 0.102269 0.564014 0.108987 0.593917 0.137307 0.579613 0.10226 0.593917 0.170877 0.502513 0.137307 0.502513 0.137307 0.541295 0.102269 0.533414 0.137307 0.541295 0.137307 0.502513 0.102269 0.564014 0.137307 0.541295 0.102269 0.533414 0.176518 0.458116 0.137307 0.502513 0.170877 0.502513 0.13285 0.502513 0.102269 0.533414 0.137307 0.502513 0.137307 0.462262 0.13285 0.502513 0.137307 0.502513 0.176518 0.458116 0.137307 0.462262 0.137307 0.502513 0.133746 0.593917 0.133843 0.709795 0.134904 0.715756 0.1929309 0.677247 0.133843 0.709795 0.132122 0.704745 0.133746 0.593917 0.132122 0.704745 0.133843 0.709795 0.135545 0.593917 0.134904 0.715756 0.135567 0.72102 0.133746 0.593917 0.134904 0.715756 0.135545 0.593917 0.135545 0.593917 0.135567 0.72102 0.135808 0.725569 0.1356199 0.593917 0.135808 0.725569 0.135582 0.729344 0.135545 0.593917 0.135808 0.725569 0.1356199 0.593917 0.1356199 0.593917 0.135582 0.729344 0.134834 0.732217 0.133969 0.593917 0.134834 0.732217 0.133544 0.734003 0.1356199 0.593917 0.134834 0.732217 0.133969 0.593917 0.133969 0.593917 0.133544 0.734003 0.131757 0.734598 0.130721 0.593917 0.131757 0.734598 0.129513 0.733977 0.133969 0.593917 0.131757 0.734598 0.130721 0.593917 0.130721 0.593917 0.129513 0.733977 0.12686 0.732148 0.102269 0.71223 0.123953 0.729214 0.12686 0.732148 0.1261309 0.593917 0.12686 0.732148 0.123953 0.729214 0.130721 0.593917 0.12686 0.732148 0.1261309 0.593917 0.102269 0.71223 0.120956 0.725375 0.123953 0.729214 0.1261309 0.593917 0.123953 0.729214 0.120956 0.725375 0.102269 0.71223 0.117928 0.720758 0.120956 0.725375 0.120564 0.593917 0.120956 0.725375 0.117928 0.720758 0.1261309 0.593917 0.120956 0.725375 0.120564 0.593917 0.102269 0.71223 0.114899 0.715419 0.117928 0.720758 0.120564 0.593917 0.117928 0.720758 0.114899 0.715419 0.102269 0.71223 0.1118929 0.709382 0.114899 0.715419 0.1144559 0.593917 0.114899 0.715419 0.1118929 0.709382 0.120564 0.593917 0.114899 0.715419 0.1144559 0.593917 0.102269 0.71223 0.108929 0.702626 0.1118929 0.709382 0.111668 0.593917 0.1118929 0.709382 0.108929 0.702626 0.1144559 0.593917 0.1118929 0.709382 0.111668 0.593917 0.102269 0.71223 0.10201 0.684878 0.108929 0.702626 0.08523297 0.630358 0.108929 0.702626 0.10201 0.684878 0.08104395 0.612151 0.108929 0.702626 0.08523297 0.630358 0.07754099 0.593917 0.108929 0.702626 0.08104395 0.612151 0.108929 0.593917 0.108929 0.702626 0.07754099 0.593917 0.111668 0.593917 0.108929 0.702626 0.108929 0.593917 0.07184296 0.669106 0.10201 0.684878 0.102269 0.71223 0.08523297 0.630358 0.10201 0.684878 0.09566998 0.666688 0.07184296 0.644669 0.09566998 0.666688 0.10201 0.684878 0.07184296 0.669106 0.07184296 0.644669 0.10201 0.684878 0.07184296 0.691448 0.102269 0.71223 0.102269 0.737057 0.07184296 0.691448 0.07184296 0.669106 0.102269 0.71223 0.07184296 0.711414 0.102269 0.737057 0.102269 0.758907 0.07184296 0.711414 0.07184296 0.691448 0.102269 0.737057 0.07184296 0.728753 0.102269 0.758907 0.102269 0.777503 0.07184296 0.728753 0.07184296 0.711414 0.102269 0.758907 0.07184296 0.743247 0.102269 0.777503 0.102269 0.792608 0.07184296 0.743247 0.07184296 0.728753 0.102269 0.777503 0.07184296 0.754713 0.102269 0.792608 0.102269 0.804033 0.07184296 0.754713 0.07184296 0.743247 0.102269 0.792608 0.07184296 0.763008 0.102269 0.804033 0.102269 0.81163 0.07184296 0.763008 0.07184296 0.754713 0.102269 0.804033 0.07184296 0.768027 0.102269 0.81163 0.102269 0.815305 0.07184296 0.768027 0.07184296 0.763008 0.102269 0.81163 0.07184296 0.769707 0.102269 0.815305 0.102269 0.815009 0.07184296 0.769707 0.07184296 0.768027 0.102269 0.815305 0.07184296 0.768027 0.102269 0.815009 0.102269 0.810748 0.07184296 0.768027 0.07184296 0.769707 0.102269 0.815009 0.07184296 0.763008 0.102269 0.810748 0.102269 0.802575 0.07184296 0.763008 0.07184296 0.768027 0.102269 0.810748 0.07184296 0.754713 0.102269 0.802575 0.102269 0.790593 0.07184296 0.754713 0.07184296 0.763008 0.102269 0.802575 0.07184296 0.743247 0.102269 0.790593 0.102269 0.774955 0.07184296 0.743247 0.07184296 0.754713 0.102269 0.790593 0.07184296 0.728753 0.102269 0.774955 0.102269 0.75586 0.07184296 0.728753 0.07184296 0.743247 0.102269 0.774955 0.07184296 0.711414 0.102269 0.75586 0.102269 0.733549 0.07184296 0.711414 0.07184296 0.728753 0.102269 0.75586 0.121406 0.726856 0.102269 0.708306 0.102269 0.733549 0.07184296 0.691448 0.102269 0.733549 0.102269 0.708306 0.1250399 0.731902 0.121406 0.726856 0.102269 0.733549 0.1282989 0.735499 0.1250399 0.731902 0.102269 0.733549 0.131083 0.737728 0.1282989 0.735499 0.102269 0.733549 0.133369 0.738755 0.131083 0.737728 0.102269 0.733549 0.07184296 0.691448 0.07184296 0.711414 0.102269 0.733549 0.104504 0.688374 0.102187 0.680477 0.102269 0.708306 0.07184296 0.669106 0.102269 0.708306 0.102187 0.680477 0.108897 0.701351 0.104504 0.688374 0.102269 0.708306 0.113265 0.711838 0.108897 0.701351 0.102269 0.708306 0.117463 0.72024 0.113265 0.711838 0.102269 0.708306 0.121406 0.726856 0.117463 0.72024 0.102269 0.708306 0.07184296 0.669106 0.07184296 0.691448 0.102269 0.708306 0.104504 0.593917 0.102187 0.680477 0.104504 0.688374 0.07184296 0.644669 0.07184296 0.669106 0.102187 0.680477 0.09795796 0.664956 0.07184296 0.644669 0.102187 0.680477 0.104504 0.593917 0.09795796 0.664956 0.102187 0.680477 0.104504 0.593917 0.104504 0.688374 0.108897 0.701351 0.112614 0.593917 0.108897 0.701351 0.113265 0.711838 0.108369 0.593917 0.108897 0.701351 0.112614 0.593917 0.104504 0.593917 0.108897 0.701351 0.108369 0.593917 0.117053 0.593917 0.113265 0.711838 0.117463 0.72024 0.112614 0.593917 0.113265 0.711838 0.117053 0.593917 0.117053 0.593917 0.117463 0.72024 0.121406 0.726856 0.122979 0.593917 0.121406 0.726856 0.1250399 0.731902 0.117053 0.593917 0.121406 0.726856 0.122979 0.593917 0.122979 0.593917 0.1250399 0.731902 0.1282989 0.735499 0.128408 0.593917 0.1282989 0.735499 0.131083 0.737728 0.122979 0.593917 0.1282989 0.735499 0.128408 0.593917 0.132943 0.593917 0.131083 0.737728 0.133369 0.738755 0.128408 0.593917 0.131083 0.737728 0.132943 0.593917 0.132943 0.593917 0.133369 0.738755 0.135227 0.738746 0.136246 0.593917 0.135227 0.738746 0.13673 0.737689 0.132943 0.593917 0.135227 0.738746 0.136246 0.593917 0.07184296 0.644669 0.08523297 0.630358 0.09566998 0.666688 0.07184296 0.618444 0.08104395 0.612151 0.08523297 0.630358 0.07184296 0.644669 0.07184296 0.618444 0.08523297 0.630358 0.07184296 0.590762 0.07754099 0.593917 0.08104395 0.612151 0.07184296 0.618444 0.07184296 0.590762 0.08104395 0.612151 0.09152597 0.593917 0.07754099 0.593917 0.08438795 0.593917 0.07184296 0.590762 0.08438795 0.593917 0.07754099 0.593917 0.108929 0.593917 0.07754099 0.593917 0.09152597 0.593917 0.07184296 0.561969 0.09152597 0.593917 0.08438795 0.593917 0.07184296 0.590762 0.07184296 0.561969 0.08438795 0.593917 0.07184296 0.561969 0.08737695 0.571361 0.09152597 0.593917 0.183551 0.569057 0.09152597 0.593917 0.08737695 0.571361 0.09399598 0.593917 0.09152597 0.593917 0.183551 0.569057 0.09399598 0.593917 0.09646695 0.593917 0.108929 0.593917 0.108929 0.593917 0.09152597 0.593917 0.09399598 0.593917 0.07184296 0.561969 0.08439797 0.548561 0.08737695 0.571361 0.179844 0.547083 0.08737695 0.571361 0.08439797 0.548561 0.179844 0.547083 0.183551 0.569057 0.08737695 0.571361 0.07184296 0.532429 0.08260297 0.525588 0.08439797 0.548561 0.1776199 0.524918 0.08439797 0.548561 0.08260297 0.525588 0.07184296 0.561969 0.07184296 0.532429 0.08439797 0.548561 0.1776199 0.524918 0.179844 0.547083 0.08439797 0.548561 0.07184296 0.502513 0.08200299 0.502513 0.08260297 0.525588 0.1776199 0.524918 0.08260297 0.525588 0.08200299 0.502513 0.07184296 0.532429 0.07184296 0.502513 0.08260297 0.525588 0.07184296 0.472597 0.08200299 0.502513 0.07184296 0.502513 0.07184296 0.472597 0.08233696 0.485294 0.08200299 0.502513 0.176868 0.502513 0.08200299 0.502513 0.08233696 0.485294 0.1776199 0.524918 0.08200299 0.502513 0.176868 0.502513 0.057473 0.502513 0.07184296 0.502513 0.07184296 0.532429 0.04641199 0.478118 0.07184296 0.502513 0.057473 0.502513 0.04641199 0.478118 0.07184296 0.472597 0.07184296 0.502513 0.04641199 0.527367 0.07184296 0.532429 0.07184296 0.561969 0.04641199 0.502513 0.057473 0.502513 0.07184296 0.532429 0.04641199 0.527367 0.04641199 0.502513 0.07184296 0.532429 0.04641199 0.551896 0.07184296 0.561969 0.07184296 0.590762 0.04641199 0.551896 0.04641199 0.527367 0.07184296 0.561969 0.04641199 0.575781 0.07184296 0.590762 0.07184296 0.618444 0.04641199 0.575781 0.04641199 0.551896 0.07184296 0.590762 0.04641199 0.598709 0.07184296 0.618444 0.07184296 0.644669 0.04641199 0.598709 0.04641199 0.575781 0.07184296 0.618444 0.04641199 0.620382 0.07184296 0.644669 0.07184296 0.669106 0.04641199 0.620382 0.04641199 0.598709 0.07184296 0.644669 0.04641199 0.640516 0.07184296 0.669106 0.07184296 0.691448 0.04641199 0.640516 0.04641199 0.620382 0.07184296 0.669106 0.04641199 0.658848 0.07184296 0.691448 0.07184296 0.711414 0.04641199 0.658848 0.04641199 0.640516 0.07184296 0.691448 0.04641199 0.675139 0.07184296 0.711414 0.07184296 0.728753 0.04641199 0.675139 0.04641199 0.658848 0.07184296 0.711414 0.04641199 0.689177 0.07184296 0.728753 0.07184296 0.743247 0.04641199 0.689177 0.04641199 0.675139 0.07184296 0.728753 0.04641199 0.700778 0.07184296 0.743247 0.07184296 0.754713 0.04641199 0.700778 0.04641199 0.689177 0.07184296 0.743247 0.04641199 0.709791 0.07184296 0.754713 0.07184296 0.763008 0.04641199 0.709791 0.04641199 0.700778 0.07184296 0.754713 0.04641199 0.716098 0.07184296 0.763008 0.07184296 0.768027 0.04641199 0.716098 0.04641199 0.709791 0.07184296 0.763008 0.04642999 0.719656 0.07184296 0.768027 0.07184296 0.769707 0.04642999 0.719656 0.04641199 0.716098 0.07184296 0.768027 0.05509197 0.738736 0.07184296 0.769707 0.07184296 0.768027 0.04658895 0.720022 0.04642999 0.719656 0.07184296 0.769707 0.04955095 0.726717 0.04658895 0.720022 0.07184296 0.769707 0.05187696 0.731839 0.04955095 0.726717 0.07184296 0.769707 0.05356895 0.735491 0.05187696 0.731839 0.07184296 0.769707 0.05462598 0.737747 0.05356895 0.735491 0.07184296 0.769707 0.05510795 0.738769 0.05462598 0.737747 0.07184296 0.769707 0.05509197 0.738736 0.05510795 0.738769 0.07184296 0.769707 0.04641199 0.716095 0.07184296 0.768027 0.07184296 0.763008 0.05457895 0.737647 0.05509197 0.738736 0.07184296 0.768027 0.05349296 0.735329 0.05457895 0.737647 0.07184296 0.768027 0.05178296 0.731634 0.05349296 0.735329 0.07184296 0.768027 0.04945296 0.726499 0.05178296 0.731634 0.07184296 0.768027 0.04649698 0.71981 0.04945296 0.726499 0.07184296 0.768027 0.389797 0.873461 0.389781 0.873461 0.3879 0.873461 0.04641199 0.716095 0.04649698 0.71981 0.07184296 0.768027 0.04641199 0.709788 0.07184296 0.763008 0.07184296 0.754713 0.04641199 0.709788 0.04641199 0.716095 0.07184296 0.763008 0.04641199 0.700774 0.07184296 0.754713 0.07184296 0.743247 0.04641199 0.700774 0.04641199 0.709788 0.07184296 0.754713 0.04641199 0.689173 0.07184296 0.743247 0.07184296 0.728753 0.04641199 0.689173 0.04641199 0.700774 0.07184296 0.743247 0.04641199 0.675135 0.07184296 0.728753 0.07184296 0.711414 0.04641199 0.675135 0.04641199 0.689173 0.07184296 0.728753 0.04641199 0.658844 0.07184296 0.711414 0.07184296 0.691448 0.04641199 0.658844 0.04641199 0.675135 0.07184296 0.711414 0.04641199 0.640512 0.07184296 0.691448 0.07184296 0.669106 0.04641199 0.640512 0.04641199 0.658844 0.07184296 0.691448 0.04641199 0.620378 0.07184296 0.669106 0.07184296 0.644669 0.04641199 0.620378 0.04641199 0.640512 0.07184296 0.669106 0.09234696 0.641371 0.07184296 0.618444 0.07184296 0.644669 0.04641199 0.598706 0.07184296 0.644669 0.07184296 0.618444 0.09795796 0.664956 0.09234696 0.641371 0.07184296 0.644669 0.04641199 0.598706 0.04641199 0.620378 0.07184296 0.644669 0.08765995 0.617673 0.07184296 0.590762 0.07184296 0.618444 0.04641199 0.575779 0.07184296 0.618444 0.07184296 0.590762 0.09234696 0.641371 0.08765995 0.617673 0.07184296 0.618444 0.04641199 0.575779 0.04641199 0.598706 0.07184296 0.618444 0.10226 0.593917 0.07184296 0.561969 0.07184296 0.590762 0.04641199 0.551895 0.07184296 0.590762 0.07184296 0.561969 0.09603798 0.593917 0.10226 0.593917 0.07184296 0.590762 0.08388698 0.593917 0.09603798 0.593917 0.07184296 0.590762 0.08765995 0.617673 0.08388698 0.593917 0.07184296 0.590762 0.04641199 0.551895 0.04641199 0.575779 0.07184296 0.590762 0.102269 0.564014 0.07184296 0.532429 0.07184296 0.561969 0.04641199 0.527366 0.07184296 0.561969 0.07184296 0.532429 0.10226 0.593917 0.102269 0.564014 0.07184296 0.561969 0.04641199 0.527366 0.04641199 0.551895 0.07184296 0.561969 0.09890699 0.502513 0.07184296 0.502513 0.07184296 0.532429 0.04641199 0.527366 0.07184296 0.532429 0.07184296 0.502513 0.102268 0.502513 0.09890699 0.502513 0.07184296 0.532429 0.102269 0.533414 0.102268 0.502513 0.07184296 0.532429 0.102269 0.564014 0.102269 0.533414 0.07184296 0.532429 0.102268 0.467274 0.07184296 0.502513 0.09890699 0.502513 0.069458 0.502513 0.04641199 0.527366 0.07184296 0.502513 0.07184296 0.472597 0.069458 0.502513 0.07184296 0.502513 0.07184296 0.472597 0.07184296 0.502513 0.102268 0.467274 0.102268 0.467274 0.09890699 0.502513 0.102268 0.502513 0.13285 0.502513 0.102268 0.502513 0.102269 0.533414 0.137307 0.462262 0.102268 0.502513 0.13285 0.502513 0.137307 0.462262 0.102268 0.467274 0.102268 0.502513 0.104504 0.593917 0.10226 0.593917 0.09603798 0.593917 0.108369 0.593917 0.108987 0.593917 0.10226 0.593917 0.104504 0.593917 0.108369 0.593917 0.10226 0.593917 0.104504 0.593917 0.09603798 0.593917 0.08388698 0.593917 0.104504 0.593917 0.08388698 0.593917 0.08765995 0.617673 0.104504 0.593917 0.08765995 0.617673 0.09234696 0.641371 0.104504 0.593917 0.09234696 0.641371 0.09795796 0.664956 0.04641199 0.478118 0.057473 0.502513 0.04641199 0.502513 0.03706097 0.502513 0.04641199 0.502513 0.04641199 0.527367 0.026295 0.483945 0.04641199 0.502513 0.03706097 0.502513 0.026295 0.483945 0.04641199 0.478118 0.04641199 0.502513 0.026295 0.538685 0.04641199 0.527367 0.04641199 0.551896 0.026295 0.502513 0.03706097 0.502513 0.04641199 0.527367 0.026295 0.520709 0.026295 0.502513 0.04641199 0.527367 0.026295 0.538685 0.026295 0.520709 0.04641199 0.527367 0.026295 0.556225 0.04641199 0.551896 0.04641199 0.575781 0.026295 0.556225 0.026295 0.538685 0.04641199 0.551896 0.026295 0.573116 0.04641199 0.575781 0.04641199 0.598709 0.026295 0.573116 0.026295 0.556225 0.04641199 0.575781 0.026295 0.589154 0.04641199 0.598709 0.04641199 0.620382 0.026295 0.589154 0.026295 0.573116 0.04641199 0.598709 0.026295 0.604146 0.04641199 0.620382 0.04641199 0.640516 0.026295 0.604146 0.026295 0.589154 0.04641199 0.620382 0.026295 0.617911 0.04641199 0.640516 0.04641199 0.658848 0.026295 0.617911 0.026295 0.604146 0.04641199 0.640516 0.026295 0.630283 0.04641199 0.658848 0.04641199 0.675139 0.026295 0.630283 0.026295 0.617911 0.04641199 0.658848 0.026295 0.641111 0.04641199 0.675139 0.04641199 0.689177 0.026295 0.641111 0.026295 0.630283 0.04641199 0.675139 0.026295 0.650266 0.04641199 0.689177 0.04641199 0.700778 0.026295 0.650266 0.026295 0.641111 0.04641199 0.689177 0.026295 0.657637 0.04641199 0.700778 0.04641199 0.709791 0.026295 0.657637 0.026295 0.650266 0.04641199 0.700778 0.026295 0.663134 0.04641199 0.709791 0.04641199 0.716098 0.026295 0.663134 0.026295 0.657637 0.04641199 0.709791 0.04297995 0.711573 0.04641199 0.716098 0.04642999 0.719656 0.02609199 0.66606 0.026295 0.663134 0.04641199 0.716098 0.03871798 0.701132 0.02609199 0.66606 0.04641199 0.716098 0.04297995 0.711573 0.03871798 0.701132 0.04641199 0.716098 0.04549199 0.593917 0.04642999 0.719656 0.04658895 0.720022 0.04549199 0.593917 0.04297995 0.711573 0.04642999 0.719656 0.04549199 0.593917 0.04658895 0.720022 0.04955095 0.726717 0.05005198 0.593917 0.04955095 0.726717 0.05187696 0.731839 0.04549199 0.593917 0.04955095 0.726717 0.05005198 0.593917 0.05327898 0.593917 0.05187696 0.731839 0.05356895 0.735491 0.05005198 0.593917 0.05187696 0.731839 0.05327898 0.593917 0.05327898 0.593917 0.05356895 0.735491 0.05462598 0.737747 0.05494999 0.593917 0.05462598 0.737747 0.05510795 0.738769 0.05327898 0.593917 0.05462598 0.737747 0.05494999 0.593917 0.05494999 0.593917 0.05510795 0.738769 0.05509197 0.738736 0.05492496 0.593917 0.05509197 0.738736 0.05457895 0.737647 0.05494999 0.593917 0.05509197 0.738736 0.05492496 0.593917 0.05492496 0.593917 0.05457895 0.737647 0.05349296 0.735329 0.05320894 0.593917 0.05349296 0.735329 0.05178296 0.731634 0.05492496 0.593917 0.05349296 0.735329 0.05320894 0.593917 0.049959 0.593917 0.05178296 0.731634 0.04945296 0.726499 0.05320894 0.593917 0.05178296 0.731634 0.049959 0.593917 0.049959 0.593917 0.04945296 0.726499 0.04649698 0.71981 0.395398 0.873461 0.395314 0.873461 0.389797 0.873461 0.04290497 0.711393 0.04649698 0.71981 0.04641199 0.716095 0.04541999 0.593917 0.04649698 0.71981 0.04290497 0.711393 0.049959 0.593917 0.04649698 0.71981 0.04541999 0.593917 0.026295 0.663134 0.04641199 0.716095 0.04641199 0.709788 0.03867197 0.701017 0.04290497 0.711393 0.04641199 0.716095 0.03380799 0.68838 0.03867197 0.701017 0.04641199 0.716095 0.02609199 0.66606 0.03380799 0.68838 0.04641199 0.716095 0.026295 0.663134 0.02609199 0.66606 0.04641199 0.716095 0.026295 0.657637 0.04641199 0.709788 0.04641199 0.700774 0.026295 0.657637 0.026295 0.663134 0.04641199 0.709788 0.026295 0.650266 0.04641199 0.700774 0.04641199 0.689173 0.026295 0.650266 0.026295 0.657637 0.04641199 0.700774 0.026295 0.641111 0.04641199 0.689173 0.04641199 0.675135 0.026295 0.641111 0.026295 0.650266 0.04641199 0.689173 0.026295 0.630283 0.04641199 0.675135 0.04641199 0.658844 0.026295 0.630283 0.026295 0.641111 0.04641199 0.675135 0.026295 0.617911 0.04641199 0.658844 0.04641199 0.640512 0.026295 0.617911 0.026295 0.630283 0.04641199 0.658844 0.026295 0.604146 0.04641199 0.640512 0.04641199 0.620378 0.026295 0.604146 0.026295 0.617911 0.04641199 0.640512 0.026295 0.589154 0.04641199 0.620378 0.04641199 0.598706 0.026295 0.589154 0.026295 0.604146 0.04641199 0.620378 0.026295 0.573116 0.04641199 0.598706 0.04641199 0.575779 0.026295 0.573116 0.026295 0.589154 0.04641199 0.598706 0.026295 0.556225 0.04641199 0.575779 0.04641199 0.551895 0.026295 0.556225 0.026295 0.573116 0.04641199 0.575779 0.026295 0.538685 0.04641199 0.551895 0.04641199 0.527366 0.026295 0.538685 0.026295 0.556225 0.04641199 0.551895 0.069458 0.502513 0.04641199 0.502513 0.04641199 0.527366 0.026295 0.520709 0.04641199 0.527366 0.04641199 0.502513 0.026295 0.520709 0.026295 0.538685 0.04641199 0.527366 0.07184296 0.472597 0.04641199 0.502513 0.069458 0.502513 0.026295 0.520709 0.04641199 0.502513 0.04486095 0.502513 0.04641199 0.478118 0.04486095 0.502513 0.04641199 0.502513 0.04641199 0.478118 0.04641199 0.502513 0.07184296 0.472597 0.026295 0.483945 0.03706097 0.502513 0.026295 0.502513 0.02096897 0.502513 0.026295 0.502513 0.026295 0.520709 0.01174396 0.490006 0.026295 0.502513 0.02096897 0.502513 0.01174396 0.490006 0.026295 0.483945 0.026295 0.502513 0.01174396 0.515118 0.026295 0.520709 0.026295 0.538685 0.01174396 0.502513 0.02096897 0.502513 0.026295 0.520709 0.01174396 0.515118 0.01174396 0.502513 0.026295 0.520709 0.01174396 0.527563 0.026295 0.538685 0.026295 0.556225 0.01174396 0.527563 0.01174396 0.515118 0.026295 0.538685 0.01174396 0.539687 0.026295 0.556225 0.026295 0.573116 0.01174396 0.539687 0.01174396 0.527563 0.026295 0.556225 0.01174396 0.551337 0.026295 0.573116 0.026295 0.589154 0.01174396 0.551337 0.01174396 0.539687 0.026295 0.573116 0.01174396 0.562362 0.026295 0.589154 0.026295 0.604146 0.01174396 0.562362 0.01174396 0.551337 0.026295 0.589154 0.01174396 0.572624 0.026295 0.604146 0.026295 0.617911 0.01174396 0.572624 0.01174396 0.562362 0.026295 0.604146 0.01174396 0.581989 0.026295 0.617911 0.026295 0.630283 0.01174396 0.581989 0.01174396 0.572624 0.026295 0.617911 0.01174396 0.59034 0.026295 0.630283 0.026295 0.641111 0.01174396 0.59034 0.01174396 0.581989 0.026295 0.630283 0.01174396 0.597569 0.026295 0.641111 0.026295 0.650266 0.01174396 0.597569 0.01174396 0.59034 0.026295 0.641111 0.01174396 0.603583 0.026295 0.650266 0.026295 0.657637 0.01174396 0.603583 0.01174396 0.597569 0.026295 0.650266 0.01174396 0.608306 0.026295 0.657637 0.026295 0.663134 0.01174396 0.608306 0.01174396 0.603583 0.026295 0.657637 0.01156699 0.611129 0.026295 0.663134 0.02609199 0.66606 0.01156699 0.611129 0.01174396 0.608306 0.026295 0.663134 0.03871798 0.701132 0.03380799 0.68838 0.02609199 0.66606 0.03380799 0.593917 0.02609199 0.66606 0.03380799 0.68838 0.01817697 0.639111 0.01156699 0.611129 0.02609199 0.66606 0.03380799 0.593917 0.01817697 0.639111 0.02609199 0.66606 0.03380799 0.593917 0.03380799 0.68838 0.03871798 0.701132 0.03991299 0.593917 0.03871798 0.701132 0.04297995 0.711573 0.03380799 0.593917 0.03871798 0.701132 0.03991299 0.593917 0.03991299 0.593917 0.04297995 0.711573 0.04549199 0.593917 0.01174396 0.490006 0.02096897 0.502513 0.01174396 0.502513 0.009357988 0.502513 0.01174396 0.502513 0.01174396 0.515118 0.002941966 0.496223 0.01174396 0.502513 0.009357988 0.502513 0.002941966 0.496223 0.01174396 0.490006 0.01174396 0.502513 0.002941966 0.515014 0.01174396 0.515118 0.01174396 0.527563 0.002941966 0.502513 0.009357988 0.502513 0.01174396 0.515118 0.002941966 0.508803 0.002941966 0.502513 0.01174396 0.515118 0.002941966 0.515014 0.002941966 0.508803 0.01174396 0.515118 0.002941966 0.521068 0.01174396 0.527563 0.01174396 0.539687 0.002941966 0.521068 0.002941966 0.515014 0.01174396 0.527563 0.002941966 0.526888 0.01174396 0.539687 0.01174396 0.551337 0.002941966 0.526888 0.002941966 0.521068 0.01174396 0.539687 0.002941966 0.532402 0.01174396 0.551337 0.01174396 0.562362 0.002941966 0.532402 0.002941966 0.526888 0.01174396 0.551337 0.002941966 0.53754 0.01174396 0.562362 0.01174396 0.572624 0.002941966 0.53754 0.002941966 0.532402 0.01174396 0.562362 0.002941966 0.542238 0.01174396 0.572624 0.01174396 0.581989 0.002941966 0.542238 0.002941966 0.53754 0.01174396 0.572624 0.002941966 0.546436 0.01174396 0.581989 0.01174396 0.59034 0.002941966 0.546436 0.002941966 0.542238 0.01174396 0.581989 0.002941966 0.550081 0.01174396 0.59034 0.01174396 0.597569 0.002941966 0.550081 0.002941966 0.546436 0.01174396 0.59034 0.002941966 0.553129 0.01174396 0.597569 0.01174396 0.603583 0.002941966 0.553129 0.002941966 0.550081 0.01174396 0.597569 0.002941966 0.555539 0.01174396 0.603583 0.01174396 0.608306 0.002941966 0.555539 0.002941966 0.553129 0.01174396 0.603583 0.008322954 0.593917 0.01174396 0.608306 0.01156699 0.611129 0.008322954 0.593917 0.002941966 0.555539 0.01174396 0.608306 0.03380799 0.593917 0.01156699 0.611129 0.01817697 0.639111 0.03380799 0.593917 0.008322954 0.593917 0.01156699 0.611129 0.002941966 0.496223 0.009357988 0.502513 0.002941966 0.502513 0.002344965 0.502513 0.002941966 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.502513 0.002344965 0.502513 0.002941966 0.496223 0.002941966 0.502513 0 0.502513 0 0.502513 0.002941966 0.508803 0.002941966 0.515014 0 0.502513 0.002344965 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.515014 0.002941966 0.521068 0 0.502513 0.002941966 0.521068 0.002941966 0.526888 0 0.502513 0.002941966 0.526888 0.002941966 0.532402 0 0.502513 0.002941966 0.532402 0.002941966 0.53754 0 0.502513 0.002941966 0.53754 0.002941966 0.542238 0 0.502513 0.002941966 0.542238 0.002941966 0.546436 0 0.502513 0.002941966 0.546436 0.002941966 0.550081 0 0.502513 0.002941966 0.550081 0.002941966 0.553129 0 0.502513 0.002941966 0.553129 0.002941966 0.555539 0.008322954 0.593917 0.002941966 0.557283 0.002941966 0.555539 0 0.502513 0.002941966 0.555539 0.002941966 0.557283 0.008048951 0.593917 0.002941966 0.558339 0.002941966 0.557283 0 0.502513 0.002941966 0.557283 0.002941966 0.558339 0.008322954 0.593917 0.008048951 0.593917 0.002941966 0.557283 0.007829964 0.593917 0.002941966 0.558692 0.002941966 0.558339 0 0.502513 0.002941966 0.558339 0.002941966 0.558692 0.007884979 0.593917 0.007829964 0.593917 0.002941966 0.558339 0.008048951 0.593917 0.007884979 0.593917 0.002941966 0.558339 0.007884979 0.593917 0.002941966 0.558339 0.002941966 0.558692 0 0.502513 0.002941966 0.558692 0.002941966 0.558339 0.007829964 0.593917 0.007884979 0.593917 0.002941966 0.558692 0.008048951 0.593917 0.002941966 0.557283 0.002941966 0.558339 0 0.502513 0.002941966 0.558339 0.002941966 0.557283 0.007884979 0.593917 0.008048951 0.593917 0.002941966 0.558339 0.01174396 0.608306 0.002941966 0.555539 0.002941966 0.557283 0 0.502513 0.002941966 0.557283 0.002941966 0.555539 0.008322954 0.593917 0.01174396 0.608306 0.002941966 0.557283 0.008048951 0.593917 0.008322954 0.593917 0.002941966 0.557283 0.01174396 0.603583 0.002941966 0.553129 0.002941966 0.555539 0 0.502513 0.002941966 0.555539 0.002941966 0.553129 0.01174396 0.608306 0.01174396 0.603583 0.002941966 0.555539 0.01174396 0.597569 0.002941966 0.550081 0.002941966 0.553129 0 0.502513 0.002941966 0.553129 0.002941966 0.550081 0.01174396 0.603583 0.01174396 0.597569 0.002941966 0.553129 0.01174396 0.59034 0.002941966 0.546436 0.002941966 0.550081 0 0.502513 0.002941966 0.550081 0.002941966 0.546436 0.01174396 0.597569 0.01174396 0.59034 0.002941966 0.550081 0.01174396 0.581989 0.002941966 0.542238 0.002941966 0.546436 0 0.502513 0.002941966 0.546436 0.002941966 0.542238 0.01174396 0.59034 0.01174396 0.581989 0.002941966 0.546436 0.01174396 0.572624 0.002941966 0.53754 0.002941966 0.542238 0 0.502513 0.002941966 0.542238 0.002941966 0.53754 0.01174396 0.581989 0.01174396 0.572624 0.002941966 0.542238 0.01174396 0.562362 0.002941966 0.532402 0.002941966 0.53754 0 0.502513 0.002941966 0.53754 0.002941966 0.532402 0.01174396 0.572624 0.01174396 0.562362 0.002941966 0.53754 0.01174396 0.551337 0.002941966 0.526888 0.002941966 0.532402 0 0.502513 0.002941966 0.532402 0.002941966 0.526888 0.01174396 0.562362 0.01174396 0.551337 0.002941966 0.532402 0.01174396 0.539687 0.002941966 0.521068 0.002941966 0.526888 0 0.502513 0.002941966 0.526888 0.002941966 0.521068 0.01174396 0.551337 0.01174396 0.539687 0.002941966 0.526888 0.01174396 0.527563 0.002941966 0.515014 0.002941966 0.521068 0 0.502513 0.002941966 0.521068 0.002941966 0.515014 0.01174396 0.539687 0.01174396 0.527563 0.002941966 0.521068 0.01174396 0.515118 0.002941966 0.508803 0.002941966 0.515014 0 0.502513 0.002941966 0.515014 0.002941966 0.508803 0.01174396 0.527563 0.01174396 0.515118 0.002941966 0.515014 0.01135295 0.502513 0.002941966 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.508803 0.002941966 0.502513 0.01174396 0.502513 0.01135295 0.502513 0.002941966 0.508803 0.01174396 0.515118 0.01174396 0.502513 0.002941966 0.508803 0.01174396 0.490006 0.002941966 0.502513 0.01135295 0.502513 0.002846956 0.502513 0 0.502513 0.002941966 0.502513 0.002941966 0.496223 0.002846956 0.502513 0.002941966 0.502513 0.002941966 0.496223 0.002941966 0.502513 0.01174396 0.490006 0.01174396 0.490006 0.01135295 0.502513 0.01174396 0.502513 0.02541399 0.502513 0.01174396 0.502513 0.01174396 0.515118 0.026295 0.483945 0.01174396 0.502513 0.02541399 0.502513 0.01174396 0.490006 0.01174396 0.502513 0.026295 0.483945 0.026295 0.538685 0.01174396 0.515118 0.01174396 0.527563 0.026295 0.520709 0.01174396 0.515118 0.026295 0.538685 0.026295 0.502513 0.01174396 0.515118 0.026295 0.520709 0.02541399 0.502513 0.01174396 0.515118 0.026295 0.502513 0.026295 0.556225 0.01174396 0.527563 0.01174396 0.539687 0.026295 0.538685 0.01174396 0.527563 0.026295 0.556225 0.026295 0.573116 0.01174396 0.539687 0.01174396 0.551337 0.026295 0.556225 0.01174396 0.539687 0.026295 0.573116 0.026295 0.589154 0.01174396 0.551337 0.01174396 0.562362 0.026295 0.573116 0.01174396 0.551337 0.026295 0.589154 0.026295 0.604146 0.01174396 0.562362 0.01174396 0.572624 0.026295 0.589154 0.01174396 0.562362 0.026295 0.604146 0.026295 0.617911 0.01174396 0.572624 0.01174396 0.581989 0.026295 0.604146 0.01174396 0.572624 0.026295 0.617911 0.026295 0.630283 0.01174396 0.581989 0.01174396 0.59034 0.026295 0.617911 0.01174396 0.581989 0.026295 0.630283 0.026295 0.641111 0.01174396 0.59034 0.01174396 0.597569 0.026295 0.630283 0.01174396 0.59034 0.026295 0.641111 0.026295 0.650266 0.01174396 0.597569 0.01174396 0.603583 0.026295 0.641111 0.01174396 0.597569 0.026295 0.650266 0.026295 0.657637 0.01174396 0.603583 0.01174396 0.608306 0.026295 0.650266 0.01174396 0.603583 0.026295 0.657637 0.008322954 0.593917 0.01156699 0.611129 0.01174396 0.608306 0.026295 0.663134 0.01174396 0.608306 0.01156699 0.611129 0.026295 0.657637 0.01174396 0.608306 0.026295 0.663134 0.03380799 0.68838 0.01156699 0.611129 0.008322954 0.593917 0.02609199 0.66606 0.01156699 0.611129 0.03380799 0.68838 0.01817697 0.639111 0.01156699 0.611129 0.02609199 0.66606 0.01817697 0.639111 0.026295 0.663134 0.01156699 0.611129 0.008322954 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.03380799 0.593917 0.008322954 0.593917 0.008322954 0.593917 0.03380799 0.593917 0.03380799 0.68838 0.008322954 0.593917 0.03380799 0.593917 0.03380799 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.007884979 0.593917 0.007829964 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.007884979 0.593917 0.002941966 0.496223 0 0.502513 0.002846956 0.502513 0.002941966 0.490012 0 0.502513 0.002941966 0.496223 0.002941966 0.483958 0 0.502513 0.002941966 0.490012 0.002941966 0.478138 0 0.502513 0.002941966 0.483958 0.002941966 0.472624 0 0.502513 0.002941966 0.478138 0.002941966 0.467486 0 0.502513 0.002941966 0.472624 0.002941966 0.462789 0 0.502513 0.002941966 0.467486 0.002941966 0.458591 0 0.502513 0.002941966 0.462789 0.002941966 0.454945 0 0.502513 0.002941966 0.458591 0.002941966 0.451898 0 0.502513 0.002941966 0.454945 0.002941966 0.449487 0 0.502513 0.002941966 0.451898 0.002941966 0.447743 0 0.502513 0.002941966 0.449487 0.002941966 0.446687 0 0.502513 0.002941966 0.447743 0.002941966 0.446334 0 0.502513 0.002941966 0.446687 0.002941966 0.446687 0 0.502513 0.002941966 0.446334 0.002941966 0.447743 0 0.502513 0.002941966 0.446687 0.002941966 0.449487 0 0.502513 0.002941966 0.447743 0.002941966 0.451898 0 0.502513 0.002941966 0.449487 0.002941966 0.454945 0 0.502513 0.002941966 0.451898 0.002941966 0.458591 0 0.502513 0.002941966 0.454945 0.002941966 0.462789 0 0.502513 0.002941966 0.458591 0.002941966 0.467486 0 0.502513 0.002941966 0.462789 0.002941966 0.472624 0 0.502513 0.002941966 0.467486 0.002941966 0.478138 0 0.502513 0.002941966 0.472624 0.002941966 0.483958 0 0.502513 0.002941966 0.478138 0.002941966 0.490012 0 0.502513 0.002941966 0.483958 0.002941966 0.496223 0 0.502513 0.002941966 0.490012 0.469011 0.502513 0.469011 0.55703 0.507956 0.502513 0.521562 0.44543 0.469011 0.502513 0.507956 0.502513 0.520866 0.873461 0.521124 0.999734 0.509391 0.999542 0.520866 0.873461 0.529869 0.873461 0.521124 0.999734 0.50904 0.873461 0.509391 0.999542 0.495215 0.999309 0.50904 0.873461 0.520866 0.873461 0.509391 0.999542 0.494872 0.873461 0.495215 0.999309 0.479343 0.999049 0.494872 0.873461 0.50904 0.873461 0.495215 0.999309 0.47908 0.873461 0.479343 0.999049 0.469055 0.99888 0.47908 0.873461 0.494872 0.873461 0.479343 0.999049 0.462654 0.998775 0.469055 0.99888 0.469012 0.987435 0.47908 0.873461 0.469055 0.99888 0.462654 0.998775 0.469011 0.445198 0.456258 0.502513 0.469011 0.502513 0.521562 0.44543 0.469011 0.445198 0.469011 0.502513 0.462456 0.873461 0.462654 0.998775 0.445986 0.998501 0.462456 0.873461 0.47908 0.873461 0.462654 0.998775 0.445823 0.873461 0.445986 0.998501 0.430159 0.998241 0.445823 0.873461 0.462456 0.873461 0.445986 0.998501 0.430024 0.873461 0.445823 0.873461 0.430159 0.998241 0.133904 0.593917 0.135784 0.711462 0.133222 0.70106 0.136866 0.593917 0.135784 0.711462 0.133904 0.593917 0.133904 0.593917 0.133222 0.70106 0.129603 0.688374 0.1174679 0.641466 0.129603 0.688374 0.123076 0.665027 0.112773 0.617746 0.129603 0.688374 0.1174679 0.641466 0.108987 0.593917 0.129603 0.688374 0.112773 0.617746 0.129603 0.593917 0.129603 0.688374 0.108987 0.593917 0.133904 0.593917 0.129603 0.688374 0.129603 0.593917 0.128408 0.593917 0.129603 0.593917 0.108987 0.593917 0.122979 0.593917 0.128408 0.593917 0.108987 0.593917 0.117053 0.593917 0.122979 0.593917 0.108987 0.593917 0.112614 0.593917 0.117053 0.593917 0.108987 0.593917 0.108369 0.593917 0.112614 0.593917 0.108987 0.593917 0.026295 0.502513 0.026295 0.520709 0.04486095 0.502513 0.04641199 0.478118 0.026295 0.502513 0.04486095 0.502513 0.03988796 0.593917 0.04290497 0.711393 0.03867197 0.701017 0.04541999 0.593917 0.04290497 0.711393 0.03988796 0.593917 0.03988796 0.593917 0.03867197 0.701017 0.03380799 0.68838 0.03988796 0.593917 0.03380799 0.68838 0.03380799 0.593917 0.01817697 0.639111 0.02609199 0.66606 0.026295 0.663134 0.026295 0.483945 0.02541399 0.502513 0.026295 0.502513 0.026295 0.483945 0.026295 0.502513 0.04641199 0.478118 0.591918 0.593917 0.638549 0.593917 0.624886 0.593917 0.794366 0.553923 0.624886 0.593917 0.638549 0.593917 0.591233 0.593917 0.632282 0.593917 0.638549 0.593917 0.632282 0.676804 0.638549 0.593917 0.632282 0.593917 0.590785 0.593917 0.591233 0.593917 0.638549 0.593917 0.591918 0.593917 0.590785 0.593917 0.638549 0.593917 0.79572 0.570943 0.794366 0.553923 0.638549 0.593917 0.635928 0.635169 0.79572 0.570943 0.638549 0.593917 0.635928 0.635169 0.638549 0.593917 0.632282 0.676804 0.593202 0.593917 0.630928 0.593917 0.632282 0.593917 0.632282 0.676804 0.632282 0.593917 0.630928 0.593917 0.591233 0.593917 0.593202 0.593917 0.632282 0.593917 0.596544 0.593917 0.629178 0.593917 0.630928 0.593917 0.630413 0.690992 0.630928 0.593917 0.629178 0.593917 0.593202 0.593917 0.596544 0.593917 0.630928 0.593917 0.632282 0.676804 0.630928 0.593917 0.630413 0.690992 0.596544 0.593917 0.627006 0.593917 0.629178 0.593917 0.6279 0.703709 0.629178 0.593917 0.627006 0.593917 0.630413 0.690992 0.629178 0.593917 0.6279 0.703709 0.601023 0.593917 0.62449 0.593917 0.627006 0.593917 0.624824 0.715193 0.627006 0.593917 0.62449 0.593917 0.596544 0.593917 0.601023 0.593917 0.627006 0.593917 0.6279 0.703709 0.627006 0.593917 0.624824 0.715193 0.601023 0.593917 0.621679 0.593917 0.62449 0.593917 0.624824 0.715193 0.62449 0.593917 0.621679 0.593917 0.606326 0.593917 0.618636 0.593917 0.621679 0.593917 0.601023 0.593917 0.606326 0.593917 0.621679 0.593917 0.606326 0.593917 0.615453 0.593917 0.618636 0.593917 0.606326 0.593917 0.6121 0.593917 0.615453 0.593917 0.896309 0.502513 0.792617 0.502513 0.792811 0.519637 0.896628 0.473634 0.792819 0.485066 0.792617 0.502513 0.896309 0.502513 0.896628 0.473634 0.792617 0.502513 0.896628 0.531392 0.792811 0.519637 0.793395 0.536821 0.896628 0.531392 0.896309 0.502513 0.792811 0.519637 0.896628 0.531392 0.793395 0.536821 0.794366 0.553923 0.897565 0.559898 0.794366 0.553923 0.79572 0.570943 0.897565 0.559898 0.896628 0.531392 0.794366 0.553923 0.635928 0.635169 0.797451 0.58783 0.79572 0.570943 0.897565 0.559898 0.79572 0.570943 0.797451 0.58783 0.635928 0.635169 0.799552 0.604573 0.797451 0.58783 0.816638 0.593917 0.797451 0.58783 0.799552 0.604573 0.899065 0.587673 0.797451 0.58783 0.816638 0.593917 0.899065 0.587673 0.897565 0.559898 0.797451 0.58783 0.632282 0.676804 0.802016 0.621149 0.799552 0.604573 0.815643 0.613145 0.799552 0.604573 0.802016 0.621149 0.635928 0.635169 0.632282 0.676804 0.799552 0.604573 0.815643 0.613145 0.816638 0.593917 0.799552 0.604573 0.6279 0.703709 0.804827 0.637482 0.802016 0.621149 0.814466 0.631592 0.802016 0.621149 0.804827 0.637482 0.630413 0.690992 0.6279 0.703709 0.802016 0.621149 0.632282 0.676804 0.630413 0.690992 0.802016 0.621149 0.814466 0.631592 0.815643 0.613145 0.802016 0.621149 0.813114 0.64918 0.804827 0.637482 0.807968 0.653536 0.6279 0.703709 0.624824 0.715193 0.804827 0.637482 0.813114 0.64918 0.814466 0.631592 0.804827 0.637482 0.811462 0.66749 0.807968 0.653536 0.811395 0.669147 0.811462 0.66749 0.811596 0.665829 0.807968 0.653536 0.813114 0.64918 0.807968 0.653536 0.811596 0.665829 0.811596 0.593917 0.811395 0.669147 0.811389 0.670394 0.811462 0.66749 0.811395 0.669147 0.811596 0.593917 0.750018 0.704868 0.811411 0.671626 0.811389 0.670394 0.811596 0.593917 0.811389 0.670394 0.811411 0.671626 0.688625 0.738111 0.750018 0.704868 0.811389 0.670394 0.812058 0.677897 0.811411 0.671626 0.750018 0.704868 0.811616 0.593917 0.811411 0.671626 0.812058 0.677897 0.811616 0.593917 0.811596 0.593917 0.811411 0.671626 0.693008 0.76114 0.750018 0.704868 0.688625 0.738111 0.754457 0.724456 0.812058 0.677897 0.750018 0.704868 0.693008 0.76114 0.754457 0.724456 0.750018 0.704868 0.623954 0.256914 0.808394 0.349452 0.81191 0.333671 0.905955 0.341434 0.81191 0.333671 0.808394 0.349452 0.750351 0.300338 0.623954 0.256914 0.81191 0.333671 0.754457 0.28057 0.750351 0.300338 0.81191 0.333671 0.81583 0.317556 0.81191 0.333671 0.905955 0.341434 0.754457 0.28057 0.81191 0.333671 0.81583 0.317556 0.621909 0.273278 0.805174 0.365671 0.808394 0.349452 0.903374 0.365251 0.808394 0.349452 0.805174 0.365671 0.623954 0.256914 0.621909 0.273278 0.808394 0.349452 0.903374 0.365251 0.905955 0.341434 0.808394 0.349452 0.617463 0.315671 0.802297 0.382139 0.805174 0.365671 0.903374 0.365251 0.805174 0.365671 0.802297 0.382139 0.621909 0.273278 0.617463 0.315671 0.805174 0.365671 0.617463 0.315671 0.799772 0.398854 0.802297 0.382139 0.901037 0.390633 0.802297 0.382139 0.799772 0.398854 0.901037 0.390633 0.903374 0.365251 0.802297 0.382139 0.613945 0.360338 0.797612 0.415792 0.799772 0.398854 0.899065 0.417353 0.799772 0.398854 0.797612 0.415792 0.617463 0.315671 0.613945 0.360338 0.799772 0.398854 0.899065 0.417353 0.901037 0.390633 0.799772 0.398854 0.6114 0.406742 0.795828 0.432908 0.797612 0.415792 0.899065 0.417353 0.797612 0.415792 0.795828 0.432908 0.613945 0.360338 0.6114 0.406742 0.797612 0.415792 0.6114 0.406742 0.794429 0.450188 0.795828 0.432908 0.897565 0.445128 0.795828 0.432908 0.794429 0.450188 0.897565 0.445128 0.899065 0.417353 0.795828 0.432908 0.609859 0.454326 0.793424 0.467575 0.794429 0.450188 0.897565 0.445128 0.794429 0.450188 0.793424 0.467575 0.6114 0.406742 0.609859 0.454326 0.794429 0.450188 0.609859 0.454326 0.792819 0.485066 0.793424 0.467575 0.896628 0.473634 0.793424 0.467575 0.792819 0.485066 0.896628 0.473634 0.897565 0.445128 0.793424 0.467575 0.573463 0.446152 0.609859 0.454326 0.6114 0.406742 0.573463 0.390538 0.6114 0.406742 0.613945 0.360338 0.573463 0.446152 0.6114 0.406742 0.573463 0.390538 0.573463 0.336408 0.613945 0.360338 0.617463 0.315671 0.573463 0.390538 0.613945 0.360338 0.573463 0.336408 0.573463 0.28448 0.617463 0.315671 0.621909 0.273278 0.573463 0.336408 0.617463 0.315671 0.573463 0.28448 0.573463 0.28448 0.621909 0.273278 0.623954 0.256914 0.688792 0.267005 0.627233 0.233672 0.623954 0.256914 0.624062 0.213328 0.623954 0.256914 0.627233 0.233672 0.750351 0.300338 0.688792 0.267005 0.623954 0.256914 0.573463 0.28448 0.623954 0.256914 0.573463 0.2354429 0.624062 0.213328 0.573463 0.2354429 0.623954 0.256914 0.63156 0.207201 0.627233 0.233672 0.688792 0.267005 0.624062 0.213328 0.627233 0.233672 0.63156 0.207201 0.693009 0.2438859 0.688792 0.267005 0.750351 0.300338 0.693009 0.2438859 0.63156 0.207201 0.688792 0.267005 0.754457 0.28057 0.693009 0.2438859 0.750351 0.300338 1 0.349198 0.905955 0.341434 0.903374 0.365251 0.910149 0.308556 0.905955 0.341434 1 0.349198 0.815905 0.317259 0.81583 0.317556 0.905955 0.341434 0.820298 0.300523 0.815905 0.317259 0.905955 0.341434 0.910149 0.308556 0.820298 0.300523 0.905955 0.341434 1 0.385273 0.903374 0.365251 0.901037 0.390633 1 0.366995 1 0.349198 0.903374 0.365251 1 0.385273 1 0.366995 0.903374 0.365251 1 0.40407 0.901037 0.390633 0.899065 0.417353 1 0.40407 1 0.385273 0.901037 0.390633 1 0.42327 0.899065 0.417353 0.897565 0.445128 1 0.42327 1 0.40407 0.899065 0.417353 1 0.462565 0.897565 0.445128 0.896628 0.473634 1 0.442796 1 0.42327 0.897565 0.445128 1 0.462565 1 0.442796 0.897565 0.445128 1 0.482458 0.896628 0.473634 0.896309 0.502513 1 0.482458 1 0.462565 0.896628 0.473634 1 0.502513 1 0.482458 0.896309 0.502513 0.896628 0.531392 1 0.502513 0.896309 0.502513 1 0.351077 1 0.349198 1 0.366995 1 0.332566 0.910149 0.308556 1 0.349198 1 0.332035 1 0.332566 1 0.349198 1 0.351077 1 0.332035 1 0.349198 1 0.370938 1 0.366995 1 0.385273 1 0.370938 1 0.351077 1 0.366995 1 0.391462 1 0.385273 1 0.40407 1 0.391462 1 0.370938 1 0.385273 1 0.412545 1 0.40407 1 0.42327 1 0.412545 1 0.391462 1 0.40407 1 0.434153 1 0.42327 1 0.442796 1 0.434153 1 0.412545 1 0.42327 1 0.456062 1 0.442796 1 0.462565 1 0.456062 1 0.434153 1 0.442796 1 0.478322 1 0.462565 1 0.482458 1 0.478322 1 0.456062 1 0.462565 1 0.500545 1 0.482458 1 0.502513 1 0.500545 1 0.478322 1 0.482458 1 0.522569 1 0.502513 0.896628 0.531392 1 0.500545 1 0.502513 1 0.522569 0.754457 0.28057 0.81583 0.317556 0.815905 0.317259 0.759019 0.261244 0.815905 0.317259 0.820298 0.300523 0.759019 0.261244 0.754457 0.28057 0.815905 0.317259 1 0.299088 0.820298 0.300523 0.910149 0.308556 0.825248 0.28348 0.759019 0.261244 0.820298 0.300523 0.825248 0.28348 0.820298 0.300523 1 0.299088 1 0.332566 1 0.316589 0.910149 0.308556 1 0.299088 0.910149 0.308556 1 0.316589 1 0.332035 1 0.316589 1 0.332566 1 0.313798 1 0.299088 1 0.316589 1 0.332035 1 0.313798 1 0.316589 0.636279 0.182569 0.63156 0.207201 0.693009 0.2438859 0.624062 0.213328 0.63156 0.207201 0.636279 0.182569 0.697618 0.221886 0.693009 0.2438859 0.754457 0.28057 0.697618 0.221886 0.636279 0.182569 0.693009 0.2438859 0.759019 0.261244 0.697618 0.221886 0.754457 0.28057 0.704674 0.193393 0.636279 0.182569 0.697618 0.221886 0.624062 0.213328 0.636279 0.182569 0.624062 0.1733 0.640054 0.1654559 0.624062 0.1733 0.636279 0.182569 0.704674 0.193393 0.640054 0.1654559 0.636279 0.182569 0.765931 0.2353529 0.697618 0.221886 0.759019 0.261244 0.765931 0.2353529 0.704674 0.193393 0.697618 0.221886 0.765931 0.2353529 0.759019 0.261244 0.825248 0.28348 0.07184296 0.472597 0.08333295 0.468165 0.08233696 0.485294 0.177636 0.479946 0.08233696 0.485294 0.08333295 0.468165 0.177636 0.479946 0.176868 0.502513 0.08233696 0.485294 0.07184296 0.443057 0.08726596 0.434374 0.08333295 0.468165 0.179884 0.457657 0.08333295 0.468165 0.08726596 0.434374 0.07184296 0.472597 0.07184296 0.443057 0.08333295 0.468165 0.179884 0.457657 0.177636 0.479946 0.08333295 0.468165 0.07184296 0.414264 0.09382796 0.400815 0.08726596 0.434374 0.183625 0.435598 0.08726596 0.434374 0.09382796 0.400815 0.07184296 0.443057 0.07184296 0.414264 0.08726596 0.434374 0.183625 0.435598 0.179884 0.457657 0.08726596 0.434374 0.07184296 0.386582 0.10216 0.370461 0.09382796 0.400815 0.18885 0.413801 0.09382796 0.400815 0.10216 0.370461 0.07184296 0.414264 0.07184296 0.386582 0.09382796 0.400815 0.18885 0.413801 0.183625 0.435598 0.09382796 0.400815 0.07184296 0.386582 0.102268 0.339397 0.10216 0.370461 0.103213 0.36715 0.10216 0.370461 0.102268 0.339397 0.18885 0.413801 0.10216 0.370461 0.103213 0.36715 0.07184296 0.360357 0.102268 0.310352 0.102268 0.339397 0.132099 0.298503 0.102268 0.339397 0.102268 0.310352 0.07184296 0.386582 0.07184296 0.360357 0.102268 0.339397 0.115783 0.333115 0.103213 0.36715 0.102268 0.339397 0.132099 0.298503 0.115783 0.333115 0.102268 0.339397 0.07184296 0.33592 0.102268 0.283748 0.102268 0.310352 0.137307 0.258698 0.102268 0.310352 0.102268 0.283748 0.07184296 0.360357 0.07184296 0.33592 0.102268 0.310352 0.136974 0.289526 0.132099 0.298503 0.102268 0.310352 0.137307 0.258698 0.136974 0.289526 0.102268 0.310352 0.07184296 0.313578 0.102268 0.259923 0.102268 0.283748 0.137307 0.2309989 0.102268 0.283748 0.102268 0.259923 0.07184296 0.33592 0.07184296 0.313578 0.102268 0.283748 0.137307 0.2309989 0.137307 0.258698 0.102268 0.283748 0.07184296 0.293612 0.102268 0.23918 0.102268 0.259923 0.137307 0.206799 0.102268 0.259923 0.102268 0.23918 0.07184296 0.313578 0.07184296 0.293612 0.102268 0.259923 0.137307 0.206799 0.137307 0.2309989 0.102268 0.259923 0.07184296 0.276273 0.102268 0.221782 0.102268 0.23918 0.137307 0.186408 0.102268 0.23918 0.102268 0.221782 0.07184296 0.293612 0.07184296 0.276273 0.102268 0.23918 0.137307 0.186408 0.137307 0.206799 0.102268 0.23918 0.07184296 0.261779 0.102268 0.207951 0.102268 0.221782 0.137307 0.170091 0.102268 0.221782 0.102268 0.207951 0.07184296 0.276273 0.07184296 0.261779 0.102268 0.221782 0.137307 0.170091 0.137307 0.186408 0.102268 0.221782 0.07184296 0.250313 0.102268 0.197861 0.102268 0.207951 0.137307 0.158057 0.102268 0.207951 0.102268 0.197861 0.07184296 0.261779 0.07184296 0.250313 0.102268 0.207951 0.137307 0.158057 0.137307 0.170091 0.102268 0.207951 0.07184296 0.242018 0.102268 0.191642 0.102268 0.197861 0.137307 0.15046 0.102268 0.197861 0.102268 0.191642 0.07184296 0.250313 0.07184296 0.242018 0.102268 0.197861 0.137307 0.15046 0.137307 0.158057 0.102268 0.197861 0.07184296 0.236999 0.102268 0.189371 0.102268 0.191642 0.137307 0.1474 0.102268 0.191642 0.102268 0.189371 0.07184296 0.242018 0.07184296 0.236999 0.102268 0.191642 0.137307 0.1474 0.137307 0.15046 0.102268 0.191642 0.07184296 0.235319 0.102268 0.191079 0.102268 0.189371 0.137307 0.1489149 0.102268 0.189371 0.102268 0.191079 0.07184296 0.236999 0.07184296 0.235319 0.102268 0.189371 0.137307 0.1489149 0.137307 0.1474 0.102268 0.189371 0.07184296 0.236999 0.102268 0.196743 0.102268 0.191079 0.137307 0.154986 0.102268 0.191079 0.102268 0.196743 0.07184296 0.235319 0.07184296 0.236999 0.102268 0.191079 0.137307 0.154986 0.137307 0.1489149 0.102268 0.191079 0.07184296 0.242018 0.102268 0.206291 0.102268 0.196743 0.137307 0.165535 0.102268 0.196743 0.102268 0.206291 0.07184296 0.236999 0.07184296 0.242018 0.102268 0.196743 0.137307 0.165535 0.137307 0.154986 0.102268 0.196743 0.07184296 0.250313 0.102268 0.219603 0.102268 0.206291 0.137307 0.180426 0.102268 0.206291 0.102268 0.219603 0.07184296 0.242018 0.07184296 0.250313 0.102268 0.206291 0.137307 0.180426 0.137307 0.165535 0.102268 0.206291 0.07184296 0.261779 0.102268 0.236508 0.102268 0.219603 0.137307 0.199466 0.102268 0.219603 0.102268 0.236508 0.07184296 0.250313 0.07184296 0.261779 0.102268 0.219603 0.137307 0.199466 0.137307 0.180426 0.102268 0.219603 0.07184296 0.276273 0.102268 0.256793 0.102268 0.236508 0.137307 0.222411 0.102268 0.236508 0.102268 0.256793 0.07184296 0.261779 0.07184296 0.276273 0.102268 0.236508 0.137307 0.222411 0.137307 0.199466 0.102268 0.236508 0.07184296 0.293612 0.102268 0.280199 0.102268 0.256793 0.137307 0.248965 0.102268 0.256793 0.102268 0.280199 0.07184296 0.276273 0.07184296 0.293612 0.102268 0.256793 0.137307 0.248965 0.137307 0.222411 0.102268 0.256793 0.07184296 0.313578 0.102268 0.30643 0.102268 0.280199 0.137307 0.278786 0.102268 0.280199 0.102268 0.30643 0.07184296 0.293612 0.07184296 0.313578 0.102268 0.280199 0.137307 0.278786 0.137307 0.248965 0.102268 0.280199 0.07184296 0.33592 0.102268 0.335151 0.102268 0.30643 0.137307 0.31149 0.102268 0.30643 0.102268 0.335151 0.07184296 0.313578 0.07184296 0.33592 0.102268 0.30643 0.137307 0.31149 0.137307 0.278786 0.102268 0.30643 0.07184296 0.360357 0.102268 0.365999 0.102268 0.335151 0.137307 0.346654 0.102268 0.335151 0.102268 0.365999 0.07184296 0.33592 0.07184296 0.360357 0.102268 0.335151 0.137307 0.346654 0.137307 0.31149 0.102268 0.335151 0.07184296 0.386582 0.102268 0.39858 0.102268 0.365999 0.137307 0.383827 0.102268 0.365999 0.102268 0.39858 0.07184296 0.360357 0.07184296 0.386582 0.102268 0.365999 0.137307 0.383827 0.137307 0.346654 0.102268 0.365999 0.07184296 0.414264 0.102268 0.432482 0.102268 0.39858 0.137307 0.422529 0.102268 0.39858 0.102268 0.432482 0.07184296 0.386582 0.07184296 0.414264 0.102268 0.39858 0.137307 0.422529 0.137307 0.383827 0.102268 0.39858 0.07184296 0.443057 0.102268 0.467274 0.102268 0.432482 0.137307 0.462262 0.102268 0.432482 0.102268 0.467274 0.07184296 0.414264 0.07184296 0.443057 0.102268 0.432482 0.137307 0.462262 0.137307 0.422529 0.102268 0.432482 0.07184296 0.443057 0.07184296 0.472597 0.102268 0.467274 0.04641199 0.478118 0.07184296 0.472597 0.07184296 0.443057 0.04641199 0.45403 0.07184296 0.443057 0.07184296 0.414264 0.04641199 0.45403 0.04641199 0.478118 0.07184296 0.443057 0.04641199 0.430551 0.07184296 0.414264 0.07184296 0.386582 0.04641199 0.430551 0.04641199 0.45403 0.07184296 0.414264 0.04641199 0.407977 0.07184296 0.386582 0.07184296 0.360357 0.04641199 0.407977 0.04641199 0.430551 0.07184296 0.386582 0.04641199 0.386592 0.07184296 0.360357 0.07184296 0.33592 0.04641199 0.386592 0.04641199 0.407977 0.07184296 0.360357 0.04641199 0.366665 0.07184296 0.33592 0.07184296 0.313578 0.04641199 0.366665 0.04641199 0.386592 0.07184296 0.33592 0.04641199 0.348447 0.07184296 0.313578 0.07184296 0.293612 0.04641199 0.348447 0.04641199 0.366665 0.07184296 0.313578 0.04641199 0.332165 0.07184296 0.293612 0.07184296 0.276273 0.04641199 0.332165 0.04641199 0.348447 0.07184296 0.293612 0.04641199 0.318026 0.07184296 0.276273 0.07184296 0.261779 0.04641199 0.318026 0.04641199 0.332165 0.07184296 0.276273 0.04641199 0.306207 0.07184296 0.261779 0.07184296 0.250313 0.04641199 0.306207 0.04641199 0.318026 0.07184296 0.261779 0.04641199 0.296857 0.07184296 0.250313 0.07184296 0.242018 0.04641199 0.296857 0.04641199 0.306207 0.07184296 0.250313 0.04641199 0.290093 0.07184296 0.242018 0.07184296 0.236999 0.04641199 0.290093 0.04641199 0.296857 0.07184296 0.242018 0.04641199 0.286 0.07184296 0.236999 0.07184296 0.235319 0.04641199 0.286 0.04641199 0.290093 0.07184296 0.236999 0.04641199 0.28463 0.07184296 0.235319 0.07184296 0.236999 0.04641199 0.28463 0.04641199 0.286 0.07184296 0.235319 0.04641199 0.286 0.07184296 0.236999 0.07184296 0.242018 0.04641199 0.286 0.04641199 0.28463 0.07184296 0.236999 0.04641199 0.290093 0.07184296 0.242018 0.07184296 0.250313 0.04641199 0.290093 0.04641199 0.286 0.07184296 0.242018 0.04641199 0.296857 0.07184296 0.250313 0.07184296 0.261779 0.04641199 0.296857 0.04641199 0.290093 0.07184296 0.250313 0.04641199 0.306207 0.07184296 0.261779 0.07184296 0.276273 0.04641199 0.306207 0.04641199 0.296857 0.07184296 0.261779 0.04641199 0.318026 0.07184296 0.276273 0.07184296 0.293612 0.04641199 0.318026 0.04641199 0.306207 0.07184296 0.276273 0.04641199 0.332165 0.07184296 0.293612 0.07184296 0.313578 0.04641199 0.332165 0.04641199 0.318026 0.07184296 0.293612 0.04641199 0.348447 0.07184296 0.313578 0.07184296 0.33592 0.04641199 0.348447 0.04641199 0.332165 0.07184296 0.313578 0.04641199 0.366665 0.07184296 0.33592 0.07184296 0.360357 0.04641199 0.366665 0.04641199 0.348447 0.07184296 0.33592 0.04641199 0.386592 0.07184296 0.360357 0.07184296 0.386582 0.04641199 0.386592 0.04641199 0.366665 0.07184296 0.360357 0.04641199 0.407977 0.07184296 0.386582 0.07184296 0.414264 0.04641199 0.407977 0.04641199 0.386592 0.07184296 0.386582 0.04641199 0.430551 0.07184296 0.414264 0.07184296 0.443057 0.04641199 0.430551 0.04641199 0.407977 0.07184296 0.414264 0.04641199 0.45403 0.07184296 0.443057 0.07184296 0.472597 0.04641199 0.45403 0.04641199 0.430551 0.07184296 0.443057 0.04641199 0.478118 0.04641199 0.45403 0.07184296 0.472597 0.1954759 0.392574 0.103213 0.36715 0.115783 0.333115 0.1954759 0.392574 0.18885 0.413801 0.103213 0.36715 0.203529 0.371874 0.115783 0.333115 0.132099 0.298503 0.203529 0.371874 0.1954759 0.392574 0.115783 0.333115 0.21288 0.351931 0.132099 0.298503 0.136974 0.289526 0.21288 0.351931 0.203529 0.371874 0.132099 0.298503 0.152923 0.263287 0.136974 0.289526 0.137307 0.258698 0.2234809 0.332846 0.136974 0.289526 0.152923 0.263287 0.2234809 0.332846 0.21288 0.351931 0.136974 0.289526 0.1764 0.231153 0.137307 0.258698 0.137307 0.2309989 0.1764 0.231153 0.152923 0.263287 0.137307 0.258698 0.176518 0.200835 0.137307 0.2309989 0.137307 0.206799 0.176518 0.200835 0.1764 0.231153 0.137307 0.2309989 0.176518 0.174342 0.137307 0.206799 0.137307 0.186408 0.176518 0.174342 0.176518 0.200835 0.137307 0.206799 0.176518 0.152055 0.137307 0.186408 0.137307 0.170091 0.176518 0.152055 0.176518 0.174342 0.137307 0.186408 0.176518 0.134261 0.137307 0.170091 0.137307 0.158057 0.176518 0.134261 0.176518 0.152055 0.137307 0.170091 0.176518 0.121187 0.137307 0.158057 0.137307 0.15046 0.176518 0.121187 0.176518 0.134261 0.137307 0.158057 0.176518 0.113003 0.137307 0.15046 0.137307 0.1474 0.176518 0.113003 0.176518 0.121187 0.137307 0.15046 0.176518 0.109811 0.137307 0.1474 0.137307 0.1489149 0.176518 0.109811 0.176518 0.113003 0.137307 0.1474 0.176518 0.111654 0.137307 0.1489149 0.137307 0.154986 0.176518 0.111654 0.176518 0.109811 0.137307 0.1489149 0.176518 0.118508 0.137307 0.154986 0.137307 0.165535 0.176518 0.118508 0.176518 0.111654 0.137307 0.154986 0.176518 0.130284 0.137307 0.165535 0.137307 0.180426 0.176518 0.130284 0.176518 0.118508 0.137307 0.165535 0.176518 0.146833 0.137307 0.180426 0.137307 0.199466 0.176518 0.146833 0.176518 0.130284 0.137307 0.180426 0.176518 0.167941 0.137307 0.199466 0.137307 0.222411 0.176518 0.167941 0.176518 0.146833 0.137307 0.199466 0.176518 0.193338 0.137307 0.222411 0.137307 0.248965 0.176518 0.193338 0.176518 0.167941 0.137307 0.222411 0.176518 0.222698 0.137307 0.248965 0.137307 0.278786 0.176518 0.222698 0.176518 0.193338 0.137307 0.248965 0.176518 0.255646 0.137307 0.278786 0.137307 0.31149 0.176518 0.255646 0.176518 0.222698 0.137307 0.278786 0.176518 0.291759 0.137307 0.31149 0.137307 0.346654 0.176518 0.291759 0.176518 0.255646 0.137307 0.31149 0.176518 0.330573 0.137307 0.346654 0.137307 0.383827 0.176518 0.330573 0.176518 0.291759 0.137307 0.346654 0.176518 0.371591 0.137307 0.383827 0.137307 0.422529 0.176518 0.371591 0.176518 0.330573 0.137307 0.383827 0.176518 0.414288 0.137307 0.422529 0.137307 0.462262 0.176518 0.414288 0.176518 0.371591 0.137307 0.422529 0.176518 0.458116 0.176518 0.414288 0.137307 0.462262 0.235328 0.314611 0.152923 0.263287 0.1764 0.231153 0.235328 0.314611 0.2234809 0.332846 0.152923 0.263287 0.178434 0.228655 0.1764 0.231153 0.176518 0.200835 0.24841 0.297265 0.1764 0.231153 0.178434 0.228655 0.24841 0.297265 0.235328 0.314611 0.1764 0.231153 0.21941 0.1554819 0.176518 0.200835 0.176518 0.174342 0.208652 0.195729 0.178434 0.228655 0.176518 0.200835 0.219151 0.18586 0.208652 0.195729 0.176518 0.200835 0.21941 0.1554819 0.219151 0.18586 0.176518 0.200835 0.21941 0.129518 0.176518 0.174342 0.176518 0.152055 0.21941 0.129518 0.21941 0.1554819 0.176518 0.174342 0.21941 0.108493 0.176518 0.152055 0.176518 0.134261 0.21941 0.108493 0.21941 0.129518 0.176518 0.152055 0.21941 0.09268498 0.176518 0.134261 0.176518 0.121187 0.21941 0.09268498 0.21941 0.108493 0.176518 0.134261 0.21941 0.082304 0.176518 0.121187 0.176518 0.113003 0.21941 0.082304 0.21941 0.09268498 0.176518 0.121187 0.21941 0.07748496 0.176518 0.113003 0.176518 0.109811 0.21941 0.07748496 0.21941 0.082304 0.176518 0.113003 0.21941 0.07829499 0.176518 0.109811 0.176518 0.111654 0.21941 0.07829499 0.21941 0.07748496 0.176518 0.109811 0.21941 0.08472096 0.176518 0.111654 0.176518 0.118508 0.21941 0.08472096 0.21941 0.07829499 0.176518 0.111654 0.21941 0.09667897 0.176518 0.118508 0.176518 0.130284 0.21941 0.09667897 0.21941 0.08472096 0.176518 0.118508 0.21941 0.11401 0.176518 0.130284 0.176518 0.146833 0.21941 0.11401 0.21941 0.09667897 0.176518 0.130284 0.21941 0.1364859 0.176518 0.146833 0.176518 0.167941 0.21941 0.1364859 0.21941 0.11401 0.176518 0.146833 0.21941 0.163807 0.176518 0.167941 0.176518 0.193338 0.21941 0.163807 0.21941 0.1364859 0.176518 0.167941 0.21941 0.195613 0.176518 0.193338 0.176518 0.222698 0.21941 0.195613 0.21941 0.163807 0.176518 0.193338 0.21941 0.231483 0.176518 0.222698 0.176518 0.255646 0.21941 0.231483 0.21941 0.195613 0.176518 0.222698 0.21941 0.270941 0.176518 0.255646 0.176518 0.291759 0.21941 0.270941 0.21941 0.231483 0.176518 0.255646 0.21941 0.313465 0.176518 0.291759 0.176518 0.330573 0.21941 0.313465 0.21941 0.270941 0.176518 0.291759 0.21941 0.358493 0.176518 0.330573 0.176518 0.371591 0.21941 0.358493 0.21941 0.313465 0.176518 0.330573 0.21941 0.405427 0.176518 0.371591 0.176518 0.414288 0.21941 0.405427 0.21941 0.358493 0.176518 0.371591 0.21941 0.453646 0.176518 0.414288 0.176518 0.458116 0.21941 0.453646 0.21941 0.405427 0.176518 0.414288 0.262704 0.280832 0.178434 0.228655 0.208652 0.195729 0.262704 0.280832 0.24841 0.297265 0.178434 0.228655 0.277977 0.265611 0.208652 0.195729 0.219151 0.18586 0.277977 0.265611 0.262704 0.280832 0.208652 0.195729 0.2433969 0.165594 0.219151 0.18586 0.21941 0.1554819 0.294268 0.251571 0.219151 0.18586 0.2433969 0.165594 0.294268 0.251571 0.277977 0.265611 0.219151 0.18586 0.265444 0.12053 0.21941 0.1554819 0.21941 0.129518 0.265201 0.149987 0.2433969 0.165594 0.21941 0.1554819 0.265444 0.12053 0.265201 0.149987 0.21941 0.1554819 0.265444 0.095676 0.21941 0.129518 0.21941 0.108493 0.265444 0.095676 0.265444 0.12053 0.21941 0.129518 0.265444 0.07596397 0.21941 0.108493 0.21941 0.09268498 0.265444 0.07596397 0.265444 0.095676 0.21941 0.108493 0.265444 0.06164395 0.21941 0.09268498 0.21941 0.082304 0.265444 0.06164395 0.265444 0.07596397 0.21941 0.09268498 0.265444 0.05289697 0.21941 0.082304 0.21941 0.07748496 0.265444 0.05289697 0.265444 0.06164395 0.21941 0.082304 0.265444 0.04983198 0.21941 0.07748496 0.21941 0.07829499 0.265444 0.04983198 0.265444 0.05289697 0.21941 0.07748496 0.265444 0.05248898 0.21941 0.07829499 0.21941 0.08472096 0.265444 0.05248898 0.265444 0.04983198 0.21941 0.07829499 0.265444 0.060835 0.21941 0.08472096 0.21941 0.09667897 0.265444 0.060835 0.265444 0.05248898 0.21941 0.08472096 0.265444 0.074763 0.21941 0.09667897 0.21941 0.11401 0.265444 0.074763 0.265444 0.060835 0.21941 0.09667897 0.265444 0.09409797 0.21941 0.11401 0.21941 0.1364859 0.265444 0.09409797 0.265444 0.074763 0.21941 0.11401 0.265444 0.118595 0.21941 0.1364859 0.21941 0.163807 0.265444 0.118595 0.265444 0.09409797 0.21941 0.1364859 0.265444 0.147944 0.21941 0.163807 0.21941 0.195613 0.265444 0.147944 0.265444 0.118595 0.21941 0.163807 0.265444 0.181776 0.21941 0.195613 0.21941 0.231483 0.265444 0.181776 0.265444 0.147944 0.21941 0.195613 0.265444 0.2196609 0.21941 0.231483 0.21941 0.270941 0.265444 0.2196609 0.265444 0.181776 0.21941 0.231483 0.265444 0.261122 0.21941 0.270941 0.21941 0.313465 0.265444 0.261122 0.265444 0.2196609 0.21941 0.270941 0.265444 0.305634 0.21941 0.313465 0.21941 0.358493 0.265444 0.305634 0.265444 0.261122 0.21941 0.313465 0.265444 0.352634 0.21941 0.358493 0.21941 0.405427 0.265444 0.352634 0.265444 0.305634 0.21941 0.358493 0.265444 0.401529 0.21941 0.405427 0.21941 0.453646 0.265444 0.401529 0.265444 0.352634 0.21941 0.405427 0.265444 0.4517 0.265444 0.401529 0.21941 0.453646 0.31139 0.238842 0.2433969 0.165594 0.265201 0.149987 0.31139 0.238842 0.294268 0.251571 0.2433969 0.165594 0.282272 0.1392779 0.265201 0.149987 0.265444 0.12053 0.31139 0.238842 0.265201 0.149987 0.282272 0.1392779 0.314043 0.09367996 0.265444 0.12053 0.265444 0.095676 0.313889 0.12255 0.282272 0.1392779 0.265444 0.12053 0.314043 0.09367996 0.313889 0.12255 0.265444 0.12053 0.314043 0.069628 0.265444 0.095676 0.265444 0.07596397 0.314043 0.069628 0.314043 0.09367996 0.265444 0.095676 0.314043 0.05087 0.265444 0.07596397 0.265444 0.06164395 0.314043 0.05087 0.314043 0.069628 0.265444 0.07596397 0.314043 0.03763699 0.265444 0.06164395 0.265444 0.05289697 0.314043 0.03763699 0.314043 0.05087 0.265444 0.06164395 0.314043 0.03008997 0.265444 0.05289697 0.265444 0.04983198 0.314043 0.03008997 0.314043 0.03763699 0.265444 0.05289697 0.314043 0.02832198 0.265444 0.04983198 0.265444 0.05248898 0.314043 0.02832198 0.314043 0.03008997 0.265444 0.04983198 0.314043 0.03235495 0.265444 0.05248898 0.265444 0.060835 0.314043 0.03235495 0.314043 0.02832198 0.265444 0.05248898 0.314043 0.04213798 0.265444 0.060835 0.265444 0.074763 0.314043 0.04213798 0.314043 0.03235495 0.265444 0.060835 0.314043 0.05755299 0.265444 0.074763 0.265444 0.09409797 0.314043 0.05755299 0.314043 0.04213798 0.265444 0.074763 0.314043 0.07841098 0.265444 0.09409797 0.265444 0.118595 0.314043 0.07841098 0.314043 0.05755299 0.265444 0.09409797 0.314043 0.104456 0.265444 0.118595 0.265444 0.147944 0.314043 0.104456 0.314043 0.07841098 0.265444 0.118595 0.314043 0.135371 0.265444 0.147944 0.265444 0.181776 0.314043 0.135371 0.314043 0.104456 0.265444 0.147944 0.314043 0.170776 0.265444 0.181776 0.265444 0.2196609 0.314043 0.170776 0.314043 0.135371 0.265444 0.181776 0.314043 0.2102389 0.265444 0.2196609 0.265444 0.261122 0.314043 0.2102389 0.314043 0.170776 0.265444 0.2196609 0.314043 0.253278 0.265444 0.261122 0.265444 0.305634 0.314043 0.253278 0.314043 0.2102389 0.265444 0.261122 0.314043 0.299365 0.265444 0.305634 0.265444 0.352634 0.314043 0.299365 0.314043 0.253278 0.265444 0.305634 0.314043 0.347937 0.265444 0.352634 0.265444 0.401529 0.314043 0.347937 0.314043 0.299365 0.265444 0.352634 0.314043 0.3984 0.265444 0.401529 0.265444 0.4517 0.314043 0.3984 0.314043 0.347937 0.265444 0.401529 0.314043 0.450136 0.314043 0.3984 0.265444 0.4517 0.329326 0.227455 0.282272 0.1392779 0.313889 0.12255 0.329326 0.227455 0.31139 0.238842 0.282272 0.1392779 0.324664 0.117693 0.313889 0.12255 0.314043 0.09367996 0.347971 0.217454 0.313889 0.12255 0.324664 0.117693 0.347971 0.217454 0.329326 0.227455 0.313889 0.12255 0.364596 0.07322597 0.314043 0.09367996 0.314043 0.069628 0.364535 0.103118 0.324664 0.117693 0.314043 0.09367996 0.364596 0.07322597 0.364535 0.103118 0.314043 0.09367996 0.364596 0.04892295 0.314043 0.069628 0.314043 0.05087 0.364596 0.04892295 0.364596 0.07322597 0.314043 0.069628 0.364596 0.03063297 0.314043 0.05087 0.314043 0.03763699 0.364596 0.03063297 0.364596 0.04892295 0.314043 0.05087 0.364596 0.01859998 0.314043 0.03763699 0.314043 0.03008997 0.364596 0.01859998 0.364596 0.03063297 0.314043 0.03763699 0.364596 0.01298296 0.314043 0.03008997 0.314043 0.02832198 0.364596 0.01298296 0.364596 0.01859998 0.314043 0.03008997 0.364596 0.01385599 0.314043 0.02832198 0.314043 0.03235495 0.364596 0.01385599 0.364596 0.01298296 0.314043 0.02832198 0.364596 0.02120798 0.314043 0.03235495 0.314043 0.04213798 0.364596 0.02120798 0.364596 0.01385599 0.314043 0.03235495 0.364596 0.03494095 0.314043 0.04213798 0.314043 0.05755299 0.364596 0.03494095 0.364596 0.02120798 0.314043 0.04213798 0.364596 0.054874 0.314043 0.05755299 0.314043 0.07841098 0.364596 0.054874 0.364596 0.03494095 0.314043 0.05755299 0.364596 0.08074098 0.314043 0.07841098 0.314043 0.104456 0.364596 0.08074098 0.364596 0.054874 0.314043 0.07841098 0.364596 0.112201 0.314043 0.104456 0.314043 0.135371 0.364596 0.112201 0.364596 0.08074098 0.314043 0.104456 0.364596 0.148835 0.314043 0.135371 0.314043 0.170776 0.364596 0.148835 0.364596 0.112201 0.314043 0.135371 0.364596 0.190159 0.314043 0.170776 0.314043 0.2102389 0.364596 0.190159 0.364596 0.148835 0.314043 0.170776 0.364596 0.235624 0.314043 0.2102389 0.314043 0.253278 0.364596 0.235624 0.364596 0.190159 0.314043 0.2102389 0.364596 0.284627 0.314043 0.253278 0.314043 0.299365 0.364596 0.284627 0.364596 0.235624 0.314043 0.253278 0.364596 0.33652 0.314043 0.299365 0.314043 0.347937 0.364596 0.33652 0.364596 0.284627 0.314043 0.299365 0.364596 0.390613 0.314043 0.347937 0.314043 0.3984 0.364596 0.390613 0.364596 0.33652 0.314043 0.347937 0.364596 0.44619 0.314043 0.3984 0.314043 0.450136 0.364596 0.44619 0.364596 0.390613 0.314043 0.3984 0.367186 0.208925 0.324664 0.117693 0.364535 0.103118 0.367186 0.208925 0.347971 0.217454 0.324664 0.117693 0.36979 0.101575 0.364535 0.103118 0.364596 0.07322597 0.386977 0.201854 0.364535 0.103118 0.36979 0.101575 0.386977 0.201854 0.367186 0.208925 0.364535 0.103118 0.416469 0.06176096 0.364596 0.07322597 0.364596 0.04892295 0.41647 0.09148496 0.36979 0.101575 0.364596 0.07322597 0.416469 0.06176096 0.41647 0.09148496 0.364596 0.07322597 0.416469 0.03780394 0.364596 0.04892295 0.364596 0.03063297 0.416469 0.03780394 0.416469 0.06176096 0.364596 0.04892295 0.416469 0.01993095 0.364596 0.03063297 0.364596 0.01859998 0.416469 0.01993095 0.416469 0.03780394 0.364596 0.03063297 0.416469 0.008375942 0.364596 0.01859998 0.364596 0.01298296 0.416469 0.008375942 0.416469 0.01993095 0.364596 0.01859998 0.416469 0.003288984 0.364596 0.01298296 0.364596 0.01385599 0.416469 0.003288984 0.416469 0.008375942 0.364596 0.01298296 0.416469 0.004736959 0.364596 0.01385599 0.364596 0.02120798 0.416469 0.004736959 0.416469 0.003288984 0.364596 0.01385599 0.416469 0.01270198 0.364596 0.02120798 0.364596 0.03494095 0.416469 0.01270198 0.416469 0.004736959 0.364596 0.02120798 0.416469 0.02707898 0.364596 0.03494095 0.364596 0.054874 0.416469 0.02707898 0.416469 0.01270198 0.364596 0.03494095 0.416469 0.04767894 0.364596 0.054874 0.364596 0.08074098 0.416469 0.04767894 0.416469 0.02707898 0.364596 0.054874 0.416469 0.074234 0.364596 0.08074098 0.364596 0.112201 0.416469 0.074234 0.416469 0.04767894 0.364596 0.08074098 0.416469 0.106395 0.364596 0.112201 0.364596 0.148835 0.416469 0.106395 0.416469 0.074234 0.364596 0.112201 0.416469 0.143742 0.364596 0.148835 0.364596 0.190159 0.416469 0.143742 0.416469 0.106395 0.364596 0.148835 0.416469 0.1857849 0.364596 0.190159 0.364596 0.235624 0.416469 0.1857849 0.416469 0.143742 0.364596 0.190159 0.416469 0.231975 0.364596 0.235624 0.364596 0.284627 0.416469 0.231975 0.416469 0.1857849 0.364596 0.235624 0.416469 0.281706 0.364596 0.284627 0.364596 0.33652 0.416469 0.281706 0.416469 0.231975 0.364596 0.284627 0.416469 0.334328 0.364596 0.33652 0.364596 0.390613 0.416469 0.334328 0.416469 0.281706 0.364596 0.33652 0.416469 0.389151 0.364596 0.390613 0.364596 0.44619 0.416469 0.389151 0.416469 0.334328 0.364596 0.390613 0.416469 0.445459 0.416469 0.389151 0.364596 0.44619 0.407116 0.196327 0.36979 0.101575 0.41647 0.09148496 0.407116 0.196327 0.386977 0.201854 0.36979 0.101575 0.46459 0.08758598 0.41647 0.09148496 0.416469 0.06176096 0.448343 0.189913 0.41647 0.09148496 0.46459 0.08758598 0.427649 0.192333 0.407116 0.196327 0.41647 0.09148496 0.448343 0.189913 0.427649 0.192333 0.41647 0.09148496 0.469011 0.05796897 0.416469 0.06176096 0.416469 0.03780394 0.469017 0.08754998 0.46459 0.08758598 0.416469 0.06176096 0.469011 0.05796897 0.469017 0.08754998 0.416469 0.06176096 0.469011 0.03410297 0.416469 0.03780394 0.416469 0.01993095 0.469011 0.03410297 0.469011 0.05796897 0.416469 0.03780394 0.469011 0.01634597 0.416469 0.01993095 0.416469 0.008375942 0.469011 0.01634597 0.469011 0.03410297 0.416469 0.01993095 0.469011 0.004927992 0.416469 0.008375942 0.416469 0.003288984 0.469011 0.004927992 0.469011 0.01634597 0.416469 0.008375942 0.469011 0 0.416469 0.003288984 0.416469 0.004736959 0.469011 0 0.469011 0.004927992 0.416469 0.003288984 0.469011 0.001624941 0.416469 0.004736959 0.416469 0.01270198 0.469011 0.001624941 0.469011 0 0.416469 0.004736959 0.469011 0.009781956 0.416469 0.01270198 0.416469 0.02707898 0.469011 0.009781956 0.469011 0.001624941 0.416469 0.01270198 0.469011 0.02436399 0.416469 0.02707898 0.416469 0.04767894 0.469011 0.02436399 0.469011 0.009781956 0.416469 0.02707898 0.469011 0.04518198 0.416469 0.04767894 0.416469 0.074234 0.469011 0.04518198 0.469011 0.02436399 0.416469 0.04767894 0.469011 0.07196396 0.416469 0.074234 0.416469 0.106395 0.469011 0.07196396 0.469011 0.04518198 0.416469 0.074234 0.469011 0.10436 0.416469 0.106395 0.416469 0.143742 0.469011 0.10436 0.469011 0.07196396 0.416469 0.106395 0.469011 0.1419489 0.416469 0.143742 0.416469 0.1857849 0.469011 0.1419489 0.469011 0.10436 0.416469 0.143742 0.469011 0.18424 0.416469 0.1857849 0.416469 0.231975 0.469011 0.18424 0.469011 0.1419489 0.416469 0.1857849 0.469011 0.230681 0.416469 0.231975 0.416469 0.281706 0.469011 0.230681 0.469011 0.18424 0.416469 0.231975 0.469011 0.280668 0.416469 0.281706 0.416469 0.334328 0.469011 0.280668 0.469011 0.230681 0.416469 0.281706 0.469011 0.333547 0.416469 0.334328 0.416469 0.389151 0.469011 0.333547 0.469011 0.280668 0.416469 0.334328 0.469011 0.38863 0.416469 0.389151 0.416469 0.445459 0.469011 0.38863 0.469011 0.333547 0.416469 0.389151 0.469011 0.445198 0.469011 0.38863 0.416469 0.445459 0.469192 0.189079 0.46459 0.08758598 0.469017 0.08754998 0.469192 0.189079 0.448343 0.189913 0.46459 0.08758598 0.521562 0.06167697 0.469017 0.08754998 0.469011 0.05796897 0.521562 0.06167697 0.512554 0.09008496 0.469017 0.08754998 0.490055 0.189828 0.469017 0.08754998 0.512554 0.09008496 0.490055 0.189828 0.469192 0.189079 0.469017 0.08754998 0.521562 0.03769296 0.469011 0.05796897 0.469011 0.03410297 0.521562 0.03769296 0.521562 0.06167697 0.469011 0.05796897 0.521562 0.01979595 0.469011 0.03410297 0.469011 0.01634597 0.521562 0.01979595 0.521562 0.03769296 0.469011 0.03410297 0.521562 0.008218944 0.469011 0.01634597 0.469011 0.004927992 0.521562 0.008218944 0.521562 0.01979595 0.469011 0.01634597 0.521562 0.003115952 0.469011 0.004927992 0.469011 0 0.521562 0.003115952 0.521562 0.008218944 0.469011 0.004927992 0.521562 0.004550993 0.469011 0 0.469011 0.001624941 0.521562 0.004550993 0.521562 0.003115952 0.469011 0 0.521562 0.01250797 0.469011 0.001624941 0.469011 0.009781956 0.521562 0.01250797 0.521562 0.004550993 0.469011 0.001624941 0.521562 0.02688097 0.469011 0.009781956 0.469011 0.02436399 0.521562 0.02688097 0.521562 0.01250797 0.469011 0.009781956 0.521562 0.04748195 0.469011 0.02436399 0.469011 0.04518198 0.521562 0.04748195 0.521562 0.02688097 0.469011 0.02436399 0.521562 0.07404196 0.469011 0.04518198 0.469011 0.07196396 0.521562 0.07404196 0.521562 0.04748195 0.469011 0.04518198 0.521562 0.106213 0.469011 0.07196396 0.469011 0.10436 0.521562 0.106213 0.521562 0.07404196 0.469011 0.07196396 0.521562 0.143573 0.469011 0.10436 0.469011 0.1419489 0.521562 0.143573 0.521562 0.106213 0.469011 0.10436 0.521562 0.185633 0.469011 0.1419489 0.469011 0.18424 0.521562 0.185633 0.521562 0.143573 0.469011 0.1419489 0.521562 0.2318429 0.469011 0.18424 0.469011 0.230681 0.521562 0.2318429 0.521562 0.185633 0.469011 0.18424 0.521562 0.281597 0.469011 0.230681 0.469011 0.280668 0.521562 0.281597 0.521562 0.2318429 0.469011 0.230681 0.521562 0.334244 0.469011 0.280668 0.469011 0.333547 0.521562 0.334244 0.521562 0.281597 0.469011 0.280668 0.521562 0.389094 0.469011 0.333547 0.469011 0.38863 0.521562 0.389094 0.521562 0.334244 0.469011 0.333547 0.521562 0.44543 0.469011 0.38863 0.469011 0.445198 0.521562 0.44543 0.521562 0.389094 0.469011 0.38863 0.521562 0.06167697 0.521583 0.091273 0.512554 0.09008496 0.490055 0.189828 0.512554 0.09008496 0.521583 0.091273 0.573463 0.07289397 0.521583 0.091273 0.521562 0.06167697 0.573463 0.07289397 0.559955 0.09893399 0.521583 0.091273 0.510792 0.192171 0.521583 0.091273 0.559955 0.09893399 0.510792 0.192171 0.490055 0.189828 0.521583 0.091273 0.573463 0.04857999 0.521562 0.06167697 0.521562 0.03769296 0.573463 0.04857999 0.573463 0.07289397 0.521562 0.06167697 0.573463 0.03028297 0.521562 0.03769296 0.521562 0.01979595 0.573463 0.03028297 0.573463 0.04857999 0.521562 0.03769296 0.573463 0.01824599 0.521562 0.01979595 0.521562 0.008218944 0.573463 0.01824599 0.573463 0.03028297 0.521562 0.01979595 0.573463 0.01262897 0.521562 0.008218944 0.521562 0.003115952 0.573463 0.01262897 0.573463 0.01824599 0.521562 0.008218944 0.573463 0.01350694 0.521562 0.003115952 0.521562 0.004550993 0.573463 0.01350694 0.573463 0.01262897 0.521562 0.003115952 0.573463 0.020868 0.521562 0.004550993 0.521562 0.01250797 0.573463 0.020868 0.573463 0.01350694 0.521562 0.004550993 0.573463 0.03461396 0.521562 0.01250797 0.521562 0.02688097 0.573463 0.03461396 0.573463 0.020868 0.521562 0.01250797 0.573463 0.05456298 0.521562 0.02688097 0.521562 0.04748195 0.573463 0.05456298 0.573463 0.03461396 0.521562 0.02688097 0.573463 0.08045095 0.521562 0.04748195 0.521562 0.07404196 0.573463 0.08045095 0.573463 0.05456298 0.521562 0.04748195 0.573463 0.111933 0.521562 0.07404196 0.521562 0.106213 0.573463 0.111933 0.573463 0.08045095 0.521562 0.07404196 0.573463 0.148594 0.521562 0.106213 0.521562 0.143573 0.573463 0.148594 0.573463 0.111933 0.521562 0.106213 0.573463 0.189947 0.521562 0.143573 0.521562 0.185633 0.573463 0.189947 0.573463 0.148594 0.521562 0.143573 0.573463 0.2354429 0.521562 0.185633 0.521562 0.2318429 0.573463 0.2354429 0.573463 0.189947 0.521562 0.185633 0.573463 0.28448 0.521562 0.2318429 0.521562 0.281597 0.573463 0.28448 0.573463 0.2354429 0.521562 0.2318429 0.573463 0.336408 0.521562 0.281597 0.521562 0.334244 0.573463 0.336408 0.573463 0.28448 0.521562 0.281597 0.573463 0.390538 0.521562 0.334244 0.521562 0.389094 0.573463 0.390538 0.573463 0.336408 0.521562 0.334244 0.573463 0.446152 0.521562 0.389094 0.521562 0.44543 0.573463 0.446152 0.573463 0.390538 0.521562 0.389094 0.573463 0.07289397 0.57351 0.102682 0.559955 0.09893399 0.531396 0.196096 0.559955 0.09893399 0.57351 0.102682 0.531396 0.196096 0.510792 0.192171 0.559955 0.09893399 0.624062 0.09294098 0.57351 0.102682 0.573463 0.07289397 0.624062 0.09294098 0.606009 0.114015 0.57351 0.102682 0.551631 0.201575 0.57351 0.102682 0.606009 0.114015 0.551631 0.201575 0.531396 0.196096 0.57351 0.102682 0.624062 0.06880098 0.573463 0.07289397 0.573463 0.04857999 0.624062 0.06880098 0.624062 0.09294098 0.573463 0.07289397 0.624062 0.05002397 0.573463 0.04857999 0.573463 0.03028297 0.624062 0.05002397 0.624062 0.06880098 0.573463 0.04857999 0.624062 0.03684198 0.573463 0.03028297 0.573463 0.01824599 0.624062 0.03684198 0.624062 0.05002397 0.573463 0.03028297 0.624062 0.02941995 0.573463 0.01824599 0.573463 0.01262897 0.624062 0.02941995 0.624062 0.03684198 0.573463 0.01824599 0.624062 0.027848 0.573463 0.01262897 0.573463 0.01350694 0.624062 0.027848 0.624062 0.02941995 0.573463 0.01262897 0.624062 0.03214496 0.573463 0.01350694 0.573463 0.020868 0.624062 0.03214496 0.624062 0.027848 0.573463 0.01350694 0.624062 0.04225999 0.573463 0.020868 0.573463 0.03461396 0.624062 0.04225999 0.624062 0.03214496 0.573463 0.020868 0.624062 0.05806595 0.573463 0.03461396 0.573463 0.05456298 0.624062 0.05806595 0.624062 0.04225999 0.573463 0.03461396 0.624062 0.079369 0.573463 0.05456298 0.573463 0.08045095 0.624062 0.079369 0.624062 0.05806595 0.573463 0.05456298 0.624062 0.105904 0.573463 0.08045095 0.573463 0.111933 0.624062 0.105904 0.624062 0.079369 0.573463 0.08045095 0.624062 0.137345 0.573463 0.111933 0.573463 0.148594 0.624062 0.137345 0.624062 0.105904 0.573463 0.111933 0.624062 0.1733 0.573463 0.148594 0.573463 0.189947 0.624062 0.1733 0.624062 0.137345 0.573463 0.148594 0.624062 0.213328 0.573463 0.189947 0.573463 0.2354429 0.624062 0.213328 0.624062 0.1733 0.573463 0.189947 0.624062 0.09294098 0.624173 0.121877 0.606009 0.114015 0.571543 0.208617 0.606009 0.114015 0.624173 0.121877 0.571543 0.208617 0.551631 0.201575 0.606009 0.114015 0.672724 0.118915 0.624173 0.121877 0.624062 0.09294098 0.672724 0.118915 0.649875 0.13504 0.624173 0.121877 0.590891 0.2171429 0.624173 0.121877 0.649875 0.13504 0.590891 0.2171429 0.571543 0.208617 0.624173 0.121877 0.672724 0.09359097 0.624062 0.09294098 0.624062 0.06880098 0.672724 0.09359097 0.672724 0.118915 0.624062 0.09294098 0.672724 0.073731 0.624062 0.06880098 0.624062 0.05002397 0.672724 0.073731 0.672724 0.09359097 0.624062 0.06880098 0.672724 0.05959999 0.624062 0.05002397 0.624062 0.03684198 0.672724 0.05959999 0.672724 0.073731 0.624062 0.05002397 0.672724 0.05138695 0.624062 0.03684198 0.624062 0.02941995 0.672724 0.05138695 0.672724 0.05959999 0.624062 0.03684198 0.672724 0.04920095 0.624062 0.02941995 0.624062 0.027848 0.672724 0.04920095 0.672724 0.05138695 0.624062 0.02941995 0.672724 0.05307096 0.624062 0.027848 0.624062 0.03214496 0.672724 0.05307096 0.672724 0.04920095 0.624062 0.027848 0.672724 0.06294697 0.624062 0.03214496 0.624062 0.04225999 0.672724 0.06294697 0.672724 0.05307096 0.624062 0.03214496 0.672724 0.06294697 0.624062 0.04225999 0.624062 0.05806595 0.672698 0.07869499 0.624062 0.05806595 0.624062 0.079369 0.672698 0.07869499 0.672724 0.06294697 0.624062 0.05806595 0.661396 0.098576 0.624062 0.079369 0.624062 0.105904 0.670826 0.08136296 0.672698 0.07869499 0.624062 0.079369 0.66606 0.08925199 0.670826 0.08136296 0.624062 0.079369 0.661396 0.098576 0.66606 0.08925199 0.624062 0.079369 0.652412 0.121392 0.624062 0.105904 0.624062 0.137345 0.656835 0.109297 0.661396 0.098576 0.624062 0.105904 0.652412 0.121392 0.656835 0.109297 0.624062 0.105904 0.644001 0.149514 0.624062 0.137345 0.624062 0.1733 0.648123 0.134808 0.652412 0.121392 0.624062 0.137345 0.644001 0.149514 0.648123 0.134808 0.624062 0.137345 0.640054 0.1654559 0.644001 0.149514 0.624062 0.1733 0.672724 0.118915 0.672887 0.149052 0.649875 0.13504 0.60968 0.2271659 0.649875 0.13504 0.672887 0.149052 0.60968 0.2271659 0.590891 0.2171429 0.649875 0.13504 0.718839 0.155048 0.672887 0.149052 0.672724 0.118915 0.718839 0.155048 0.690835 0.161611 0.672887 0.149052 0.62776 0.2386 0.672887 0.149052 0.690835 0.161611 0.62776 0.2386 0.60968 0.2271659 0.672887 0.149052 0.718839 0.129548 0.672724 0.118915 0.672724 0.09359097 0.718839 0.129548 0.718839 0.155048 0.672724 0.118915 0.718839 0.108757 0.672724 0.09359097 0.672724 0.073731 0.718839 0.108757 0.718839 0.129548 0.672724 0.09359097 0.718839 0.09293699 0.672724 0.073731 0.672724 0.05959999 0.718839 0.09293699 0.718839 0.108757 0.672724 0.073731 0.718845 0.08228898 0.672724 0.05959999 0.672724 0.05138695 0.718845 0.08228898 0.718839 0.09293699 0.672724 0.05959999 0.710349 0.07168 0.672724 0.05138695 0.672724 0.04920095 0.715306 0.077286 0.718845 0.08228898 0.672724 0.05138695 0.710349 0.07168 0.715306 0.077286 0.672724 0.05138695 0.700467 0.06511598 0.672724 0.04920095 0.672724 0.05307096 0.705418 0.067649 0.710349 0.07168 0.672724 0.04920095 0.700467 0.06511598 0.705418 0.067649 0.672724 0.04920095 0.690497 0.064538 0.672724 0.05307096 0.672724 0.06294697 0.695491 0.06407898 0.700467 0.06511598 0.672724 0.05307096 0.690497 0.064538 0.695491 0.06407898 0.672724 0.05307096 0.680571 0.06997096 0.672724 0.06294697 0.672698 0.07869499 0.685525 0.06650799 0.690497 0.064538 0.672724 0.06294697 0.680571 0.06997096 0.685525 0.06650799 0.672724 0.06294697 0.736859 0.116113 0.672698 0.07869499 0.670826 0.08136296 0.736859 0.116113 0.680571 0.06997096 0.672698 0.07869499 0.728491 0.129417 0.670826 0.08136296 0.66606 0.08925199 0.728491 0.129417 0.736859 0.116113 0.670826 0.08136296 0.728491 0.129417 0.66606 0.08925199 0.661396 0.098576 0.72024 0.14689 0.661396 0.098576 0.656835 0.109297 0.72024 0.14689 0.728491 0.129417 0.661396 0.098576 0.72024 0.14689 0.656835 0.109297 0.652412 0.121392 0.712256 0.168301 0.652412 0.121392 0.648123 0.134808 0.712256 0.168301 0.72024 0.14689 0.652412 0.121392 0.712256 0.168301 0.648123 0.134808 0.644001 0.149514 0.704674 0.193393 0.644001 0.149514 0.640054 0.1654559 0.704674 0.193393 0.712256 0.168301 0.644001 0.149514 0.718839 0.155048 0.719071 0.184704 0.690835 0.161611 0.645017 0.251398 0.690835 0.161611 0.719071 0.184704 0.645017 0.251398 0.62776 0.2386 0.690835 0.161611 0.754333 0.190326 0.719071 0.184704 0.718839 0.155048 0.757788 0.2089689 0.728136 0.193109 0.719071 0.184704 0.661432 0.265526 0.719071 0.184704 0.728136 0.193109 0.754333 0.190326 0.757788 0.2089689 0.719071 0.184704 0.661432 0.265526 0.645017 0.251398 0.719071 0.184704 0.750668 0.172748 0.718839 0.155048 0.718839 0.129548 0.750668 0.172748 0.754333 0.190326 0.718839 0.155048 0.742735 0.141025 0.718839 0.129548 0.718839 0.108757 0.746788 0.156288 0.750668 0.172748 0.718839 0.129548 0.742735 0.141025 0.746788 0.156288 0.718839 0.129548 0.734111 0.114279 0.718839 0.108757 0.718839 0.09293699 0.738502 0.127003 0.742735 0.141025 0.718839 0.108757 0.734111 0.114279 0.738502 0.127003 0.718839 0.108757 0.724921 0.09292 0.718839 0.09293699 0.718845 0.08228898 0.729586 0.102907 0.734111 0.114279 0.718839 0.09293699 0.724921 0.09292 0.729586 0.102907 0.718839 0.09293699 0.774461 0.118588 0.718845 0.08228898 0.715306 0.077286 0.720161 0.08437097 0.724921 0.09292 0.718845 0.08228898 0.774461 0.118588 0.720161 0.08437097 0.718845 0.08228898 0.768104 0.1084 0.715306 0.077286 0.710349 0.07168 0.768104 0.1084 0.774461 0.118588 0.715306 0.077286 0.760989 0.103177 0.710349 0.07168 0.705418 0.067649 0.760989 0.103177 0.768104 0.1084 0.710349 0.07168 0.760989 0.103177 0.705418 0.067649 0.700467 0.06511598 0.753288 0.102818 0.700467 0.06511598 0.695491 0.06407898 0.753288 0.102818 0.760989 0.103177 0.700467 0.06511598 0.753288 0.102818 0.695491 0.06407898 0.690497 0.064538 0.745183 0.107184 0.690497 0.064538 0.685525 0.06650799 0.745183 0.107184 0.753288 0.102818 0.690497 0.064538 0.745183 0.107184 0.685525 0.06650799 0.680571 0.06997096 0.736859 0.116113 0.745183 0.107184 0.680571 0.06997096 0.757788 0.2089689 0.761044 0.228627 0.728136 0.193109 0.676806 0.280841 0.728136 0.193109 0.761044 0.228627 0.676806 0.280841 0.661432 0.265526 0.728136 0.193109 0.792162 0.242654 0.761044 0.228627 0.757788 0.2089689 0.691181 0.297378 0.676806 0.280841 0.761044 0.228627 0.782695 0.261627 0.691181 0.297378 0.761044 0.228627 0.792162 0.242654 0.782695 0.261627 0.761044 0.228627 0.790434 0.208712 0.757788 0.2089689 0.754333 0.190326 0.790434 0.208712 0.792162 0.242654 0.757788 0.2089689 0.790434 0.208712 0.754333 0.190326 0.750668 0.172748 0.787889 0.1790339 0.750668 0.172748 0.746788 0.156288 0.787889 0.1790339 0.790434 0.208712 0.750668 0.172748 0.787889 0.1790339 0.746788 0.156288 0.742735 0.141025 0.784405 0.15398 0.742735 0.141025 0.738502 0.127003 0.784405 0.15398 0.787889 0.1790339 0.742735 0.141025 0.784405 0.15398 0.738502 0.127003 0.734111 0.114279 0.779923 0.13379 0.734111 0.114279 0.729586 0.102907 0.779923 0.13379 0.784405 0.15398 0.734111 0.114279 0.779923 0.13379 0.729586 0.102907 0.724921 0.09292 0.774461 0.118588 0.724921 0.09292 0.720161 0.08437097 0.774461 0.118588 0.779923 0.13379 0.724921 0.09292 0.026295 0.483945 0.04641199 0.478118 0.04641199 0.45403 0.026295 0.465611 0.04641199 0.45403 0.04641199 0.430551 0.026295 0.465611 0.026295 0.483945 0.04641199 0.45403 0.026295 0.447741 0.04641199 0.430551 0.04641199 0.407977 0.026295 0.447741 0.026295 0.465611 0.04641199 0.430551 0.026295 0.430559 0.04641199 0.407977 0.04641199 0.386592 0.026295 0.430559 0.026295 0.447741 0.04641199 0.407977 0.026295 0.414283 0.04641199 0.386592 0.04641199 0.366665 0.026295 0.414283 0.026295 0.430559 0.04641199 0.386592 0.026295 0.399116 0.04641199 0.366665 0.04641199 0.348447 0.026295 0.399116 0.026295 0.414283 0.04641199 0.366665 0.026295 0.385249 0.04641199 0.348447 0.04641199 0.332165 0.026295 0.385249 0.026295 0.399116 0.04641199 0.348447 0.026295 0.372857 0.04641199 0.332165 0.04641199 0.318026 0.026295 0.372857 0.026295 0.385249 0.04641199 0.332165 0.026295 0.362095 0.04641199 0.318026 0.04641199 0.306207 0.026295 0.362095 0.026295 0.372857 0.04641199 0.318026 0.026295 0.353099 0.04641199 0.306207 0.04641199 0.296857 0.026295 0.353099 0.026295 0.362095 0.04641199 0.306207 0.026295 0.345982 0.04641199 0.296857 0.04641199 0.290093 0.026295 0.345982 0.026295 0.353099 0.04641199 0.296857 0.026295 0.340834 0.04641199 0.290093 0.04641199 0.286 0.026295 0.340834 0.026295 0.345982 0.04641199 0.290093 0.026295 0.337719 0.04641199 0.286 0.04641199 0.28463 0.026295 0.337719 0.026295 0.340834 0.04641199 0.286 0.026295 0.336676 0.04641199 0.28463 0.04641199 0.286 0.026295 0.336676 0.026295 0.337719 0.04641199 0.28463 0.026295 0.337719 0.04641199 0.286 0.04641199 0.290093 0.026295 0.337719 0.026295 0.336676 0.04641199 0.286 0.026295 0.340834 0.04641199 0.290093 0.04641199 0.296857 0.026295 0.340834 0.026295 0.337719 0.04641199 0.290093 0.026295 0.345982 0.04641199 0.296857 0.04641199 0.306207 0.026295 0.345982 0.026295 0.340834 0.04641199 0.296857 0.026295 0.353099 0.04641199 0.306207 0.04641199 0.318026 0.026295 0.353099 0.026295 0.345982 0.04641199 0.306207 0.026295 0.362095 0.04641199 0.318026 0.04641199 0.332165 0.026295 0.362095 0.026295 0.353099 0.04641199 0.318026 0.026295 0.372857 0.04641199 0.332165 0.04641199 0.348447 0.026295 0.372857 0.026295 0.362095 0.04641199 0.332165 0.026295 0.385249 0.04641199 0.348447 0.04641199 0.366665 0.026295 0.385249 0.026295 0.372857 0.04641199 0.348447 0.026295 0.399116 0.04641199 0.366665 0.04641199 0.386592 0.026295 0.399116 0.026295 0.385249 0.04641199 0.366665 0.026295 0.414283 0.04641199 0.386592 0.04641199 0.407977 0.026295 0.414283 0.026295 0.399116 0.04641199 0.386592 0.026295 0.430559 0.04641199 0.407977 0.04641199 0.430551 0.026295 0.430559 0.026295 0.414283 0.04641199 0.407977 0.026295 0.447741 0.04641199 0.430551 0.04641199 0.45403 0.026295 0.447741 0.026295 0.430559 0.04641199 0.430551 0.026295 0.465611 0.04641199 0.45403 0.04641199 0.478118 0.026295 0.465611 0.026295 0.447741 0.04641199 0.45403 0.026295 0.483945 0.026295 0.465611 0.04641199 0.478118 0.01174396 0.490006 0.026295 0.483945 0.026295 0.465611 0.01174396 0.477655 0.026295 0.465611 0.026295 0.447741 0.01174396 0.477655 0.01174396 0.490006 0.026295 0.465611 0.01174396 0.465618 0.026295 0.447741 0.026295 0.430559 0.01174396 0.465618 0.01174396 0.477655 0.026295 0.447741 0.01174396 0.454044 0.026295 0.430559 0.026295 0.414283 0.01174396 0.454044 0.01174396 0.465618 0.026295 0.430559 0.01174396 0.44308 0.026295 0.414283 0.026295 0.399116 0.01174396 0.44308 0.01174396 0.454044 0.026295 0.414283 0.01174396 0.432864 0.026295 0.399116 0.026295 0.385249 0.01174396 0.432864 0.01174396 0.44308 0.026295 0.399116 0.01174396 0.423523 0.026295 0.385249 0.026295 0.372857 0.01174396 0.423523 0.01174396 0.432864 0.026295 0.385249 0.01174396 0.415176 0.026295 0.372857 0.026295 0.362095 0.01174396 0.415176 0.01174396 0.423523 0.026295 0.372857 0.01174396 0.407926 0.026295 0.362095 0.026295 0.353099 0.01174396 0.407926 0.01174396 0.415176 0.026295 0.362095 0.01174396 0.401867 0.026295 0.353099 0.026295 0.345982 0.01174396 0.401867 0.01174396 0.407926 0.026295 0.353099 0.01174396 0.397073 0.026295 0.345982 0.026295 0.340834 0.01174396 0.397073 0.01174396 0.401867 0.026295 0.345982 0.01174396 0.393605 0.026295 0.340834 0.026295 0.337719 0.01174396 0.393605 0.01174396 0.397073 0.026295 0.340834 0.01174396 0.391507 0.026295 0.337719 0.026295 0.336676 0.01174396 0.391507 0.01174396 0.393605 0.026295 0.337719 0.01174396 0.390804 0.026295 0.336676 0.026295 0.337719 0.01174396 0.390804 0.01174396 0.391507 0.026295 0.336676 0.01174396 0.391507 0.026295 0.337719 0.026295 0.340834 0.01174396 0.391507 0.01174396 0.390804 0.026295 0.337719 0.01174396 0.393605 0.026295 0.340834 0.026295 0.345982 0.01174396 0.393605 0.01174396 0.391507 0.026295 0.340834 0.01174396 0.397073 0.026295 0.345982 0.026295 0.353099 0.01174396 0.397073 0.01174396 0.393605 0.026295 0.345982 0.01174396 0.401867 0.026295 0.353099 0.026295 0.362095 0.01174396 0.401867 0.01174396 0.397073 0.026295 0.353099 0.01174396 0.407926 0.026295 0.362095 0.026295 0.372857 0.01174396 0.407926 0.01174396 0.401867 0.026295 0.362095 0.01174396 0.415176 0.026295 0.372857 0.026295 0.385249 0.01174396 0.415176 0.01174396 0.407926 0.026295 0.372857 0.01174396 0.423523 0.026295 0.385249 0.026295 0.399116 0.01174396 0.423523 0.01174396 0.415176 0.026295 0.385249 0.01174396 0.432864 0.026295 0.399116 0.026295 0.414283 0.01174396 0.432864 0.01174396 0.423523 0.026295 0.399116 0.01174396 0.44308 0.026295 0.414283 0.026295 0.430559 0.01174396 0.44308 0.01174396 0.432864 0.026295 0.414283 0.01174396 0.454044 0.026295 0.430559 0.026295 0.447741 0.01174396 0.454044 0.01174396 0.44308 0.026295 0.430559 0.01174396 0.465618 0.026295 0.447741 0.026295 0.465611 0.01174396 0.465618 0.01174396 0.454044 0.026295 0.447741 0.01174396 0.477655 0.026295 0.465611 0.026295 0.483945 0.01174396 0.477655 0.01174396 0.465618 0.026295 0.465611 0.01174396 0.490006 0.01174396 0.477655 0.026295 0.483945 0.002941966 0.496223 0.01174396 0.490006 0.01174396 0.477655 0.002941966 0.490012 0.01174396 0.477655 0.01174396 0.465618 0.002941966 0.490012 0.002941966 0.496223 0.01174396 0.477655 0.002941966 0.483958 0.01174396 0.465618 0.01174396 0.454044 0.002941966 0.483958 0.002941966 0.490012 0.01174396 0.465618 0.002941966 0.478138 0.01174396 0.454044 0.01174396 0.44308 0.002941966 0.478138 0.002941966 0.483958 0.01174396 0.454044 0.002941966 0.472624 0.01174396 0.44308 0.01174396 0.432864 0.002941966 0.472624 0.002941966 0.478138 0.01174396 0.44308 0.002941966 0.467486 0.01174396 0.432864 0.01174396 0.423523 0.002941966 0.467486 0.002941966 0.472624 0.01174396 0.432864 0.002941966 0.462789 0.01174396 0.423523 0.01174396 0.415176 0.002941966 0.462789 0.002941966 0.467486 0.01174396 0.423523 0.002941966 0.458591 0.01174396 0.415176 0.01174396 0.407926 0.002941966 0.458591 0.002941966 0.462789 0.01174396 0.415176 0.002941966 0.454945 0.01174396 0.407926 0.01174396 0.401867 0.002941966 0.454945 0.002941966 0.458591 0.01174396 0.407926 0.002941966 0.451898 0.01174396 0.401867 0.01174396 0.397073 0.002941966 0.451898 0.002941966 0.454945 0.01174396 0.401867 0.002941966 0.449487 0.01174396 0.397073 0.01174396 0.393605 0.002941966 0.449487 0.002941966 0.451898 0.01174396 0.397073 0.002941966 0.447743 0.01174396 0.393605 0.01174396 0.391507 0.002941966 0.447743 0.002941966 0.449487 0.01174396 0.393605 0.002941966 0.446687 0.01174396 0.391507 0.01174396 0.390804 0.002941966 0.446687 0.002941966 0.447743 0.01174396 0.391507 0.002941966 0.446334 0.01174396 0.390804 0.01174396 0.391507 0.002941966 0.446334 0.002941966 0.446687 0.01174396 0.390804 0.002941966 0.446687 0.01174396 0.391507 0.01174396 0.393605 0.002941966 0.446687 0.002941966 0.446334 0.01174396 0.391507 0.002941966 0.447743 0.01174396 0.393605 0.01174396 0.397073 0.002941966 0.447743 0.002941966 0.446687 0.01174396 0.393605 0.002941966 0.449487 0.01174396 0.397073 0.01174396 0.401867 0.002941966 0.449487 0.002941966 0.447743 0.01174396 0.397073 0.002941966 0.451898 0.01174396 0.401867 0.01174396 0.407926 0.002941966 0.451898 0.002941966 0.449487 0.01174396 0.401867 0.002941966 0.454945 0.01174396 0.407926 0.01174396 0.415176 0.002941966 0.454945 0.002941966 0.451898 0.01174396 0.407926 0.002941966 0.458591 0.01174396 0.415176 0.01174396 0.423523 0.002941966 0.458591 0.002941966 0.454945 0.01174396 0.415176 0.002941966 0.462789 0.01174396 0.423523 0.01174396 0.432864 0.002941966 0.462789 0.002941966 0.458591 0.01174396 0.423523 0.002941966 0.467486 0.01174396 0.432864 0.01174396 0.44308 0.002941966 0.467486 0.002941966 0.462789 0.01174396 0.432864 0.002941966 0.472624 0.01174396 0.44308 0.01174396 0.454044 0.002941966 0.472624 0.002941966 0.467486 0.01174396 0.44308 0.002941966 0.478138 0.01174396 0.454044 0.01174396 0.465618 0.002941966 0.478138 0.002941966 0.472624 0.01174396 0.454044 0.002941966 0.483958 0.01174396 0.465618 0.01174396 0.477655 0.002941966 0.483958 0.002941966 0.478138 0.01174396 0.465618 0.002941966 0.490012 0.01174396 0.477655 0.01174396 0.490006 0.002941966 0.490012 0.002941966 0.483958 0.01174396 0.477655 0.002941966 0.496223 0.002941966 0.490012 0.01174396 0.490006 0.221364 0.482277 0.176868 0.502513 0.177636 0.479946 0.22131 0.521977 0.1776199 0.524918 0.176868 0.502513 0.221364 0.482277 0.22131 0.521977 0.176868 0.502513 0.221364 0.482277 0.177636 0.479946 0.179884 0.457657 0.2269189 0.443054 0.179884 0.457657 0.183625 0.435598 0.2269189 0.443054 0.221364 0.482277 0.179884 0.457657 0.2269189 0.443054 0.183625 0.435598 0.18885 0.413801 0.237852 0.405142 0.18885 0.413801 0.1954759 0.392574 0.237852 0.405142 0.2269189 0.443054 0.18885 0.413801 0.237852 0.405142 0.1954759 0.392574 0.203529 0.371874 0.253943 0.369349 0.203529 0.371874 0.21288 0.351931 0.253943 0.369349 0.237852 0.405142 0.203529 0.371874 0.274861 0.336466 0.21288 0.351931 0.2234809 0.332846 0.274861 0.336466 0.253943 0.369349 0.21288 0.351931 0.274861 0.336466 0.2234809 0.332846 0.235328 0.314611 0.300197 0.307215 0.235328 0.314611 0.24841 0.297265 0.300197 0.307215 0.274861 0.336466 0.235328 0.314611 0.329118 0.282457 0.24841 0.297265 0.262704 0.280832 0.329118 0.282457 0.300197 0.307215 0.24841 0.297265 0.329118 0.282457 0.262704 0.280832 0.277977 0.265611 0.361204 0.262568 0.277977 0.265611 0.294268 0.251571 0.361204 0.262568 0.329118 0.282457 0.277977 0.265611 0.395916 0.247904 0.294268 0.251571 0.31139 0.238842 0.395916 0.247904 0.361204 0.262568 0.294268 0.251571 0.450942 0.236687 0.31139 0.238842 0.329326 0.227455 0.414034 0.242677 0.395916 0.247904 0.31139 0.238842 0.432383 0.2389349 0.414034 0.242677 0.31139 0.238842 0.450942 0.236687 0.432383 0.2389349 0.31139 0.238842 0.60968 0.2271659 0.329326 0.227455 0.347971 0.217454 0.62776 0.2386 0.329326 0.227455 0.60968 0.2271659 0.469751 0.235918 0.329326 0.227455 0.62776 0.2386 0.469751 0.235918 0.450942 0.236687 0.329326 0.227455 0.590891 0.2171429 0.347971 0.217454 0.367186 0.208925 0.60968 0.2271659 0.347971 0.217454 0.590891 0.2171429 0.571543 0.208617 0.367186 0.208925 0.386977 0.201854 0.590891 0.2171429 0.367186 0.208925 0.571543 0.208617 0.551631 0.201575 0.386977 0.201854 0.407116 0.196327 0.571543 0.208617 0.386977 0.201854 0.551631 0.201575 0.531396 0.196096 0.407116 0.196327 0.427649 0.192333 0.551631 0.201575 0.407116 0.196327 0.531396 0.196096 0.510792 0.192171 0.427649 0.192333 0.448343 0.189913 0.531396 0.196096 0.427649 0.192333 0.510792 0.192171 0.490055 0.189828 0.448343 0.189913 0.469192 0.189079 0.510792 0.192171 0.448343 0.189913 0.490055 0.189828 0.50689 0.238896 0.62776 0.2386 0.645017 0.251398 0.50689 0.238896 0.469751 0.235918 0.62776 0.2386 0.577939 0.262382 0.645017 0.251398 0.661432 0.265526 0.543239 0.247788 0.50689 0.238896 0.645017 0.251398 0.577939 0.262382 0.543239 0.247788 0.645017 0.251398 0.577939 0.262382 0.661432 0.265526 0.676806 0.280841 0.6101 0.282251 0.676806 0.280841 0.691181 0.297378 0.6101 0.282251 0.577939 0.262382 0.676806 0.280841 0.782695 0.261627 0.704319 0.314818 0.691181 0.297378 0.639155 0.307068 0.691181 0.297378 0.704319 0.314818 0.639155 0.307068 0.6101 0.282251 0.691181 0.297378 0.792958 0.280024 0.716196 0.333138 0.704319 0.314818 0.652449 0.321296 0.704319 0.314818 0.716196 0.333138 0.782695 0.261627 0.792958 0.280024 0.704319 0.314818 0.652449 0.321296 0.639155 0.307068 0.704319 0.314818 0.802414 0.298995 0.726806 0.352293 0.716196 0.333138 0.664644 0.336472 0.716196 0.333138 0.726806 0.352293 0.792958 0.280024 0.802414 0.298995 0.716196 0.333138 0.664644 0.336472 0.652449 0.321296 0.716196 0.333138 0.815647 0.329808 0.736147 0.372282 0.726806 0.352293 0.685683 0.36958 0.726806 0.352293 0.736147 0.372282 0.802414 0.298995 0.815647 0.329808 0.726806 0.352293 0.685683 0.36958 0.664644 0.336472 0.726806 0.352293 0.818636 0.337669 0.744174 0.393004 0.736147 0.372282 0.685683 0.36958 0.736147 0.372282 0.744174 0.393004 0.815647 0.329808 0.818636 0.337669 0.736147 0.372282 0.831335 0.376692 0.750768 0.414218 0.744174 0.393004 0.701822 0.405616 0.744174 0.393004 0.750768 0.414218 0.818636 0.337669 0.831335 0.376692 0.744174 0.393004 0.701822 0.405616 0.685683 0.36958 0.744174 0.393004 0.838339 0.416896 0.755951 0.435969 0.750768 0.414218 0.701822 0.405616 0.750768 0.414218 0.755951 0.435969 0.831335 0.376692 0.838339 0.416896 0.750768 0.414218 0.838339 0.416896 0.759658 0.457943 0.755951 0.435969 0.712724 0.443722 0.755951 0.435969 0.759658 0.457943 0.712724 0.443722 0.701822 0.405616 0.755951 0.435969 0.842785 0.4585 0.761882 0.480108 0.759658 0.457943 0.712724 0.443722 0.759658 0.457943 0.761882 0.480108 0.838339 0.416896 0.842785 0.4585 0.759658 0.457943 0.844381 0.502513 0.762633 0.502513 0.761882 0.480108 0.718191 0.48305 0.761882 0.480108 0.762633 0.502513 0.842785 0.4585 0.844381 0.502513 0.761882 0.480108 0.718191 0.48305 0.712724 0.443722 0.761882 0.480108 0.843623 0.532838 0.762633 0.502513 0.844381 0.502513 0.761865 0.52508 0.762633 0.502513 0.843623 0.532838 0.718138 0.522749 0.762633 0.502513 0.761865 0.52508 0.718138 0.522749 0.718191 0.48305 0.762633 0.502513 1 0.500545 0.844381 0.502513 0.842785 0.4585 1 0.522699 0.843623 0.532838 0.844381 0.502513 1 0.522699 0.844381 0.502513 1 0.500545 1 0.456062 0.842785 0.4585 0.838339 0.416896 1 0.478322 0.842785 0.4585 1 0.456062 1 0.500545 0.842785 0.4585 1 0.478322 1 0.412545 0.838339 0.416896 0.831335 0.376692 1 0.434153 0.838339 0.416896 1 0.412545 1 0.456062 0.838339 0.416896 1 0.434153 0.837076 0.337754 0.831335 0.376692 0.818636 0.337669 1 0.391462 0.831335 0.376692 1 0.370938 0.837076 0.337754 1 0.370938 0.831335 0.376692 1 0.412545 0.831335 0.376692 1 0.391462 0.837076 0.337754 0.818636 0.337669 0.815647 0.329808 0.819035 0.290247 0.815647 0.329808 0.802414 0.298995 0.837076 0.337754 0.815647 0.329808 0.843886 0.300883 0.819035 0.290247 0.843886 0.300883 0.815647 0.329808 0.819035 0.290247 0.802414 0.298995 0.792958 0.280024 0.792162 0.242654 0.792958 0.280024 0.782695 0.261627 0.822294 0.254266 0.792958 0.280024 0.792162 0.242654 0.822294 0.254266 0.819035 0.290247 0.792958 0.280024 0.832029 0.593917 0.837495 0.593917 0.812115 0.593917 0.755877 0.569428 0.832029 0.593917 0.826559 0.593917 0.812115 0.593917 0.826559 0.593917 0.832029 0.593917 0.77787 0.593917 0.755877 0.569428 0.826559 0.593917 0.822537 0.625081 0.826559 0.593917 0.812115 0.682229 0.812115 0.593917 0.812115 0.682229 0.826559 0.593917 0.77787 0.593917 0.826559 0.593917 0.822537 0.625081 0.755877 0.569428 0.837495 0.593917 0.832029 0.593917 0.755877 0.569428 0.841297 0.56369 0.837495 0.593917 1 0.566683 0.837495 0.593917 0.841297 0.56369 0.812115 0.593917 0.837495 0.593917 0.848384 0.593917 0.848384 0.593917 0.859274 0.593917 0.812115 0.593917 1 0.588406 0.848384 0.593917 0.837495 0.593917 1 0.588406 0.837495 0.593917 1 0.566683 0.759618 0.547369 0.843623 0.532838 0.841297 0.56369 1 0.544743 0.841297 0.56369 0.843623 0.532838 0.755877 0.569428 0.759618 0.547369 0.841297 0.56369 1 0.566683 0.841297 0.56369 1 0.544743 0.759618 0.547369 0.761865 0.52508 0.843623 0.532838 1 0.544743 0.843623 0.532838 1 0.522699 0.718138 0.522749 0.761865 0.52508 0.759618 0.547369 0.712583 0.561973 0.759618 0.547369 0.755877 0.569428 0.712583 0.561973 0.718138 0.522749 0.759618 0.547369 0.766414 0.593917 0.750652 0.591225 0.755877 0.569428 0.712583 0.561973 0.755877 0.569428 0.750652 0.591225 0.772146 0.593917 0.766414 0.593917 0.755877 0.569428 0.77787 0.593917 0.772146 0.593917 0.755877 0.569428 0.757124 0.625156 0.744026 0.612452 0.750652 0.591225 0.701649 0.599884 0.750652 0.591225 0.744026 0.612452 0.757124 0.625156 0.750652 0.591225 0.766414 0.593917 0.701649 0.599884 0.712583 0.561973 0.750652 0.591225 0.757124 0.625156 0.735973 0.633152 0.744026 0.612452 0.701649 0.599884 0.744026 0.612452 0.735973 0.633152 0.745128 0.65543 0.726621 0.653095 0.735973 0.633152 0.685559 0.635677 0.735973 0.633152 0.726621 0.653095 0.757124 0.625156 0.745128 0.65543 0.735973 0.633152 0.685559 0.635677 0.701649 0.599884 0.735973 0.633152 0.73353 0.681538 0.716021 0.672181 0.726621 0.653095 0.664641 0.66856 0.726621 0.653095 0.716021 0.672181 0.736516 0.674599 0.73353 0.681538 0.726621 0.653095 0.740377 0.665972 0.736516 0.674599 0.726621 0.653095 0.745128 0.65543 0.740377 0.665972 0.726621 0.653095 0.664641 0.66856 0.685559 0.635677 0.726621 0.653095 0.729361 0.695677 0.704174 0.690415 0.716021 0.672181 0.664641 0.66856 0.716021 0.672181 0.704174 0.690415 0.729384 0.693908 0.729361 0.695677 0.716021 0.672181 0.730025 0.691053 0.729384 0.693908 0.716021 0.672181 0.731385 0.686967 0.730025 0.691053 0.716021 0.672181 0.73353 0.681538 0.731385 0.686967 0.716021 0.672181 0.639305 0.697812 0.704174 0.690415 0.691091 0.707761 0.729844 0.696544 0.778922 0.749673 0.704174 0.690415 0.729361 0.695677 0.729844 0.696544 0.704174 0.690415 0.639305 0.697812 0.664641 0.66856 0.704174 0.690415 0.610383 0.722569 0.691091 0.707761 0.676797 0.724194 0.610383 0.722569 0.639305 0.697812 0.691091 0.707761 0.610383 0.722569 0.676797 0.724194 0.661524 0.739415 0.578297 0.742459 0.661524 0.739415 0.645234 0.753456 0.578297 0.742459 0.610383 0.722569 0.661524 0.739415 0.543586 0.757122 0.645234 0.753456 0.628112 0.766184 0.543586 0.757122 0.578297 0.742459 0.645234 0.753456 0.48856 0.768339 0.628112 0.766184 0.610176 0.777572 0.525467 0.762349 0.543586 0.757122 0.628112 0.766184 0.507118 0.766091 0.525467 0.762349 0.628112 0.766184 0.48856 0.768339 0.507118 0.766091 0.628112 0.766184 0.329822 0.77786 0.610176 0.777572 0.591531 0.787572 0.311742 0.766426 0.610176 0.777572 0.329822 0.77786 0.469751 0.769108 0.610176 0.777572 0.311742 0.766426 0.48856 0.768339 0.610176 0.777572 0.469751 0.769108 0.348611 0.787884 0.591531 0.787572 0.572316 0.796101 0.329822 0.77786 0.591531 0.787572 0.348611 0.787884 0.367959 0.796409 0.572316 0.796101 0.552525 0.803172 0.348611 0.787884 0.572316 0.796101 0.367959 0.796409 0.387871 0.803451 0.552525 0.803172 0.532386 0.808699 0.367959 0.796409 0.552525 0.803172 0.387871 0.803451 0.408105 0.80893 0.532386 0.808699 0.511853 0.812693 0.387871 0.803451 0.532386 0.808699 0.408105 0.80893 0.42871 0.812855 0.511853 0.812693 0.491159 0.815114 0.408105 0.80893 0.511853 0.812693 0.42871 0.812855 0.449447 0.815199 0.491159 0.815114 0.47031 0.815947 0.42871 0.812855 0.491159 0.815114 0.449447 0.815199 0.432612 0.76613 0.311742 0.766426 0.294485 0.753628 0.432612 0.76613 0.469751 0.769108 0.311742 0.766426 0.361563 0.742644 0.294485 0.753628 0.27807 0.7395 0.396263 0.757238 0.432612 0.76613 0.294485 0.753628 0.361563 0.742644 0.396263 0.757238 0.294485 0.753628 0.361563 0.742644 0.27807 0.7395 0.262696 0.724185 0.329402 0.722775 0.262696 0.724185 0.2483209 0.707649 0.329402 0.722775 0.361563 0.742644 0.262696 0.724185 0.300347 0.697958 0.2483209 0.707649 0.235183 0.690209 0.300347 0.697958 0.329402 0.722775 0.2483209 0.707649 0.208483 0.68798 0.223305 0.671888 0.235183 0.690209 0.287053 0.68373 0.235183 0.690209 0.223305 0.671888 0.209724 0.691965 0.208483 0.68798 0.235183 0.690209 0.210189 0.694622 0.209724 0.691965 0.235183 0.690209 0.210002 0.696128 0.210189 0.694622 0.235183 0.690209 0.209277 0.696675 0.210002 0.696128 0.235183 0.690209 0.287053 0.68373 0.300347 0.697958 0.235183 0.690209 0.1993629 0.666499 0.212696 0.652733 0.223305 0.671888 0.274858 0.668555 0.223305 0.671888 0.212696 0.652733 0.203356 0.675439 0.1993629 0.666499 0.223305 0.671888 0.206381 0.68253 0.203356 0.675439 0.223305 0.671888 0.208483 0.68798 0.206381 0.68253 0.223305 0.671888 0.274858 0.668555 0.287053 0.68373 0.223305 0.671888 0.194373 0.65543 0.203354 0.632744 0.212696 0.652733 0.253819 0.635446 0.212696 0.652733 0.203354 0.632744 0.1993629 0.666499 0.194373 0.65543 0.212696 0.652733 0.253819 0.635446 0.274858 0.668555 0.212696 0.652733 0.1823779 0.625156 0.195327 0.612022 0.203354 0.632744 0.253819 0.635446 0.203354 0.632744 0.195327 0.612022 0.194373 0.65543 0.1823779 0.625156 0.203354 0.632744 0.173088 0.593917 0.1887339 0.590809 0.195327 0.612022 0.23768 0.59941 0.195327 0.612022 0.1887339 0.590809 0.1823779 0.625156 0.173088 0.593917 0.195327 0.612022 0.23768 0.59941 0.253819 0.635446 0.195327 0.612022 0.09646695 0.593917 0.183551 0.569057 0.1887339 0.590809 0.23768 0.59941 0.1887339 0.590809 0.183551 0.569057 0.161632 0.593917 0.09646695 0.593917 0.1887339 0.590809 0.167356 0.593917 0.1887339 0.590809 0.173088 0.593917 0.167356 0.593917 0.161632 0.593917 0.1887339 0.590809 0.226778 0.561305 0.183551 0.569057 0.179844 0.547083 0.09646695 0.593917 0.09399598 0.593917 0.183551 0.569057 0.226778 0.561305 0.23768 0.59941 0.183551 0.569057 0.226778 0.561305 0.179844 0.547083 0.1776199 0.524918 0.22131 0.521977 0.226778 0.561305 0.1776199 0.524918 0.161632 0.593917 0.106427 0.634365 0.09646695 0.593917 0.119982 0.593917 0.09646695 0.593917 0.106427 0.634365 0.119982 0.593917 0.108929 0.593917 0.09646695 0.593917 0.171077 0.626682 0.119982 0.673721 0.106427 0.634365 0.119982 0.593917 0.106427 0.634365 0.119982 0.673721 0.161632 0.593917 0.171077 0.626682 0.106427 0.634365 0.1833209 0.65829 0.125511 0.687615 0.119982 0.673721 0.119982 0.593917 0.119982 0.673721 0.125511 0.687615 0.171077 0.626682 0.1833209 0.65829 0.119982 0.673721 0.1833209 0.65829 0.130129 0.699442 0.125511 0.687615 0.125651 0.593917 0.125511 0.687615 0.130129 0.699442 0.119982 0.593917 0.125511 0.687615 0.125651 0.593917 0.188288 0.668764 0.132122 0.704745 0.130129 0.699442 0.13036 0.593917 0.130129 0.699442 0.132122 0.704745 0.1833209 0.65829 0.188288 0.668764 0.130129 0.699442 0.125651 0.593917 0.130129 0.699442 0.13036 0.593917 0.188288 0.668764 0.1929309 0.677247 0.132122 0.704745 0.13036 0.593917 0.132122 0.704745 0.133746 0.593917 0.739602 0.68789 0.793088 0.724745 0.778922 0.749673 0.792246 0.76015 0.778922 0.749673 0.793088 0.724745 0.736557 0.691717 0.739602 0.68789 0.778922 0.749673 0.734072 0.694352 0.736557 0.691717 0.778922 0.749673 0.732164 0.695929 0.734072 0.694352 0.778922 0.749673 0.730777 0.696624 0.732164 0.695929 0.778922 0.749673 0.729844 0.696544 0.730777 0.696624 0.778922 0.749673 0.743159 0.682767 0.796192 0.718751 0.793088 0.724745 0.821712 0.744407 0.793088 0.724745 0.796192 0.718751 0.739602 0.68789 0.743159 0.682767 0.793088 0.724745 0.792246 0.76015 0.793088 0.724745 0.821712 0.744407 0.756181 0.65829 0.811536 0.685426 0.796192 0.718751 0.811435 0.693364 0.796192 0.718751 0.811536 0.685426 0.751534 0.668135 0.756181 0.65829 0.796192 0.718751 0.747164 0.676227 0.751534 0.668135 0.796192 0.718751 0.743159 0.682767 0.747164 0.676227 0.796192 0.718751 0.81202 0.699554 0.796192 0.718751 0.811435 0.693364 0.813211 0.704175 0.796192 0.718751 0.81202 0.699554 0.814904 0.707334 0.796192 0.718751 0.813211 0.704175 0.816911 0.709131 0.796192 0.718751 0.814904 0.707334 0.818564 0.709749 0.796192 0.718751 0.816911 0.709131 0.821712 0.744407 0.796192 0.718751 0.818564 0.709749 0.768425 0.626682 0.811774 0.683933 0.811536 0.685426 0.811515 0.593917 0.811536 0.685426 0.811774 0.683933 0.756181 0.65829 0.768425 0.626682 0.811536 0.685426 0.811409 0.593917 0.811536 0.685426 0.811515 0.593917 0.811435 0.693364 0.811536 0.685426 0.811409 0.593917 0.768425 0.626682 0.812115 0.682229 0.811774 0.683933 0.811515 0.593917 0.811774 0.683933 0.812115 0.682229 0.822537 0.625081 0.812115 0.682229 0.817775 0.653891 0.768425 0.626682 0.817775 0.653891 0.812115 0.682229 0.811515 0.593917 0.812115 0.682229 0.812115 0.593917 0.768425 0.626682 0.822537 0.625081 0.817775 0.653891 0.768425 0.626682 0.77787 0.593917 0.822537 0.625081 0.756181 0.593917 0.766414 0.593917 0.772146 0.593917 0.757124 0.625156 0.766414 0.593917 0.745128 0.65543 0.745128 0.593917 0.745128 0.65543 0.766414 0.593917 0.750655 0.593917 0.745128 0.593917 0.766414 0.593917 0.753442 0.593917 0.750655 0.593917 0.766414 0.593917 0.756181 0.593917 0.753442 0.593917 0.766414 0.593917 0.756181 0.593917 0.772146 0.593917 0.77787 0.593917 0.756181 0.593917 0.77787 0.593917 0.768425 0.626682 0.756181 0.593917 0.768425 0.626682 0.756181 0.65829 0.756181 0.593917 0.756181 0.65829 0.751534 0.668135 0.750655 0.593917 0.751534 0.668135 0.747164 0.676227 0.753442 0.593917 0.751534 0.668135 0.750655 0.593917 0.756181 0.593917 0.751534 0.668135 0.753442 0.593917 0.744546 0.593917 0.747164 0.676227 0.743159 0.682767 0.750655 0.593917 0.747164 0.676227 0.744546 0.593917 0.744546 0.593917 0.743159 0.682767 0.739602 0.68789 0.738978 0.593917 0.739602 0.68789 0.736557 0.691717 0.744546 0.593917 0.739602 0.68789 0.738978 0.593917 0.734388 0.593917 0.736557 0.691717 0.734072 0.694352 0.738978 0.593917 0.736557 0.691717 0.734388 0.593917 0.734388 0.593917 0.734072 0.694352 0.732164 0.695929 0.731141 0.593917 0.732164 0.695929 0.730777 0.696624 0.734388 0.593917 0.732164 0.695929 0.731141 0.593917 0.731141 0.593917 0.730777 0.696624 0.729844 0.696544 0.72949 0.593917 0.729844 0.696544 0.729361 0.695677 0.731141 0.593917 0.729844 0.696544 0.72949 0.593917 0.72949 0.593917 0.729361 0.695677 0.729384 0.693908 0.729566 0.593917 0.729384 0.693908 0.730025 0.691053 0.72949 0.593917 0.729384 0.693908 0.729566 0.593917 0.731365 0.593917 0.730025 0.691053 0.731385 0.686967 0.729566 0.593917 0.730025 0.691053 0.731365 0.593917 0.731365 0.593917 0.731385 0.686967 0.73353 0.681538 0.734751 0.593917 0.73353 0.681538 0.736516 0.674599 0.731365 0.593917 0.73353 0.681538 0.734751 0.593917 0.73946 0.593917 0.736516 0.674599 0.740377 0.665972 0.734751 0.593917 0.736516 0.674599 0.73946 0.593917 0.73946 0.593917 0.740377 0.665972 0.745128 0.65543 0.73946 0.593917 0.745128 0.65543 0.745128 0.593917 0.194373 0.593917 0.173088 0.593917 0.1823779 0.625156 0.167356 0.593917 0.173088 0.593917 0.1833209 0.593917 0.1833209 0.593917 0.161632 0.593917 0.167356 0.593917 0.1833209 0.593917 0.173088 0.593917 0.194373 0.593917 0.194373 0.593917 0.1823779 0.625156 0.194373 0.65543 0.194373 0.593917 0.194373 0.65543 0.1993629 0.666499 0.200043 0.593917 0.1993629 0.666499 0.203356 0.675439 0.200043 0.593917 0.194373 0.593917 0.1993629 0.666499 0.204752 0.593917 0.203356 0.675439 0.206381 0.68253 0.200043 0.593917 0.203356 0.675439 0.204752 0.593917 0.208138 0.593917 0.206381 0.68253 0.208483 0.68798 0.204752 0.593917 0.206381 0.68253 0.208138 0.593917 0.208138 0.593917 0.208483 0.68798 0.209724 0.691965 0.209936 0.593917 0.209724 0.691965 0.210189 0.694622 0.208138 0.593917 0.209724 0.691965 0.209936 0.593917 0.210011 0.593917 0.210189 0.694622 0.210002 0.696128 0.209936 0.593917 0.210189 0.694622 0.210011 0.593917 0.210011 0.593917 0.210002 0.696128 0.209277 0.696675 0.20836 0.593917 0.209277 0.696675 0.208057 0.696361 0.210011 0.593917 0.209277 0.696675 0.20836 0.593917 0.20836 0.593917 0.208057 0.696361 0.206293 0.695128 0.2051129 0.593917 0.206293 0.695128 0.203889 0.692777 0.20836 0.593917 0.206293 0.695128 0.2051129 0.593917 0.2051129 0.593917 0.203889 0.692777 0.200815 0.6891 0.200523 0.593917 0.200815 0.6891 0.197138 0.68397 0.2051129 0.593917 0.200815 0.6891 0.200523 0.593917 0.194955 0.593917 0.197138 0.68397 0.1929309 0.677247 0.200523 0.593917 0.197138 0.68397 0.194955 0.593917 0.188847 0.593917 0.1929309 0.677247 0.188288 0.668764 0.194955 0.593917 0.1929309 0.677247 0.188847 0.593917 0.18606 0.593917 0.188288 0.668764 0.1833209 0.65829 0.188847 0.593917 0.188288 0.668764 0.18606 0.593917 0.161632 0.593917 0.1833209 0.65829 0.171077 0.626682 0.1833209 0.593917 0.1833209 0.65829 0.161632 0.593917 0.18606 0.593917 0.1833209 0.65829 0.1833209 0.593917 0.853365 0.593917 0.811515 0.593917 0.812115 0.593917 0.859274 0.593917 0.853365 0.593917 0.812115 0.593917 0.853365 0.593917 0.811409 0.593917 0.811515 0.593917 0.853365 0.593917 0.811807 0.593917 0.811409 0.593917 0.811435 0.693364 0.811409 0.593917 0.811807 0.593917 0.853365 0.593917 0.812682 0.593917 0.811807 0.593917 0.81202 0.699554 0.811807 0.593917 0.812682 0.593917 0.81202 0.699554 0.811435 0.693364 0.811807 0.593917 0.851226 0.593917 0.814029 0.593917 0.812682 0.593917 0.813211 0.704175 0.812682 0.593917 0.814029 0.593917 0.853365 0.593917 0.851226 0.593917 0.812682 0.593917 0.813211 0.704175 0.81202 0.699554 0.812682 0.593917 0.851226 0.593917 0.8158 0.593917 0.814029 0.593917 0.814904 0.707334 0.814029 0.593917 0.8158 0.593917 0.814904 0.707334 0.813211 0.704175 0.814029 0.593917 0.847834 0.593917 0.817969 0.593917 0.8158 0.593917 0.816911 0.709131 0.8158 0.593917 0.817969 0.593917 0.851226 0.593917 0.847834 0.593917 0.8158 0.593917 0.816911 0.709131 0.814904 0.707334 0.8158 0.593917 0.843422 0.593917 0.820476 0.593917 0.817969 0.593917 0.818564 0.709749 0.817969 0.593917 0.820476 0.593917 0.847834 0.593917 0.843422 0.593917 0.817969 0.593917 0.818564 0.709749 0.816911 0.709131 0.817969 0.593917 0.843422 0.593917 0.823276 0.593917 0.820476 0.593917 0.82174 0.709556 0.820476 0.593917 0.823276 0.593917 0.819145 0.709835 0.818564 0.709749 0.820476 0.593917 0.82174 0.709556 0.819145 0.709835 0.820476 0.593917 0.838279 0.593917 0.826296 0.593917 0.823276 0.593917 0.824868 0.708096 0.823276 0.593917 0.826296 0.593917 0.843422 0.593917 0.838279 0.593917 0.823276 0.593917 0.824868 0.708096 0.82174 0.709556 0.823276 0.593917 0.838279 0.593917 0.82944 0.593917 0.826296 0.593917 0.828482 0.705166 0.826296 0.593917 0.82944 0.593917 0.828482 0.705166 0.824868 0.708096 0.826296 0.593917 0.838279 0.593917 0.83274 0.593917 0.82944 0.593917 0.832378 0.700644 0.82944 0.593917 0.83274 0.593917 0.832378 0.700644 0.828482 0.705166 0.82944 0.593917 0.836399 0.694428 0.83274 0.593917 0.838279 0.593917 0.836399 0.694428 0.832378 0.700644 0.83274 0.593917 0.840411 0.686351 0.838279 0.593917 0.843422 0.593917 0.836399 0.694428 0.838279 0.593917 0.840411 0.686351 0.844502 0.681691 0.843422 0.593917 0.847834 0.593917 0.844502 0.681691 0.840411 0.686351 0.843422 0.593917 0.848211 0.675225 0.847834 0.593917 0.851226 0.593917 0.848211 0.675225 0.844502 0.681691 0.847834 0.593917 0.851271 0.666742 0.851226 0.593917 0.853365 0.593917 0.851271 0.666742 0.848211 0.675225 0.851226 0.593917 0.85669 0.625553 0.853365 0.593917 0.859274 0.593917 0.853365 0.655982 0.851271 0.666742 0.853365 0.593917 0.85669 0.625553 0.853365 0.655982 0.853365 0.593917 1 0.588406 0.859274 0.593917 0.848384 0.593917 1 0.609646 0.859274 0.593917 1 0.588406 0.85669 0.625553 0.859274 0.593917 1 0.609646 1 0.669842 0.840411 0.686351 0.844502 0.681691 0.841952 0.694475 0.836399 0.694428 0.840411 0.686351 1 0.688437 0.841952 0.694475 0.840411 0.686351 1 0.688437 0.840411 0.686351 1 0.669842 1 0.669842 0.844502 0.681691 0.848211 0.675225 1 0.669842 0.848211 0.675225 0.851271 0.666742 1 0.650529 0.851271 0.666742 0.853365 0.655982 1 0.669842 0.851271 0.666742 1 0.650529 1 0.650529 0.853365 0.655982 1 0.630454 0.85669 0.625553 1 0.630454 0.853365 0.655982 0.821712 0.744407 0.818564 0.709749 0.819145 0.709835 0.821712 0.744407 0.819145 0.709835 0.82174 0.709556 0.850996 0.736571 0.82174 0.709556 0.824868 0.708096 0.850996 0.736571 0.821712 0.744407 0.82174 0.709556 0.843524 0.702427 0.824868 0.708096 0.828482 0.705166 0.843524 0.702427 0.850996 0.736571 0.824868 0.708096 0.843524 0.702427 0.828482 0.705166 0.832378 0.700644 0.841952 0.694475 0.832378 0.700644 0.836399 0.694428 0.841952 0.694475 0.843524 0.702427 0.832378 0.700644 0.850996 0.736571 0.824502 0.775395 0.821712 0.744407 0.792246 0.76015 0.821712 0.744407 0.824502 0.775395 0.8583 0.766162 0.826598 0.802161 0.824502 0.775395 0.790682 0.792447 0.824502 0.775395 0.826598 0.802161 0.850996 0.736571 0.8583 0.766162 0.824502 0.775395 0.790682 0.792447 0.792246 0.76015 0.824502 0.775395 0.86481 0.790594 0.827686 0.824377 0.826598 0.802161 0.78841 0.821011 0.826598 0.802161 0.827686 0.824377 0.8583 0.766162 0.86481 0.790594 0.826598 0.802161 0.78841 0.821011 0.790682 0.792447 0.826598 0.802161 0.871946 0.816989 0.82754 0.841871 0.827686 0.824377 0.785322 0.845527 0.827686 0.824377 0.82754 0.841871 0.869978 0.809548 0.871946 0.816989 0.827686 0.824377 0.86481 0.790594 0.869978 0.809548 0.827686 0.824377 0.785322 0.845527 0.78841 0.821011 0.827686 0.824377 0.874444 0.828055 0.826047 0.854624 0.82754 0.841871 0.781356 0.865771 0.82754 0.841871 0.826047 0.854624 0.87343 0.82319 0.874444 0.828055 0.82754 0.841871 0.871946 0.816989 0.87343 0.82319 0.82754 0.841871 0.781356 0.865771 0.785322 0.845527 0.82754 0.841871 0.874778 0.833551 0.823213 0.862748 0.826047 0.854624 0.776508 0.881618 0.826047 0.854624 0.823213 0.862748 0.874895 0.831506 0.874778 0.833551 0.826047 0.854624 0.874444 0.828055 0.874895 0.831506 0.826047 0.854624 0.776508 0.881618 0.781356 0.865771 0.826047 0.854624 0.874093 0.834213 0.81914 0.866449 0.823213 0.862748 0.770834 0.89302 0.823213 0.862748 0.81914 0.866449 0.874778 0.833551 0.874093 0.834213 0.823213 0.862748 0.770834 0.89302 0.776508 0.881618 0.823213 0.862748 0.87099 0.831374 0.814001 0.865986 0.81914 0.866449 0.764433 0.899996 0.81914 0.866449 0.814001 0.865986 0.872824 0.83349 0.87099 0.831374 0.81914 0.866449 0.874093 0.834213 0.872824 0.83349 0.81914 0.866449 0.764433 0.899996 0.770834 0.89302 0.81914 0.866449 0.865622 0.822877 0.808003 0.861639 0.814001 0.865986 0.757438 0.902616 0.814001 0.865986 0.808003 0.861639 0.868586 0.827839 0.865622 0.822877 0.814001 0.865986 0.87099 0.831374 0.868586 0.827839 0.814001 0.865986 0.757438 0.902616 0.764433 0.899996 0.814001 0.865986 0.862271 0.81662 0.801369 0.853685 0.808003 0.861639 0.749999 0.900979 0.808003 0.861639 0.801369 0.853685 0.865622 0.822877 0.862271 0.81662 0.808003 0.861639 0.749999 0.900979 0.757438 0.902616 0.808003 0.861639 0.854443 0.800545 0.794312 0.842388 0.801369 0.853685 0.74227 0.895211 0.801369 0.853685 0.794312 0.842388 0.858535 0.809218 0.854443 0.800545 0.801369 0.853685 0.862271 0.81662 0.858535 0.809218 0.801369 0.853685 0.74227 0.895211 0.749999 0.900979 0.801369 0.853685 0.849978 0.790477 0.787033 0.827991 0.794312 0.842388 0.734403 0.885457 0.794312 0.842388 0.787033 0.827991 0.854443 0.800545 0.849978 0.790477 0.794312 0.842388 0.734403 0.885457 0.74227 0.895211 0.794312 0.842388 0.840312 0.766438 0.77971 0.810723 0.787033 0.827991 0.726539 0.871876 0.787033 0.827991 0.77971 0.810723 0.845223 0.779092 0.840312 0.766438 0.787033 0.827991 0.849978 0.790477 0.845223 0.779092 0.787033 0.827991 0.726539 0.871876 0.734403 0.885457 0.787033 0.827991 0.835222 0.75255 0.772507 0.790794 0.77971 0.810723 0.718812 0.854648 0.77971 0.810723 0.772507 0.790794 0.840312 0.766438 0.835222 0.75255 0.77971 0.810723 0.718812 0.854648 0.726539 0.871876 0.77971 0.810723 0.830187 0.737547 0.765567 0.768414 0.772507 0.790794 0.711343 0.833967 0.772507 0.790794 0.765567 0.768414 0.835222 0.75255 0.830187 0.737547 0.772507 0.790794 0.711343 0.833967 0.718812 0.854648 0.772507 0.790794 0.820298 0.704504 0.759019 0.743783 0.765567 0.768414 0.704244 0.810053 0.765567 0.768414 0.759019 0.743783 0.825223 0.721509 0.820298 0.704504 0.765567 0.768414 0.830187 0.737547 0.825223 0.721509 0.765567 0.768414 0.704244 0.810053 0.711343 0.833967 0.765567 0.768414 0.754457 0.724456 0.759019 0.743783 0.820298 0.704504 0.697617 0.78314 0.704244 0.810053 0.759019 0.743783 0.693008 0.76114 0.697617 0.78314 0.759019 0.743783 0.693008 0.76114 0.759019 0.743783 0.754457 0.724456 0.910149 0.69647 0.820298 0.704504 0.825223 0.721509 0.817786 0.695094 0.754457 0.724456 0.820298 0.704504 0.910149 0.69647 0.817786 0.695094 0.820298 0.704504 1 0.706099 0.825223 0.721509 0.830187 0.737547 1 0.688437 0.825223 0.721509 1 0.706099 0.910149 0.69647 0.825223 0.721509 1 0.688437 1 0.722604 0.830187 0.737547 0.835222 0.75255 1 0.706099 0.830187 0.737547 1 0.722604 1 0.737987 0.835222 0.75255 0.840312 0.766438 1 0.722604 0.835222 0.75255 1 0.737987 1 0.752187 0.840312 0.766438 0.845223 0.779092 1 0.737987 0.840312 0.766438 1 0.752187 1 0.765053 0.845223 0.779092 0.849978 0.790477 1 0.752187 0.845223 0.779092 1 0.765053 1 0.776599 0.849978 0.790477 0.854443 0.800545 1 0.765053 0.849978 0.790477 1 0.776599 1 0.786693 0.854443 0.800545 0.858535 0.809218 1 0.776599 0.854443 0.800545 1 0.786693 1 0.795347 0.858535 0.809218 0.862271 0.81662 1 0.786693 0.858535 0.809218 1 0.795347 1 0.80247 0.862271 0.81662 0.865622 0.822877 1 0.795347 0.862271 0.81662 1 0.80247 1 0.808058 0.865622 0.822877 0.868586 0.827839 1 0.80247 0.865622 0.822877 1 0.808058 1 0.812066 0.868586 0.827839 0.87099 0.831374 1 0.808058 0.868586 0.827839 1 0.812066 1 0.812066 0.87099 0.831374 0.872824 0.83349 1 0.814477 0.872824 0.83349 0.874093 0.834213 1 0.812066 0.872824 0.83349 1 0.814477 1 0.815286 0.874093 0.834213 0.874778 0.833551 1 0.814477 0.874093 0.834213 1 0.815286 1 0.814477 0.874778 0.833551 0.874895 0.831506 1 0.815286 0.874778 0.833551 1 0.814477 1 0.812065 0.874895 0.831506 0.874444 0.828055 1 0.814477 0.874895 0.831506 1 0.812065 1 0.808057 0.874444 0.828055 0.87343 0.82319 1 0.812065 0.874444 0.828055 1 0.808057 1 0.802469 0.87343 0.82319 0.871946 0.816989 1 0.808057 0.87343 0.82319 1 0.802469 1 0.795347 0.871946 0.816989 0.869978 0.809548 1 0.802469 0.871946 0.816989 1 0.795347 1 0.786692 0.869978 0.809548 0.86481 0.790594 1 0.795347 0.869978 0.809548 1 0.786692 1 0.765052 0.86481 0.790594 0.8583 0.766162 1 0.776598 0.86481 0.790594 1 0.765052 1 0.786692 0.86481 0.790594 1 0.776598 1 0.737986 0.8583 0.766162 0.850996 0.736571 1 0.752186 0.8583 0.766162 1 0.737986 1 0.765052 0.8583 0.766162 1 0.752186 1 0.706098 0.850996 0.736571 0.843524 0.702427 1 0.722604 0.850996 0.736571 1 0.706098 1 0.737986 0.850996 0.736571 1 0.722604 1 0.688437 0.843524 0.702427 0.841952 0.694475 1 0.706098 0.843524 0.702427 1 0.688437 0.754457 0.724456 0.813446 0.68263 0.812058 0.677897 0.813343 0.593917 0.812058 0.677897 0.813446 0.68263 0.813343 0.593917 0.811616 0.593917 0.812058 0.677897 0.815904 0.687765 0.815422 0.685847 0.813446 0.68263 0.813343 0.593917 0.813446 0.68263 0.815422 0.685847 0.754457 0.724456 0.815904 0.687765 0.813446 0.68263 0.817983 0.689344 0.815422 0.685847 0.815904 0.687765 0.816626 0.593917 0.813343 0.593917 0.815422 0.685847 0.817983 0.689344 0.816626 0.593917 0.815422 0.685847 0.817786 0.695094 0.815904 0.687765 0.754457 0.724456 0.820732 0.691805 0.815904 0.687765 0.817786 0.695094 0.817983 0.689344 0.815904 0.687765 0.820732 0.691805 0.826462 0.694287 0.817786 0.695094 0.829537 0.694513 0.910149 0.69647 0.829537 0.694513 0.817786 0.695094 0.82356 0.693404 0.817786 0.695094 0.826462 0.694287 0.820732 0.691805 0.817786 0.695094 0.82356 0.693404 0.811462 0.66749 0.811596 0.593917 0.811596 0.665829 0.813114 0.64918 0.811596 0.665829 0.811596 0.593917 0.853885 0.593917 0.811596 0.593917 0.811616 0.593917 0.858426 0.593917 0.811596 0.593917 0.853885 0.593917 0.837562 0.593917 0.811596 0.593917 0.858426 0.593917 0.816638 0.593917 0.811596 0.593917 0.837562 0.593917 0.815643 0.613145 0.811596 0.593917 0.816638 0.593917 0.814466 0.631592 0.811596 0.593917 0.815643 0.613145 0.813114 0.64918 0.811596 0.593917 0.814466 0.631592 0.852178 0.593917 0.811616 0.593917 0.813343 0.593917 0.853885 0.593917 0.811616 0.593917 0.852178 0.593917 0.848898 0.593917 0.813343 0.593917 0.816626 0.593917 0.852178 0.593917 0.813343 0.593917 0.848898 0.593917 0.844313 0.593917 0.816626 0.593917 0.821202 0.593917 0.820732 0.691805 0.821202 0.593917 0.816626 0.593917 0.848898 0.593917 0.816626 0.593917 0.844313 0.593917 0.817983 0.689344 0.820732 0.691805 0.816626 0.593917 0.838784 0.593917 0.821202 0.593917 0.826717 0.593917 0.826462 0.694287 0.826717 0.593917 0.821202 0.593917 0.844313 0.593917 0.821202 0.593917 0.838784 0.593917 0.82356 0.693404 0.826462 0.694287 0.821202 0.593917 0.820732 0.691805 0.82356 0.693404 0.821202 0.593917 0.838784 0.593917 0.826717 0.593917 0.83274 0.593917 0.829537 0.694513 0.83274 0.593917 0.826717 0.593917 0.826462 0.694287 0.829537 0.694513 0.826717 0.593917 0.83635 0.692688 0.838784 0.593917 0.83274 0.593917 0.832837 0.694023 0.83635 0.692688 0.83274 0.593917 0.829537 0.694513 0.832837 0.694023 0.83274 0.593917 0.843764 0.686813 0.844313 0.593917 0.838784 0.593917 0.840032 0.690341 0.843764 0.686813 0.838784 0.593917 0.83635 0.692688 0.840032 0.690341 0.838784 0.593917 0.847336 0.681984 0.848898 0.593917 0.844313 0.593917 0.843764 0.686813 0.847336 0.681984 0.844313 0.593917 0.850505 0.675752 0.852178 0.593917 0.848898 0.593917 0.847336 0.681984 0.850505 0.675752 0.848898 0.593917 0.853885 0.662112 0.853885 0.593917 0.852178 0.593917 0.853521 0.665051 0.853885 0.662112 0.852178 0.593917 0.852966 0.667966 0.853521 0.665051 0.852178 0.593917 0.850505 0.675752 0.852966 0.667966 0.852178 0.593917 0.858426 0.593917 0.853885 0.593917 0.853885 0.662112 0.903374 0.639776 0.853885 0.662112 0.853521 0.665051 0.85752 0.612009 0.858426 0.593917 0.853885 0.662112 0.855244 0.646172 0.853885 0.662112 0.903374 0.639776 0.856458 0.629449 0.853885 0.662112 0.855244 0.646172 0.85752 0.612009 0.853885 0.662112 0.856458 0.629449 0.903374 0.639776 0.853521 0.665051 0.852966 0.667966 0.910149 0.69647 0.852966 0.667966 0.850505 0.675752 0.905955 0.663592 0.903374 0.639776 0.852966 0.667966 0.910149 0.69647 0.905955 0.663592 0.852966 0.667966 0.910149 0.69647 0.850505 0.675752 0.847336 0.681984 0.910149 0.69647 0.847336 0.681984 0.843764 0.686813 0.910149 0.69647 0.843764 0.686813 0.840032 0.690341 0.910149 0.69647 0.840032 0.690341 0.83635 0.692688 0.910149 0.69647 0.83635 0.692688 0.832837 0.694023 0.910149 0.69647 0.832837 0.694023 0.829537 0.694513 0.899065 0.587673 0.837562 0.593917 0.858426 0.593917 0.85752 0.612009 0.899065 0.587673 0.858426 0.593917 0.899065 0.587673 0.816638 0.593917 0.837562 0.593917 1 0.542461 0.896628 0.531392 0.897565 0.559898 1 0.542461 1 0.522569 0.896628 0.531392 1 0.56223 0.897565 0.559898 0.899065 0.587673 1 0.56223 1 0.542461 0.897565 0.559898 0.85752 0.612009 0.901037 0.614393 0.899065 0.587673 1 0.581756 0.899065 0.587673 0.901037 0.614393 1 0.581756 1 0.56223 0.899065 0.587673 0.856458 0.629449 0.903374 0.639776 0.901037 0.614393 1 0.619753 0.901037 0.614393 0.903374 0.639776 0.85752 0.612009 0.856458 0.629449 0.901037 0.614393 1 0.600956 1 0.581756 0.901037 0.614393 1 0.619753 1 0.600956 0.901037 0.614393 1 0.638031 0.903374 0.639776 0.905955 0.663592 0.856458 0.629449 0.855244 0.646172 0.903374 0.639776 1 0.638031 1 0.619753 0.903374 0.639776 1 0.655828 1 0.638031 0.905955 0.663592 1 0.672461 1 0.655828 0.905955 0.663592 1 0.672461 0.905955 0.663592 1 0.688437 0.910149 0.69647 1 0.688437 0.905955 0.663592 1 0.522699 1 0.522569 1 0.542461 1 0.522699 1 0.500545 1 0.522569 1 0.544743 1 0.542461 1 0.56223 1 0.544743 1 0.522699 1 0.542461 1 0.566683 1 0.56223 1 0.581756 1 0.566683 1 0.544743 1 0.56223 1 0.588406 1 0.581756 1 0.600956 1 0.588406 1 0.566683 1 0.581756 1 0.609646 1 0.600956 1 0.619753 1 0.609646 1 0.588406 1 0.600956 1 0.630454 1 0.619753 1 0.638031 1 0.630454 1 0.609646 1 0.619753 1 0.650529 1 0.638031 1 0.655828 1 0.650529 1 0.630454 1 0.638031 1 0.669842 1 0.650529 1 0.655828 1 0.672461 1 0.669842 1 0.655828 1 0.296579 1 0.282713 1 0.299088 0.830249 0.267332 1 0.299088 1 0.282713 1 0.313798 1 0.296579 1 0.299088 0.830249 0.267332 0.825248 0.28348 1 0.299088 1 0.280339 1 0.267434 1 0.282713 0.835326 0.252169 1 0.282713 1 0.267434 1 0.296579 1 0.280339 1 0.282713 0.835326 0.252169 0.830249 0.267332 1 0.282713 1 0.265261 1 0.253271 1 0.267434 0.840502 0.238082 1 0.267434 1 0.253271 1 0.280339 1 0.265261 1 0.267434 0.840502 0.238082 0.835326 0.252169 1 0.267434 1 0.251357 1 0.240434 1 0.253271 0.845536 0.225181 1 0.253271 1 0.240434 1 0.265261 1 0.251357 1 0.253271 0.845536 0.225181 0.840502 0.238082 1 0.253271 1 0.238714 1 0.228901 1 0.240434 0.850415 0.213499 1 0.240434 1 0.228901 1 0.251357 1 0.238714 1 0.240434 0.850415 0.213499 0.845536 0.225181 1 0.240434 1 0.2274309 1 0.218791 1 0.228901 0.85505 0.203182 1 0.228901 1 0.218791 1 0.238714 1 0.2274309 1 0.228901 0.85505 0.203182 0.850415 0.213499 1 0.228901 1 0.217501 1 0.210156 1 0.218791 0.859223 0.194376 1 0.218791 1 0.210156 1 0.2274309 1 0.217501 1 0.218791 0.859223 0.194376 0.85505 0.203182 1 0.218791 1 0.209053 1 0.202994 1 0.210156 0.862989 0.187034 1 0.210156 1 0.202994 1 0.217501 1 0.209053 1 0.210156 0.862989 0.187034 0.859223 0.194376 1 0.210156 1 0.202063 1 0.19734 1 0.202994 0.866287 0.1810089 1 0.202994 1 0.19734 1 0.209053 1 0.202063 1 0.202994 0.866287 0.1810089 0.862989 0.187034 1 0.202994 1 0.196622 1 0.1931959 1 0.19734 0.869131 0.176309 1 0.19734 1 0.1931959 1 0.202063 1 0.196622 1 0.19734 0.869131 0.176309 0.866287 0.1810089 1 0.19734 1 0.1927379 1 0.190667 1 0.1931959 0.871459 0.173049 1 0.1931959 1 0.190667 1 0.196622 1 0.1927379 1 0.1931959 0.871459 0.173049 0.869131 0.176309 1 0.1931959 1 0.190436 1 0.18975 1 0.190667 0.873169 0.171244 1 0.190667 1 0.18975 1 0.1927379 1 0.190436 1 0.190667 0.873169 0.171244 0.871459 0.173049 1 0.190667 0.874293 0.170841 1 0.18975 1 0.190436 0.874293 0.170841 0.873169 0.171244 1 0.18975 0.874858 0.171805 1 0.190436 1 0.1927379 0.874858 0.171805 0.874293 0.170841 1 0.190436 0.874852 0.174093 1 0.1927379 1 0.196622 0.874852 0.174093 0.874858 0.171805 1 0.1927379 0.873276 0.182592 1 0.196622 1 0.202063 0.874314 0.177687 0.874852 0.174093 1 0.196622 0.873276 0.182592 0.874314 0.177687 1 0.196622 0.873276 0.182592 1 0.202063 1 0.209053 0.869759 0.196326 1 0.209053 1 0.217501 0.869759 0.196326 0.873276 0.182592 1 0.209053 0.869759 0.196326 1 0.217501 1 0.2274309 0.864527 0.215445 1 0.2274309 1 0.238714 0.864527 0.215445 0.869759 0.196326 1 0.2274309 0.864527 0.215445 1 0.238714 1 0.251357 0.858161 0.2392899 1 0.251357 1 0.265261 0.858161 0.2392899 0.864527 0.215445 1 0.251357 0.858161 0.2392899 1 0.265261 1 0.280339 0.851119 0.267802 1 0.280339 1 0.296579 0.851119 0.267802 0.858161 0.2392899 1 0.280339 0.851119 0.267802 1 0.296579 1 0.313798 0.843886 0.300883 1 0.313798 1 0.332035 0.843886 0.300883 0.851119 0.267802 1 0.313798 0.837076 0.337754 1 0.332035 1 0.351077 0.837076 0.337754 0.843886 0.300883 1 0.332035 0.837076 0.337754 1 0.351077 1 0.370938 0.85669 0.625553 1 0.609646 1 0.630454 1 0.688437 1 0.688437 1 0.669842 1 0.672461 1 0.688437 1 0.669842 1 0.706099 1 0.706098 1 0.688437 1 0.688437 1 0.706099 1 0.688437 1 0.722604 1 0.722604 1 0.706098 1 0.706099 1 0.722604 1 0.706098 1 0.737987 1 0.737986 1 0.722604 1 0.722604 1 0.737987 1 0.722604 1 0.737987 1 0.752186 1 0.737986 1 0.752187 1 0.765052 1 0.752186 1 0.737987 1 0.752187 1 0.752186 1 0.765053 1 0.776598 1 0.765052 1 0.752187 1 0.765053 1 0.765052 1 0.776599 1 0.786692 1 0.776598 1 0.765053 1 0.776599 1 0.776598 1 0.786693 1 0.795347 1 0.786692 1 0.776599 1 0.786693 1 0.786692 1 0.795347 1 0.802469 1 0.795347 1 0.786693 1 0.795347 1 0.795347 1 0.808058 1 0.808057 1 0.802469 1 0.80247 1 0.808058 1 0.802469 1 0.795347 1 0.80247 1 0.802469 1 0.812066 1 0.812065 1 0.808057 1 0.808058 1 0.812066 1 0.808057 1 0.814477 1 0.814477 1 0.812065 1 0.812066 1 0.814477 1 0.812065 1 0.814477 1 0.815286 1 0.814477 0.765931 0.2353529 0.825248 0.28348 0.830249 0.267332 0.77327 0.2119719 0.830249 0.267332 0.835326 0.252169 0.765931 0.2353529 0.830249 0.267332 0.77327 0.2119719 0.77327 0.2119719 0.835326 0.252169 0.840502 0.238082 0.780885 0.191338 0.840502 0.238082 0.845536 0.225181 0.77327 0.2119719 0.840502 0.238082 0.780885 0.191338 0.788604 0.173695 0.845536 0.225181 0.850415 0.213499 0.780885 0.191338 0.845536 0.225181 0.788604 0.173695 0.788604 0.173695 0.850415 0.213499 0.85505 0.203182 0.796235 0.1592929 0.85505 0.203182 0.859223 0.194376 0.788604 0.173695 0.85505 0.203182 0.796235 0.1592929 0.803561 0.148403 0.859223 0.194376 0.862989 0.187034 0.796235 0.1592929 0.859223 0.194376 0.803561 0.148403 0.803561 0.148403 0.862989 0.187034 0.866287 0.1810089 0.810343 0.141317 0.866287 0.1810089 0.869131 0.176309 0.803561 0.148403 0.866287 0.1810089 0.810343 0.141317 0.816325 0.1383489 0.869131 0.176309 0.871459 0.173049 0.810343 0.141317 0.869131 0.176309 0.816325 0.1383489 0.816325 0.1383489 0.871459 0.173049 0.873169 0.171244 0.821252 0.139828 0.873169 0.171244 0.874293 0.170841 0.816325 0.1383489 0.873169 0.171244 0.821252 0.139828 0.821252 0.139828 0.874293 0.170841 0.874858 0.171805 0.824897 0.146073 0.874858 0.171805 0.874852 0.174093 0.821252 0.139828 0.874858 0.171805 0.824897 0.146073 0.824897 0.146073 0.874852 0.174093 0.874314 0.177687 0.827093 0.157361 0.874314 0.177687 0.873276 0.182592 0.824897 0.146073 0.874314 0.177687 0.827093 0.157361 0.827784 0.173876 0.873276 0.182592 0.869759 0.196326 0.827093 0.157361 0.873276 0.182592 0.827784 0.173876 0.827045 0.195658 0.869759 0.196326 0.864527 0.215445 0.827784 0.173876 0.869759 0.196326 0.827045 0.195658 0.825101 0.222566 0.864527 0.215445 0.858161 0.2392899 0.827045 0.195658 0.864527 0.215445 0.825101 0.222566 0.822294 0.254266 0.858161 0.2392899 0.851119 0.267802 0.825101 0.222566 0.858161 0.2392899 0.822294 0.254266 0.819035 0.290247 0.851119 0.267802 0.843886 0.300883 0.822294 0.254266 0.851119 0.267802 0.819035 0.290247 0.825101 0.222566 0.792162 0.242654 0.790434 0.208712 0.825101 0.222566 0.822294 0.254266 0.792162 0.242654 0.827045 0.195658 0.790434 0.208712 0.787889 0.1790339 0.827045 0.195658 0.825101 0.222566 0.790434 0.208712 0.827784 0.173876 0.787889 0.1790339 0.784405 0.15398 0.827784 0.173876 0.827045 0.195658 0.787889 0.1790339 0.827093 0.157361 0.784405 0.15398 0.779923 0.13379 0.827093 0.157361 0.827784 0.173876 0.784405 0.15398 0.824897 0.146073 0.779923 0.13379 0.774461 0.118588 0.824897 0.146073 0.827093 0.157361 0.779923 0.13379 0.821252 0.139828 0.774461 0.118588 0.768104 0.1084 0.821252 0.139828 0.824897 0.146073 0.774461 0.118588 0.816325 0.1383489 0.768104 0.1084 0.760989 0.103177 0.816325 0.1383489 0.821252 0.139828 0.768104 0.1084 0.810343 0.141317 0.760989 0.103177 0.753288 0.102818 0.810343 0.141317 0.816325 0.1383489 0.760989 0.103177 0.803561 0.148403 0.753288 0.102818 0.745183 0.107184 0.803561 0.148403 0.810343 0.141317 0.753288 0.102818 0.796235 0.1592929 0.745183 0.107184 0.736859 0.116113 0.796235 0.1592929 0.803561 0.148403 0.745183 0.107184 0.788604 0.173695 0.736859 0.116113 0.728491 0.129417 0.788604 0.173695 0.796235 0.1592929 0.736859 0.116113 0.780885 0.191338 0.728491 0.129417 0.72024 0.14689 0.780885 0.191338 0.788604 0.173695 0.728491 0.129417 0.77327 0.2119719 0.72024 0.14689 0.712256 0.168301 0.77327 0.2119719 0.780885 0.191338 0.72024 0.14689 0.765931 0.2353529 0.712256 0.168301 0.704674 0.193393 0.765931 0.2353529 0.77327 0.2119719 0.712256 0.168301 0.469751 0.769108 0.469751 0.769108 0.432612 0.76613 0.50689 0.76613 0.48856 0.768339 0.469751 0.769108 0.50689 0.76613 0.469751 0.769108 0.469751 0.769108 0.432383 0.766091 0.432612 0.76613 0.396263 0.757238 0.450942 0.768339 0.469751 0.769108 0.432612 0.76613 0.432383 0.766091 0.450942 0.768339 0.432612 0.76613 0.395916 0.757122 0.396263 0.757238 0.361563 0.742644 0.414034 0.762349 0.432383 0.766091 0.396263 0.757238 0.395916 0.757122 0.414034 0.762349 0.396263 0.757238 0.361204 0.742459 0.361563 0.742644 0.329402 0.722775 0.361204 0.742459 0.395916 0.757122 0.361563 0.742644 0.329118 0.722569 0.329402 0.722775 0.300347 0.697958 0.329118 0.722569 0.361204 0.742459 0.329402 0.722775 0.300197 0.697812 0.300347 0.697958 0.287053 0.68373 0.300197 0.697812 0.329118 0.722569 0.300347 0.697958 0.274861 0.66856 0.287053 0.68373 0.274858 0.668555 0.274861 0.66856 0.300197 0.697812 0.287053 0.68373 0.253943 0.635677 0.274858 0.668555 0.253819 0.635446 0.253943 0.635677 0.274861 0.66856 0.274858 0.668555 0.237852 0.599884 0.253819 0.635446 0.23768 0.59941 0.237852 0.599884 0.253943 0.635677 0.253819 0.635446 0.2269189 0.561973 0.23768 0.59941 0.226778 0.561305 0.2269189 0.561973 0.237852 0.599884 0.23768 0.59941 0.221364 0.522749 0.226778 0.561305 0.22131 0.521977 0.221364 0.522749 0.2269189 0.561973 0.226778 0.561305 0.22131 0.48305 0.22131 0.521977 0.221364 0.482277 0.22131 0.48305 0.221364 0.522749 0.22131 0.521977 0.226778 0.443722 0.221364 0.482277 0.2269189 0.443054 0.226778 0.443722 0.22131 0.48305 0.221364 0.482277 0.23768 0.405616 0.2269189 0.443054 0.237852 0.405142 0.23768 0.405616 0.226778 0.443722 0.2269189 0.443054 0.253819 0.36958 0.237852 0.405142 0.253943 0.369349 0.253819 0.36958 0.23768 0.405616 0.237852 0.405142 0.274858 0.336472 0.253943 0.369349 0.274861 0.336466 0.274858 0.336472 0.253819 0.36958 0.253943 0.369349 0.287053 0.321296 0.274861 0.336466 0.300197 0.307215 0.287053 0.321296 0.274858 0.336472 0.274861 0.336466 0.300347 0.307068 0.300197 0.307215 0.329118 0.282457 0.300347 0.307068 0.287053 0.321296 0.300197 0.307215 0.329402 0.282251 0.329118 0.282457 0.361204 0.262568 0.329402 0.282251 0.300347 0.307068 0.329118 0.282457 0.361563 0.262382 0.361204 0.262568 0.395916 0.247904 0.361563 0.262382 0.329402 0.282251 0.361204 0.262568 0.396263 0.247788 0.395916 0.247904 0.414034 0.242677 0.396263 0.247788 0.361563 0.262382 0.395916 0.247904 0.396263 0.247788 0.414034 0.242677 0.432383 0.2389349 0.432612 0.238896 0.432383 0.2389349 0.450942 0.236687 0.432612 0.238896 0.396263 0.247788 0.432383 0.2389349 0.432612 0.238896 0.450942 0.236687 0.469751 0.235918 0.469751 0.235918 0.469751 0.235918 0.50689 0.238896 0.469751 0.235918 0.432612 0.238896 0.469751 0.235918 0.507118 0.2389349 0.50689 0.238896 0.543239 0.247788 0.48856 0.236687 0.469751 0.235918 0.50689 0.238896 0.507118 0.2389349 0.48856 0.236687 0.50689 0.238896 0.543586 0.247904 0.543239 0.247788 0.577939 0.262382 0.525467 0.242677 0.507118 0.2389349 0.543239 0.247788 0.543586 0.247904 0.525467 0.242677 0.543239 0.247788 0.578297 0.262568 0.577939 0.262382 0.6101 0.282251 0.578297 0.262568 0.543586 0.247904 0.577939 0.262382 0.610383 0.282457 0.6101 0.282251 0.639155 0.307068 0.610383 0.282457 0.578297 0.262568 0.6101 0.282251 0.639305 0.307215 0.639155 0.307068 0.652449 0.321296 0.639305 0.307215 0.610383 0.282457 0.639155 0.307068 0.664641 0.336466 0.652449 0.321296 0.664644 0.336472 0.664641 0.336466 0.639305 0.307215 0.652449 0.321296 0.685559 0.369349 0.664644 0.336472 0.685683 0.36958 0.685559 0.369349 0.664641 0.336466 0.664644 0.336472 0.701649 0.405142 0.685683 0.36958 0.701822 0.405616 0.701649 0.405142 0.685559 0.369349 0.685683 0.36958 0.712583 0.443054 0.701822 0.405616 0.712724 0.443722 0.712583 0.443054 0.701649 0.405142 0.701822 0.405616 0.718138 0.482277 0.712724 0.443722 0.718191 0.48305 0.718138 0.482277 0.712583 0.443054 0.712724 0.443722 0.718191 0.521977 0.718191 0.48305 0.718138 0.522749 0.718191 0.521977 0.718138 0.482277 0.718191 0.48305 0.712724 0.561305 0.718138 0.522749 0.712583 0.561973 0.712724 0.561305 0.718191 0.521977 0.718138 0.522749 0.701822 0.59941 0.712583 0.561973 0.701649 0.599884 0.701822 0.59941 0.712724 0.561305 0.712583 0.561973 0.685683 0.635446 0.701649 0.599884 0.685559 0.635677 0.685683 0.635446 0.701822 0.59941 0.701649 0.599884 0.664644 0.668555 0.685559 0.635677 0.664641 0.66856 0.664644 0.668555 0.685683 0.635446 0.685559 0.635677 0.652449 0.68373 0.664641 0.66856 0.639305 0.697812 0.652449 0.68373 0.664644 0.668555 0.664641 0.66856 0.639155 0.697958 0.639305 0.697812 0.610383 0.722569 0.639155 0.697958 0.652449 0.68373 0.639305 0.697812 0.6101 0.722775 0.610383 0.722569 0.578297 0.742459 0.6101 0.722775 0.639155 0.697958 0.610383 0.722569 0.577939 0.742644 0.578297 0.742459 0.543586 0.757122 0.577939 0.742644 0.6101 0.722775 0.578297 0.742459 0.543239 0.757238 0.543586 0.757122 0.525467 0.762349 0.543239 0.757238 0.577939 0.742644 0.543586 0.757122 0.543239 0.757238 0.525467 0.762349 0.507118 0.766091 0.50689 0.76613 0.507118 0.766091 0.48856 0.768339 0.50689 0.76613 0.543239 0.757238 0.507118 0.766091 0.50689 0.76613 0.469751 0.769108 0.450942 0.768339 0.50689 0.76613 0.450942 0.768339 0.432383 0.766091 0.50689 0.76613 0.432383 0.766091 0.414034 0.762349 0.543239 0.757238 0.414034 0.762349 0.395916 0.757122 0.50689 0.76613 0.414034 0.762349 0.543239 0.757238 0.577939 0.742644 0.395916 0.757122 0.361204 0.742459 0.543239 0.757238 0.395916 0.757122 0.577939 0.742644 0.6101 0.722775 0.361204 0.742459 0.329118 0.722569 0.577939 0.742644 0.361204 0.742459 0.6101 0.722775 0.639155 0.697958 0.329118 0.722569 0.300197 0.697812 0.6101 0.722775 0.329118 0.722569 0.639155 0.697958 0.652449 0.68373 0.300197 0.697812 0.274861 0.66856 0.639155 0.697958 0.300197 0.697812 0.652449 0.68373 0.664644 0.668555 0.274861 0.66856 0.253943 0.635677 0.652449 0.68373 0.274861 0.66856 0.664644 0.668555 0.685683 0.635446 0.253943 0.635677 0.237852 0.599884 0.664644 0.668555 0.253943 0.635677 0.685683 0.635446 0.701822 0.59941 0.237852 0.599884 0.2269189 0.561973 0.685683 0.635446 0.237852 0.599884 0.701822 0.59941 0.712724 0.561305 0.2269189 0.561973 0.221364 0.522749 0.701822 0.59941 0.2269189 0.561973 0.712724 0.561305 0.718191 0.521977 0.221364 0.522749 0.22131 0.48305 0.712724 0.561305 0.221364 0.522749 0.718191 0.521977 0.718138 0.482277 0.22131 0.48305 0.226778 0.443722 0.718191 0.521977 0.22131 0.48305 0.718138 0.482277 0.712583 0.443054 0.226778 0.443722 0.23768 0.405616 0.718138 0.482277 0.226778 0.443722 0.712583 0.443054 0.701649 0.405142 0.23768 0.405616 0.253819 0.36958 0.712583 0.443054 0.23768 0.405616 0.701649 0.405142 0.685559 0.369349 0.253819 0.36958 0.274858 0.336472 0.701649 0.405142 0.253819 0.36958 0.685559 0.369349 0.664641 0.336466 0.274858 0.336472 0.287053 0.321296 0.685559 0.369349 0.274858 0.336472 0.664641 0.336466 0.639305 0.307215 0.287053 0.321296 0.300347 0.307068 0.664641 0.336466 0.287053 0.321296 0.639305 0.307215 0.610383 0.282457 0.300347 0.307068 0.329402 0.282251 0.639305 0.307215 0.300347 0.307068 0.610383 0.282457 0.578297 0.262568 0.329402 0.282251 0.361563 0.262382 0.610383 0.282457 0.329402 0.282251 0.578297 0.262568 0.543586 0.247904 0.361563 0.262382 0.396263 0.247788 0.578297 0.262568 0.361563 0.262382 0.543586 0.247904 0.525467 0.242677 0.396263 0.247788 0.432612 0.238896 0.543586 0.247904 0.396263 0.247788 0.525467 0.242677 0.48856 0.236687 0.432612 0.238896 0.469751 0.235918 0.507118 0.2389349 0.432612 0.238896 0.48856 0.236687 0.525467 0.242677 0.432612 0.238896 0.507118 0.2389349 0.119982 0.593917 0.111668 0.593917 0.108929 0.593917 0.119982 0.593917 0.1144559 0.593917 0.111668 0.593917 0.119982 0.593917 0.120564 0.593917 0.1144559 0.593917 0.125651 0.593917 0.1261309 0.593917 0.120564 0.593917 0.119982 0.593917 0.125651 0.593917 0.120564 0.593917 0.13036 0.593917 0.130721 0.593917 0.1261309 0.593917 0.125651 0.593917 0.13036 0.593917 0.1261309 0.593917 0.133746 0.593917 0.133969 0.593917 0.130721 0.593917 0.13036 0.593917 0.133746 0.593917 0.130721 0.593917 0.135545 0.593917 0.1356199 0.593917 0.133969 0.593917 0.133746 0.593917 0.135545 0.593917 0.133969 0.593917 0.744546 0.593917 0.73946 0.593917 0.745128 0.593917 0.750655 0.593917 0.744546 0.593917 0.745128 0.593917 0.738978 0.593917 0.734751 0.593917 0.73946 0.593917 0.744546 0.593917 0.738978 0.593917 0.73946 0.593917 0.734388 0.593917 0.731365 0.593917 0.734751 0.593917 0.738978 0.593917 0.734388 0.593917 0.734751 0.593917 0.731141 0.593917 0.729566 0.593917 0.731365 0.593917 0.734388 0.593917 0.731141 0.593917 0.731365 0.593917 0.731141 0.593917 0.72949 0.593917 0.729566 0.593917 0.18606 0.593917 0.1833209 0.593917 0.194373 0.593917 0.188847 0.593917 0.18606 0.593917 0.194373 0.593917 0.194955 0.593917 0.188847 0.593917 0.194373 0.593917 0.200043 0.593917 0.194955 0.593917 0.194373 0.593917 0.200043 0.593917 0.200523 0.593917 0.194955 0.593917 0.204752 0.593917 0.2051129 0.593917 0.200523 0.593917 0.200043 0.593917 0.204752 0.593917 0.200523 0.593917 0.208138 0.593917 0.20836 0.593917 0.2051129 0.593917 0.204752 0.593917 0.208138 0.593917 0.2051129 0.593917 0.209936 0.593917 0.210011 0.593917 0.20836 0.593917 0.208138 0.593917 0.209936 0.593917 0.20836 0.593917 0.30722 0.593917 0.348716 0.593917 0.347584 0.593917 0.30722 0.593917 0.348269 0.593917 0.348716 0.593917 0.30722 0.593917 0.3463 0.593917 0.348269 0.593917 0.310324 0.593917 0.342959 0.593917 0.3463 0.593917 0.308574 0.593917 0.310324 0.593917 0.3463 0.593917 0.30722 0.593917 0.308574 0.593917 0.3463 0.593917 0.315012 0.593917 0.338479 0.593917 0.342959 0.593917 0.312496 0.593917 0.315012 0.593917 0.342959 0.593917 0.310324 0.593917 0.312496 0.593917 0.342959 0.593917 0.320866 0.593917 0.333177 0.593917 0.338479 0.593917 0.317823 0.593917 0.320866 0.593917 0.338479 0.593917 0.315012 0.593917 0.317823 0.593917 0.338479 0.593917 0.324049 0.593917 0.327402 0.593917 0.333177 0.593917 0.320866 0.593917 0.324049 0.593917 0.333177 0.593917 0.132943 0.593917 0.133904 0.593917 0.129603 0.593917 0.128408 0.593917 0.132943 0.593917 0.129603 0.593917 0.136246 0.593917 0.136866 0.593917 0.133904 0.593917 0.132943 0.593917 0.136246 0.593917 0.133904 0.593917 0.138074 0.593917 0.138289 0.593917 0.136866 0.593917 0.136246 0.593917 0.138074 0.593917 0.136866 0.593917 0.03991299 0.593917 0.03988796 0.593917 0.03380799 0.593917 0.03380799 0.593917 0.03991299 0.593917 0.03380799 0.593917 0.03991299 0.593917 0.04541999 0.593917 0.03988796 0.593917 0.04549199 0.593917 0.049959 0.593917 0.04541999 0.593917 0.03991299 0.593917 0.04549199 0.593917 0.04541999 0.593917 0.05005198 0.593917 0.05320894 0.593917 0.049959 0.593917 0.04549199 0.593917 0.05005198 0.593917 0.049959 0.593917 0.05327898 0.593917 0.05492496 0.593917 0.05320894 0.593917 0.05005198 0.593917 0.05327898 0.593917 0.05320894 0.593917 0.05327898 0.593917 0.05494999 0.593917 0.05492496 0.593917 0.535486 0.873461 0.537367 0.873461 0.53547 0.873461 0.529953 0.873461 0.53547 0.873461 0.529869 0.873461 0.535486 0.873461 0.53547 0.873461 0.529953 0.873461 0.521065 0.873461 0.529869 0.873461 0.520866 0.873461 0.529953 0.873461 0.529869 0.873461 0.521065 0.873461 0.509356 0.873461 0.520866 0.873461 0.50904 0.873461 0.521065 0.873461 0.520866 0.873461 0.509356 0.873461 0.495243 0.873461 0.50904 0.873461 0.494872 0.873461 0.509356 0.873461 0.50904 0.873461 0.495243 0.873461 0.479444 0.873461 0.494872 0.873461 0.47908 0.873461 0.495243 0.873461 0.494872 0.873461 0.479444 0.873461 0.462811 0.873461 0.47908 0.873461 0.462456 0.873461 0.479444 0.873461 0.47908 0.873461 0.462811 0.873461 0.446187 0.873461 0.462456 0.873461 0.445823 0.873461 0.462811 0.873461 0.462456 0.873461 0.446187 0.873461 0.430395 0.873461 0.445823 0.873461 0.430024 0.873461 0.446187 0.873461 0.445823 0.873461 0.430395 0.873461 0.416227 0.873461 0.430024 0.873461 0.415911 0.873461 0.430395 0.873461 0.430024 0.873461 0.416227 0.873461 0.404401 0.873461 0.415911 0.873461 0.404202 0.873461 0.416227 0.873461 0.415911 0.873461 0.404401 0.873461 0.395398 0.873461 0.404202 0.873461 0.395314 0.873461 0.404401 0.873461 0.404202 0.873461 0.395398 0.873461 0.389797 0.873461 0.395314 0.873461 0.389781 0.873461 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 6 6 10 2 2 11 8 8 12 7 7 13 2 2 14 9 9 15 10 9 16 11 9 17 12 10 18 13 11 19 1 1 20 3 3 21 5 5 22 14 12 23 0 0 24 12 10 25 1 1 26 15 13 27 16 14 28 13 11 29 17 15 30 18 16 31 19 17 32 12 10 33 15 13 34 13 11 35 15 13 36 20 18 37 16 14 38 21 19 39 19 17 40 22 20 41 17 15 42 19 17 43 21 19 44 15 13 45 23 21 46 20 18 47 24 22 48 22 20 49 25 23 50 21 19 51 22 20 52 24 22 53 26 24 54 27 25 55 23 21 56 28 26 57 25 23 58 29 27 59 15 13 60 26 24 61 23 21 62 24 22 63 25 23 64 28 26 65 26 24 66 30 28 67 27 25 68 28 26 69 29 27 70 31 29 71 26 24 72 32 30 73 30 28 74 33 31 75 31 29 76 34 32 77 28 26 78 31 29 79 33 31 80 26 24 81 35 33 82 32 30 83 33 31 84 34 32 85 36 34 86 26 24 87 37 35 88 35 33 89 38 36 90 36 34 91 39 37 92 33 31 93 36 34 94 38 36 95 26 24 96 40 38 97 37 35 98 41 39 99 39 37 100 42 40 101 38 36 102 39 37 103 41 39 104 43 41 105 44 42 106 40 38 107 41 39 108 42 40 109 45 43 110 26 24 111 43 41 112 40 38 113 43 41 114 46 44 115 44 42 116 47 45 117 45 43 118 48 46 119 41 39 120 45 43 121 47 45 122 43 41 123 49 47 124 46 44 125 50 48 126 48 46 127 51 49 128 47 45 129 48 46 130 50 48 131 43 41 132 52 50 133 49 47 134 53 51 135 51 49 136 54 52 137 50 48 138 51 49 139 53 51 140 55 53 141 56 54 142 57 55 143 53 51 144 54 52 145 58 56 146 59 57 147 58 56 148 54 52 149 55 53 150 60 58 151 56 54 152 61 59 153 56 54 154 60 58 155 26 24 156 62 60 157 43 41 158 63 61 159 43 41 160 62 60 161 64 62 162 57 55 163 65 63 164 64 62 165 55 53 166 57 55 167 66 64 168 67 65 169 62 60 170 68 66 171 62 60 172 67 65 173 26 24 174 66 64 175 62 60 176 68 66 177 63 61 178 62 60 179 69 67 180 70 68 181 67 65 182 71 69 183 67 65 184 70 68 185 66 64 186 69 67 187 67 65 188 72 70 189 68 66 190 67 65 191 71 69 192 72 70 193 67 65 194 73 71 195 74 72 196 70 68 197 75 73 198 70 68 199 74 72 200 69 67 201 73 71 202 70 68 203 76 74 204 71 69 205 70 68 206 75 73 207 76 74 208 70 68 209 77 75 210 78 76 211 74 72 212 79 77 213 74 72 214 78 76 215 73 71 216 77 75 217 74 72 218 80 78 219 75 73 220 74 72 221 79 77 222 80 78 223 74 72 224 81 79 225 82 80 226 78 76 227 83 81 228 78 76 229 82 80 230 77 75 231 81 79 232 78 76 233 84 82 234 79 77 235 78 76 236 83 81 237 84 82 238 78 76 239 85 83 240 86 84 241 82 80 242 87 85 243 82 80 244 86 84 245 81 79 246 85 83 247 82 80 248 88 86 249 83 81 250 82 80 251 89 87 252 88 86 253 82 80 254 87 85 255 89 87 256 82 80 257 90 88 258 91 89 259 86 84 260 87 85 261 86 84 262 91 89 263 85 83 264 90 88 265 86 84 266 92 90 267 93 91 268 91 89 269 94 92 270 91 89 271 93 91 272 90 88 273 92 90 274 91 89 275 94 92 276 87 85 277 91 89 278 95 93 279 96 94 280 93 91 281 97 95 282 93 91 283 96 94 284 92 90 285 95 93 286 93 91 287 97 95 288 94 92 289 93 91 290 98 96 291 99 97 292 96 94 293 100 98 294 96 94 295 99 97 296 95 93 297 98 96 298 96 94 299 100 98 300 97 95 301 96 94 302 101 99 303 102 100 304 99 97 305 103 101 306 99 97 307 102 100 308 98 96 309 101 99 310 99 97 311 103 101 312 100 98 313 99 97 314 104 102 315 105 103 316 102 100 317 106 104 318 102 100 319 105 103 320 101 99 321 104 102 322 102 100 323 106 104 324 103 101 325 102 100 326 107 105 327 108 106 328 105 103 329 109 107 330 105 103 331 108 106 332 104 102 333 107 105 334 105 103 335 109 107 336 106 104 337 105 103 338 110 108 339 111 109 340 108 106 341 112 110 342 108 106 343 111 109 344 113 111 345 110 108 346 108 106 347 107 105 348 113 111 349 108 106 350 112 110 351 109 107 352 108 106 353 114 112 354 115 113 355 116 114 356 117 115 357 112 110 358 111 109 359 114 112 360 118 116 361 115 113 362 119 117 363 116 114 364 120 118 365 119 117 366 114 112 367 116 114 368 121 119 369 113 111 370 107 105 371 122 120 372 120 118 373 123 121 374 122 120 375 119 117 376 120 118 377 124 122 378 107 105 379 104 102 380 125 123 381 121 119 382 107 105 383 126 124 384 125 123 385 107 105 386 124 122 387 126 124 388 107 105 389 127 125 390 104 102 391 101 99 392 127 125 393 124 122 394 104 102 395 128 126 396 101 99 397 98 96 398 128 126 399 127 125 400 101 99 401 129 127 402 98 96 403 95 93 404 129 127 405 128 126 406 98 96 407 130 128 408 95 93 409 92 90 410 131 129 411 129 127 412 95 93 413 130 128 414 131 129 415 95 93 416 132 130 417 92 90 418 90 88 419 133 131 420 130 128 421 92 90 422 134 132 423 133 131 424 92 90 425 135 133 426 134 132 427 92 90 428 132 130 429 135 133 430 92 90 431 136 134 432 90 88 433 85 83 434 136 134 435 132 130 436 90 88 437 137 135 438 85 83 439 81 79 440 137 135 441 136 134 442 85 83 443 138 136 444 81 79 445 77 75 446 138 136 447 137 135 448 81 79 449 139 137 450 77 75 451 73 71 452 139 137 453 138 136 454 77 75 455 140 138 456 73 71 457 69 67 458 140 138 459 139 137 460 73 71 461 141 139 462 69 67 463 66 64 464 141 139 465 140 138 466 69 67 467 142 140 468 66 64 469 26 24 470 142 140 471 141 139 472 66 64 473 143 141 474 26 24 475 15 13 476 143 141 477 142 140 478 26 24 479 144 142 480 15 13 481 12 10 482 144 142 483 143 141 484 15 13 485 145 143 486 12 10 487 0 0 488 145 143 489 144 142 490 12 10 491 146 144 492 0 0 493 6 6 494 146 144 495 145 143 496 0 0 497 147 145 498 148 146 499 6 6 500 149 147 501 6 6 502 148 146 503 7 7 504 147 145 505 6 6 506 149 147 507 146 144 508 6 6 509 150 148 510 151 149 511 152 150 512 153 151 513 149 147 514 148 146 515 154 152 516 155 153 517 151 149 518 154 152 519 151 149 520 150 148 521 156 154 522 157 155 523 158 156 524 159 157 525 160 158 526 161 159 527 162 160 528 160 158 529 159 157 530 8 8 531 163 161 532 7 7 533 164 162 534 158 156 535 165 163 536 166 164 537 156 154 538 158 156 539 164 162 540 166 164 541 158 156 542 9 9 543 167 9 544 10 9 545 9 9 546 168 9 547 167 9 548 169 165 549 165 163 550 170 166 551 169 165 552 164 162 553 165 163 554 171 167 555 172 168 556 173 169 557 174 170 558 64 62 559 65 63 560 175 171 561 174 170 562 65 63 563 171 167 564 176 172 565 172 168 566 177 173 567 173 169 568 178 174 569 171 167 570 173 169 571 177 173 572 179 175 573 180 176 574 181 177 575 182 178 576 181 177 577 183 179 578 179 175 579 181 177 580 182 178 581 182 178 582 183 179 583 184 180 584 185 181 585 184 180 586 186 182 587 182 178 588 184 180 589 185 181 590 185 181 591 186 182 592 187 183 593 188 184 594 187 183 595 189 185 596 185 181 597 187 183 598 188 184 599 188 184 600 189 185 601 190 186 602 191 187 603 190 186 604 192 188 605 188 184 606 190 186 607 191 187 608 191 187 609 192 188 610 193 189 611 194 190 612 89 87 613 87 85 614 195 191 615 193 189 616 196 192 617 191 187 618 193 189 619 195 191 620 197 193 621 87 85 622 94 92 623 197 193 624 194 190 625 87 85 626 198 194 627 94 92 628 97 95 629 199 195 630 197 193 631 94 92 632 198 194 633 199 195 634 94 92 635 200 196 636 97 95 637 100 98 638 201 197 639 198 194 640 97 95 641 200 196 642 201 197 643 97 95 644 202 198 645 100 98 646 103 101 647 203 199 648 200 196 649 100 98 650 202 198 651 203 199 652 100 98 653 204 200 654 103 101 655 106 104 656 205 201 657 202 198 658 103 101 659 204 200 660 205 201 661 103 101 662 206 202 663 106 104 664 109 107 665 206 202 666 204 200 667 106 104 668 207 203 669 109 107 670 112 110 671 207 203 672 206 202 673 109 107 674 117 115 675 208 204 676 112 110 677 209 205 678 112 110 679 208 204 680 209 205 681 207 203 682 112 110 683 210 206 684 211 207 685 118 116 686 212 208 687 209 205 688 208 204 689 213 209 690 214 210 691 211 207 692 210 206 693 213 209 694 211 207 695 114 112 696 210 206 697 118 116 698 215 211 699 196 192 700 216 212 701 195 191 702 196 192 703 215 211 704 215 211 705 216 212 706 217 213 707 218 214 708 217 213 709 219 215 710 215 211 711 217 213 712 218 214 713 218 214 714 219 215 715 220 216 716 221 217 717 220 216 718 222 218 719 218 214 720 220 216 721 221 217 722 223 219 723 222 218 724 224 220 725 221 217 726 222 218 727 223 219 728 223 219 729 224 220 730 225 221 731 223 219 732 225 221 733 226 222 734 227 223 735 205 201 736 204 200 737 228 224 738 226 222 739 229 225 740 223 219 741 226 222 742 228 224 743 230 226 744 204 200 745 206 202 746 231 227 747 227 223 748 204 200 749 230 226 750 231 227 751 204 200 752 232 228 753 206 202 754 207 203 755 233 229 756 230 226 757 206 202 758 232 228 759 233 229 760 206 202 761 234 230 762 207 203 763 209 205 764 235 231 765 232 228 766 207 203 767 234 230 768 235 231 769 207 203 770 212 208 771 236 232 772 209 205 773 237 233 774 209 205 775 236 232 776 238 234 777 234 230 778 209 205 779 237 233 780 238 234 781 209 205 782 239 235 783 240 236 784 214 210 785 241 237 786 237 233 787 236 232 788 242 238 789 241 237 790 236 232 791 243 239 792 244 240 793 240 236 794 239 235 795 243 239 796 240 236 797 213 209 798 239 235 799 214 210 800 228 224 801 229 225 802 245 241 803 246 242 804 245 241 805 247 243 806 228 224 807 245 241 808 246 242 809 246 242 810 247 243 811 248 244 812 249 245 813 248 244 814 250 246 815 246 242 816 248 244 817 249 245 818 249 245 819 250 246 820 251 247 821 252 248 822 251 247 823 253 249 824 249 245 825 251 247 826 252 248 827 254 250 828 253 249 829 255 251 830 252 248 831 253 249 832 254 250 833 254 250 834 255 251 835 256 252 836 257 253 837 256 252 838 258 254 839 254 250 840 256 252 841 257 253 842 242 238 843 259 255 844 241 237 845 257 253 846 258 254 847 260 256 848 261 257 849 262 258 850 244 240 851 263 259 852 264 260 853 262 258 854 265 261 855 262 258 856 264 260 857 261 257 858 263 259 859 262 258 860 266 262 861 260 256 862 267 263 863 257 253 864 260 256 865 266 262 866 243 239 867 261 257 868 244 240 869 268 264 870 123 121 871 269 265 872 268 264 873 122 120 874 123 121 875 270 266 876 125 123 877 126 124 878 271 267 879 269 265 880 272 268 881 271 267 882 268 264 883 269 265 884 273 269 885 126 124 886 124 122 887 274 270 888 270 266 889 126 124 890 275 271 891 274 270 892 126 124 893 273 269 894 275 271 895 126 124 896 276 272 897 124 122 898 127 125 899 276 272 900 273 269 901 124 122 902 277 273 903 127 125 904 128 126 905 277 273 906 276 272 907 127 125 908 278 274 909 128 126 910 129 127 911 279 275 912 277 273 913 128 126 914 280 276 915 279 275 916 128 126 917 281 277 918 280 276 919 128 126 920 282 278 921 281 277 922 128 126 923 278 274 924 282 278 925 128 126 926 283 279 927 284 280 928 285 281 929 283 279 930 286 282 931 284 280 932 287 283 933 285 281 934 288 284 935 287 283 936 283 279 937 285 281 938 289 285 939 288 284 940 290 286 941 289 285 942 287 283 943 288 284 944 291 287 945 292 288 946 293 289 947 289 285 948 290 286 949 294 290 950 295 291 951 293 289 952 296 292 953 295 291 954 291 287 955 293 289 956 297 293 957 296 292 958 298 294 959 297 293 960 295 291 961 296 292 962 299 295 963 132 130 964 136 134 965 297 293 966 298 294 967 300 296 968 301 297 969 136 134 970 137 135 971 302 298 972 299 295 973 136 134 974 303 299 975 302 298 976 136 134 977 304 300 978 303 299 979 136 134 980 305 301 981 304 300 982 136 134 983 301 297 984 305 301 985 136 134 986 306 302 987 137 135 988 138 136 989 306 302 990 301 297 991 137 135 992 307 303 993 138 136 994 139 137 995 307 303 996 306 302 997 138 136 998 308 304 999 139 137 1000 140 138 1001 308 304 1002 307 303 1003 139 137 1004 309 305 1005 140 138 1006 141 139 1007 309 305 1008 308 304 1009 140 138 1010 310 306 1011 141 139 1012 142 140 1013 310 306 1014 309 305 1015 141 139 1016 311 307 1017 142 140 1018 143 141 1019 311 307 1020 310 306 1021 142 140 1022 312 308 1023 143 141 1024 144 142 1025 312 308 1026 311 307 1027 143 141 1028 313 309 1029 144 142 1030 145 143 1031 313 309 1032 312 308 1033 144 142 1034 314 310 1035 145 143 1036 146 144 1037 314 310 1038 313 309 1039 145 143 1040 315 311 1041 146 144 1042 149 147 1043 315 311 1044 314 310 1045 146 144 1046 153 151 1047 316 312 1048 149 147 1049 317 313 1050 149 147 1051 316 312 1052 317 313 1053 315 311 1054 149 147 1055 154 152 1056 318 314 1057 155 153 1058 317 313 1059 316 312 1060 319 315 1061 320 316 1062 321 317 1063 318 314 1064 154 152 1065 320 316 1066 318 314 1067 322 318 1068 272 268 1069 323 319 1070 322 318 1071 271 267 1072 272 268 1073 324 320 1074 323 319 1075 325 321 1076 324 320 1077 322 318 1078 323 319 1079 326 322 1080 275 271 1081 273 269 1082 326 322 1083 327 323 1084 275 271 1085 328 324 1086 325 321 1087 329 325 1088 328 324 1089 324 320 1090 325 321 1091 330 326 1092 273 269 1093 276 272 1094 330 326 1095 326 322 1096 273 269 1097 331 327 1098 276 272 1099 277 273 1100 331 327 1101 330 326 1102 276 272 1103 332 328 1104 277 273 1105 279 275 1106 332 328 1107 331 327 1108 277 273 1109 333 329 1110 334 330 1111 335 331 1112 336 332 1113 332 328 1114 279 275 1115 333 329 1116 337 333 1117 334 330 1118 338 334 1119 335 331 1120 339 335 1121 338 334 1122 333 329 1123 335 331 1124 340 336 1125 339 335 1126 341 337 1127 340 336 1128 338 334 1129 339 335 1130 342 338 1131 341 337 1132 286 282 1133 342 338 1134 340 336 1135 341 337 1136 283 279 1137 342 338 1138 286 282 1139 326 322 1140 343 339 1141 327 323 1142 328 324 1143 329 325 1144 344 340 1145 345 341 1146 343 339 1147 326 322 1148 346 342 1149 344 340 1150 347 343 1151 346 342 1152 328 324 1153 344 340 1154 348 344 1155 326 322 1156 330 326 1157 349 345 1158 345 341 1159 326 322 1160 348 344 1161 349 345 1162 326 322 1163 350 346 1164 330 326 1165 331 327 1166 350 346 1167 348 344 1168 330 326 1169 351 347 1170 331 327 1171 332 328 1172 351 347 1173 350 346 1174 331 327 1175 352 348 1176 353 349 1177 332 328 1178 354 350 1179 332 328 1180 353 349 1181 355 351 1182 352 348 1183 332 328 1184 336 332 1185 355 351 1186 332 328 1187 354 350 1188 351 347 1189 332 328 1190 356 352 1191 357 353 1192 358 354 1193 359 355 1194 354 350 1195 353 349 1196 356 352 1197 360 356 1198 357 353 1199 361 357 1200 358 354 1201 362 358 1202 361 357 1203 356 352 1204 358 354 1205 363 359 1206 362 358 1207 337 333 1208 363 359 1209 361 357 1210 362 358 1211 333 329 1212 363 359 1213 337 333 1214 364 360 1215 347 343 1216 365 361 1217 364 360 1218 346 342 1219 347 343 1220 366 362 1221 349 345 1222 348 344 1223 366 362 1224 367 363 1225 349 345 1226 368 364 1227 365 361 1228 369 365 1229 368 364 1230 364 360 1231 365 361 1232 370 366 1233 348 344 1234 350 346 1235 370 366 1236 366 362 1237 348 344 1238 371 367 1239 350 346 1240 351 347 1241 371 367 1242 370 366 1243 350 346 1244 372 368 1245 351 347 1246 354 350 1247 372 368 1248 371 367 1249 351 347 1250 373 369 1251 374 370 1252 354 350 1253 375 371 1254 354 350 1255 374 370 1256 376 372 1257 373 369 1258 354 350 1259 359 355 1260 376 372 1261 354 350 1262 375 371 1263 372 368 1264 354 350 1265 377 373 1266 378 374 1267 374 370 1268 379 375 1269 374 370 1270 378 374 1271 380 376 1272 377 373 1273 374 370 1274 381 377 1275 380 376 1276 374 370 1277 382 378 1278 381 377 1279 374 370 1280 373 369 1281 382 378 1282 374 370 1283 379 375 1284 375 371 1285 374 370 1286 383 379 1287 384 380 1288 378 374 1289 385 381 1290 378 374 1291 384 380 1292 386 382 1293 383 379 1294 378 374 1295 387 383 1296 386 382 1297 378 374 1298 377 373 1299 387 383 1300 378 374 1301 385 381 1302 379 375 1303 378 374 1304 388 384 1305 389 385 1306 384 380 1307 390 386 1308 384 380 1309 389 385 1310 383 379 1311 388 384 1312 384 380 1313 390 386 1314 385 381 1315 384 380 1316 391 387 1317 392 388 1318 389 385 1319 393 389 1320 389 385 1321 392 388 1322 388 384 1323 391 387 1324 389 385 1325 393 389 1326 390 386 1327 389 385 1328 394 390 1329 395 391 1330 392 388 1331 396 392 1332 392 388 1333 395 391 1334 391 387 1335 394 390 1336 392 388 1337 396 392 1338 393 389 1339 392 388 1340 397 393 1341 398 394 1342 395 391 1343 399 395 1344 395 391 1345 398 394 1346 394 390 1347 397 393 1348 395 391 1349 399 395 1350 396 392 1351 395 391 1352 400 396 1353 401 397 1354 398 394 1355 402 398 1356 398 394 1357 401 397 1358 397 393 1359 400 396 1360 398 394 1361 402 398 1362 399 395 1363 398 394 1364 403 399 1365 404 400 1366 401 397 1367 405 401 1368 401 397 1369 404 400 1370 400 396 1371 403 399 1372 401 397 1373 405 401 1374 402 398 1375 401 397 1376 406 402 1377 407 403 1378 404 400 1379 408 404 1380 404 400 1381 407 403 1382 403 399 1383 406 402 1384 404 400 1385 408 404 1386 405 401 1387 404 400 1388 409 405 1389 410 406 1390 407 403 1391 411 407 1392 407 403 1393 410 406 1394 406 402 1395 409 405 1396 407 403 1397 412 408 1398 408 404 1399 407 403 1400 413 409 1401 412 408 1402 407 403 1403 414 410 1404 413 409 1405 407 403 1406 411 407 1407 414 410 1408 407 403 1409 415 411 1410 416 412 1411 410 406 1412 417 413 1413 410 406 1414 416 412 1415 409 405 1416 415 411 1417 410 406 1418 418 414 1419 411 407 1420 410 406 1421 419 415 1422 418 414 1423 410 406 1424 420 416 1425 419 415 1426 410 406 1427 421 417 1428 420 416 1429 410 406 1430 417 413 1431 421 417 1432 410 406 1433 422 418 1434 423 419 1435 416 412 1436 424 420 1437 416 412 1438 423 419 1439 415 411 1440 422 418 1441 416 412 1442 425 421 1443 417 413 1444 416 412 1445 426 422 1446 425 421 1447 416 412 1448 424 420 1449 426 422 1450 416 412 1451 427 423 1452 428 424 1453 423 419 1454 429 425 1455 423 419 1456 428 424 1457 422 418 1458 427 423 1459 423 419 1460 429 425 1461 424 420 1462 423 419 1463 430 426 1464 431 427 1465 428 424 1466 432 428 1467 428 424 1468 431 427 1469 433 429 1470 430 426 1471 428 424 1472 434 430 1473 433 429 1474 428 424 1475 427 423 1476 434 430 1477 428 424 1478 435 431 1479 429 425 1480 428 424 1481 436 432 1482 435 431 1483 428 424 1484 432 428 1485 436 432 1486 428 424 1487 437 433 1488 438 434 1489 439 435 1490 440 436 1491 432 428 1492 431 427 1493 441 437 1494 442 438 1495 438 434 1496 437 433 1497 441 437 1498 438 434 1499 437 433 1500 439 435 1501 443 439 1502 444 440 1503 433 429 1504 434 430 1505 445 441 1506 443 439 1507 446 442 1508 445 441 1509 437 433 1510 443 439 1511 315 311 1512 434 430 1513 427 423 1514 317 313 1515 434 430 1516 315 311 1517 447 443 1518 434 430 1519 317 313 1520 444 440 1521 434 430 1522 447 443 1523 314 310 1524 427 423 1525 422 418 1526 315 311 1527 427 423 1528 314 310 1529 313 309 1530 422 418 1531 415 411 1532 314 310 1533 422 418 1534 313 309 1535 312 308 1536 415 411 1537 409 405 1538 313 309 1539 415 411 1540 312 308 1541 311 307 1542 409 405 1543 406 402 1544 312 308 1545 409 405 1546 311 307 1547 310 306 1548 406 402 1549 403 399 1550 311 307 1551 406 402 1552 310 306 1553 309 305 1554 403 399 1555 400 396 1556 310 306 1557 403 399 1558 309 305 1559 308 304 1560 400 396 1561 397 393 1562 309 305 1563 400 396 1564 308 304 1565 307 303 1566 397 393 1567 394 390 1568 308 304 1569 397 393 1570 307 303 1571 306 302 1572 394 390 1573 391 387 1574 307 303 1575 394 390 1576 306 302 1577 301 297 1578 391 387 1579 388 384 1580 306 302 1581 391 387 1582 301 297 1583 448 444 1584 388 384 1585 383 379 1586 449 445 1587 301 297 1588 388 384 1589 450 446 1590 449 445 1591 388 384 1592 448 444 1593 450 446 1594 388 384 1595 451 447 1596 452 448 1597 453 449 1598 451 447 1599 454 450 1600 452 448 1601 455 451 1602 453 449 1603 456 452 1604 455 451 1605 451 447 1606 453 449 1607 457 453 1608 456 452 1609 458 454 1610 457 453 1611 455 451 1612 456 452 1613 459 455 1614 458 454 1615 460 456 1616 461 457 1617 457 453 1618 458 454 1619 459 455 1620 461 457 1621 458 454 1622 459 455 1623 460 456 1624 462 458 1625 463 459 1626 464 460 1627 465 461 1628 466 462 1629 459 455 1630 462 458 1631 467 463 1632 465 461 1633 468 464 1634 467 463 1635 463 459 1636 465 461 1637 469 465 1638 468 464 1639 470 466 1640 469 465 1641 467 463 1642 468 464 1643 471 467 1644 470 466 1645 360 356 1646 471 467 1647 469 465 1648 470 466 1649 356 352 1650 471 467 1651 360 356 1652 366 362 1653 472 468 1654 367 363 1655 473 469 1656 369 365 1657 474 470 1658 473 469 1659 368 364 1660 369 365 1661 475 471 1662 472 468 1663 366 362 1664 475 471 1665 476 472 1666 472 468 1667 477 473 1668 474 470 1669 478 474 1670 477 473 1671 473 469 1672 474 470 1673 479 475 1674 366 362 1675 370 366 1676 479 475 1677 475 471 1678 366 362 1679 480 476 1680 370 366 1681 371 367 1682 480 476 1683 479 475 1684 370 366 1685 481 477 1686 371 367 1687 372 368 1688 481 477 1689 480 476 1690 371 367 1691 482 478 1692 372 368 1693 375 371 1694 482 478 1695 481 477 1696 372 368 1697 483 479 1698 375 371 1699 379 375 1700 483 479 1701 482 478 1702 375 371 1703 484 480 1704 379 375 1705 385 381 1706 484 480 1707 483 479 1708 379 375 1709 485 481 1710 385 381 1711 390 386 1712 485 481 1713 484 480 1714 385 381 1715 486 482 1716 390 386 1717 393 389 1718 486 482 1719 485 481 1720 390 386 1721 487 483 1722 393 389 1723 396 392 1724 487 483 1725 486 482 1726 393 389 1727 487 483 1728 396 392 1729 399 395 1730 488 484 1731 399 395 1732 402 398 1733 488 484 1734 487 483 1735 399 395 1736 489 485 1737 402 398 1738 405 401 1739 489 485 1740 488 484 1741 402 398 1742 490 486 1743 405 401 1744 408 404 1745 490 486 1746 489 485 1747 405 401 1748 491 487 1749 408 404 1750 412 408 1751 491 487 1752 490 486 1753 408 404 1754 492 488 1755 493 489 1756 412 408 1757 494 490 1758 412 408 1759 493 489 1760 495 491 1761 492 488 1762 412 408 1763 496 492 1764 495 491 1765 412 408 1766 497 493 1767 496 492 1768 412 408 1769 498 494 1770 497 493 1771 412 408 1772 413 409 1773 498 494 1774 412 408 1775 494 490 1776 491 487 1777 412 408 1778 499 495 1779 500 496 1780 501 497 1781 502 498 1782 494 490 1783 493 489 1784 503 499 1785 504 500 1786 500 496 1787 503 499 1788 500 496 1789 499 495 1790 505 501 1791 501 497 1792 506 502 1793 499 495 1794 501 497 1795 505 501 1796 507 503 1797 506 502 1798 508 504 1799 505 501 1800 506 502 1801 507 503 1802 509 505 1803 508 504 1804 510 506 1805 507 503 1806 508 504 1807 509 505 1808 511 507 1809 510 506 1810 512 508 1811 509 505 1812 510 506 1813 511 507 1814 511 507 1815 512 508 1816 513 509 1817 514 510 1818 513 509 1819 515 511 1820 511 507 1821 513 509 1822 514 510 1823 516 512 1824 515 511 1825 517 513 1826 514 510 1827 515 511 1828 516 512 1829 516 512 1830 517 513 1831 518 514 1832 519 515 1833 518 514 1834 520 516 1835 516 512 1836 518 514 1837 519 515 1838 519 515 1839 520 516 1840 521 517 1841 522 518 1842 521 517 1843 523 519 1844 519 515 1845 521 517 1846 522 518 1847 524 520 1848 523 519 1849 525 521 1850 522 518 1851 523 519 1852 524 520 1853 526 522 1854 525 521 1855 527 523 1856 524 520 1857 525 521 1858 526 522 1859 526 522 1860 527 523 1861 528 524 1862 529 525 1863 530 526 1864 531 527 1865 532 528 1866 530 526 1867 529 525 1868 526 522 1869 528 524 1870 533 529 1871 534 9 1872 535 9 1873 536 9 1874 537 9 1875 535 9 1876 534 9 1877 538 9 1878 535 9 1879 537 9 1880 539 530 1881 436 432 1882 432 428 1883 540 531 1884 436 432 1885 539 530 1886 440 436 1887 541 532 1888 432 428 1889 539 530 1890 432 428 1891 541 532 1892 441 437 1893 542 533 1894 442 438 1895 543 534 1896 539 530 1897 541 532 1898 544 535 1899 545 536 1900 542 533 1901 441 437 1902 544 535 1903 542 533 1904 475 471 1905 546 537 1906 476 472 1907 547 538 1908 478 474 1909 548 539 1910 547 538 1911 477 473 1912 478 474 1913 549 540 1914 546 537 1915 475 471 1916 549 540 1917 550 541 1918 546 537 1919 551 542 1920 548 539 1921 552 543 1922 551 542 1923 547 538 1924 548 539 1925 553 544 1926 475 471 1927 479 475 1928 553 544 1929 549 540 1930 475 471 1931 554 545 1932 479 475 1933 480 476 1934 554 545 1935 553 544 1936 479 475 1937 555 546 1938 480 476 1939 481 477 1940 555 546 1941 554 545 1942 480 476 1943 556 547 1944 481 477 1945 482 478 1946 556 547 1947 555 546 1948 481 477 1949 557 548 1950 482 478 1951 483 479 1952 557 548 1953 556 547 1954 482 478 1955 558 549 1956 483 479 1957 484 480 1958 558 549 1959 557 548 1960 483 479 1961 559 550 1962 484 480 1963 485 481 1964 559 550 1965 558 549 1966 484 480 1967 560 551 1968 485 481 1969 486 482 1970 560 551 1971 559 550 1972 485 481 1973 561 552 1974 486 482 1975 487 483 1976 561 552 1977 560 551 1978 486 482 1979 562 553 1980 487 483 1981 488 484 1982 562 553 1983 561 552 1984 487 483 1985 563 554 1986 488 484 1987 489 485 1988 563 554 1989 562 553 1990 488 484 1991 564 555 1992 489 485 1993 490 486 1994 564 555 1995 563 554 1996 489 485 1997 565 556 1998 490 486 1999 491 487 2000 565 556 2001 564 555 2002 490 486 2003 566 557 2004 491 487 2005 494 490 2006 566 557 2007 565 556 2008 491 487 2009 502 498 2010 567 558 2011 494 490 2012 568 559 2013 494 490 2014 567 558 2015 568 559 2016 566 557 2017 494 490 2018 569 560 2019 570 561 2020 567 558 2021 571 562 2022 567 558 2023 570 561 2024 572 563 2025 569 560 2026 567 558 2027 502 498 2028 572 563 2029 567 558 2030 571 562 2031 568 559 2032 567 558 2033 573 564 2034 574 565 2035 570 561 2036 575 566 2037 570 561 2038 574 565 2039 569 560 2040 573 564 2041 570 561 2042 575 566 2043 571 562 2044 570 561 2045 540 531 2046 539 530 2047 574 565 2048 576 567 2049 574 565 2050 539 530 2051 573 564 2052 540 531 2053 574 565 2054 576 567 2055 575 566 2056 574 565 2057 543 534 2058 577 568 2059 539 530 2060 576 567 2061 539 530 2062 577 568 2063 544 535 2064 578 569 2065 545 536 2066 579 570 2067 576 567 2068 577 568 2069 580 571 2070 581 572 2071 578 569 2072 544 535 2073 580 571 2074 578 569 2075 582 573 2076 583 574 2077 584 575 2078 585 9 2079 538 9 2080 537 9 2081 582 573 2082 584 575 2083 586 576 2084 587 577 2085 588 578 2086 589 579 2087 590 580 2088 589 579 2089 504 500 2090 591 581 2091 589 579 2092 590 580 2093 587 577 2094 589 579 2095 591 581 2096 590 580 2097 504 500 2098 503 499 2099 549 540 2100 592 582 2101 550 541 2102 593 583 2103 552 543 2104 594 584 2105 593 583 2106 551 542 2107 552 543 2108 595 585 2109 592 582 2110 549 540 2111 595 585 2112 596 586 2113 592 582 2114 597 587 2115 594 584 2116 598 588 2117 597 587 2118 593 583 2119 594 584 2120 599 589 2121 549 540 2122 553 544 2123 599 589 2124 595 585 2125 549 540 2126 600 590 2127 553 544 2128 554 545 2129 600 590 2130 599 589 2131 553 544 2132 601 591 2133 554 545 2134 555 546 2135 601 591 2136 600 590 2137 554 545 2138 602 592 2139 555 546 2140 556 547 2141 602 592 2142 601 591 2143 555 546 2144 603 593 2145 556 547 2146 557 548 2147 603 593 2148 602 592 2149 556 547 2150 604 594 2151 557 548 2152 558 549 2153 604 594 2154 603 593 2155 557 548 2156 605 595 2157 558 549 2158 559 550 2159 605 595 2160 604 594 2161 558 549 2162 606 596 2163 559 550 2164 560 551 2165 606 596 2166 605 595 2167 559 550 2168 607 597 2169 560 551 2170 561 552 2171 607 597 2172 606 596 2173 560 551 2174 608 598 2175 561 552 2176 562 553 2177 608 598 2178 607 597 2179 561 552 2180 609 599 2181 562 553 2182 563 554 2183 609 599 2184 608 598 2185 562 553 2186 610 600 2187 563 554 2188 564 555 2189 610 600 2190 609 599 2191 563 554 2192 611 601 2193 564 555 2194 565 556 2195 611 601 2196 610 600 2197 564 555 2198 612 602 2199 565 556 2200 566 557 2201 612 602 2202 611 601 2203 565 556 2204 613 603 2205 566 557 2206 568 559 2207 613 603 2208 612 602 2209 566 557 2210 614 604 2211 568 559 2212 571 562 2213 614 604 2214 613 603 2215 568 559 2216 615 605 2217 571 562 2218 575 566 2219 615 605 2220 614 604 2221 571 562 2222 616 606 2223 575 566 2224 576 567 2225 616 606 2226 615 605 2227 575 566 2228 579 570 2229 617 607 2230 576 567 2231 618 608 2232 576 567 2233 617 607 2234 618 608 2235 616 606 2236 576 567 2237 580 571 2238 619 609 2239 581 572 2240 620 610 2241 618 608 2242 617 607 2243 621 611 2244 622 612 2245 619 609 2246 580 571 2247 621 611 2248 619 609 2249 595 585 2250 623 613 2251 596 586 2252 624 614 2253 598 588 2254 625 615 2255 624 614 2256 597 587 2257 598 588 2258 595 585 2259 626 616 2260 623 613 2261 627 617 2262 625 615 2263 628 618 2264 627 617 2265 624 614 2266 625 615 2267 629 619 2268 626 616 2269 595 585 2270 630 620 2271 631 621 2272 626 616 2273 632 622 2274 628 618 2275 633 623 2276 629 619 2277 630 620 2278 626 616 2279 632 622 2280 627 617 2281 628 618 2282 634 624 2283 595 585 2284 599 589 2285 634 624 2286 629 619 2287 595 585 2288 635 625 2289 599 589 2290 600 590 2291 635 625 2292 634 624 2293 599 589 2294 636 626 2295 600 590 2296 601 591 2297 636 626 2298 635 625 2299 600 590 2300 637 627 2301 601 591 2302 602 592 2303 637 627 2304 636 626 2305 601 591 2306 638 628 2307 602 592 2308 603 593 2309 638 628 2310 637 627 2311 602 592 2312 639 629 2313 603 593 2314 604 594 2315 639 629 2316 638 628 2317 603 593 2318 640 630 2319 604 594 2320 605 595 2321 640 630 2322 639 629 2323 604 594 2324 641 631 2325 605 595 2326 606 596 2327 641 631 2328 640 630 2329 605 595 2330 642 632 2331 606 596 2332 607 597 2333 642 632 2334 641 631 2335 606 596 2336 643 633 2337 607 597 2338 608 598 2339 643 633 2340 642 632 2341 607 597 2342 644 634 2343 608 598 2344 609 599 2345 644 634 2346 643 633 2347 608 598 2348 645 635 2349 609 599 2350 610 600 2351 645 635 2352 644 634 2353 609 599 2354 646 636 2355 610 600 2356 611 601 2357 646 636 2358 645 635 2359 610 600 2360 647 637 2361 611 601 2362 612 602 2363 647 637 2364 646 636 2365 611 601 2366 648 638 2367 612 602 2368 613 603 2369 649 639 2370 647 637 2371 612 602 2372 650 640 2373 649 639 2374 612 602 2375 651 641 2376 650 640 2377 612 602 2378 648 638 2379 651 641 2380 612 602 2381 652 642 2382 613 603 2383 614 604 2384 653 643 2385 648 638 2386 613 603 2387 652 642 2388 653 643 2389 613 603 2390 654 644 2391 614 604 2392 615 605 2393 654 644 2394 652 642 2395 614 604 2396 655 645 2397 615 605 2398 616 606 2399 655 645 2400 654 644 2401 615 605 2402 656 646 2403 616 606 2404 618 608 2405 656 646 2406 655 645 2407 616 606 2408 620 610 2409 657 647 2410 618 608 2411 658 648 2412 618 608 2413 657 647 2414 658 648 2415 656 646 2416 618 608 2417 621 611 2418 659 649 2419 622 612 2420 660 650 2421 658 648 2422 657 647 2423 661 651 2424 662 652 2425 659 649 2426 621 611 2427 661 651 2428 659 649 2429 630 620 2430 663 653 2431 631 621 2432 664 654 2433 633 623 2434 665 655 2435 664 654 2436 632 622 2437 633 623 2438 666 656 2439 663 653 2440 630 620 2441 667 657 2442 668 658 2443 663 653 2444 669 659 2445 665 655 2446 670 660 2447 666 656 2448 667 657 2449 663 653 2450 671 661 2451 664 654 2452 665 655 2453 672 662 2454 671 661 2455 665 655 2456 673 663 2457 672 662 2458 665 655 2459 674 664 2460 673 663 2461 665 655 2462 675 665 2463 674 664 2464 665 655 2465 669 659 2466 675 665 2467 665 655 2468 676 666 2469 630 620 2470 629 619 2471 677 667 2472 666 656 2473 630 620 2474 678 668 2475 677 667 2476 630 620 2477 679 669 2478 678 668 2479 630 620 2480 680 670 2481 679 669 2482 630 620 2483 681 671 2484 680 670 2485 630 620 2486 682 672 2487 681 671 2488 630 620 2489 683 673 2490 682 672 2491 630 620 2492 684 674 2493 683 673 2494 630 620 2495 676 666 2496 684 674 2497 630 620 2498 685 675 2499 629 619 2500 634 624 2501 685 675 2502 676 666 2503 629 619 2504 686 676 2505 634 624 2506 635 625 2507 686 676 2508 685 675 2509 634 624 2510 687 677 2511 635 625 2512 636 626 2513 687 677 2514 686 676 2515 635 625 2516 688 678 2517 636 626 2518 637 627 2519 688 678 2520 687 677 2521 636 626 2522 689 679 2523 637 627 2524 638 628 2525 689 679 2526 688 678 2527 637 627 2528 690 680 2529 638 628 2530 639 629 2531 690 680 2532 689 679 2533 638 628 2534 691 681 2535 639 629 2536 640 630 2537 691 681 2538 690 680 2539 639 629 2540 692 682 2541 640 630 2542 641 631 2543 692 682 2544 691 681 2545 640 630 2546 693 683 2547 641 631 2548 642 632 2549 693 683 2550 692 682 2551 641 631 2552 694 684 2553 642 632 2554 643 633 2555 694 684 2556 693 683 2557 642 632 2558 695 685 2559 643 633 2560 644 634 2561 695 685 2562 694 684 2563 643 633 2564 696 686 2565 644 634 2566 645 635 2567 696 686 2568 695 685 2569 644 634 2570 696 686 2571 645 635 2572 646 636 2573 697 687 2574 646 636 2575 647 637 2576 698 688 2577 696 686 2578 646 636 2579 699 689 2580 698 688 2581 646 636 2582 700 690 2583 699 689 2584 646 636 2585 697 687 2586 700 690 2587 646 636 2588 701 691 2589 702 692 2590 703 693 2591 701 691 2592 704 694 2593 702 692 2594 705 695 2595 703 693 2596 706 696 2597 701 691 2598 703 693 2599 705 695 2600 707 697 2601 706 696 2602 708 698 2603 705 695 2604 706 696 2605 707 697 2606 707 697 2607 708 698 2608 709 699 2609 707 697 2610 709 699 2611 710 700 2612 711 701 2613 653 643 2614 652 642 2615 712 702 2616 710 700 2617 713 703 2618 707 697 2619 710 700 2620 712 702 2621 714 704 2622 652 642 2623 654 644 2624 715 705 2625 711 701 2626 652 642 2627 716 706 2628 715 705 2629 652 642 2630 714 704 2631 716 706 2632 652 642 2633 717 707 2634 654 644 2635 655 645 2636 717 707 2637 714 704 2638 654 644 2639 718 708 2640 655 645 2641 656 646 2642 719 709 2643 717 707 2644 655 645 2645 718 708 2646 719 709 2647 655 645 2648 720 710 2649 656 646 2650 658 648 2651 721 711 2652 656 646 2653 720 710 2654 718 708 2655 656 646 2656 721 711 2657 660 650 2658 722 712 2659 658 648 2660 723 713 2661 658 648 2662 722 712 2663 720 710 2664 658 648 2665 723 713 2666 661 651 2667 724 714 2668 662 652 2669 725 715 2670 723 713 2671 722 712 2672 726 716 2673 727 717 2674 724 714 2675 661 651 2676 726 716 2677 724 714 2678 728 718 2679 729 719 2680 730 720 2681 669 659 2682 670 660 2683 731 721 2684 728 718 2685 732 722 2686 729 719 2687 733 723 2688 730 720 2689 734 724 2690 728 718 2691 730 720 2692 733 723 2693 733 723 2694 734 724 2695 735 725 2696 736 726 2697 735 725 2698 737 727 2699 733 723 2700 735 725 2701 736 726 2702 736 726 2703 737 727 2704 738 728 2705 739 729 2706 738 728 2707 740 730 2708 736 726 2709 738 728 2710 739 729 2711 739 729 2712 740 730 2713 741 731 2714 742 732 2715 741 731 2716 743 733 2717 739 729 2718 741 731 2719 742 732 2720 742 732 2721 743 733 2722 744 734 2723 684 674 2724 745 735 2725 683 673 2726 746 736 2727 744 734 2728 747 737 2729 742 732 2730 744 734 2731 746 736 2732 684 674 2733 748 738 2734 745 735 2735 746 736 2736 747 737 2737 749 739 2738 684 674 2739 750 740 2740 748 738 2741 751 741 2742 749 739 2743 752 742 2744 746 736 2745 749 739 2746 751 741 2747 684 674 2748 753 743 2749 750 740 2750 751 741 2751 752 742 2752 754 744 2753 684 674 2754 755 745 2755 753 743 2756 756 746 2757 754 744 2758 757 747 2759 751 741 2760 754 744 2761 756 746 2762 684 674 2763 758 748 2764 755 745 2765 759 749 2766 757 747 2767 760 750 2768 756 746 2769 757 747 2770 759 749 2771 684 674 2772 761 751 2773 758 748 2774 762 752 2775 763 753 2776 764 754 2777 765 755 2778 763 753 2779 762 752 2780 766 756 2781 763 753 2782 765 755 2783 767 757 2784 763 753 2785 766 756 2786 759 749 2787 760 750 2788 768 758 2789 769 759 2790 761 751 2791 684 674 2792 762 752 2793 764 754 2794 770 760 2795 771 761 2796 772 762 2797 761 751 2798 769 759 2799 771 761 2800 761 751 2801 773 763 2802 684 674 2803 676 666 2804 773 763 2805 769 759 2806 684 674 2807 774 764 2808 676 666 2809 685 675 2810 774 764 2811 773 763 2812 676 666 2813 775 765 2814 685 675 2815 686 676 2816 775 765 2817 774 764 2818 685 675 2819 776 766 2820 686 676 2821 687 677 2822 776 766 2823 775 765 2824 686 676 2825 777 767 2826 687 677 2827 688 678 2828 777 767 2829 776 766 2830 687 677 2831 778 768 2832 688 678 2833 689 679 2834 778 768 2835 777 767 2836 688 678 2837 779 769 2838 689 679 2839 690 680 2840 779 769 2841 778 768 2842 689 679 2843 780 770 2844 690 680 2845 691 681 2846 780 770 2847 779 769 2848 690 680 2849 781 771 2850 691 681 2851 692 682 2852 781 771 2853 780 770 2854 691 681 2855 782 772 2856 692 682 2857 693 683 2858 782 772 2859 781 771 2860 692 682 2861 783 773 2862 693 683 2863 694 684 2864 783 773 2865 782 772 2866 693 683 2867 784 774 2868 694 684 2869 695 685 2870 784 774 2871 783 773 2872 694 684 2873 785 775 2874 695 685 2875 696 686 2876 785 775 2877 784 774 2878 695 685 2879 786 776 2880 696 686 2881 698 688 2882 786 776 2883 785 775 2884 696 686 2885 787 777 2886 788 778 2887 698 688 2888 789 779 2889 698 688 2890 788 778 2891 790 780 2892 787 777 2893 698 688 2894 791 781 2895 790 780 2896 698 688 2897 792 782 2898 791 781 2899 698 688 2900 699 689 2901 792 782 2902 698 688 2903 789 779 2904 786 776 2905 698 688 2906 793 783 2907 794 784 2908 788 778 2909 795 785 2910 788 778 2911 794 784 2912 796 786 2913 793 783 2914 788 778 2915 797 787 2916 796 786 2917 788 778 2918 798 788 2919 797 787 2920 788 778 2921 787 777 2922 798 788 2923 788 778 2924 795 785 2925 789 779 2926 788 778 2927 799 789 2928 800 790 2929 801 791 2930 802 792 2931 795 785 2932 794 784 2933 803 793 2934 802 792 2935 794 784 2936 799 789 2937 804 794 2938 800 790 2939 805 795 2940 806 796 2941 807 797 2942 808 798 2943 807 797 2944 809 799 2945 810 800 2946 807 797 2947 808 798 2948 805 795 2949 807 797 2950 810 800 2951 811 801 2952 809 799 2953 812 802 2954 808 798 2955 809 799 2956 811 801 2957 811 801 2958 812 802 2959 813 803 2960 814 804 2961 813 803 2962 815 805 2963 811 801 2964 813 803 2965 814 804 2966 814 804 2967 815 805 2968 816 806 2969 817 807 2970 816 806 2971 818 808 2972 814 804 2973 816 806 2974 817 807 2975 819 809 2976 818 808 2977 820 810 2978 817 807 2979 818 808 2980 819 809 2981 819 809 2982 820 810 2983 821 811 2984 701 691 2985 821 811 2986 704 694 2987 819 809 2988 821 811 2989 701 691 2990 771 761 2991 822 812 2992 772 762 2993 823 813 2994 824 814 2995 822 812 2996 771 761 2997 823 813 2998 822 812 2999 825 815 3000 826 816 3001 824 814 3002 823 813 3003 825 815 3004 824 814 3005 827 9 3006 828 9 3007 829 9 3008 825 815 3009 830 817 3010 826 816 3011 831 9 3012 828 9 3013 827 9 3014 832 818 3015 833 819 3016 830 817 3017 825 815 3018 832 818 3019 830 817 3020 832 818 3021 834 820 3022 833 819 3023 835 821 3024 836 822 3025 837 823 3026 838 824 3027 836 822 3028 835 821 3029 839 9 3030 840 9 3031 831 9 3032 831 9 3033 827 9 3034 839 9 3035 832 818 3036 841 825 3037 834 820 3038 842 826 3039 837 823 3040 843 827 3041 842 826 3042 835 821 3043 837 823 3044 844 828 3045 845 829 3046 841 825 3047 846 830 3048 843 827 3049 847 831 3050 832 818 3051 844 828 3052 841 825 3053 846 830 3054 842 826 3055 843 827 3056 848 832 3057 849 833 3058 845 829 3059 846 830 3060 847 831 3061 850 834 3062 844 828 3063 848 832 3064 845 829 3065 851 835 3066 852 836 3067 853 837 3068 851 835 3069 854 838 3070 852 836 3071 855 839 3072 856 840 3073 857 841 3074 846 830 3075 850 834 3076 858 842 3077 859 843 3078 848 832 3079 844 828 3080 860 844 3081 853 837 3082 861 845 3083 860 844 3084 851 835 3085 853 837 3086 862 846 3087 844 828 3088 832 818 3089 863 847 3090 859 843 3091 844 828 3092 862 846 3093 863 847 3094 844 828 3095 864 848 3096 832 818 3097 825 815 3098 864 848 3099 862 846 3100 832 818 3101 865 849 3102 825 815 3103 823 813 3104 865 849 3105 864 848 3106 825 815 3107 866 850 3108 823 813 3109 771 761 3110 866 850 3111 865 849 3112 823 813 3113 867 851 3114 771 761 3115 769 759 3116 867 851 3117 866 850 3118 771 761 3119 868 852 3120 769 759 3121 773 763 3122 868 852 3123 867 851 3124 769 759 3125 869 853 3126 773 763 3127 774 764 3128 869 853 3129 868 852 3130 773 763 3131 870 854 3132 774 764 3133 775 765 3134 870 854 3135 869 853 3136 774 764 3137 871 855 3138 775 765 3139 776 766 3140 871 855 3141 870 854 3142 775 765 3143 872 856 3144 776 766 3145 777 767 3146 872 856 3147 871 855 3148 776 766 3149 873 857 3150 777 767 3151 778 768 3152 873 857 3153 872 856 3154 777 767 3155 874 858 3156 778 768 3157 779 769 3158 874 858 3159 873 857 3160 778 768 3161 875 859 3162 779 769 3163 780 770 3164 875 859 3165 874 858 3166 779 769 3167 876 860 3168 780 770 3169 781 771 3170 877 861 3171 875 859 3172 780 770 3173 878 862 3174 877 861 3175 780 770 3176 879 863 3177 878 862 3178 780 770 3179 880 864 3180 879 863 3181 780 770 3182 881 865 3183 880 864 3184 780 770 3185 882 866 3186 881 865 3187 780 770 3188 876 860 3189 882 866 3190 780 770 3191 883 867 3192 781 771 3193 782 772 3194 884 868 3195 876 860 3196 781 771 3197 885 869 3198 884 868 3199 781 771 3200 886 870 3201 885 869 3202 781 771 3203 887 871 3204 886 870 3205 781 771 3206 888 872 3207 887 871 3208 781 771 3209 889 9 3210 890 9 3211 891 9 3212 883 867 3213 888 872 3214 781 771 3215 892 873 3216 782 772 3217 783 773 3218 892 873 3219 883 867 3220 782 772 3221 893 874 3222 783 773 3223 784 774 3224 893 874 3225 892 873 3226 783 773 3227 894 875 3228 784 774 3229 785 775 3230 894 875 3231 893 874 3232 784 774 3233 895 876 3234 785 775 3235 786 776 3236 895 876 3237 894 875 3238 785 775 3239 896 877 3240 786 776 3241 789 779 3242 896 877 3243 895 876 3244 786 776 3245 897 878 3246 789 779 3247 795 785 3248 897 878 3249 896 877 3250 789 779 3251 898 879 3252 795 785 3253 802 792 3254 898 879 3255 897 878 3256 795 785 3257 899 880 3258 900 881 3259 802 792 3260 901 882 3261 802 792 3262 900 881 3263 803 793 3264 899 880 3265 802 792 3266 901 882 3267 898 879 3268 802 792 3269 902 883 3270 903 884 3271 900 881 3272 904 885 3273 900 881 3274 903 884 3275 899 880 3276 902 883 3277 900 881 3278 904 885 3279 901 882 3280 900 881 3281 721 711 3282 905 886 3283 903 884 3284 906 887 3285 903 884 3286 905 886 3287 907 888 3288 721 711 3289 903 884 3290 908 889 3291 907 888 3292 903 884 3293 902 883 3294 908 889 3295 903 884 3296 906 887 3297 904 885 3298 903 884 3299 720 710 3300 909 890 3301 905 886 3302 910 891 3303 905 886 3304 909 890 3305 721 711 3306 720 710 3307 905 886 3308 910 891 3309 906 887 3310 905 886 3311 911 892 3312 912 893 3313 909 890 3314 910 891 3315 909 890 3316 912 893 3317 913 894 3318 911 892 3319 909 890 3320 723 713 3321 913 894 3322 909 890 3323 720 710 3324 723 713 3325 909 890 3326 914 895 3327 915 896 3328 916 897 3329 917 898 3330 910 891 3331 912 893 3332 918 899 3333 919 900 3334 915 896 3335 918 899 3336 915 896 3337 914 895 3338 914 895 3339 916 897 3340 920 901 3341 725 715 3342 913 894 3343 723 713 3344 726 716 3345 920 901 3346 727 717 3347 726 716 3348 914 895 3349 920 901 3350 921 9 3351 922 9 3352 923 9 3353 924 9 3354 925 9 3355 922 9 3356 921 9 3357 924 9 3358 922 9 3359 921 9 3360 923 9 3361 926 9 3362 799 789 3363 927 902 3364 928 903 3365 799 789 3366 928 903 3367 929 904 3368 799 789 3369 929 904 3370 804 794 3371 860 844 3372 861 845 3373 930 905 3374 931 906 3375 863 847 3376 862 846 3377 932 907 3378 930 905 3379 933 908 3380 932 907 3381 860 844 3382 930 905 3383 934 909 3384 862 846 3385 864 848 3386 935 910 3387 931 906 3388 862 846 3389 936 911 3390 935 910 3391 862 846 3392 934 909 3393 936 911 3394 862 846 3395 937 912 3396 864 848 3397 865 849 3398 937 912 3399 934 909 3400 864 848 3401 938 913 3402 865 849 3403 866 850 3404 938 913 3405 937 912 3406 865 849 3407 939 914 3408 866 850 3409 867 851 3410 939 914 3411 938 913 3412 866 850 3413 940 915 3414 867 851 3415 868 852 3416 940 915 3417 939 914 3418 867 851 3419 941 916 3420 868 852 3421 869 853 3422 941 916 3423 940 915 3424 868 852 3425 942 917 3426 869 853 3427 870 854 3428 942 917 3429 941 916 3430 869 853 3431 943 918 3432 870 854 3433 871 855 3434 943 918 3435 942 917 3436 870 854 3437 944 919 3438 871 855 3439 872 856 3440 944 919 3441 943 918 3442 871 855 3443 945 920 3444 872 856 3445 873 857 3446 945 920 3447 944 919 3448 872 856 3449 946 921 3450 873 857 3451 874 858 3452 946 921 3453 945 920 3454 873 857 3455 947 922 3456 874 858 3457 875 859 3458 948 923 3459 946 921 3460 874 858 3461 949 924 3462 948 923 3463 874 858 3464 947 922 3465 949 924 3466 874 858 3467 950 925 3468 951 926 3469 952 927 3470 950 925 3471 953 928 3472 951 926 3473 950 925 3474 952 927 3475 954 929 3476 955 930 3477 954 929 3478 956 931 3479 950 925 3480 954 929 3481 955 930 3482 957 932 3483 956 931 3484 958 933 3485 955 930 3486 956 931 3487 957 932 3488 957 932 3489 958 933 3490 959 934 3491 960 935 3492 959 934 3493 961 936 3494 957 932 3495 959 934 3496 960 935 3497 960 935 3498 961 936 3499 962 937 3500 963 938 3501 962 937 3502 964 939 3503 960 935 3504 962 937 3505 963 938 3506 963 938 3507 964 939 3508 965 940 3509 966 941 3510 965 940 3511 967 942 3512 963 938 3513 965 940 3514 966 941 3515 968 943 3516 967 942 3517 969 944 3518 966 941 3519 967 942 3520 968 943 3521 968 943 3522 969 944 3523 970 945 3524 971 946 3525 972 947 3526 889 9 3527 973 948 3528 888 872 3529 883 867 3530 974 949 3531 970 945 3532 975 950 3533 968 943 3534 970 945 3535 974 949 3536 976 951 3537 883 867 3538 892 873 3539 977 952 3540 973 948 3541 883 867 3542 978 953 3543 977 952 3544 883 867 3545 979 954 3546 978 953 3547 883 867 3548 976 951 3549 979 954 3550 883 867 3551 980 955 3552 892 873 3553 893 874 3554 980 955 3555 976 951 3556 892 873 3557 981 956 3558 893 874 3559 894 875 3560 981 956 3561 980 955 3562 893 874 3563 982 957 3564 894 875 3565 895 876 3566 982 957 3567 981 956 3568 894 875 3569 983 958 3570 895 876 3571 896 877 3572 983 958 3573 982 957 3574 895 876 3575 984 959 3576 896 877 3577 897 878 3578 984 959 3579 983 958 3580 896 877 3581 985 960 3582 897 878 3583 898 879 3584 985 960 3585 984 959 3586 897 878 3587 986 961 3588 898 879 3589 901 882 3590 986 961 3591 985 960 3592 898 879 3593 987 962 3594 901 882 3595 904 885 3596 987 962 3597 986 961 3598 901 882 3599 988 963 3600 904 885 3601 906 887 3602 988 963 3603 987 962 3604 904 885 3605 989 964 3606 906 887 3607 910 891 3608 989 964 3609 988 963 3610 906 887 3611 917 898 3612 990 965 3613 910 891 3614 991 966 3615 910 891 3616 990 965 3617 991 966 3618 989 964 3619 910 891 3620 918 899 3621 992 967 3622 919 900 3623 991 966 3624 990 965 3625 993 968 3626 994 969 3627 995 970 3628 992 967 3629 994 969 3630 992 967 3631 918 899 3632 932 907 3633 933 908 3634 996 971 3635 997 972 3636 935 910 3637 936 911 3638 998 973 3639 996 971 3640 999 974 3641 998 973 3642 932 907 3643 996 971 3644 1000 975 3645 936 911 3646 934 909 3647 1001 976 3648 997 972 3649 936 911 3650 1000 975 3651 1001 976 3652 936 911 3653 1002 977 3654 934 909 3655 937 912 3656 1002 977 3657 1000 975 3658 934 909 3659 1003 978 3660 937 912 3661 938 913 3662 1003 978 3663 1002 977 3664 937 912 3665 1004 979 3666 938 913 3667 939 914 3668 1004 979 3669 1003 978 3670 938 913 3671 1005 980 3672 939 914 3673 940 915 3674 1005 980 3675 1004 979 3676 939 914 3677 1006 981 3678 940 915 3679 941 916 3680 1006 981 3681 1005 980 3682 940 915 3683 1007 982 3684 941 916 3685 942 917 3686 1007 982 3687 1006 981 3688 941 916 3689 1008 983 3690 942 917 3691 943 918 3692 1008 983 3693 1007 982 3694 942 917 3695 1009 984 3696 943 918 3697 944 919 3698 1009 984 3699 1008 983 3700 943 918 3701 1010 985 3702 944 919 3703 945 920 3704 1010 985 3705 1009 984 3706 944 919 3707 1011 986 3708 945 920 3709 946 921 3710 1011 986 3711 1010 985 3712 945 920 3713 1012 987 3714 946 921 3715 948 923 3716 1012 987 3717 1011 986 3718 946 921 3719 949 924 3720 1013 988 3721 948 923 3722 1014 989 3723 1015 989 3724 1016 989 3725 1017 990 3726 1012 987 3727 948 923 3728 1014 989 3729 1018 989 3730 1015 989 3731 1019 991 3732 1020 992 3733 1021 993 3734 1022 994 3735 1021 993 3736 953 928 3737 1019 991 3738 1021 993 3739 1022 994 3740 1022 994 3741 953 928 3742 950 925 3743 998 973 3744 999 974 3745 1023 995 3746 1024 996 3747 1001 976 3748 1000 975 3749 1025 997 3750 1023 995 3751 1026 998 3752 1025 997 3753 998 973 3754 1023 995 3755 1027 999 3756 1000 975 3757 1002 977 3758 1028 1000 3759 1024 996 3760 1000 975 3761 1029 1001 3762 1028 1000 3763 1000 975 3764 1027 999 3765 1029 1001 3766 1000 975 3767 1030 1002 3768 1002 977 3769 1003 978 3770 1030 1002 3771 1027 999 3772 1002 977 3773 1031 1003 3774 1003 978 3775 1004 979 3776 1031 1003 3777 1030 1002 3778 1003 978 3779 1032 1004 3780 1004 979 3781 1005 980 3782 1032 1004 3783 1031 1003 3784 1004 979 3785 1033 1005 3786 1005 980 3787 1006 981 3788 1033 1005 3789 1032 1004 3790 1005 980 3791 1034 1006 3792 1006 981 3793 1007 982 3794 1034 1006 3795 1033 1005 3796 1006 981 3797 1035 1007 3798 1007 982 3799 1008 983 3800 1035 1007 3801 1034 1006 3802 1007 982 3803 1036 1008 3804 1008 983 3805 1009 984 3806 1036 1008 3807 1035 1007 3808 1008 983 3809 1037 1009 3810 1009 984 3811 1010 985 3812 1037 1009 3813 1036 1008 3814 1009 984 3815 1038 1010 3816 1010 985 3817 1011 986 3818 1038 1010 3819 1037 1009 3820 1010 985 3821 1039 1011 3822 1011 986 3823 1012 987 3824 1039 1011 3825 1038 1010 3826 1011 986 3827 1014 989 3828 1040 989 3829 1018 989 3830 1014 989 3831 1041 989 3832 1040 989 3833 1025 997 3834 1026 998 3835 1042 1012 3836 1043 1013 3837 1028 1000 3838 1029 1001 3839 1044 1014 3840 1042 1012 3841 1045 1015 3842 1025 997 3843 1042 1012 3844 1044 1014 3845 1046 1016 3846 1029 1001 3847 1027 999 3848 1046 1016 3849 1043 1013 3850 1029 1001 3851 1046 1016 3852 1027 999 3853 1030 1002 3854 1046 1016 3855 1030 1002 3856 1031 1003 3857 1046 1016 3858 1031 1003 3859 1032 1004 3860 1046 1016 3861 1032 1004 3862 1033 1005 3863 1046 1016 3864 1033 1005 3865 1034 1006 3866 1046 1016 3867 1034 1006 3868 1035 1007 3869 1046 1016 3870 1035 1007 3871 1036 1008 3872 1046 1016 3873 1036 1008 3874 1037 1009 3875 1046 1016 3876 1037 1009 3877 1038 1010 3878 1039 1011 3879 1047 1017 3880 1038 1010 3881 1046 1016 3882 1038 1010 3883 1047 1017 3884 1048 1018 3885 1049 1019 3886 1047 1017 3887 1046 1016 3888 1047 1017 3889 1049 1019 3890 1039 1011 3891 1048 1018 3892 1047 1017 3893 1050 1020 3894 1051 1021 3895 1049 1019 3896 1046 1016 3897 1049 1019 3898 1051 1021 3899 1052 1022 3900 1050 1020 3901 1049 1019 3902 1048 1018 3903 1052 1022 3904 1049 1019 3905 1053 1023 3906 1054 1024 3907 1051 1021 3908 1046 1016 3909 1051 1021 3910 1054 1024 3911 1050 1020 3912 1053 1023 3913 1051 1021 3914 1055 1025 3915 1056 1026 3916 1054 1024 3917 1046 1016 3918 1054 1024 3919 1056 1026 3920 1053 1023 3921 1055 1025 3922 1054 1024 3923 1057 1027 3924 1058 1028 3925 1056 1026 3926 1046 1016 3927 1056 1026 3928 1058 1028 3929 1059 1029 3930 1057 1027 3931 1056 1026 3932 1055 1025 3933 1059 1029 3934 1056 1026 3935 1060 1030 3936 1061 1031 3937 1058 1028 3938 1046 1016 3939 1058 1028 3940 1061 1031 3941 1057 1027 3942 1060 1030 3943 1058 1028 3944 1062 1032 3945 1063 1033 3946 1061 1031 3947 1046 1016 3948 1061 1031 3949 1063 1033 3950 1060 1030 3951 1062 1032 3952 1061 1031 3953 1064 1034 3954 1065 1035 3955 1063 1033 3956 1046 1016 3957 1063 1033 3958 1065 1035 3959 1062 1032 3960 1064 1034 3961 1063 1033 3962 1066 1036 3963 1067 1037 3964 1065 1035 3965 1046 1016 3966 1065 1035 3967 1067 1037 3968 1064 1034 3969 1066 1036 3970 1065 1035 3971 1068 1038 3972 1069 1039 3973 1067 1037 3974 1046 1016 3975 1067 1037 3976 1069 1039 3977 1066 1036 3978 1068 1038 3979 1067 1037 3980 1070 1040 3981 1071 1041 3982 1069 1039 3983 1046 1016 3984 1069 1039 3985 1071 1041 3986 1068 1038 3987 1070 1040 3988 1069 1039 3989 1072 1042 3990 1073 1043 3991 1071 1041 3992 1046 1016 3993 1071 1041 3994 1073 1043 3995 1070 1040 3996 1072 1042 3997 1071 1041 3998 1074 1044 3999 1075 1045 4000 1073 1043 4001 1046 1016 4002 1073 1043 4003 1075 1045 4004 1072 1042 4005 1074 1044 4006 1073 1043 4007 1076 1046 4008 1077 1047 4009 1075 1045 4010 1046 1016 4011 1075 1045 4012 1077 1047 4013 1074 1044 4014 1076 1046 4015 1075 1045 4016 1078 1048 4017 1079 1049 4018 1077 1047 4019 1046 1016 4020 1077 1047 4021 1079 1049 4022 1076 1046 4023 1078 1048 4024 1077 1047 4025 1080 1050 4026 1081 1051 4027 1079 1049 4028 1046 1016 4029 1079 1049 4030 1081 1051 4031 1082 1052 4032 1080 1050 4033 1079 1049 4034 1078 1048 4035 1082 1052 4036 1079 1049 4037 1083 1053 4038 1084 1054 4039 1085 1055 4040 1086 1056 4041 1046 1016 4042 1081 1051 4043 1087 1057 4044 1088 1058 4045 1084 1054 4046 1087 1057 4047 1084 1054 4048 1083 1053 4049 1083 1053 4050 1085 1055 4051 1089 1059 4052 1090 1060 4053 1082 1052 4054 1078 1048 4055 1091 1061 4056 1089 1059 4057 1092 1062 4058 1083 1053 4059 1089 1059 4060 1091 1061 4061 989 964 4062 1078 1048 4063 1076 1046 4064 991 966 4065 1078 1048 4066 989 964 4067 1093 1063 4068 1078 1048 4069 991 966 4070 1090 1060 4071 1078 1048 4072 1093 1063 4073 988 963 4074 1076 1046 4075 1074 1044 4076 989 964 4077 1076 1046 4078 988 963 4079 987 962 4080 1074 1044 4081 1072 1042 4082 988 963 4083 1074 1044 4084 987 962 4085 986 961 4086 1072 1042 4087 1070 1040 4088 987 962 4089 1072 1042 4090 986 961 4091 985 960 4092 1070 1040 4093 1068 1038 4094 986 961 4095 1070 1040 4096 985 960 4097 984 959 4098 1068 1038 4099 1066 1036 4100 985 960 4101 1068 1038 4102 984 959 4103 983 958 4104 1066 1036 4105 1064 1034 4106 984 959 4107 1066 1036 4108 983 958 4109 982 957 4110 1064 1034 4111 1062 1032 4112 983 958 4113 1064 1034 4114 982 957 4115 981 956 4116 1062 1032 4117 1060 1030 4118 982 957 4119 1062 1032 4120 981 956 4121 980 955 4122 1060 1030 4123 1057 1027 4124 981 956 4125 1060 1030 4126 980 955 4127 1059 1029 4128 1094 1064 4129 1057 1027 4130 976 951 4131 1057 1027 4132 1094 1064 4133 980 955 4134 1057 1027 4135 976 951 4136 1095 1065 4137 1096 1066 4138 1097 1067 4139 1098 1068 4140 1096 1066 4141 1095 1065 4142 1099 1068 4143 1096 1066 4144 1098 1068 4145 1100 1069 4146 976 951 4147 1094 1064 4148 1101 9 4149 1102 9 4150 1103 9 4151 1104 9 4152 1102 9 4153 1101 9 4154 1105 1068 4155 1095 1065 4156 1097 1067 4157 1104 9 4158 1106 9 4159 1102 9 4160 1107 9 4161 1103 9 4162 1108 9 4163 1101 9 4164 1103 9 4165 1107 9 4166 1109 9 4167 1108 9 4168 1110 9 4169 1107 9 4170 1108 9 4171 1109 9 4172 1087 1057 4173 1044 1014 4174 1088 1058 4175 1111 1070 4176 1044 1014 4177 1087 1057 4178 1112 1071 4179 1044 1014 4180 1111 1070 4181 1113 1072 4182 1044 1014 4183 1112 1071 4184 1114 1073 4185 1044 1014 4186 1113 1072 4187 1115 1074 4188 1044 1014 4189 1114 1073 4190 1116 1075 4191 1044 1014 4192 1115 1074 4193 1117 1076 4194 1044 1014 4195 1116 1075 4196 1118 1077 4197 1044 1014 4198 1117 1076 4199 1119 1078 4200 1044 1014 4201 1118 1077 4202 1120 1079 4203 1044 1014 4204 1119 1078 4205 1121 1080 4206 1044 1014 4207 1120 1079 4208 1122 1081 4209 1044 1014 4210 1121 1080 4211 1123 1082 4212 1044 1014 4213 1122 1081 4214 1124 1083 4215 1044 1014 4216 1123 1082 4217 1125 1084 4218 1044 1014 4219 1124 1083 4220 1126 1085 4221 1044 1014 4222 1125 1084 4223 1127 1086 4224 1044 1014 4225 1126 1085 4226 1128 1087 4227 1044 1014 4228 1127 1086 4229 1129 1088 4230 1044 1014 4231 1128 1087 4232 1130 1089 4233 1044 1014 4234 1129 1088 4235 1131 1090 4236 1044 1014 4237 1130 1089 4238 1132 1091 4239 1044 1014 4240 1131 1090 4241 1133 1092 4242 1044 1014 4243 1132 1091 4244 1134 1093 4245 1044 1014 4246 1133 1092 4247 1135 1094 4248 1044 1014 4249 1134 1093 4250 1025 997 4251 1044 1014 4252 1135 1094 4253 447 443 4254 317 313 4255 319 315 4256 320 316 4257 1136 1095 4258 321 317 4259 1137 1096 4260 300 296 4261 1138 1097 4262 1137 1096 4263 297 293 4264 300 296 4265 1139 1098 4266 1138 1097 4267 1140 1099 4268 1139 1098 4269 1137 1096 4270 1138 1097 4271 1141 1100 4272 1140 1099 4273 1142 1101 4274 1141 1100 4275 1139 1098 4276 1140 1099 4277 1143 1102 4278 1142 1101 4279 1144 1103 4280 1143 1102 4281 1141 1100 4282 1142 1101 4283 449 445 4284 305 301 4285 301 297 4286 1143 1102 4287 1144 1103 4288 1145 1104 4289 445 441 4290 446 442 4291 1136 1095 4292 320 316 4293 445 441 4294 1136 1095 4295 1146 1105 4296 1145 1104 4297 1147 1106 4298 1146 1105 4299 1143 1102 4300 1145 1104 4301 1148 1107 4302 1147 1106 4303 454 450 4304 1148 1107 4305 1146 1105 4306 1147 1106 4307 451 447 4308 1148 1107 4309 454 450 4310 1149 1108 4311 713 703 4312 1150 1109 4313 712 702 4314 713 703 4315 1149 1108 4316 1149 1108 4317 1150 1109 4318 1151 1110 4319 1152 1111 4320 1153 1112 4321 1154 1113 4322 1155 1114 4323 1153 1112 4324 1152 1111 4325 1156 1115 4326 1153 1112 4327 1155 1114 4328 1157 1116 4329 1153 1112 4330 1156 1115 4331 1149 1108 4332 1151 1110 4333 1158 1117 4334 1159 9 4335 1160 9 4336 925 9 4337 1161 9 4338 1159 9 4339 925 9 4340 1162 9 4341 1161 9 4342 925 9 4343 1163 9 4344 1162 9 4345 925 9 4346 924 9 4347 1163 9 4348 925 9 4349 1093 1063 4350 991 966 4351 993 968 4352 994 969 4353 1164 1118 4354 995 970 4355 1165 1119 4356 975 950 4357 1166 1120 4358 974 949 4359 975 950 4360 1165 1119 4361 1165 1119 4362 1166 1120 4363 1167 1121 4364 1165 1119 4365 1167 1121 4366 1168 1122 4367 1100 1069 4368 979 954 4369 976 951 4370 1091 1061 4371 1092 1062 4372 1164 1118 4373 1091 1061 4374 1164 1118 4375 994 969 4376 9 9 4377 1169 9 4378 168 9 4379 169 165 4380 170 166 4381 1170 1123 4382 1171 9 4383 1172 9 4384 1169 9 4385 1173 1124 4386 1174 1125 4387 1175 1126 4388 1176 9 4389 1171 9 4390 1169 9 4391 9 9 4392 1176 9 4393 1169 9 4394 1177 1127 4395 169 165 4396 1170 1123 4397 1178 1128 4398 1177 1127 4399 1170 1123 4400 1179 1129 4401 1174 1125 4402 1173 1124 4403 1180 9 4404 1181 9 4405 1172 9 4406 1182 1130 4407 1183 1131 4408 1184 1132 4409 1171 9 4410 1180 9 4411 1172 9 4412 1185 9 4413 1186 9 4414 1181 9 4415 1187 1133 4416 1184 1132 4417 1188 1134 4418 1180 9 4419 1185 9 4420 1181 9 4421 1182 1130 4422 1184 1132 4423 1187 1133 4424 1185 9 4425 1189 9 4426 1186 9 4427 1190 1135 4428 1188 1134 4429 1191 1136 4430 1187 1133 4431 1188 1134 4432 1190 1135 4433 1192 9 4434 1193 9 4435 1189 9 4436 59 57 4437 1191 1136 4438 1194 1137 4439 1185 9 4440 1192 9 4441 1189 9 4442 1190 1135 4443 1191 1136 4444 59 57 4445 1192 9 4446 1195 9 4447 1193 9 4448 59 57 4449 1194 1137 4450 58 56 4451 1196 9 4452 1197 9 4453 1195 9 4454 1192 9 4455 1196 9 4456 1195 9 4457 1196 9 4458 1198 9 4459 1197 9 4460 1196 9 4461 1199 9 4462 1198 9 4463 1200 1138 4464 1201 1139 4465 1202 1140 4466 1203 1141 4467 1204 1142 4468 1205 1143 4469 1206 1144 4470 1203 1141 4471 1205 1143 4472 1207 1145 4473 1202 1140 4474 1208 1146 4475 1207 1145 4476 1200 1138 4477 1202 1140 4478 1207 1145 4479 1208 1146 4480 1209 1147 4481 1210 1148 4482 1209 1147 4483 1211 1149 4484 1210 1148 4485 1207 1145 4486 1209 1147 4487 1178 1128 4488 1212 1150 4489 1177 1127 4490 1210 1148 4491 1211 1149 4492 1213 1151 4493 1178 1128 4494 1214 1152 4495 1212 1150 4496 1215 1153 4497 1213 1151 4498 1216 1154 4499 1217 1155 4500 1213 1151 4501 1215 1153 4502 1217 1155 4503 1210 1148 4504 1213 1151 4505 1218 1156 4506 1219 1157 4507 1214 1152 4508 1220 1158 4509 1216 1154 4510 1221 1159 4511 1178 1128 4512 1218 1156 4513 1214 1152 4514 1220 1158 4515 1215 1153 4516 1216 1154 4517 1222 1160 4518 60 58 4519 1219 1157 4520 1223 1161 4521 1221 1159 4522 1224 1162 4523 1225 1163 4524 1222 1160 4525 1219 1157 4526 1218 1156 4527 1225 1163 4528 1219 1157 4529 1223 1161 4530 1220 1158 4531 1221 1159 4532 1226 1164 4533 1224 1162 4534 1227 1165 4535 1222 1160 4536 61 59 4537 60 58 4538 1226 1164 4539 1223 1161 4540 1224 1162 4541 1228 1166 4542 1227 1165 4543 1229 1167 4544 1228 1166 4545 1230 1168 4546 1227 1165 4547 1226 1164 4548 1227 1165 4549 1230 1168 4550 1231 1169 4551 1232 1170 4552 1233 1171 4553 1234 1172 4554 1232 1170 4555 1231 1169 4556 1235 1173 4557 1236 1174 4558 174 170 4559 1231 1169 4560 1233 1171 4561 1237 1175 4562 175 171 4563 1235 1173 4564 174 170 4565 1238 1176 4566 1239 1177 4567 1240 1178 4568 1241 1179 4569 1237 1175 4570 1242 1180 4571 1241 1179 4572 1231 1169 4573 1237 1175 4574 171 167 4575 1240 1178 4576 176 172 4577 1243 1181 4578 1238 1176 4579 1240 1178 4580 171 167 4581 1243 1181 4582 1240 1178 4583 1244 1182 4584 1245 1183 4585 1246 1184 4586 1247 1185 4587 1248 1186 4588 1249 1187 4589 1250 1188 4590 1244 1182 4591 1246 1184 4592 1251 1189 4593 1252 1190 4594 1253 1191 4595 1254 1192 4596 1255 1193 4597 1256 1194 4598 1251 1189 4599 1253 1191 4600 1257 1195 4601 1258 1196 4602 1259 1197 4603 1245 1183 4604 1260 1198 4605 1249 1187 4606 1261 1199 4607 1244 1182 4608 1258 1196 4609 1245 1183 4610 1260 1198 4611 1247 1185 4612 1249 1187 4613 1262 1200 4614 1263 1201 4615 1259 1197 4616 1260 1198 4617 1261 1199 4618 1264 1202 4619 1258 1196 4620 1262 1200 4621 1259 1197 4622 1262 1200 4623 1265 1203 4624 1263 1201 4625 1266 1204 4626 1264 1202 4627 1267 1205 4628 1266 1204 4629 1260 1198 4630 1264 1202 4631 1268 1206 4632 1269 1207 4633 1265 1203 4634 1270 1208 4635 1267 1205 4636 1271 1209 4637 1262 1200 4638 1268 1206 4639 1265 1203 4640 1270 1208 4641 1266 1204 4642 1267 1205 4643 1272 1210 4644 1273 1211 4645 1269 1207 4646 1270 1208 4647 1271 1209 4648 1274 1212 4649 1268 1206 4650 1272 1210 4651 1269 1207 4652 1272 1210 4653 1275 1213 4654 1273 1211 4655 1276 1214 4656 1274 1212 4657 1277 1215 4658 1276 1214 4659 1270 1208 4660 1274 1212 4661 162 160 4662 1278 1216 4663 1275 1213 4664 1276 1214 4665 1277 1215 4666 1279 1217 4667 1272 1210 4668 162 160 4669 1275 1213 4670 162 160 4671 159 157 4672 1278 1216 4673 1203 1141 4674 1279 1217 4675 1204 1142 4676 1203 1141 4677 1276 1214 4678 1279 1217 4679 154 152 4680 150 148 4681 1280 1218 4682 1281 1219 4683 1280 1218 4684 1282 1220 4685 154 152 4686 1280 1218 4687 1281 1219 4688 1283 1221 4689 1282 1220 4690 1284 1222 4691 1281 1219 4692 1282 1220 4693 1283 1221 4694 1285 1223 4695 1284 1222 4696 1286 1224 4697 1283 1221 4698 1284 1222 4699 1285 1223 4700 1285 1223 4701 1286 1224 4702 1287 1225 4703 1288 1226 4704 1289 1227 4705 1244 1182 4706 1290 1228 4707 1287 1225 4708 1291 1229 4709 1250 1188 4710 1288 1226 4711 1244 1182 4712 1285 1223 4713 1287 1225 4714 1292 1230 4715 1290 1228 4716 1292 1230 4717 1287 1225 4718 1293 1231 4719 1294 1232 4720 1295 1233 4721 1290 1228 4722 1291 1229 4723 1296 1234 4724 1297 1235 4725 1295 1233 4726 1252 1190 4727 1297 1235 4728 1293 1231 4729 1295 1233 4730 1251 1189 4731 1297 1235 4732 1252 1190 4733 1298 1236 4734 1247 1185 4735 1260 1198 4736 1299 1237 4737 1256 1194 4738 1300 1238 4739 1301 1239 4740 1254 1192 4741 1256 1194 4742 1302 1240 4743 1301 1239 4744 1256 1194 4745 1299 1237 4746 1302 1240 4747 1256 1194 4748 1303 1241 4749 1260 1198 4750 1266 1204 4751 1304 1242 4752 1298 1236 4753 1260 1198 4754 1303 1241 4755 1304 1242 4756 1260 1198 4757 1305 1243 4758 1266 1204 4759 1270 1208 4760 1305 1243 4761 1303 1241 4762 1266 1204 4763 1306 1244 4764 1270 1208 4765 1276 1214 4766 1306 1244 4767 1305 1243 4768 1270 1208 4769 1307 1245 4770 1276 1214 4771 1203 1141 4772 1308 1246 4773 1306 1244 4774 1276 1214 4775 1307 1245 4776 1308 1246 4777 1276 1214 4778 1309 1247 4779 1203 1141 4780 1206 1144 4781 1309 1247 4782 1307 1245 4783 1203 1141 4784 1310 1248 4785 1309 1247 4786 1206 1144 4787 1207 1145 4788 1311 1249 4789 1200 1138 4790 1312 1250 4791 1313 1251 4792 1314 1252 4793 1315 1253 4794 1299 1237 4795 1300 1238 4796 1316 1254 4797 1317 1255 4798 1313 1251 4799 1312 1250 4800 1316 1254 4801 1313 1251 4802 1318 1256 4803 1314 1252 4804 1319 1257 4805 1318 1256 4806 1312 1250 4807 1314 1252 4808 1320 1258 4809 1319 1257 4810 1321 1259 4811 1320 1258 4812 1318 1256 4813 1319 1257 4814 1322 1260 4815 1321 1259 4816 1323 1261 4817 1322 1260 4818 1320 1258 4819 1321 1259 4820 1324 1262 4821 1323 1261 4822 1325 1263 4823 1324 1262 4824 1322 1260 4825 1323 1261 4826 1326 1264 4827 1325 1263 4828 1327 1265 4829 1326 1264 4830 1324 1262 4831 1325 1263 4832 1328 1266 4833 1327 1265 4834 1329 1267 4835 1328 1266 4836 1326 1264 4837 1327 1265 4838 1330 1268 4839 1329 1267 4840 1331 1269 4841 1330 1268 4842 1328 1266 4843 1329 1267 4844 1332 1270 4845 1311 1249 4846 1207 1145 4847 1330 1268 4848 1331 1269 4849 1333 1271 4850 1251 1189 4851 1257 1195 4852 1334 1272 4853 1335 1273 4854 1334 1272 4855 1336 1274 4856 1335 1273 4857 1251 1189 4858 1334 1272 4859 1337 1275 4860 1338 1276 4861 1339 1277 4862 1340 1278 4863 1341 1279 4864 1342 1280 4865 1343 1281 4866 1338 1276 4867 1337 1275 4868 1315 1253 4869 1344 1282 4870 1299 1237 4871 1337 1275 4872 1339 1277 4873 1345 1283 4874 1316 1254 4875 1346 1284 4876 1317 1255 4877 1347 1285 4878 1348 1286 4879 1346 1284 4880 1316 1254 4881 1347 1285 4882 1346 1284 4883 1349 1287 4884 1293 1231 4885 1297 1235 4886 1290 1228 4887 1296 1234 4888 1350 1288 4889 1351 1289 4890 1297 1235 4891 1251 1189 4892 1351 1289 4893 1349 1287 4894 1297 1235 4895 1335 1273 4896 1351 1289 4897 1251 1189 4898 1352 1290 4899 1353 1291 4900 1354 1292 4901 1290 1228 4902 1350 1288 4903 1355 1293 4904 1356 1294 4905 1355 1293 4906 1350 1288 4907 1352 1290 4908 1357 1295 4909 1353 1291 4910 1358 1296 4911 1354 1292 4912 1341 1279 4913 1358 1296 4914 1352 1290 4915 1354 1292 4916 1358 1296 4917 1341 1279 4918 1340 1278 4919 851 835 4920 1359 1297 4921 854 838 4922 1360 1298 4923 857 841 4924 1361 1299 4925 1360 1298 4926 855 839 4927 857 841 4928 1362 1300 4929 1363 1301 4930 1359 1297 4931 1364 1302 4932 1361 1299 4933 1365 1303 4934 851 835 4935 1362 1300 4936 1359 1297 4937 1364 1302 4938 1360 1298 4939 1361 1299 4940 1366 1304 4941 1367 1305 4942 1363 1301 4943 1368 1306 4944 1365 1303 4945 1369 1307 4946 1362 1300 4947 1366 1304 4948 1363 1301 4949 1368 1306 4950 1364 1302 4951 1365 1303 4952 1370 1308 4953 1371 1309 4954 1367 1305 4955 1372 1310 4956 1369 1307 4957 1373 1311 4958 1366 1304 4959 1370 1308 4960 1367 1305 4961 1372 1310 4962 1368 1306 4963 1369 1307 4964 1370 1308 4965 1374 1312 4966 1371 1309 4967 1375 1313 4968 1371 1309 4969 1374 1312 4970 1372 1310 4971 1373 1311 4972 1376 1314 4973 1377 1315 4974 1378 1316 4975 1374 1312 4976 1379 1317 4977 1374 1312 4978 1378 1316 4979 1370 1308 4980 1377 1315 4981 1374 1312 4982 1380 1318 4983 1375 1313 4984 1374 1312 4985 1379 1317 4986 1380 1318 4987 1374 1312 4988 1381 1319 4989 1382 1320 4990 1378 1316 4991 1383 1321 4992 1378 1316 4993 1382 1320 4994 1377 1315 4995 1381 1319 4996 1378 1316 4997 1384 1322 4998 1379 1317 4999 1378 1316 5000 1383 1321 5001 1384 1322 5002 1378 1316 5003 1385 1323 5004 1386 1324 5005 1382 1320 5006 1387 1325 5007 1382 1320 5008 1386 1324 5009 1381 1319 5010 1385 1323 5011 1382 1320 5012 1387 1325 5013 1383 1321 5014 1382 1320 5015 1388 1326 5016 1389 1327 5017 1386 1324 5018 1390 1328 5019 1386 1324 5020 1389 1327 5021 1385 1323 5022 1388 1326 5023 1386 1324 5024 1390 1328 5025 1387 1325 5026 1386 1324 5027 1391 1329 5028 1392 1330 5029 1389 1327 5030 1393 1331 5031 1389 1327 5032 1392 1330 5033 1388 1326 5034 1391 1329 5035 1389 1327 5036 1393 1331 5037 1390 1328 5038 1389 1327 5039 1394 1332 5040 1395 1333 5041 1392 1330 5042 1396 1334 5043 1392 1330 5044 1395 1333 5045 1391 1329 5046 1394 1332 5047 1392 1330 5048 1396 1334 5049 1393 1331 5050 1392 1330 5051 1397 1335 5052 1398 1336 5053 1395 1333 5054 1399 1337 5055 1395 1333 5056 1398 1336 5057 1394 1332 5058 1397 1335 5059 1395 1333 5060 1399 1337 5061 1396 1334 5062 1395 1333 5063 1400 1338 5064 1401 1339 5065 1398 1336 5066 1402 1340 5067 1398 1336 5068 1401 1339 5069 1397 1335 5070 1400 1338 5071 1398 1336 5072 1402 1340 5073 1399 1337 5074 1398 1336 5075 1403 1341 5076 1404 1342 5077 1401 1339 5078 1405 1343 5079 1401 1339 5080 1404 1342 5081 1400 1338 5082 1403 1341 5083 1401 1339 5084 1405 1343 5085 1402 1340 5086 1401 1339 5087 1406 1344 5088 1407 1345 5089 1404 1342 5090 1408 1346 5091 1404 1342 5092 1407 1345 5093 1403 1341 5094 1406 1344 5095 1404 1342 5096 1408 1346 5097 1405 1343 5098 1404 1342 5099 1409 1347 5100 1410 1348 5101 1407 1345 5102 1411 1349 5103 1407 1345 5104 1410 1348 5105 1406 1344 5106 1409 1347 5107 1407 1345 5108 1411 1349 5109 1408 1346 5110 1407 1345 5111 1412 1350 5112 1413 1351 5113 1410 1348 5114 1414 1352 5115 1410 1348 5116 1413 1351 5117 1409 1347 5118 1412 1350 5119 1410 1348 5120 1414 1352 5121 1411 1349 5122 1410 1348 5123 1415 1353 5124 1416 1354 5125 1413 1351 5126 1417 1355 5127 1413 1351 5128 1416 1354 5129 1412 1350 5130 1415 1353 5131 1413 1351 5132 1417 1355 5133 1414 1352 5134 1413 1351 5135 1418 1356 5136 1419 1357 5137 1416 1354 5138 1420 1358 5139 1416 1354 5140 1419 1357 5141 1415 1353 5142 1418 1356 5143 1416 1354 5144 1420 1358 5145 1417 1355 5146 1416 1354 5147 1421 1359 5148 1422 1360 5149 1419 1357 5150 1423 1361 5151 1419 1357 5152 1422 1360 5153 1418 1356 5154 1421 1359 5155 1419 1357 5156 1423 1361 5157 1420 1358 5158 1419 1357 5159 1424 1362 5160 1425 1363 5161 1422 1360 5162 1426 1364 5163 1422 1360 5164 1425 1363 5165 1421 1359 5166 1424 1362 5167 1422 1360 5168 1426 1364 5169 1423 1361 5170 1422 1360 5171 1427 1365 5172 1428 1366 5173 1425 1363 5174 1429 1367 5175 1425 1363 5176 1428 1366 5177 1424 1362 5178 1427 1365 5179 1425 1363 5180 1429 1367 5181 1426 1364 5182 1425 1363 5183 1430 1368 5184 1431 1369 5185 1428 1366 5186 1432 1370 5187 1428 1366 5188 1431 1369 5189 1427 1365 5190 1430 1368 5191 1428 1366 5192 1432 1370 5193 1429 1367 5194 1428 1366 5195 1433 1371 5196 1434 1372 5197 1431 1369 5198 1435 1373 5199 1431 1369 5200 1434 1372 5201 1430 1368 5202 1433 1371 5203 1431 1369 5204 1435 1373 5205 1432 1370 5206 1431 1369 5207 1436 1374 5208 1437 1375 5209 1434 1372 5210 1438 1376 5211 1434 1372 5212 1437 1375 5213 1433 1371 5214 1436 1374 5215 1434 1372 5216 1438 1376 5217 1435 1373 5218 1434 1372 5219 1439 1377 5220 1440 1378 5221 1437 1375 5222 1441 1379 5223 1437 1375 5224 1440 1378 5225 1436 1374 5226 1439 1377 5227 1437 1375 5228 1441 1379 5229 1438 1376 5230 1437 1375 5231 1442 1380 5232 914 895 5233 1440 1378 5234 726 716 5235 1440 1378 5236 914 895 5237 1439 1377 5238 1442 1380 5239 1440 1378 5240 726 716 5241 1441 1379 5242 1440 1378 5243 1442 1380 5244 918 899 5245 914 895 5246 994 969 5247 918 899 5248 1442 1380 5249 1443 1381 5250 1442 1380 5251 1439 1377 5252 1443 1381 5253 994 969 5254 1442 1380 5255 1444 1382 5256 1439 1377 5257 1436 1374 5258 1444 1382 5259 1443 1381 5260 1439 1377 5261 1445 1383 5262 1436 1374 5263 1433 1371 5264 1445 1383 5265 1444 1382 5266 1436 1374 5267 1446 1384 5268 1433 1371 5269 1430 1368 5270 1446 1384 5271 1445 1383 5272 1433 1371 5273 1447 1385 5274 1430 1368 5275 1427 1365 5276 1447 1385 5277 1446 1384 5278 1430 1368 5279 1448 1386 5280 1427 1365 5281 1424 1362 5282 1448 1386 5283 1447 1385 5284 1427 1365 5285 1449 1387 5286 1424 1362 5287 1421 1359 5288 1449 1387 5289 1448 1386 5290 1424 1362 5291 1450 1388 5292 1421 1359 5293 1418 1356 5294 1450 1388 5295 1449 1387 5296 1421 1359 5297 1451 1389 5298 1418 1356 5299 1415 1353 5300 1451 1389 5301 1450 1388 5302 1418 1356 5303 1452 1390 5304 1415 1353 5305 1412 1350 5306 1452 1390 5307 1451 1389 5308 1415 1353 5309 1453 1391 5310 1412 1350 5311 1409 1347 5312 1453 1391 5313 1452 1390 5314 1412 1350 5315 1454 1392 5316 1409 1347 5317 1406 1344 5318 1454 1392 5319 1453 1391 5320 1409 1347 5321 1455 1393 5322 1406 1344 5323 1403 1341 5324 1455 1393 5325 1454 1392 5326 1406 1344 5327 1456 1394 5328 1403 1341 5329 1400 1338 5330 1456 1394 5331 1455 1393 5332 1403 1341 5333 1457 1395 5334 1400 1338 5335 1397 1335 5336 1457 1395 5337 1456 1394 5338 1400 1338 5339 1458 1396 5340 1397 1335 5341 1394 1332 5342 1458 1396 5343 1457 1395 5344 1397 1335 5345 1459 1397 5346 1394 1332 5347 1391 1329 5348 1459 1397 5349 1458 1396 5350 1394 1332 5351 1460 1398 5352 1391 1329 5353 1388 1326 5354 1460 1398 5355 1459 1397 5356 1391 1329 5357 1461 1399 5358 1388 1326 5359 1385 1323 5360 1461 1399 5361 1460 1398 5362 1388 1326 5363 1462 1400 5364 1385 1323 5365 1381 1319 5366 1462 1400 5367 1461 1399 5368 1385 1323 5369 1463 1401 5370 1381 1319 5371 1377 1315 5372 1463 1401 5373 1462 1400 5374 1381 1319 5375 1464 1402 5376 1377 1315 5377 1370 1308 5378 1464 1402 5379 1463 1401 5380 1377 1315 5381 1465 1403 5382 1370 1308 5383 1366 1304 5384 1465 1403 5385 1464 1402 5386 1370 1308 5387 1466 1404 5388 1366 1304 5389 1362 1300 5390 1466 1404 5391 1465 1403 5392 1366 1304 5393 1467 1405 5394 1362 1300 5395 851 835 5396 1467 1405 5397 1466 1404 5398 1362 1300 5399 860 844 5400 1467 1405 5401 851 835 5402 1468 1406 5403 1376 1314 5404 1469 1407 5405 1468 1406 5406 1372 1310 5407 1376 1314 5408 1470 1408 5409 1469 1407 5410 1471 1409 5411 1470 1408 5412 1468 1406 5413 1469 1407 5414 1472 1410 5415 1471 1409 5416 1473 1411 5417 1472 1410 5418 1470 1408 5419 1471 1409 5420 1474 1412 5421 1384 1322 5422 1383 1321 5423 1475 1413 5424 1473 1411 5425 1476 1414 5426 1475 1413 5427 1472 1410 5428 1473 1411 5429 1477 1415 5430 1383 1321 5431 1387 1325 5432 1477 1415 5433 1474 1412 5434 1383 1321 5435 1478 1416 5436 1387 1325 5437 1390 1328 5438 1478 1416 5439 1477 1415 5440 1387 1325 5441 1479 1417 5442 1390 1328 5443 1393 1331 5444 1479 1417 5445 1478 1416 5446 1390 1328 5447 1480 1418 5448 1393 1331 5449 1396 1334 5450 1480 1418 5451 1479 1417 5452 1393 1331 5453 1481 1419 5454 1396 1334 5455 1399 1337 5456 1481 1419 5457 1480 1418 5458 1396 1334 5459 1482 1420 5460 1399 1337 5461 1402 1340 5462 1482 1420 5463 1481 1419 5464 1399 1337 5465 1483 1421 5466 1402 1340 5467 1405 1343 5468 1483 1421 5469 1482 1420 5470 1402 1340 5471 1484 1422 5472 1405 1343 5473 1408 1346 5474 1484 1422 5475 1483 1421 5476 1405 1343 5477 1485 1423 5478 1408 1346 5479 1411 1349 5480 1485 1423 5481 1484 1422 5482 1408 1346 5483 1486 1424 5484 1411 1349 5485 1414 1352 5486 1486 1424 5487 1485 1423 5488 1411 1349 5489 1487 1425 5490 1414 1352 5491 1417 1355 5492 1487 1425 5493 1486 1424 5494 1414 1352 5495 1488 1426 5496 1417 1355 5497 1420 1358 5498 1488 1426 5499 1487 1425 5500 1417 1355 5501 1489 1427 5502 1420 1358 5503 1423 1361 5504 1489 1427 5505 1488 1426 5506 1420 1358 5507 1490 1428 5508 1423 1361 5509 1426 1364 5510 1490 1428 5511 1489 1427 5512 1423 1361 5513 1491 1429 5514 1426 1364 5515 1429 1367 5516 1491 1429 5517 1490 1428 5518 1426 1364 5519 1492 1430 5520 1429 1367 5521 1432 1370 5522 1492 1430 5523 1491 1429 5524 1429 1367 5525 1493 1431 5526 1432 1370 5527 1435 1373 5528 1493 1431 5529 1492 1430 5530 1432 1370 5531 1494 1432 5532 1435 1373 5533 1438 1376 5534 1494 1432 5535 1493 1431 5536 1435 1373 5537 1495 1433 5538 1438 1376 5539 1441 1379 5540 1495 1433 5541 1494 1432 5542 1438 1376 5543 1496 1434 5544 1441 1379 5545 726 716 5546 1496 1434 5547 1495 1433 5548 1441 1379 5549 661 651 5550 1496 1434 5551 726 716 5552 1497 1435 5553 1476 1414 5554 1498 1436 5555 1497 1435 5556 1475 1413 5557 1476 1414 5558 1499 1437 5559 1477 1415 5560 1478 1416 5561 1500 1438 5562 1498 1436 5563 1501 1439 5564 1500 1438 5565 1497 1435 5566 1498 1436 5567 1502 1440 5568 1478 1416 5569 1479 1417 5570 1503 1441 5571 1499 1437 5572 1478 1416 5573 1504 1442 5574 1503 1441 5575 1478 1416 5576 1502 1440 5577 1504 1442 5578 1478 1416 5579 1505 1443 5580 1479 1417 5581 1480 1418 5582 1505 1443 5583 1502 1440 5584 1479 1417 5585 1506 1444 5586 1480 1418 5587 1481 1419 5588 1506 1444 5589 1505 1443 5590 1480 1418 5591 1507 1445 5592 1481 1419 5593 1482 1420 5594 1507 1445 5595 1506 1444 5596 1481 1419 5597 1508 1446 5598 1482 1420 5599 1483 1421 5600 1508 1446 5601 1507 1445 5602 1482 1420 5603 1509 1447 5604 1483 1421 5605 1484 1422 5606 1509 1447 5607 1508 1446 5608 1483 1421 5609 1510 1448 5610 1484 1422 5611 1485 1423 5612 1510 1448 5613 1509 1447 5614 1484 1422 5615 1511 1449 5616 1485 1423 5617 1486 1424 5618 1511 1449 5619 1510 1448 5620 1485 1423 5621 1512 1450 5622 1486 1424 5623 1487 1425 5624 1512 1450 5625 1511 1449 5626 1486 1424 5627 1513 1451 5628 1487 1425 5629 1488 1426 5630 1513 1451 5631 1512 1450 5632 1487 1425 5633 1514 1452 5634 1488 1426 5635 1489 1427 5636 1514 1452 5637 1513 1451 5638 1488 1426 5639 1515 1453 5640 1489 1427 5641 1490 1428 5642 1515 1453 5643 1514 1452 5644 1489 1427 5645 1516 1454 5646 1490 1428 5647 1491 1429 5648 1516 1454 5649 1515 1453 5650 1490 1428 5651 1517 1455 5652 1491 1429 5653 1492 1430 5654 1517 1455 5655 1516 1454 5656 1491 1429 5657 1518 1456 5658 1492 1430 5659 1493 1431 5660 1518 1456 5661 1517 1455 5662 1492 1430 5663 1519 1457 5664 1493 1431 5665 1494 1432 5666 1519 1457 5667 1518 1456 5668 1493 1431 5669 1520 1458 5670 1494 1432 5671 1495 1433 5672 1520 1458 5673 1519 1457 5674 1494 1432 5675 1521 1459 5676 1495 1433 5677 1496 1434 5678 1521 1459 5679 1520 1458 5680 1495 1433 5681 621 611 5682 1496 1434 5683 661 651 5684 621 611 5685 1521 1459 5686 1496 1434 5687 1522 1460 5688 1501 1439 5689 1523 1461 5690 1522 1460 5691 1500 1438 5692 1501 1439 5693 1524 1462 5694 1523 1461 5695 1525 1463 5696 1524 1462 5697 1522 1460 5698 1523 1461 5699 1526 1464 5700 1504 1442 5701 1502 1440 5702 1527 1465 5703 1525 1463 5704 1528 1466 5705 1527 1465 5706 1524 1462 5707 1525 1463 5708 1529 1467 5709 1502 1440 5710 1505 1443 5711 1530 1468 5712 1526 1464 5713 1502 1440 5714 1529 1467 5715 1530 1468 5716 1502 1440 5717 1531 1469 5718 1505 1443 5719 1506 1444 5720 1531 1469 5721 1529 1467 5722 1505 1443 5723 1532 1470 5724 1506 1444 5725 1507 1445 5726 1532 1470 5727 1531 1469 5728 1506 1444 5729 1533 1471 5730 1507 1445 5731 1508 1446 5732 1533 1471 5733 1532 1470 5734 1507 1445 5735 1534 1472 5736 1508 1446 5737 1509 1447 5738 1534 1472 5739 1533 1471 5740 1508 1446 5741 1535 1473 5742 1509 1447 5743 1510 1448 5744 1535 1473 5745 1534 1472 5746 1509 1447 5747 1536 1474 5748 1510 1448 5749 1511 1449 5750 1536 1474 5751 1535 1473 5752 1510 1448 5753 1537 1475 5754 1511 1449 5755 1512 1450 5756 1537 1475 5757 1536 1474 5758 1511 1449 5759 1538 1476 5760 1512 1450 5761 1513 1451 5762 1538 1476 5763 1537 1475 5764 1512 1450 5765 1539 1477 5766 1513 1451 5767 1514 1452 5768 1539 1477 5769 1538 1476 5770 1513 1451 5771 1540 1478 5772 1514 1452 5773 1515 1453 5774 1540 1478 5775 1539 1477 5776 1514 1452 5777 1541 1479 5778 1515 1453 5779 1516 1454 5780 1541 1479 5781 1540 1478 5782 1515 1453 5783 1542 1480 5784 1516 1454 5785 1517 1455 5786 1542 1480 5787 1541 1479 5788 1516 1454 5789 1543 1481 5790 1517 1455 5791 1518 1456 5792 1543 1481 5793 1542 1480 5794 1517 1455 5795 1544 1482 5796 1518 1456 5797 1519 1457 5798 1544 1482 5799 1543 1481 5800 1518 1456 5801 1545 1483 5802 1519 1457 5803 1520 1458 5804 1545 1483 5805 1544 1482 5806 1519 1457 5807 1546 1484 5808 1520 1458 5809 1521 1459 5810 1546 1484 5811 1545 1483 5812 1520 1458 5813 1547 1485 5814 1521 1459 5815 621 611 5816 1547 1485 5817 1546 1484 5818 1521 1459 5819 580 571 5820 1547 1485 5821 621 611 5822 1548 1486 5823 1528 1466 5824 1549 1487 5825 1548 1486 5826 1527 1465 5827 1528 1466 5828 1550 1488 5829 1530 1468 5830 1529 1467 5831 1548 1486 5832 1549 1487 5833 1551 1489 5834 1552 1490 5835 1529 1467 5836 1531 1469 5837 1553 1491 5838 1550 1488 5839 1529 1467 5840 1552 1490 5841 1553 1491 5842 1529 1467 5843 1554 1492 5844 1531 1469 5845 1532 1470 5846 1554 1492 5847 1552 1490 5848 1531 1469 5849 1555 1493 5850 1532 1470 5851 1533 1471 5852 1555 1493 5853 1554 1492 5854 1532 1470 5855 1556 1494 5856 1533 1471 5857 1534 1472 5858 1556 1494 5859 1555 1493 5860 1533 1471 5861 1557 1495 5862 1534 1472 5863 1535 1473 5864 1557 1495 5865 1556 1494 5866 1534 1472 5867 1558 1496 5868 1535 1473 5869 1536 1474 5870 1558 1496 5871 1557 1495 5872 1535 1473 5873 1559 1497 5874 1536 1474 5875 1537 1475 5876 1559 1497 5877 1558 1496 5878 1536 1474 5879 1560 1498 5880 1537 1475 5881 1538 1476 5882 1560 1498 5883 1559 1497 5884 1537 1475 5885 1561 1499 5886 1538 1476 5887 1539 1477 5888 1561 1499 5889 1560 1498 5890 1538 1476 5891 1562 1500 5892 1539 1477 5893 1540 1478 5894 1562 1500 5895 1561 1499 5896 1539 1477 5897 1563 1501 5898 1540 1478 5899 1541 1479 5900 1563 1501 5901 1562 1500 5902 1540 1478 5903 1564 1502 5904 1541 1479 5905 1542 1480 5906 1564 1502 5907 1563 1501 5908 1541 1479 5909 1565 1503 5910 1542 1480 5911 1543 1481 5912 1565 1503 5913 1564 1502 5914 1542 1480 5915 1566 1504 5916 1543 1481 5917 1544 1482 5918 1566 1504 5919 1565 1503 5920 1543 1481 5921 1567 1505 5922 1544 1482 5923 1545 1483 5924 1567 1505 5925 1566 1504 5926 1544 1482 5927 1568 1506 5928 1545 1483 5929 1546 1484 5930 1568 1506 5931 1567 1505 5932 1545 1483 5933 1569 1507 5934 1546 1484 5935 1547 1485 5936 1569 1507 5937 1568 1506 5938 1546 1484 5939 1570 1508 5940 1547 1485 5941 580 571 5942 1570 1508 5943 1569 1507 5944 1547 1485 5945 544 535 5946 1570 1508 5947 580 571 5948 1571 1509 5949 1551 1489 5950 1572 1510 5951 1571 1509 5952 1548 1486 5953 1551 1489 5954 1573 1511 5955 1553 1491 5956 1552 1490 5957 1574 1512 5958 1572 1510 5959 1575 1513 5960 1574 1512 5961 1571 1509 5962 1572 1510 5963 1576 1514 5964 1552 1490 5965 1554 1492 5966 1577 1515 5967 1573 1511 5968 1552 1490 5969 1576 1514 5970 1577 1515 5971 1552 1490 5972 1578 1516 5973 1554 1492 5974 1555 1493 5975 1578 1516 5976 1576 1514 5977 1554 1492 5978 1579 1517 5979 1555 1493 5980 1556 1494 5981 1579 1517 5982 1578 1516 5983 1555 1493 5984 1580 1518 5985 1556 1494 5986 1557 1495 5987 1580 1518 5988 1579 1517 5989 1556 1494 5990 1581 1519 5991 1557 1495 5992 1558 1496 5993 1581 1519 5994 1580 1518 5995 1557 1495 5996 1582 1520 5997 1558 1496 5998 1559 1497 5999 1582 1520 6000 1581 1519 6001 1558 1496 6002 1583 1521 6003 1559 1497 6004 1560 1498 6005 1583 1521 6006 1582 1520 6007 1559 1497 6008 1584 1522 6009 1560 1498 6010 1561 1499 6011 1584 1522 6012 1583 1521 6013 1560 1498 6014 1585 1523 6015 1561 1499 6016 1562 1500 6017 1585 1523 6018 1584 1522 6019 1561 1499 6020 1586 1524 6021 1562 1500 6022 1563 1501 6023 1586 1524 6024 1585 1523 6025 1562 1500 6026 1587 1525 6027 1563 1501 6028 1564 1502 6029 1587 1525 6030 1586 1524 6031 1563 1501 6032 1588 1526 6033 1564 1502 6034 1565 1503 6035 1588 1526 6036 1587 1525 6037 1564 1502 6038 1589 1527 6039 1565 1503 6040 1566 1504 6041 1589 1527 6042 1588 1526 6043 1565 1503 6044 1590 1528 6045 1566 1504 6046 1567 1505 6047 1590 1528 6048 1589 1527 6049 1566 1504 6050 1591 1529 6051 1567 1505 6052 1568 1506 6053 1591 1529 6054 1590 1528 6055 1567 1505 6056 1592 1530 6057 1568 1506 6058 1569 1507 6059 1592 1530 6060 1591 1529 6061 1568 1506 6062 1593 1531 6063 1569 1507 6064 1570 1508 6065 1593 1531 6066 1592 1530 6067 1569 1507 6068 441 437 6069 1570 1508 6070 544 535 6071 441 437 6072 1593 1531 6073 1570 1508 6074 1594 1532 6075 1575 1513 6076 1595 1533 6077 1594 1532 6078 1574 1512 6079 1575 1513 6080 1596 1534 6081 1577 1515 6082 1576 1514 6083 1597 1535 6084 1595 1533 6085 1598 1536 6086 1597 1535 6087 1594 1532 6088 1595 1533 6089 1599 1537 6090 1576 1514 6091 1578 1516 6092 1600 1538 6093 1596 1534 6094 1576 1514 6095 1599 1537 6096 1600 1538 6097 1576 1514 6098 1601 1539 6099 1578 1516 6100 1579 1517 6101 1601 1539 6102 1599 1537 6103 1578 1516 6104 1602 1540 6105 1579 1517 6106 1580 1518 6107 1602 1540 6108 1601 1539 6109 1579 1517 6110 1603 1541 6111 1580 1518 6112 1581 1519 6113 1603 1541 6114 1602 1540 6115 1580 1518 6116 1604 1542 6117 1581 1519 6118 1582 1520 6119 1604 1542 6120 1603 1541 6121 1581 1519 6122 1605 1543 6123 1582 1520 6124 1583 1521 6125 1605 1543 6126 1604 1542 6127 1582 1520 6128 1606 1544 6129 1583 1521 6130 1584 1522 6131 1606 1544 6132 1605 1543 6133 1583 1521 6134 1607 1545 6135 1584 1522 6136 1585 1523 6137 1607 1545 6138 1606 1544 6139 1584 1522 6140 1608 1546 6141 1585 1523 6142 1586 1524 6143 1608 1546 6144 1607 1545 6145 1585 1523 6146 1609 1547 6147 1586 1524 6148 1587 1525 6149 1609 1547 6150 1608 1546 6151 1586 1524 6152 1610 1548 6153 1587 1525 6154 1588 1526 6155 1610 1548 6156 1609 1547 6157 1587 1525 6158 1611 1549 6159 1588 1526 6160 1589 1527 6161 1611 1549 6162 1610 1548 6163 1588 1526 6164 1612 1550 6165 1589 1527 6166 1590 1528 6167 1612 1550 6168 1611 1549 6169 1589 1527 6170 1613 1551 6171 1590 1528 6172 1591 1529 6173 1613 1551 6174 1612 1550 6175 1590 1528 6176 1614 1552 6177 1591 1529 6178 1592 1530 6179 1614 1552 6180 1613 1551 6181 1591 1529 6182 1615 1553 6183 1592 1530 6184 1593 1531 6185 1615 1553 6186 1614 1552 6187 1592 1530 6188 1616 1554 6189 1593 1531 6190 441 437 6191 1616 1554 6192 1615 1553 6193 1593 1531 6194 437 433 6195 1616 1554 6196 441 437 6197 1617 1555 6198 1598 1536 6199 1618 1556 6200 1617 1555 6201 1597 1535 6202 1598 1536 6203 1619 1557 6204 1600 1538 6205 1599 1537 6206 1620 1558 6207 1618 1556 6208 1621 1559 6209 1622 1560 6210 1617 1555 6211 1618 1556 6212 1620 1558 6213 1622 1560 6214 1618 1556 6215 1623 1561 6216 1599 1537 6217 1601 1539 6218 1624 1562 6219 1619 1557 6220 1599 1537 6221 1623 1561 6222 1624 1562 6223 1599 1537 6224 1625 1563 6225 1601 1539 6226 1602 1540 6227 1625 1563 6228 1623 1561 6229 1601 1539 6230 1626 1564 6231 1602 1540 6232 1603 1541 6233 1626 1564 6234 1625 1563 6235 1602 1540 6236 1627 1565 6237 1603 1541 6238 1604 1542 6239 1627 1565 6240 1626 1564 6241 1603 1541 6242 1628 1566 6243 1604 1542 6244 1605 1543 6245 1628 1566 6246 1627 1565 6247 1604 1542 6248 1629 1567 6249 1605 1543 6250 1606 1544 6251 1629 1567 6252 1628 1566 6253 1605 1543 6254 1630 1568 6255 1606 1544 6256 1607 1545 6257 1630 1568 6258 1629 1567 6259 1606 1544 6260 1631 1569 6261 1607 1545 6262 1608 1546 6263 1631 1569 6264 1630 1568 6265 1607 1545 6266 1632 1570 6267 1608 1546 6268 1609 1547 6269 1632 1570 6270 1631 1569 6271 1608 1546 6272 1633 1571 6273 1609 1547 6274 1610 1548 6275 1633 1571 6276 1632 1570 6277 1609 1547 6278 1634 1572 6279 1610 1548 6280 1611 1549 6281 1634 1572 6282 1633 1571 6283 1610 1548 6284 1635 1573 6285 1611 1549 6286 1612 1550 6287 1635 1573 6288 1634 1572 6289 1611 1549 6290 1636 1574 6291 1612 1550 6292 1613 1551 6293 1636 1574 6294 1635 1573 6295 1612 1550 6296 1637 1575 6297 1613 1551 6298 1614 1552 6299 1637 1575 6300 1636 1574 6301 1613 1551 6302 1638 1576 6303 1614 1552 6304 1615 1553 6305 1638 1576 6306 1637 1575 6307 1614 1552 6308 1639 1577 6309 1615 1553 6310 1616 1554 6311 1639 1577 6312 1638 1576 6313 1615 1553 6314 1640 1578 6315 1616 1554 6316 437 433 6317 1640 1578 6318 1639 1577 6319 1616 1554 6320 445 441 6321 1640 1578 6322 437 433 6323 1641 1579 6324 1621 1559 6325 1642 1580 6326 1641 1579 6327 1620 1558 6328 1621 1559 6329 1643 1581 6330 1624 1562 6331 1623 1561 6332 1643 1581 6333 1644 1582 6334 1624 1562 6335 1645 1583 6336 1642 1580 6337 1646 1584 6338 1645 1583 6339 1641 1579 6340 1642 1580 6341 1647 1585 6342 1623 1561 6343 1625 1563 6344 1647 1585 6345 1643 1581 6346 1623 1561 6347 1648 1586 6348 1625 1563 6349 1626 1564 6350 1648 1586 6351 1647 1585 6352 1625 1563 6353 1649 1587 6354 1626 1564 6355 1627 1565 6356 1649 1587 6357 1648 1586 6358 1626 1564 6359 1650 1588 6360 1627 1565 6361 1628 1566 6362 1650 1588 6363 1649 1587 6364 1627 1565 6365 1651 1589 6366 1628 1566 6367 1629 1567 6368 1651 1589 6369 1650 1588 6370 1628 1566 6371 1652 1590 6372 1629 1567 6373 1630 1568 6374 1652 1590 6375 1651 1589 6376 1629 1567 6377 1653 1591 6378 1630 1568 6379 1631 1569 6380 1653 1591 6381 1652 1590 6382 1630 1568 6383 1654 1592 6384 1631 1569 6385 1632 1570 6386 1654 1592 6387 1653 1591 6388 1631 1569 6389 1655 1593 6390 1632 1570 6391 1633 1571 6392 1655 1593 6393 1654 1592 6394 1632 1570 6395 1656 1594 6396 1633 1571 6397 1634 1572 6398 1656 1594 6399 1655 1593 6400 1633 1571 6401 1657 1595 6402 1634 1572 6403 1635 1573 6404 1657 1595 6405 1656 1594 6406 1634 1572 6407 1658 1596 6408 1635 1573 6409 1636 1574 6410 1658 1596 6411 1657 1595 6412 1635 1573 6413 1659 1597 6414 1636 1574 6415 1637 1575 6416 1659 1597 6417 1658 1596 6418 1636 1574 6419 1660 1598 6420 1637 1575 6421 1638 1576 6422 1660 1598 6423 1659 1597 6424 1637 1575 6425 1661 1599 6426 1638 1576 6427 1639 1577 6428 1661 1599 6429 1660 1598 6430 1638 1576 6431 1662 1600 6432 1639 1577 6433 1640 1578 6434 1662 1600 6435 1661 1599 6436 1639 1577 6437 320 316 6438 1640 1578 6439 445 441 6440 320 316 6441 1662 1600 6442 1640 1578 6443 1643 1581 6444 1663 1601 6445 1644 1582 6446 1645 1583 6447 1646 1584 6448 1664 1602 6449 1665 1603 6450 1663 1601 6451 1643 1581 6452 1665 1603 6453 1666 1604 6454 1663 1601 6455 1667 1605 6456 1664 1602 6457 1668 1606 6458 1667 1605 6459 1645 1583 6460 1664 1602 6461 1669 1607 6462 1643 1581 6463 1647 1585 6464 1669 1607 6465 1665 1603 6466 1643 1581 6467 1670 1608 6468 1647 1585 6469 1648 1586 6470 1670 1608 6471 1669 1607 6472 1647 1585 6473 1671 1609 6474 1648 1586 6475 1649 1587 6476 1671 1609 6477 1670 1608 6478 1648 1586 6479 1672 1610 6480 1649 1587 6481 1650 1588 6482 1672 1610 6483 1671 1609 6484 1649 1587 6485 1673 1611 6486 1650 1588 6487 1651 1589 6488 1673 1611 6489 1672 1610 6490 1650 1588 6491 1674 1612 6492 1651 1589 6493 1652 1590 6494 1674 1612 6495 1673 1611 6496 1651 1589 6497 1675 1613 6498 1652 1590 6499 1653 1591 6500 1675 1613 6501 1674 1612 6502 1652 1590 6503 1676 1614 6504 1653 1591 6505 1654 1592 6506 1676 1614 6507 1675 1613 6508 1653 1591 6509 1677 1615 6510 1654 1592 6511 1655 1593 6512 1677 1615 6513 1676 1614 6514 1654 1592 6515 1678 1616 6516 1655 1593 6517 1656 1594 6518 1678 1616 6519 1677 1615 6520 1655 1593 6521 1679 1617 6522 1656 1594 6523 1657 1595 6524 1679 1617 6525 1678 1616 6526 1656 1594 6527 1680 1618 6528 1657 1595 6529 1658 1596 6530 1680 1618 6531 1679 1617 6532 1657 1595 6533 1292 1230 6534 1658 1596 6535 1659 1597 6536 1292 1230 6537 1680 1618 6538 1658 1596 6539 1285 1223 6540 1659 1597 6541 1660 1598 6542 1285 1223 6543 1292 1230 6544 1659 1597 6545 1283 1221 6546 1660 1598 6547 1661 1599 6548 1283 1221 6549 1285 1223 6550 1660 1598 6551 1281 1219 6552 1661 1599 6553 1662 1600 6554 1281 1219 6555 1283 1221 6556 1661 1599 6557 154 152 6558 1662 1600 6559 320 316 6560 154 152 6561 1281 1219 6562 1662 1600 6563 1665 1603 6564 1681 1619 6565 1666 1604 6566 1682 1620 6567 1668 1606 6568 1683 1621 6569 1682 1620 6570 1667 1605 6571 1668 1606 6572 1684 1622 6573 1681 1619 6574 1665 1603 6575 1684 1622 6576 1685 1623 6577 1681 1619 6578 1686 1624 6579 1683 1621 6580 1687 1625 6581 1686 1624 6582 1682 1620 6583 1683 1621 6584 1688 1626 6585 1665 1603 6586 1669 1607 6587 1688 1626 6588 1684 1622 6589 1665 1603 6590 1689 1627 6591 1669 1607 6592 1670 1608 6593 1689 1627 6594 1688 1626 6595 1669 1607 6596 1690 1628 6597 1670 1608 6598 1671 1609 6599 1690 1628 6600 1689 1627 6601 1670 1608 6602 1691 1629 6603 1671 1609 6604 1672 1610 6605 1691 1629 6606 1690 1628 6607 1671 1609 6608 1692 1630 6609 1672 1610 6610 1673 1611 6611 1692 1630 6612 1691 1629 6613 1672 1610 6614 1693 1631 6615 1673 1611 6616 1674 1612 6617 1693 1631 6618 1692 1630 6619 1673 1611 6620 1694 1632 6621 1674 1612 6622 1675 1613 6623 1694 1632 6624 1693 1631 6625 1674 1612 6626 1695 1633 6627 1675 1613 6628 1676 1614 6629 1695 1633 6630 1694 1632 6631 1675 1613 6632 1696 1634 6633 1676 1614 6634 1677 1615 6635 1696 1634 6636 1695 1633 6637 1676 1614 6638 1697 1635 6639 1677 1615 6640 1678 1616 6641 1697 1635 6642 1696 1634 6643 1677 1615 6644 1698 1636 6645 1678 1616 6646 1679 1617 6647 1698 1636 6648 1697 1635 6649 1678 1616 6650 1355 1293 6651 1679 1617 6652 1680 1618 6653 1355 1293 6654 1698 1636 6655 1679 1617 6656 1290 1228 6657 1680 1618 6658 1292 1230 6659 1290 1228 6660 1355 1293 6661 1680 1618 6662 1684 1622 6663 1699 1637 6664 1685 1623 6665 1700 1638 6666 1687 1625 6667 1701 1639 6668 1700 1638 6669 1686 1624 6670 1687 1625 6671 1702 1640 6672 1699 1637 6673 1684 1622 6674 1702 1640 6675 1703 1641 6676 1699 1637 6677 1704 1642 6678 1701 1639 6679 1705 1643 6680 1704 1642 6681 1700 1638 6682 1701 1639 6683 1706 1644 6684 1684 1622 6685 1688 1626 6686 1706 1644 6687 1702 1640 6688 1684 1622 6689 1707 1645 6690 1688 1626 6691 1689 1627 6692 1707 1645 6693 1706 1644 6694 1688 1626 6695 1708 1646 6696 1689 1627 6697 1690 1628 6698 1708 1646 6699 1707 1645 6700 1689 1627 6701 1709 1647 6702 1690 1628 6703 1691 1629 6704 1709 1647 6705 1708 1646 6706 1690 1628 6707 1710 1648 6708 1691 1629 6709 1692 1630 6710 1710 1648 6711 1709 1647 6712 1691 1629 6713 1711 1649 6714 1692 1630 6715 1693 1631 6716 1711 1649 6717 1710 1648 6718 1692 1630 6719 1712 1650 6720 1693 1631 6721 1694 1632 6722 1712 1650 6723 1711 1649 6724 1693 1631 6725 1712 1650 6726 1694 1632 6727 1695 1633 6728 1713 1651 6729 1695 1633 6730 1696 1634 6731 1713 1651 6732 1712 1650 6733 1695 1633 6734 1714 1652 6735 1696 1634 6736 1697 1635 6737 1715 1653 6738 1713 1651 6739 1696 1634 6740 1716 1654 6741 1715 1653 6742 1696 1634 6743 1714 1652 6744 1716 1654 6745 1696 1634 6746 1717 1655 6747 1697 1635 6748 1698 1636 6749 1718 1656 6750 1714 1652 6751 1697 1635 6752 1717 1655 6753 1718 1656 6754 1697 1635 6755 1719 1657 6756 1698 1636 6757 1355 1293 6758 1720 1658 6759 1717 1655 6760 1698 1636 6761 1719 1657 6762 1720 1658 6763 1698 1636 6764 1356 1294 6765 1719 1657 6766 1355 1293 6767 1702 1640 6768 1721 1659 6769 1703 1641 6770 1722 1660 6771 1705 1643 6772 1723 1661 6773 1722 1660 6774 1704 1642 6775 1705 1643 6776 1724 1662 6777 1721 1659 6778 1702 1640 6779 1724 1662 6780 1725 1663 6781 1721 1659 6782 1726 1664 6783 1723 1661 6784 1727 1665 6785 1726 1664 6786 1722 1660 6787 1723 1661 6788 1728 1666 6789 1702 1640 6790 1706 1644 6791 1728 1666 6792 1724 1662 6793 1702 1640 6794 1729 1667 6795 1706 1644 6796 1707 1645 6797 1729 1667 6798 1728 1666 6799 1706 1644 6800 1730 1668 6801 1707 1645 6802 1708 1646 6803 1730 1668 6804 1729 1667 6805 1707 1645 6806 1731 1669 6807 1708 1646 6808 1709 1647 6809 1731 1669 6810 1730 1668 6811 1708 1646 6812 1732 1670 6813 1709 1647 6814 1710 1648 6815 1733 1671 6816 1731 1669 6817 1709 1647 6818 1732 1670 6819 1733 1671 6820 1709 1647 6821 1734 1672 6822 1710 1648 6823 1711 1649 6824 1735 1673 6825 1732 1670 6826 1710 1648 6827 1734 1672 6828 1735 1673 6829 1710 1648 6830 1736 1674 6831 1711 1649 6832 1712 1650 6833 1737 1675 6834 1734 1672 6835 1711 1649 6836 1736 1674 6837 1737 1675 6838 1711 1649 6839 1738 1676 6840 1712 1650 6841 1713 1651 6842 1739 1677 6843 1736 1674 6844 1712 1650 6845 1738 1676 6846 1739 1677 6847 1712 1650 6848 1740 1678 6849 1741 1679 6850 1742 1680 6851 1740 1678 6852 1743 1681 6853 1741 1679 6854 1744 1682 6855 1742 1680 6856 1745 1683 6857 1744 1682 6858 1740 1678 6859 1742 1680 6860 1744 1682 6861 1745 1683 6862 1746 1684 6863 1747 1685 6864 1746 1684 6865 1748 1686 6866 1747 1685 6867 1744 1682 6868 1746 1684 6869 1747 1685 6870 1748 1686 6871 1749 1687 6872 1750 1688 6873 1749 1687 6874 1751 1689 6875 1750 1688 6876 1747 1685 6877 1749 1687 6878 1750 1688 6879 1751 1689 6880 1752 1690 6881 1352 1290 6882 1752 1690 6883 1357 1295 6884 1352 1290 6885 1750 1688 6886 1752 1690 6887 1724 1662 6888 1753 1691 6889 1725 1663 6890 1754 1692 6891 1727 1665 6892 1755 1693 6893 1754 1692 6894 1726 1664 6895 1727 1665 6896 1756 1694 6897 1753 1691 6898 1724 1662 6899 1757 1695 6900 1758 1696 6901 1753 1691 6902 1759 1697 6903 1755 1693 6904 1760 1698 6905 1756 1694 6906 1757 1695 6907 1753 1691 6908 1759 1697 6909 1754 1692 6910 1755 1693 6911 1761 1699 6912 1724 1662 6913 1728 1666 6914 1761 1699 6915 1756 1694 6916 1724 1662 6917 1762 1700 6918 1728 1666 6919 1729 1667 6920 1763 1701 6921 1761 1699 6922 1728 1666 6923 1762 1700 6924 1763 1701 6925 1728 1666 6926 1764 1702 6927 1729 1667 6928 1730 1668 6929 1765 1703 6930 1762 1700 6931 1729 1667 6932 1764 1702 6933 1765 1703 6934 1729 1667 6935 1766 1704 6936 1730 1668 6937 1731 1669 6938 1767 1705 6939 1764 1702 6940 1730 1668 6941 1766 1704 6942 1767 1705 6943 1730 1668 6944 1768 1706 6945 1769 1707 6946 1770 1708 6947 1771 1709 6948 1766 1704 6949 1731 1669 6950 1768 1706 6951 1772 1710 6952 1769 1707 6953 1773 1711 6954 1770 1708 6955 1774 1712 6956 1773 1711 6957 1768 1706 6958 1770 1708 6959 1775 1713 6960 1774 1712 6961 1776 1714 6962 1775 1713 6963 1773 1711 6964 1774 1712 6965 1775 1713 6966 1776 1714 6967 1777 1715 6968 1778 1716 6969 1777 1715 6970 1779 1717 6971 1778 1716 6972 1775 1713 6973 1777 1715 6974 1778 1716 6975 1779 1717 6976 1780 1718 6977 1781 1719 6978 1780 1718 6979 1782 1720 6980 1781 1719 6981 1778 1716 6982 1780 1718 6983 1781 1719 6984 1782 1720 6985 1743 1681 6986 1740 1678 6987 1781 1719 6988 1743 1681 6989 1757 1695 6990 1783 1721 6991 1758 1696 6992 1784 1722 6993 1760 1698 6994 1785 1723 6995 1784 1722 6996 1759 1697 6997 1760 1698 6998 1786 1724 6999 1787 1725 7000 1788 1726 7001 1789 1727 7002 1784 1722 7003 1785 1723 7004 1790 1728 7005 1789 1727 7006 1785 1723 7007 1786 1724 7008 1791 1729 7009 1787 1725 7010 1792 1730 7011 1788 1726 7012 1793 1731 7013 1792 1730 7014 1786 1724 7015 1788 1726 7016 1792 1730 7017 1793 1731 7018 1794 1732 7019 1795 1733 7020 1794 1732 7021 1796 1734 7022 1795 1733 7023 1792 1730 7024 1794 1732 7025 1795 1733 7026 1796 1734 7027 1797 1735 7028 1798 1736 7029 1797 1735 7030 1799 1737 7031 1798 1736 7032 1795 1733 7033 1797 1735 7034 1798 1736 7035 1799 1737 7036 1800 1738 7037 1801 1739 7038 1800 1738 7039 1802 1740 7040 1801 1739 7041 1798 1736 7042 1800 1738 7043 1801 1739 7044 1802 1740 7045 1803 1741 7046 1768 1706 7047 1803 1741 7048 1772 1710 7049 1768 1706 7050 1801 1739 7051 1803 1741 7052 1091 1061 7053 994 969 7054 1443 1381 7055 1804 1742 7056 1443 1381 7057 1444 1382 7058 1804 1742 7059 1091 1061 7060 1443 1381 7061 1805 1743 7062 1444 1382 7063 1445 1383 7064 1805 1743 7065 1804 1742 7066 1444 1382 7067 1806 1744 7068 1445 1383 7069 1446 1384 7070 1806 1744 7071 1805 1743 7072 1445 1383 7073 1807 1745 7074 1446 1384 7075 1447 1385 7076 1807 1745 7077 1806 1744 7078 1446 1384 7079 1808 1746 7080 1447 1385 7081 1448 1386 7082 1808 1746 7083 1807 1745 7084 1447 1385 7085 1809 1747 7086 1448 1386 7087 1449 1387 7088 1809 1747 7089 1808 1746 7090 1448 1386 7091 1810 1748 7092 1449 1387 7093 1450 1388 7094 1810 1748 7095 1809 1747 7096 1449 1387 7097 1811 1749 7098 1450 1388 7099 1451 1389 7100 1811 1749 7101 1810 1748 7102 1450 1388 7103 1812 1750 7104 1451 1389 7105 1452 1390 7106 1812 1750 7107 1811 1749 7108 1451 1389 7109 1813 1751 7110 1452 1390 7111 1453 1391 7112 1813 1751 7113 1812 1750 7114 1452 1390 7115 1814 1752 7116 1453 1391 7117 1454 1392 7118 1814 1752 7119 1813 1751 7120 1453 1391 7121 1815 1753 7122 1454 1392 7123 1455 1393 7124 1815 1753 7125 1814 1752 7126 1454 1392 7127 1816 1754 7128 1455 1393 7129 1456 1394 7130 1816 1754 7131 1815 1753 7132 1455 1393 7133 1817 1755 7134 1456 1394 7135 1457 1395 7136 1817 1755 7137 1816 1754 7138 1456 1394 7139 1818 1756 7140 1457 1395 7141 1458 1396 7142 1818 1756 7143 1817 1755 7144 1457 1395 7145 1819 1757 7146 1458 1396 7147 1459 1397 7148 1819 1757 7149 1818 1756 7150 1458 1396 7151 1820 1758 7152 1459 1397 7153 1460 1398 7154 1820 1758 7155 1819 1757 7156 1459 1397 7157 1821 1759 7158 1460 1398 7159 1461 1399 7160 1821 1759 7161 1820 1758 7162 1460 1398 7163 1822 1760 7164 1461 1399 7165 1462 1400 7166 1822 1760 7167 1821 1759 7168 1461 1399 7169 1823 1761 7170 1462 1400 7171 1463 1401 7172 1823 1761 7173 1822 1760 7174 1462 1400 7175 1824 1762 7176 1463 1401 7177 1464 1402 7178 1824 1762 7179 1823 1761 7180 1463 1401 7181 1825 1763 7182 1464 1402 7183 1465 1403 7184 1825 1763 7185 1824 1762 7186 1464 1402 7187 1826 1764 7188 1465 1403 7189 1466 1404 7190 1826 1764 7191 1825 1763 7192 1465 1403 7193 1827 1765 7194 1466 1404 7195 1467 1405 7196 1827 1765 7197 1826 1764 7198 1466 1404 7199 1828 1766 7200 1467 1405 7201 860 844 7202 1828 1766 7203 1827 1765 7204 1467 1405 7205 932 907 7206 1828 1766 7207 860 844 7208 1083 1053 7209 1091 1061 7210 1804 1742 7211 1829 1767 7212 1804 1742 7213 1805 1743 7214 1829 1767 7215 1083 1053 7216 1804 1742 7217 1830 1768 7218 1805 1743 7219 1806 1744 7220 1830 1768 7221 1829 1767 7222 1805 1743 7223 1831 1769 7224 1806 1744 7225 1807 1745 7226 1831 1769 7227 1830 1768 7228 1806 1744 7229 1832 1770 7230 1807 1745 7231 1808 1746 7232 1832 1770 7233 1831 1769 7234 1807 1745 7235 1833 1771 7236 1808 1746 7237 1809 1747 7238 1833 1771 7239 1832 1770 7240 1808 1746 7241 1834 1772 7242 1809 1747 7243 1810 1748 7244 1834 1772 7245 1833 1771 7246 1809 1747 7247 1835 1773 7248 1810 1748 7249 1811 1749 7250 1835 1773 7251 1834 1772 7252 1810 1748 7253 1836 1774 7254 1811 1749 7255 1812 1750 7256 1836 1774 7257 1835 1773 7258 1811 1749 7259 1837 1775 7260 1812 1750 7261 1813 1751 7262 1837 1775 7263 1836 1774 7264 1812 1750 7265 1838 1776 7266 1813 1751 7267 1814 1752 7268 1838 1776 7269 1837 1775 7270 1813 1751 7271 1839 1777 7272 1814 1752 7273 1815 1753 7274 1839 1777 7275 1838 1776 7276 1814 1752 7277 1840 1778 7278 1815 1753 7279 1816 1754 7280 1840 1778 7281 1839 1777 7282 1815 1753 7283 1841 1779 7284 1816 1754 7285 1817 1755 7286 1841 1779 7287 1840 1778 7288 1816 1754 7289 1842 1780 7290 1817 1755 7291 1818 1756 7292 1842 1780 7293 1841 1779 7294 1817 1755 7295 1843 1781 7296 1818 1756 7297 1819 1757 7298 1843 1781 7299 1842 1780 7300 1818 1756 7301 1844 1782 7302 1819 1757 7303 1820 1758 7304 1844 1782 7305 1843 1781 7306 1819 1757 7307 1845 1783 7308 1820 1758 7309 1821 1759 7310 1845 1783 7311 1844 1782 7312 1820 1758 7313 1846 1784 7314 1821 1759 7315 1822 1760 7316 1846 1784 7317 1845 1783 7318 1821 1759 7319 1847 1785 7320 1822 1760 7321 1823 1761 7322 1847 1785 7323 1846 1784 7324 1822 1760 7325 1848 1786 7326 1823 1761 7327 1824 1762 7328 1848 1786 7329 1847 1785 7330 1823 1761 7331 1849 1787 7332 1824 1762 7333 1825 1763 7334 1849 1787 7335 1848 1786 7336 1824 1762 7337 1850 1788 7338 1825 1763 7339 1826 1764 7340 1850 1788 7341 1849 1787 7342 1825 1763 7343 1851 1789 7344 1826 1764 7345 1827 1765 7346 1851 1789 7347 1850 1788 7348 1826 1764 7349 1852 1790 7350 1827 1765 7351 1828 1766 7352 1852 1790 7353 1851 1789 7354 1827 1765 7355 1853 1791 7356 1828 1766 7357 932 907 7358 1853 1791 7359 1852 1790 7360 1828 1766 7361 998 973 7362 1853 1791 7363 932 907 7364 1087 1057 7365 1083 1053 7366 1829 1767 7367 1111 1070 7368 1829 1767 7369 1830 1768 7370 1111 1070 7371 1087 1057 7372 1829 1767 7373 1112 1071 7374 1830 1768 7375 1831 1769 7376 1112 1071 7377 1111 1070 7378 1830 1768 7379 1113 1072 7380 1831 1769 7381 1832 1770 7382 1113 1072 7383 1112 1071 7384 1831 1769 7385 1114 1073 7386 1832 1770 7387 1833 1771 7388 1114 1073 7389 1113 1072 7390 1832 1770 7391 1115 1074 7392 1833 1771 7393 1834 1772 7394 1115 1074 7395 1114 1073 7396 1833 1771 7397 1116 1075 7398 1834 1772 7399 1835 1773 7400 1116 1075 7401 1115 1074 7402 1834 1772 7403 1117 1076 7404 1835 1773 7405 1836 1774 7406 1117 1076 7407 1116 1075 7408 1835 1773 7409 1118 1077 7410 1836 1774 7411 1837 1775 7412 1118 1077 7413 1117 1076 7414 1836 1774 7415 1119 1078 7416 1837 1775 7417 1838 1776 7418 1119 1078 7419 1118 1077 7420 1837 1775 7421 1120 1079 7422 1838 1776 7423 1839 1777 7424 1120 1079 7425 1119 1078 7426 1838 1776 7427 1121 1080 7428 1839 1777 7429 1840 1778 7430 1121 1080 7431 1120 1079 7432 1839 1777 7433 1122 1081 7434 1840 1778 7435 1841 1779 7436 1122 1081 7437 1121 1080 7438 1840 1778 7439 1123 1082 7440 1841 1779 7441 1842 1780 7442 1123 1082 7443 1122 1081 7444 1841 1779 7445 1124 1083 7446 1842 1780 7447 1843 1781 7448 1124 1083 7449 1123 1082 7450 1842 1780 7451 1125 1084 7452 1843 1781 7453 1844 1782 7454 1125 1084 7455 1124 1083 7456 1843 1781 7457 1126 1085 7458 1844 1782 7459 1845 1783 7460 1126 1085 7461 1125 1084 7462 1844 1782 7463 1127 1086 7464 1845 1783 7465 1846 1784 7466 1127 1086 7467 1126 1085 7468 1845 1783 7469 1128 1087 7470 1846 1784 7471 1847 1785 7472 1128 1087 7473 1127 1086 7474 1846 1784 7475 1129 1088 7476 1847 1785 7477 1848 1786 7478 1129 1088 7479 1128 1087 7480 1847 1785 7481 1130 1089 7482 1848 1786 7483 1849 1787 7484 1130 1089 7485 1129 1088 7486 1848 1786 7487 1131 1090 7488 1849 1787 7489 1850 1788 7490 1131 1090 7491 1130 1089 7492 1849 1787 7493 1132 1091 7494 1850 1788 7495 1851 1789 7496 1132 1091 7497 1131 1090 7498 1850 1788 7499 1133 1092 7500 1851 1789 7501 1852 1790 7502 1133 1092 7503 1132 1091 7504 1851 1789 7505 1134 1093 7506 1852 1790 7507 1853 1791 7508 1134 1093 7509 1133 1092 7510 1852 1790 7511 1135 1094 7512 1853 1791 7513 998 973 7514 1135 1094 7515 1134 1093 7516 1853 1791 7517 1025 997 7518 1135 1094 7519 998 973 7520 1854 1792 7521 1855 1068 7522 1856 1793 7523 1857 1068 7524 1858 1794 7525 1855 1068 7526 1854 1792 7527 1857 1068 7528 1855 1068 7529 1854 1792 7530 1856 1793 7531 1859 1795 7532 1860 1796 7533 1859 1795 7534 1861 1068 7535 1860 1796 7536 1854 1792 7537 1859 1795 7538 1860 1796 7539 1861 1068 7540 1862 1797 7541 1863 1798 7542 1862 1797 7543 1864 1799 7544 1863 1798 7545 1860 1796 7546 1862 1797 7547 1863 1798 7548 1864 1799 7549 1865 1800 7550 1866 1801 7551 1865 1800 7552 1867 1802 7553 1866 1801 7554 1863 1798 7555 1865 1800 7556 1868 1803 7557 1867 1802 7558 1869 1068 7559 1868 1803 7560 1866 1801 7561 1867 1802 7562 1868 1803 7563 1869 1068 7564 1870 1804 7565 1871 1805 7566 1870 1804 7567 1872 1806 7568 1871 1805 7569 1868 1803 7570 1870 1804 7571 1873 1807 7572 1872 1806 7573 1874 1808 7574 1873 1807 7575 1871 1805 7576 1872 1806 7577 1873 1807 7578 1874 1808 7579 1875 1809 7580 1876 1810 7581 1875 1809 7582 1877 1811 7583 1876 1810 7584 1873 1807 7585 1875 1809 7586 1878 1812 7587 1877 1811 7588 1879 1068 7589 1878 1812 7590 1876 1810 7591 1877 1811 7592 1880 1068 7593 1879 1068 7594 1881 1813 7595 1882 1068 7596 1878 1812 7597 1879 1068 7598 1883 1068 7599 1882 1068 7600 1879 1068 7601 1880 1068 7602 1883 1068 7603 1879 1068 7604 1884 1814 7605 1881 1813 7606 1885 1815 7607 1886 1816 7608 1881 1813 7609 1884 1814 7610 1887 1068 7611 1881 1813 7612 1886 1816 7613 1887 1068 7614 1880 1068 7615 1881 1813 7616 1888 1817 7617 1885 1815 7618 1889 1818 7619 1884 1814 7620 1885 1815 7621 1888 1817 7622 1890 1819 7623 1889 1818 7624 1891 1820 7625 1888 1817 7626 1889 1818 7627 1890 1819 7628 1892 1821 7629 1891 1820 7630 1893 1068 7631 1890 1819 7632 1891 1820 7633 1892 1821 7634 1894 1068 7635 1893 1068 7636 1895 1068 7637 1892 1821 7638 1893 1068 7639 1894 1068 7640 1896 1068 7641 1895 1068 7642 1897 1068 7643 1894 1068 7644 1895 1068 7645 1896 1068 7646 1898 1068 7647 1897 1068 7648 1899 1068 7649 1896 1068 7650 1897 1068 7651 1898 1068 7652 1900 1822 7653 1886 1816 7654 1901 1823 7655 1900 1822 7656 1887 1068 7657 1886 1816 7658 1902 1824 7659 1901 1823 7660 1903 1068 7661 1904 1825 7662 1900 1822 7663 1901 1823 7664 1902 1824 7665 1904 1825 7666 1901 1823 7667 1902 1824 7668 1903 1068 7669 1905 1068 7670 1906 1068 7671 1905 1068 7672 1907 1068 7673 1906 1068 7674 1902 1824 7675 1905 1068 7676 1790 1728 7677 1908 1826 7678 1789 1727 7679 1909 1068 7680 1907 1068 7681 1910 1827 7682 1909 1068 7683 1906 1068 7684 1907 1068 7685 1911 1828 7686 1912 1829 7687 1908 1826 7688 1913 1830 7689 1910 1827 7690 1914 1831 7691 1790 1728 7692 1911 1828 7693 1908 1826 7694 1913 1830 7695 1909 1068 7696 1910 1827 7697 1915 1832 7698 1916 1833 7699 1912 1829 7700 1917 1834 7701 1914 1831 7702 1918 1835 7703 1911 1828 7704 1915 1832 7705 1912 1829 7706 1917 1834 7707 1913 1830 7708 1914 1831 7709 1919 1836 7710 1920 1837 7711 1916 1833 7712 1921 1838 7713 1918 1835 7714 1922 1839 7715 1915 1832 7716 1919 1836 7717 1916 1833 7718 1921 1838 7719 1917 1834 7720 1918 1835 7721 1923 1840 7722 1924 1841 7723 1920 1837 7724 1921 1838 7725 1922 1839 7726 1925 1842 7727 1919 1836 7728 1923 1840 7729 1920 1837 7730 1926 1843 7731 1927 1844 7732 1924 1841 7733 1928 1845 7734 1925 1842 7735 1929 1846 7736 1923 1840 7737 1926 1843 7738 1924 1841 7739 1928 1845 7740 1921 1838 7741 1925 1842 7742 1930 1847 7743 1931 1848 7744 1927 1844 7745 1928 1845 7746 1929 1846 7747 1932 1068 7748 1926 1843 7749 1930 1847 7750 1927 1844 7751 1930 1847 7752 1933 1849 7753 1931 1848 7754 1934 1850 7755 1932 1068 7756 1935 1851 7757 1934 1850 7758 1928 1845 7759 1932 1068 7760 1936 1852 7761 1937 1853 7762 1933 1849 7763 1934 1850 7764 1935 1851 7765 1938 1854 7766 1930 1847 7767 1936 1852 7768 1933 1849 7769 1939 1855 7770 1940 1856 7771 1937 1853 7772 1941 1068 7773 1938 1854 7774 1942 1068 7775 1936 1852 7776 1939 1855 7777 1937 1853 7778 1941 1068 7779 1934 1850 7780 1938 1854 7781 1943 1857 7782 1944 1858 7783 1945 1859 7784 1946 1860 7785 1944 1858 7786 1943 1857 7787 1947 1861 7788 1942 1068 7789 1948 1862 7790 1947 1861 7791 1941 1068 7792 1942 1068 7793 1949 1863 7794 1950 1864 7795 1951 1865 7796 1952 1866 7797 1953 1867 7798 1950 1864 7799 1952 1866 7800 1950 1864 7801 1949 1863 7802 1954 1868 7803 1951 1865 7804 1955 1869 7805 1956 1870 7806 1951 1865 7807 1954 1868 7808 1949 1863 7809 1951 1865 7810 1956 1870 7811 1957 1871 7812 1955 1869 7813 1958 1872 7814 1959 1873 7815 1955 1869 7816 1957 1871 7817 1954 1868 7818 1955 1869 7819 1959 1873 7820 1960 1874 7821 1961 1875 7822 1962 1876 7823 1963 1877 7824 1958 1872 7825 1964 1878 7826 1965 1879 7827 1964 1878 7828 1958 1872 7829 1957 1871 7830 1958 1872 7831 1963 1877 7832 1960 1874 7833 1962 1876 7834 1966 1880 7835 1967 1881 7836 1966 1880 7837 1968 1882 7838 1960 1874 7839 1966 1880 7840 1969 1883 7841 1967 1881 7842 1969 1883 7843 1966 1880 7844 1967 1881 7845 1968 1882 7846 1970 1884 7847 1786 1724 7848 1970 1884 7849 1791 1729 7850 1971 1885 7851 1970 1884 7852 1786 1724 7853 1971 1885 7854 1967 1881 7855 1970 1884 7856 1972 9 7857 1973 9 7858 1974 9 7859 1975 1886 7860 1976 1887 7861 1977 1888 7862 1974 9 7863 1978 9 7864 1972 9 7865 1979 1889 7866 1975 1886 7867 1977 1888 7868 1980 1890 7869 1981 1891 7870 1982 1892 7871 1983 1893 7872 1982 1892 7873 1981 1891 7874 1979 1889 7875 1977 1888 7876 1984 1894 7877 1975 1886 7878 1985 1895 7879 1976 1887 7880 1975 1886 7881 1986 1896 7882 1985 1895 7883 1987 1897 7884 1988 1898 7885 1989 1899 7886 1974 9 7887 1973 9 7888 1990 9 7889 1990 9 7890 1991 9 7891 1974 9 7892 1992 1900 7893 1993 1901 7894 1988 1898 7895 1992 1900 7896 1988 1898 7897 1987 1897 7898 1994 1902 7899 1943 1857 7900 1986 1896 7901 1995 1903 7902 1989 1899 7903 1953 1867 7904 1975 1886 7905 1994 1902 7906 1986 1896 7907 1987 1897 7908 1989 1899 7909 1995 1903 7910 1994 1902 7911 1946 1860 7912 1943 1857 7913 1995 1903 7914 1953 1867 7915 1952 1866 7916 1947 1861 7917 1948 1862 7918 1996 1904 7919 1997 1905 7920 1996 1904 7921 1998 1068 7922 1997 1905 7923 1947 1861 7924 1996 1904 7925 1999 1906 7926 2000 1907 7927 1975 1886 7928 1997 1905 7929 1998 1068 7930 2001 1908 7931 2002 1909 7932 1999 1906 7933 1975 1886 7934 1979 1889 7935 2002 1909 7936 1975 1886 7937 2003 1910 7938 2004 1911 7939 2000 1907 7940 2005 1912 7941 2001 1908 7942 2006 1913 7943 2003 1910 7944 2000 1907 7945 1999 1906 7946 2005 1912 7947 1997 1905 7948 2001 1908 7949 2003 1910 7950 2007 1914 7951 2004 1911 7952 2005 1912 7953 2006 1913 7954 2008 1915 7955 2009 1916 7956 2010 1917 7957 2007 1914 7958 2011 1918 7959 2008 1915 7960 2012 1919 7961 2003 1910 7962 2009 1916 7963 2007 1914 7964 2011 1918 7965 2005 1912 7966 2008 1915 7967 2013 1920 7968 2014 1921 7969 2010 1917 7970 2015 1922 7971 2012 1919 7972 2016 1068 7973 2017 1923 7974 2013 1920 7975 2010 1917 7976 2018 1924 7977 2017 1923 7978 2010 1917 7979 2009 1916 7980 2018 1924 7981 2010 1917 7982 2015 1922 7983 2011 1918 7984 2012 1919 7985 2019 1925 7986 264 260 7987 2014 1921 7988 2015 1922 7989 2016 1068 7990 2020 1926 7991 2021 1927 7992 2019 1925 7993 2014 1921 7994 2022 1928 7995 2021 1927 7996 2014 1921 7997 2023 1929 7998 2022 1928 7999 2014 1921 8000 2013 1920 8001 2023 1929 8002 2014 1921 8003 2024 1930 8004 2020 1926 8005 2025 1931 8006 2026 1932 8007 265 261 8008 264 260 8009 2019 1925 8010 2026 1932 8011 264 260 8012 2024 1930 8013 2015 1922 8014 2020 1926 8015 2027 1933 8016 2025 1931 8017 2028 1934 8018 2027 1933 8019 2024 1930 8020 2025 1931 8021 2027 1933 8022 2028 1934 8023 2029 1935 8024 2030 1936 8025 2029 1935 8026 2031 1937 8027 2030 1936 8028 2027 1933 8029 2029 1935 8030 2032 1938 8031 2031 1937 8032 2033 1068 8033 2032 1938 8034 2030 1936 8035 2031 1937 8036 2034 1068 8037 2033 1068 8038 2035 1939 8039 2036 1068 8040 2032 1938 8041 2033 1068 8042 2037 1068 8043 2036 1068 8044 2033 1068 8045 2034 1068 8046 2037 1068 8047 2033 1068 8048 2038 1940 8049 2035 1939 8050 2039 1941 8051 2040 1942 8052 2035 1939 8053 2038 1940 8054 2041 1068 8055 2035 1939 8056 2040 1942 8057 2034 1068 8058 2035 1939 8059 2041 1068 8060 2042 1943 8061 2039 1941 8062 2043 1944 8063 2038 1940 8064 2039 1941 8065 2042 1943 8066 2044 1945 8067 2043 1944 8068 2045 1946 8069 2042 1943 8070 2043 1944 8071 2044 1945 8072 2046 1947 8073 2045 1946 8074 2047 1068 8075 2044 1945 8076 2045 1946 8077 2046 1947 8078 2048 1068 8079 2047 1068 8080 2049 1068 8081 2046 1947 8082 2047 1068 8083 2048 1068 8084 2050 1068 8085 2049 1068 8086 2051 1068 8087 2048 1068 8088 2049 1068 8089 2050 1068 8090 2052 1068 8091 2051 1068 8092 2053 1068 8093 2050 1068 8094 2051 1068 8095 2052 1068 8096 2054 1948 8097 2040 1942 8098 2055 1949 8099 2054 1948 8100 2041 1068 8101 2040 1942 8102 2056 1950 8103 2055 1949 8104 2057 1068 8105 2058 1951 8106 2054 1948 8107 2055 1949 8108 2056 1950 8109 2058 1951 8110 2055 1949 8111 2056 1950 8112 2057 1068 8113 2059 1068 8114 2060 1068 8115 2059 1068 8116 2061 1068 8117 2060 1068 8118 2056 1950 8119 2059 1068 8120 2062 1068 8121 2061 1068 8122 2063 1952 8123 2062 1068 8124 2060 1068 8125 2061 1068 8126 2064 1953 8127 2065 1954 8128 632 622 8129 2066 1955 8130 2063 1952 8131 2067 1956 8132 2068 1957 8133 2064 1953 8134 632 622 8135 2069 1958 8136 2068 1957 8137 632 622 8138 2070 1959 8139 2069 1958 8140 632 622 8141 664 654 8142 2070 1959 8143 632 622 8144 2066 1955 8145 2062 1068 8146 2063 1952 8147 2071 1960 8148 2072 1961 8149 2065 1954 8150 2073 1962 8151 2067 1956 8152 2074 1963 8153 2075 1964 8154 2071 1960 8155 2065 1954 8156 2076 1965 8157 2075 1964 8158 2065 1954 8159 2064 1953 8160 2076 1965 8161 2065 1954 8162 2073 1962 8163 2066 1955 8164 2067 1956 8165 2077 1966 8166 2078 1967 8167 2072 1961 8168 2079 1968 8169 2074 1963 8170 2080 1969 8171 2071 1960 8172 2077 1966 8173 2072 1961 8174 2079 1968 8175 2073 1962 8176 2074 1963 8177 2081 1970 8178 2082 1971 8179 2078 1967 8180 2079 1968 8181 2080 1969 8182 2083 1972 8183 2077 1966 8184 2081 1970 8185 2078 1967 8186 2084 1973 8187 2085 1974 8188 2082 1971 8189 2086 1975 8190 2083 1972 8191 2087 1976 8192 2081 1970 8193 2084 1973 8194 2082 1971 8195 2086 1975 8196 2079 1968 8197 2083 1972 8198 2088 1977 8199 835 821 8200 2085 1974 8201 2086 1975 8202 2087 1976 8203 2089 1068 8204 2090 1978 8205 2088 1977 8206 2085 1974 8207 2091 1979 8208 2085 1974 8209 2084 1973 8210 2091 1979 8211 2090 1978 8212 2085 1974 8213 2092 1980 8214 2089 1068 8215 2093 1981 8216 2088 1977 8217 838 824 8218 835 821 8219 2092 1980 8220 2086 1975 8221 2089 1068 8222 2092 1980 8223 2093 1981 8224 1858 1794 8225 1857 1068 8226 2092 1980 8227 1858 1794 8228 2090 1978 8229 2094 1982 8230 2088 1977 8231 2095 1983 8232 2096 1984 8233 2097 1985 8234 2098 9 8235 831 9 8236 840 9 8237 2099 1986 8238 2100 1987 8239 2094 1982 8240 2095 1983 8241 2097 1985 8242 2101 1988 8243 2090 1978 8244 2099 1986 8245 2094 1982 8246 2102 1989 8247 2103 1990 8248 2100 1987 8249 2104 1991 8250 2105 1992 8251 2106 1993 8252 2099 1986 8253 2102 1989 8254 2100 1987 8255 2102 1989 8256 2107 1994 8257 2103 1990 8258 2108 1995 8259 2106 1993 8260 2109 1996 8261 2104 1991 8262 2106 1993 8263 2108 1995 8264 2110 1997 8265 731 721 8266 2107 1994 8267 2111 1998 8268 2109 1996 8269 732 722 8270 2102 1989 8271 2110 1997 8272 2107 1994 8273 2108 1995 8274 2109 1996 8275 2111 1998 8276 2110 1997 8277 669 659 8278 731 721 8279 2111 1998 8280 732 722 8281 728 718 8282 2112 1999 8283 2113 2000 8284 265 261 8285 266 262 8286 267 263 8287 2114 2001 8288 2115 2002 8289 2112 1999 8290 265 261 8291 2116 2003 8292 2115 2002 8293 265 261 8294 2117 2004 8295 2116 2003 8296 265 261 8297 2118 2005 8298 2117 2004 8299 265 261 8300 2026 1932 8301 2118 2005 8302 265 261 8303 2119 2006 8304 2120 2007 8305 2113 2000 8306 2121 2008 8307 2114 2001 8308 2122 2009 8309 2112 1999 8310 2119 2006 8311 2113 2000 8312 266 262 8313 2114 2001 8314 2121 2008 8315 2123 2010 8316 2124 2011 8317 2120 2007 8318 2125 2012 8319 2122 2009 8320 2126 2013 8321 2127 2014 8322 2123 2010 8323 2120 2007 8324 2128 2015 8325 2127 2014 8326 2120 2007 8327 2119 2006 8328 2128 2015 8329 2120 2007 8330 2129 2016 8331 2122 2009 8332 2125 2012 8333 2130 2017 8334 2122 2009 8335 2129 2016 8336 2131 2018 8337 2122 2009 8338 2130 2017 8339 2132 2019 8340 2122 2009 8341 2131 2018 8342 2133 2020 8343 2122 2009 8344 2132 2019 8345 2121 2008 8346 2122 2009 8347 2133 2020 8348 2134 2021 8349 2135 2022 8350 2124 2011 8351 2136 2023 8352 2137 2024 8353 2138 2025 8354 2123 2010 8355 2134 2021 8356 2124 2011 8357 2139 2026 8358 2137 2024 8359 2136 2023 8360 2140 2027 8361 2137 2024 8362 2139 2026 8363 2134 2021 8364 2141 2028 8365 2135 2022 8366 2136 2023 8367 2138 2025 8368 2142 2029 8369 1980 1890 8370 1982 1892 8371 2143 2030 8372 2134 2021 8373 2144 2031 8374 2141 2028 8375 2136 2023 8376 2142 2029 8377 2145 2032 8378 2134 2021 8379 1984 1894 8380 2144 2031 8381 2134 2021 8382 1979 1889 8383 1984 1894 8384 2146 9 8385 2147 9 8386 2148 9 8387 2149 2033 8388 2150 2034 8389 2151 2035 8390 2152 2036 8391 2151 2035 8392 2150 2034 8393 2153 9 8394 2154 9 8395 2147 9 8396 2155 9 8397 2153 9 8398 2147 9 8399 2146 9 8400 2155 9 8401 2147 9 8402 2146 9 8403 2148 9 8404 2156 9 8405 2157 2037 8406 2158 2038 8407 2159 2039 8408 2157 2037 8409 2159 2039 8410 2160 2040 8411 2161 2041 8412 2162 2042 8413 2163 2043 8414 2164 2044 8415 2163 2043 8416 2165 2045 8417 2166 2046 8418 2163 2043 8419 2164 2044 8420 2161 2041 8421 2163 2043 8422 2166 2046 8423 2167 2047 8424 2165 2045 8425 2168 2048 8426 2164 2044 8427 2165 2045 8428 2167 2047 8429 2167 2047 8430 2168 2048 8431 2169 2049 8432 2170 2050 8433 2169 2049 8434 2171 2051 8435 2167 2047 8436 2169 2049 8437 2170 2050 8438 2172 2052 8439 2171 2051 8440 2173 2053 8441 2170 2050 8442 2171 2051 8443 2172 2052 8444 2172 2052 8445 2173 2053 8446 2174 2054 8447 2175 2055 8448 2174 2054 8449 2176 2056 8450 2172 2052 8451 2174 2054 8452 2175 2055 8453 2175 2055 8454 2176 2056 8455 2177 2057 8456 2178 2058 8457 2177 2057 8458 2179 2059 8459 2175 2055 8460 2177 2057 8461 2178 2058 8462 2178 2058 8463 2179 2059 8464 2180 2060 8465 2181 2061 8466 2180 2060 8467 2182 2062 8468 2178 2058 8469 2180 2060 8470 2181 2061 8471 2183 2063 8472 2182 2062 8473 2184 2064 8474 2181 2061 8475 2182 2062 8476 2183 2063 8477 2183 2063 8478 2184 2064 8479 2185 2065 8480 2186 2066 8481 2185 2065 8482 2187 2067 8483 2183 2063 8484 2185 2065 8485 2186 2066 8486 2188 2068 8487 2187 2067 8488 2189 2069 8489 2186 2066 8490 2187 2067 8491 2188 2068 8492 2188 2068 8493 2189 2069 8494 2190 2070 8495 2188 2068 8496 2190 2070 8497 2191 2071 8498 2192 2072 8499 2193 2073 8500 2194 2074 8501 2195 9 8502 2196 9 8503 2197 9 8504 2197 9 8505 2198 9 8506 2195 9 8507 2197 9 8508 2196 9 8509 2199 9 8510 2192 2072 8511 2194 2074 8512 2200 2075 8513 2201 2076 8514 2202 2077 8515 2203 2078 8516 2204 2079 8517 2203 2078 8518 2205 2080 8519 2204 2079 8520 2201 2076 8521 2203 2078 8522 2206 2081 8523 2205 2080 8524 2207 2082 8525 2204 2079 8526 2205 2080 8527 2206 2081 8528 2208 2083 8529 2207 2082 8530 2209 2084 8531 2206 2081 8532 2207 2082 8533 2208 2083 8534 2208 2083 8535 2209 2084 8536 2210 2085 8537 2211 2086 8538 2210 2085 8539 2212 2087 8540 2208 2083 8541 2210 2085 8542 2211 2086 8543 2213 2088 8544 2212 2087 8545 2214 2089 8546 2211 2086 8547 2212 2087 8548 2213 2088 8549 2213 2088 8550 2214 2089 8551 2215 2090 8552 2216 2091 8553 2215 2090 8554 2217 2092 8555 2213 2088 8556 2215 2090 8557 2216 2091 8558 2216 2091 8559 2217 2092 8560 2218 2093 8561 2219 2094 8562 2218 2093 8563 2220 2095 8564 2216 2091 8565 2218 2093 8566 2219 2094 8567 2219 2094 8568 2220 2095 8569 2221 2096 8570 2222 2097 8571 2221 2096 8572 2223 2098 8573 2219 2094 8574 2221 2096 8575 2222 2097 8576 2224 2099 8577 2223 2098 8578 2225 2100 8579 2222 2097 8580 2223 2098 8581 2224 2099 8582 2226 2101 8583 2225 2100 8584 2227 2102 8585 2224 2099 8586 2225 2100 8587 2226 2101 8588 2228 2103 8589 2227 2102 8590 2229 2104 8591 2226 2101 8592 2227 2102 8593 2228 2103 8594 2230 2105 8595 2231 2106 8596 2232 2107 8597 2233 2108 8598 2231 2106 8599 2230 2105 8600 2228 2103 8601 2229 2104 8602 2234 2109 8603 2235 9 8604 2236 9 8605 1974 9 8606 1991 9 8607 2235 9 8608 1974 9 8609 2235 9 8610 2237 9 8611 2236 9 8612 2235 9 8613 2238 9 8614 2237 9 8615 2140 2027 8616 2139 2026 8617 2239 2110 8618 2235 9 8619 2240 9 8620 2238 9 8621 2241 2111 8622 2239 2110 8623 2242 2112 8624 2241 2111 8625 2140 2027 8626 2239 2110 8627 2243 9 8628 2244 9 8629 2240 9 8630 2245 2113 8631 2242 2112 8632 2246 2114 8633 2235 9 8634 2243 9 8635 2240 9 8636 2245 2113 8637 2241 2111 8638 2242 2112 8639 2243 9 8640 2247 9 8641 2244 9 8642 2248 2115 8643 2246 2114 8644 2249 2116 8645 2248 2115 8646 2245 2113 8647 2246 2114 8648 2250 9 8649 2251 9 8650 2247 9 8651 2252 2117 8652 2249 2116 8653 2253 2118 8654 2243 9 8655 2250 9 8656 2247 9 8657 2252 2117 8658 2248 2115 8659 2249 2116 8660 2254 9 8661 2255 9 8662 2251 9 8663 2256 2119 8664 2253 2118 8665 2257 2120 8666 2250 9 8667 2254 9 8668 2251 9 8669 2256 2119 8670 2252 2117 8671 2253 2118 8672 2254 9 8673 2258 9 8674 2255 9 8675 2259 2121 8676 2257 2120 8677 2260 2122 8678 2261 2123 8679 2256 2119 8680 2257 2120 8681 2259 2121 8682 2261 2123 8683 2257 2120 8684 2262 9 8685 2263 9 8686 2258 9 8687 2264 2124 8688 2260 2122 8689 2265 2125 8690 2254 9 8691 2262 9 8692 2258 9 8693 2264 2124 8694 2259 2121 8695 2260 2122 8696 2262 9 8697 2266 9 8698 2263 9 8699 2267 2126 8700 2265 2125 8701 2268 2127 8702 2267 2126 8703 2264 2124 8704 2265 2125 8705 2262 9 8706 2269 9 8707 2266 9 8708 2270 2128 8709 2268 2127 8710 2271 2129 8711 2270 2128 8712 2267 2126 8713 2268 2127 8714 2272 2130 8715 2271 2129 8716 2273 2131 8717 2272 2130 8718 2270 2128 8719 2271 2129 8720 2274 2132 8721 2273 2131 8722 2275 2133 8723 2272 2130 8724 2273 2131 8725 2274 2132 8726 2276 2134 8727 2275 2133 8728 2277 2135 8729 2276 2134 8730 2274 2132 8731 2275 2133 8732 2278 2136 8733 2277 2135 8734 2279 2137 8735 2278 2136 8736 2276 2134 8737 2277 2135 8738 2280 2138 8739 2279 2137 8740 2281 2139 8741 2280 2138 8742 2278 2136 8743 2279 2137 8744 2282 2140 8745 2283 2141 8746 2284 2142 8747 2285 2143 8748 2280 2138 8749 2281 2139 8750 2282 2140 8751 2286 2144 8752 2283 2141 8753 1992 1900 8754 2287 2145 8755 1993 1901 8756 2288 2146 8757 2287 2145 8758 1992 1900 8759 2289 2147 8760 2287 2145 8761 2288 2146 8762 2290 2148 8763 2291 2149 8764 2292 2150 8765 2293 2151 8766 2294 2152 8767 2295 2153 8768 2296 2154 8769 2297 2155 8770 2291 2149 8771 2296 2154 8772 2291 2149 8773 2290 2148 8774 2290 2148 8775 2292 2150 8776 2298 2156 8777 2290 2148 8778 2298 2156 8779 2299 2157 8780 2300 2158 8781 2299 2157 8782 2301 2159 8783 2290 2148 8784 2299 2157 8785 2300 2158 8786 2300 2158 8787 2301 2159 8788 2302 2160 8789 2289 2147 8790 2302 2160 8791 2301 2159 8792 2121 2008 8793 2133 2020 8794 2303 2161 8795 2121 2008 8796 2303 2161 8797 2304 2162 8798 2305 2163 8799 2304 2162 8800 2306 2164 8801 2305 2163 8802 2121 2008 8803 2304 2162 8804 2307 2165 8805 2306 2164 8806 2308 2166 8807 2307 2165 8808 2305 2163 8809 2306 2164 8810 2307 2165 8811 2308 2166 8812 2309 2167 8813 2293 2151 8814 2309 2167 8815 2294 2152 8816 2293 2151 8817 2307 2165 8818 2309 2167 8819 2305 2163 8820 2310 2168 8821 2121 2008 8822 266 262 8823 2121 2008 8824 2310 2168 8825 2311 2169 8826 2312 2170 8827 2310 2168 8828 257 253 8829 2310 2168 8830 2312 2170 8831 2305 2163 8832 2311 2169 8833 2310 2168 8834 257 253 8835 266 262 8836 2310 2168 8837 2313 2171 8838 2314 2172 8839 2312 2170 8840 254 250 8841 2312 2170 8842 2314 2172 8843 2311 2169 8844 2313 2171 8845 2312 2170 8846 254 250 8847 257 253 8848 2312 2170 8849 2315 2173 8850 2316 2174 8851 2314 2172 8852 252 248 8853 2314 2172 8854 2316 2174 8855 2317 2175 8856 2315 2173 8857 2314 2172 8858 2313 2171 8859 2317 2175 8860 2314 2172 8861 252 248 8862 254 250 8863 2314 2172 8864 2318 2176 8865 2319 2177 8866 2316 2174 8867 249 245 8868 2316 2174 8869 2319 2177 8870 2320 2178 8871 2318 2176 8872 2316 2174 8873 2315 2173 8874 2320 2178 8875 2316 2174 8876 249 245 8877 252 248 8878 2316 2174 8879 2321 2179 8880 2322 2180 8881 2319 2177 8882 246 242 8883 2319 2177 8884 2322 2180 8885 2323 2181 8886 2321 2179 8887 2319 2177 8888 2318 2176 8889 2323 2181 8890 2319 2177 8891 246 242 8892 249 245 8893 2319 2177 8894 2324 2182 8895 2325 2183 8896 2322 2180 8897 228 224 8898 2322 2180 8899 2325 2183 8900 2321 2179 8901 2324 2182 8902 2322 2180 8903 228 224 8904 246 242 8905 2322 2180 8906 2326 2184 8907 2327 2185 8908 2325 2183 8909 223 219 8910 2325 2183 8911 2327 2185 8912 2328 2186 8913 2326 2184 8914 2325 2183 8915 2324 2182 8916 2328 2186 8917 2325 2183 8918 223 219 8919 228 224 8920 2325 2183 8921 2329 2187 8922 2330 2188 8923 2327 2185 8924 221 217 8925 2327 2185 8926 2330 2188 8927 2331 2189 8928 2329 2187 8929 2327 2185 8930 2326 2184 8931 2331 2189 8932 2327 2185 8933 221 217 8934 223 219 8935 2327 2185 8936 2332 2190 8937 2333 2191 8938 2330 2188 8939 218 214 8940 2330 2188 8941 2333 2191 8942 2329 2187 8943 2332 2190 8944 2330 2188 8945 218 214 8946 221 217 8947 2330 2188 8948 2334 2192 8949 2335 2193 8950 2333 2191 8951 215 211 8952 2333 2191 8953 2335 2193 8954 2336 2194 8955 2334 2192 8956 2333 2191 8957 2332 2190 8958 2336 2194 8959 2333 2191 8960 215 211 8961 218 214 8962 2333 2191 8963 2337 2195 8964 2338 2196 8965 2335 2193 8966 195 191 8967 2335 2193 8968 2338 2196 8969 2334 2192 8970 2337 2195 8971 2335 2193 8972 195 191 8973 215 211 8974 2335 2193 8975 2339 2197 8976 2340 2198 8977 2338 2196 8978 191 187 8979 2338 2196 8980 2340 2198 8981 2341 2199 8982 2339 2197 8983 2338 2196 8984 2337 2195 8985 2341 2199 8986 2338 2196 8987 191 187 8988 195 191 8989 2338 2196 8990 2342 2200 8991 2343 2201 8992 2340 2198 8993 188 184 8994 2340 2198 8995 2343 2201 8996 2339 2197 8997 2342 2200 8998 2340 2198 8999 188 184 9000 191 187 9001 2340 2198 9002 2344 2202 9003 2345 2203 9004 2343 2201 9005 185 181 9006 2343 2201 9007 2345 2203 9008 2342 2200 9009 2344 2202 9010 2343 2201 9011 185 181 9012 188 184 9013 2343 2201 9014 2346 2204 9015 2347 2205 9016 2345 2203 9017 182 178 9018 2345 2203 9019 2347 2205 9020 2348 2206 9021 2346 2204 9022 2345 2203 9023 2344 2202 9024 2348 2206 9025 2345 2203 9026 182 178 9027 185 181 9028 2345 2203 9029 1243 1181 9030 2349 2207 9031 2350 2208 9032 179 175 9033 182 178 9034 2347 2205 9035 171 167 9036 177 173 9037 2349 2207 9038 171 167 9039 2349 2207 9040 1243 1181 9041 2351 2209 9042 2352 2210 9043 2353 2211 9044 2354 2212 9045 1243 1181 9046 2350 2208 9047 2355 2213 9048 2356 2214 9049 2357 2215 9050 2358 2216 9051 2353 2211 9052 2359 2217 9053 2360 2218 9054 2353 2211 9055 2358 2216 9056 2351 2209 9057 2353 2211 9058 2360 2218 9059 2361 2219 9060 2359 2217 9061 2362 2220 9062 2358 2216 9063 2359 2217 9064 2361 2219 9065 2363 2221 9066 2362 2220 9067 2364 2222 9068 2361 2219 9069 2362 2220 9070 2363 2221 9071 2365 2223 9072 2364 2222 9073 2366 2224 9074 2363 2221 9075 2364 2222 9076 2365 2223 9077 2367 2225 9078 2366 2224 9079 2368 2226 9080 2365 2223 9081 2366 2224 9082 2367 2225 9083 2369 2227 9084 2368 2226 9085 2370 2228 9086 2367 2225 9087 2368 2226 9088 2369 2227 9089 2371 2229 9090 2370 2228 9091 2372 2230 9092 2369 2227 9093 2370 2228 9094 2371 2229 9095 2373 2231 9096 2372 2230 9097 2374 2232 9098 2371 2229 9099 2372 2230 9100 2373 2231 9101 2375 2233 9102 2374 2232 9103 2376 2234 9104 2373 2231 9105 2374 2232 9106 2375 2233 9107 2377 2235 9108 2376 2234 9109 2378 2236 9110 2375 2233 9111 2376 2234 9112 2377 2235 9113 2379 2237 9114 2378 2236 9115 2380 2238 9116 2377 2235 9117 2378 2236 9118 2379 2237 9119 2379 2237 9120 2380 2238 9121 2381 2239 9122 2382 2240 9123 2381 2239 9124 2383 2241 9125 2379 2237 9126 2381 2239 9127 2382 2240 9128 2384 2242 9129 2383 2241 9130 2385 2243 9131 2382 2240 9132 2383 2241 9133 2384 2242 9134 2386 2244 9135 2385 2243 9136 2387 2245 9137 2384 2242 9138 2385 2243 9139 2386 2244 9140 2388 2246 9141 2387 2245 9142 2389 2247 9143 2386 2244 9144 2387 2245 9145 2388 2246 9146 2390 2248 9147 2389 2247 9148 2391 2249 9149 2388 2246 9150 2389 2247 9151 2390 2248 9152 2392 2250 9153 2391 2249 9154 2393 2251 9155 2390 2248 9156 2391 2249 9157 2392 2250 9158 2394 2252 9159 2393 2251 9160 2395 2253 9161 2392 2250 9162 2393 2251 9163 2394 2252 9164 2396 2254 9165 2395 2253 9166 2397 2255 9167 2394 2252 9168 2395 2253 9169 2396 2254 9170 2398 2256 9171 2397 2255 9172 2399 2257 9173 2400 2258 9174 2397 2255 9175 2398 2256 9176 2396 2254 9177 2397 2255 9178 2400 2258 9179 2401 2259 9180 2399 2257 9181 2402 2260 9182 2403 2261 9183 2399 2257 9184 2401 2259 9185 2398 2256 9186 2399 2257 9187 2403 2261 9188 2404 2262 9189 2402 2260 9190 2405 2263 9191 2406 2264 9192 2402 2260 9193 2404 2262 9194 2401 2259 9195 2402 2260 9196 2406 2264 9197 2296 2154 9198 2405 2263 9199 2297 2155 9200 2404 2262 9201 2405 2263 9202 2296 2154 9203 1243 1181 9204 2407 2265 9205 1238 1176 9206 2408 2266 9207 1242 1180 9208 2409 2267 9209 2408 2266 9210 1241 1179 9211 1242 1180 9212 2410 2268 9213 2411 2269 9214 2407 2265 9215 2408 2266 9216 2409 2267 9217 2412 2270 9218 1243 1181 9219 2410 2268 9220 2407 2265 9221 2413 2271 9222 2414 2272 9223 2415 2273 9224 2416 2274 9225 2408 2266 9226 2412 2270 9227 2417 2275 9228 2416 2274 9229 2412 2270 9230 2354 2212 9231 2410 2268 9232 1243 1181 9233 2418 2276 9234 2415 2273 9235 2356 2214 9236 2413 2271 9237 2415 2273 9238 2418 2276 9239 2419 2277 9240 2356 2214 9241 2420 2278 9242 2355 2213 9243 2420 2278 9244 2356 2214 9245 2421 2279 9246 2356 2214 9247 2419 2277 9248 2418 2276 9249 2356 2214 9250 2421 2279 9251 1234 1172 9252 1231 1169 9253 2422 2280 9254 2423 2281 9255 2424 2282 9256 2425 2283 9257 2426 9 9258 2427 9 9259 2428 9 9260 2429 9 9261 2427 9 9262 2426 9 9263 2430 9 9264 2427 9 9265 2429 9 9266 2431 9 9267 2427 9 9268 2430 9 9269 2432 2284 9270 2425 2283 9271 2433 2285 9272 2434 2286 9273 2425 2283 9274 2432 2284 9275 2423 2281 9276 2425 2283 9277 2434 2286 9278 2435 9 9279 2428 9 9280 2436 9 9281 2426 9 9282 2428 9 9283 2435 9 9284 2437 9 9285 2436 9 9286 2438 9 9287 2435 9 9288 2436 9 9289 2437 9 9290 2439 9 9291 2438 9 9292 2440 9 9293 2441 2287 9294 2442 2288 9295 2416 2274 9296 2437 9 9297 2438 9 9298 2439 9 9299 2417 2275 9300 2441 2287 9301 2416 2274 9302 2443 9 9303 2440 9 9304 2444 9 9305 2445 2289 9306 2446 2290 9307 2442 2288 9308 2439 9 9309 2440 9 9310 2443 9 9311 2447 2291 9312 2445 2289 9313 2442 2288 9314 2441 2287 9315 2447 2291 9316 2442 2288 9317 2443 9 9318 2444 9 9319 2448 9 9320 2449 2292 9321 2450 2293 9322 2446 2290 9323 2445 2289 9324 2449 2292 9325 2446 2290 9326 2451 2294 9327 2452 2295 9328 2450 2293 9329 2453 2296 9330 2451 2294 9331 2450 2293 9332 2449 2292 9333 2453 2296 9334 2450 2293 9335 2454 2297 9336 2455 2298 9337 2452 2295 9338 2456 2299 9339 2454 2297 9340 2452 2295 9341 2451 2294 9342 2456 2299 9343 2452 2295 9344 2457 2300 9345 2458 2301 9346 2455 2298 9347 2454 2297 9348 2457 2300 9349 2455 2298 9350 2459 2302 9351 2460 2303 9352 2458 2301 9353 2457 2300 9354 2459 2302 9355 2458 2301 9356 2461 2304 9357 2462 2305 9358 2460 2303 9359 2463 2306 9360 2461 2304 9361 2460 2303 9362 2464 2307 9363 2463 2306 9364 2460 2303 9365 2459 2302 9366 2464 2307 9367 2460 2303 9368 2465 2308 9369 2466 2309 9370 2467 2310 9371 2468 2311 9372 2469 2312 9373 2470 2313 9374 2471 2314 9375 2465 2308 9376 2467 2310 9377 2472 2315 9378 2469 2312 9379 2468 2311 9380 2473 2316 9381 2467 2310 9382 2474 2317 9383 2471 2314 9384 2467 2310 9385 2473 2316 9386 2468 2311 9387 2470 2313 9388 2475 2318 9389 2355 2213 9390 2476 2319 9391 2477 2320 9392 2478 2321 9393 2468 2311 9394 2475 2318 9395 2355 2213 9396 2479 2322 9397 2476 2319 9398 2355 2213 9399 2477 2320 9400 2480 2323 9401 2355 2213 9402 2480 2323 9403 2481 2324 9404 2355 2213 9405 2481 2324 9406 2482 2325 9407 2355 2213 9408 2482 2325 9409 2483 2326 9410 2355 2213 9411 2483 2326 9412 2484 2327 9413 2355 2213 9414 2484 2327 9415 2420 2278 9416 1217 1155 9417 2485 2328 9418 2486 2329 9419 2487 2330 9420 1217 1155 9421 2486 2329 9422 1217 1155 9423 1215 1153 9424 2485 2328 9425 2488 2331 9426 1207 1145 9427 1210 1148 9428 2488 2331 9429 1332 1270 9430 1207 1145 9431 2489 2332 9432 1210 1148 9433 1217 1155 9434 2489 2332 9435 2488 2331 9436 1210 1148 9437 2487 2330 9438 2490 2333 9439 1217 1155 9440 2491 2334 9441 1217 1155 9442 2490 2333 9443 2491 2334 9444 2489 2332 9445 1217 1155 9446 2492 2335 9447 2468 2311 9448 2490 2333 9449 2493 2336 9450 2490 2333 9451 2468 2311 9452 2487 2330 9453 2492 2335 9454 2490 2333 9455 2494 2337 9456 2491 2334 9457 2490 2333 9458 2493 2336 9459 2494 2337 9460 2490 2333 9461 2495 2338 9462 2468 2311 9463 2478 2321 9464 2492 2335 9465 2472 2315 9466 2468 2311 9467 2495 2338 9468 2493 2336 9469 2468 2311 9470 2496 2339 9471 2495 2338 9472 2478 2321 9473 2497 2340 9474 2498 2341 9475 2479 2322 9476 2497 2340 9477 2479 2322 9478 2499 2342 9479 2355 2213 9480 2499 2342 9481 2479 2322 9482 2500 2343 9483 1333 1271 9484 2501 2344 9485 2500 2343 9486 1330 1268 9487 1333 1271 9488 2502 2345 9489 2501 2344 9490 2503 2346 9491 2502 2345 9492 2500 2343 9493 2501 2344 9494 2504 2347 9495 2503 2346 9496 2505 2348 9497 2504 2347 9498 2502 2345 9499 2503 2346 9500 2506 2349 9501 2505 2348 9502 2507 2350 9503 2506 2349 9504 2504 2347 9505 2505 2348 9506 2508 2351 9507 2507 2350 9508 2509 2352 9509 2508 2351 9510 2506 2349 9511 2507 2350 9512 2510 2353 9513 2509 2352 9514 2511 2354 9515 2510 2353 9516 2508 2351 9517 2509 2352 9518 2512 2355 9519 2511 2354 9520 2513 2356 9521 2512 2355 9522 2510 2353 9523 2511 2354 9524 2514 2357 9525 2512 2355 9526 2513 2356 9527 2515 2358 9528 2514 2357 9529 2513 2356 9530 2516 2359 9531 2517 2360 9532 1348 1286 9533 2518 2361 9534 1337 1275 9535 2519 2362 9536 1347 1285 9537 2516 2359 9538 1348 1286 9539 2518 2361 9540 1343 1281 9541 1337 1275 9542 2520 2363 9543 2521 2364 9544 2517 2360 9545 2522 2365 9546 2519 2362 9547 2523 2366 9548 2516 2359 9549 2520 2363 9550 2517 2360 9551 2522 2365 9552 2518 2361 9553 2519 2362 9554 2524 2367 9555 2525 2368 9556 2521 2364 9557 2526 2369 9558 2523 2366 9559 2527 2370 9560 2520 2363 9561 2524 2367 9562 2521 2364 9563 2526 2369 9564 2522 2365 9565 2523 2366 9566 2528 2371 9567 2529 2372 9568 2525 2368 9569 2530 2373 9570 2527 2370 9571 2531 2374 9572 2524 2367 9573 2528 2371 9574 2525 2368 9575 2530 2373 9576 2526 2369 9577 2527 2370 9578 2532 2375 9579 2533 2376 9580 2529 2372 9581 2534 2377 9582 2531 2374 9583 2535 2378 9584 2528 2371 9585 2532 2375 9586 2529 2372 9587 2534 2377 9588 2530 2373 9589 2531 2374 9590 2536 2379 9591 2537 2380 9592 2533 2376 9593 2538 2381 9594 2535 2378 9595 2539 2382 9596 2532 2375 9597 2536 2379 9598 2533 2376 9599 2538 2381 9600 2534 2377 9601 2535 2378 9602 2540 2383 9603 2541 2384 9604 2537 2380 9605 2542 2385 9606 2539 2382 9607 2543 2386 9608 2536 2379 9609 2540 2383 9610 2537 2380 9611 2542 2385 9612 2538 2381 9613 2539 2382 9614 2544 2387 9615 2545 2388 9616 2541 2384 9617 2546 2389 9618 2543 2386 9619 2547 2390 9620 2540 2383 9621 2544 2387 9622 2541 2384 9623 2546 2389 9624 2542 2385 9625 2543 2386 9626 2548 2391 9627 2549 2392 9628 2545 2388 9629 2550 2393 9630 2547 2390 9631 2551 2394 9632 2544 2387 9633 2548 2391 9634 2545 2388 9635 2550 2393 9636 2546 2389 9637 2547 2390 9638 2552 2395 9639 2553 2396 9640 2549 2392 9641 2554 2397 9642 2551 2394 9643 2555 2398 9644 2548 2391 9645 2552 2395 9646 2549 2392 9647 2554 2397 9648 2550 2393 9649 2551 2394 9650 2556 2399 9651 2557 2399 9652 2553 2396 9653 2558 2400 9654 2555 2398 9655 2559 2401 9656 2552 2395 9657 2556 2399 9658 2553 2396 9659 2558 2400 9660 2554 2397 9661 2555 2398 9662 2560 2399 9663 2561 2399 9664 2557 2399 9665 2562 2402 9666 2559 2401 9667 2563 2403 9668 2556 2399 9669 2560 2399 9670 2557 2399 9671 2562 2402 9672 2558 2400 9673 2559 2401 9674 2564 2404 9675 2563 2403 9676 2565 2405 9677 2564 2404 9678 2562 2402 9679 2563 2403 9680 2566 2406 9681 2565 2405 9682 2567 2407 9683 2566 2406 9684 2564 2404 9685 2565 2405 9686 2568 2408 9687 2567 2407 9688 2569 2409 9689 2568 2408 9690 2566 2406 9691 2567 2407 9692 2570 2410 9693 2569 2409 9694 2571 2411 9695 2572 2412 9696 2568 2408 9697 2569 2409 9698 2570 2410 9699 2572 2412 9700 2569 2409 9701 2570 2410 9702 2571 2411 9703 2573 2413 9704 2574 2414 9705 2573 2413 9706 2575 2415 9707 2574 2414 9708 2570 2410 9709 2573 2413 9710 2574 2414 9711 2575 2415 9712 2576 2416 9713 2577 2417 9714 2576 2416 9715 2578 2418 9716 2577 2417 9717 2574 2414 9718 2576 2416 9719 2577 2417 9720 2578 2418 9721 2579 2419 9722 2580 2420 9723 2579 2419 9724 2581 2421 9725 2580 2420 9726 2577 2417 9727 2579 2419 9728 2580 2420 9729 2581 2421 9730 2582 2422 9731 2583 2423 9732 2582 2422 9733 2584 2424 9734 2583 2423 9735 2580 2420 9736 2582 2422 9737 2583 2423 9738 2584 2424 9739 2585 2425 9740 2586 2426 9741 2585 2425 9742 2587 2427 9743 2586 2426 9744 2583 2423 9745 2585 2425 9746 1965 1879 9747 2587 2427 9748 2588 2428 9749 1965 1879 9750 2586 2426 9751 2587 2427 9752 1965 1879 9753 2588 2428 9754 1964 1878 9755 2289 2147 9756 2288 2146 9757 2302 2160 9758 2589 2429 9759 2590 2430 9760 2514 2357 9761 2515 2358 9762 2589 2429 9763 2514 2357 9764 2591 2431 9765 2592 2432 9766 2590 2430 9767 2589 2429 9768 2591 2431 9769 2590 2430 9770 2593 2433 9771 2594 2434 9772 2592 2432 9773 2591 2431 9774 2593 2433 9775 2592 2432 9776 2595 2435 9777 2596 2436 9778 2594 2434 9779 2593 2433 9780 2595 2435 9781 2594 2434 9782 2595 2435 9783 2597 2437 9784 2596 2436 9785 2598 2438 9786 2599 2439 9787 2597 2437 9788 2595 2435 9789 2598 2438 9790 2597 2437 9791 2600 2440 9792 2601 2441 9793 2599 2439 9794 2598 2438 9795 2600 2440 9796 2599 2439 9797 2602 2442 9798 2603 2443 9799 2601 2441 9800 2600 2440 9801 2602 2442 9802 2601 2441 9803 2604 2444 9804 2605 2445 9805 2603 2443 9806 2602 2442 9807 2604 2444 9808 2603 2443 9809 2606 2446 9810 2607 2447 9811 2605 2445 9812 2604 2444 9813 2606 2446 9814 2605 2445 9815 2608 2448 9816 2609 2449 9817 2607 2447 9818 2610 2450 9819 2608 2448 9820 2607 2447 9821 2606 2446 9822 2610 2450 9823 2607 2447 9824 2611 2451 9825 2612 2452 9826 2609 2449 9827 2608 2448 9828 2611 2451 9829 2609 2449 9830 2613 2453 9831 2614 2454 9832 2612 2452 9833 2611 2451 9834 2613 2453 9835 2612 2452 9836 2613 2453 9837 2615 2455 9838 2614 2454 9839 1358 1296 9840 1340 1278 9841 2616 2456 9842 2617 2457 9843 2616 2456 9844 2618 2458 9845 1358 1296 9846 2616 2456 9847 2617 2457 9848 2617 2457 9849 2618 2458 9850 2619 2459 9851 2620 2460 9852 2619 2459 9853 2621 2461 9854 2617 2457 9855 2619 2459 9856 2620 2460 9857 2622 2462 9858 2621 2461 9859 2623 2463 9860 2620 2460 9861 2621 2461 9862 2622 2462 9863 2622 2462 9864 2623 2463 9865 2624 2464 9866 2625 2465 9867 2624 2464 9868 2626 2466 9869 2622 2462 9870 2624 2464 9871 2625 2465 9872 2627 2467 9873 2626 2466 9874 2628 2468 9875 2625 2465 9876 2626 2466 9877 2627 2467 9878 2627 2467 9879 2628 2468 9880 2629 2469 9881 2630 2470 9882 2629 2469 9883 2631 2471 9884 2627 2467 9885 2629 2469 9886 2630 2470 9887 2632 2472 9888 2631 2471 9889 2633 2473 9890 2630 2470 9891 2631 2471 9892 2632 2472 9893 2632 2472 9894 2633 2473 9895 2634 2474 9896 2635 2475 9897 2634 2474 9898 2636 2476 9899 2632 2472 9900 2634 2474 9901 2635 2475 9902 2635 2475 9903 2636 2476 9904 2637 2477 9905 2638 2478 9906 2637 2477 9907 2639 2479 9908 2635 2475 9909 2637 2477 9910 2638 2478 9911 2638 2478 9912 2639 2479 9913 2640 2480 9914 2641 2481 9915 2640 2480 9916 2642 2482 9917 2638 2478 9918 2640 2480 9919 2641 2481 9920 2643 2483 9921 2642 2482 9922 2644 2484 9923 2641 2481 9924 2642 2482 9925 2643 2483 9926 2645 2485 9927 2644 2484 9928 2646 2486 9929 2643 2483 9930 2644 2484 9931 2645 2485 9932 2647 2487 9933 2646 2486 9934 2648 2488 9935 2645 2485 9936 2646 2486 9937 2647 2487 9938 1971 1885 9939 2648 2488 9940 2649 2489 9941 2647 2487 9942 2648 2488 9943 1971 1885 9944 1967 1881 9945 2649 2489 9946 1969 1883 9947 1971 1885 9948 2649 2489 9949 1967 1881 9950 2647 2487 9951 1786 1724 9952 1792 1730 9953 2647 2487 9954 1971 1885 9955 1786 1724 9956 2645 2485 9957 1792 1730 9958 1795 1733 9959 2645 2485 9960 2647 2487 9961 1792 1730 9962 2643 2483 9963 1795 1733 9964 1798 1736 9965 2643 2483 9966 2645 2485 9967 1795 1733 9968 2641 2481 9969 1798 1736 9970 1801 1739 9971 2641 2481 9972 2643 2483 9973 1798 1736 9974 2638 2478 9975 1801 1739 9976 1768 1706 9977 2638 2478 9978 2641 2481 9979 1801 1739 9980 2635 2475 9981 1768 1706 9982 1773 1711 9983 2635 2475 9984 2638 2478 9985 1768 1706 9986 2632 2472 9987 1773 1711 9988 1775 1713 9989 2632 2472 9990 2635 2475 9991 1773 1711 9992 2630 2470 9993 1775 1713 9994 1778 1716 9995 2630 2470 9996 2632 2472 9997 1775 1713 9998 2627 2467 9999 1778 1716 10000 1781 1719 10001 2627 2467 10002 2630 2470 10003 1778 1716 10004 2625 2465 10005 1781 1719 10006 1740 1678 10007 2625 2465 10008 2627 2467 10009 1781 1719 10010 2622 2462 10011 1740 1678 10012 1744 1682 10013 2622 2462 10014 2625 2465 10015 1740 1678 10016 2620 2460 10017 1744 1682 10018 1747 1685 10019 2620 2460 10020 2622 2462 10021 1744 1682 10022 2617 2457 10023 1747 1685 10024 1750 1688 10025 2617 2457 10026 2620 2460 10027 1747 1685 10028 1358 1296 10029 1750 1688 10030 1352 1290 10031 1358 1296 10032 2617 2457 10033 1750 1688 10034 2650 2490 10035 2651 2491 10036 2652 2492 10037 2653 2493 10038 2654 2494 10039 2655 2495 10040 2653 2493 10041 2655 2495 10042 2656 2496 10043 2657 2497 10044 2652 2492 10045 2658 2498 10046 2659 2499 10047 2650 2490 10048 2652 2492 10049 2657 2497 10050 2659 2499 10051 2652 2492 10052 2660 2500 10053 2658 2498 10054 2661 2501 10055 2662 2502 10056 2657 2497 10057 2658 2498 10058 2660 2500 10059 2662 2502 10060 2658 2498 10061 2663 2503 10062 2661 2501 10063 2664 2504 10064 2663 2503 10065 2660 2500 10066 2661 2501 10067 2665 2505 10068 2664 2504 10069 2666 2506 10070 2665 2505 10071 2663 2503 10072 2664 2504 10073 2667 2507 10074 2666 2506 10075 2668 2508 10076 2667 2507 10077 2665 2505 10078 2666 2506 10079 2669 2509 10080 2668 2508 10081 2670 2510 10082 2669 2509 10083 2667 2507 10084 2668 2508 10085 2671 2511 10086 2670 2510 10087 2672 2512 10088 2671 2511 10089 2669 2509 10090 2670 2510 10091 2673 2513 10092 2672 2512 10093 2674 2514 10094 2673 2513 10095 2671 2511 10096 2672 2512 10097 2675 2515 10098 2674 2514 10099 2676 2516 10100 2675 2515 10101 2673 2513 10102 2674 2514 10103 2677 2517 10104 2676 2516 10105 2678 2518 10106 2677 2517 10107 2675 2515 10108 2676 2516 10109 2679 2519 10110 2678 2518 10111 2680 2520 10112 2679 2519 10113 2677 2517 10114 2678 2518 10115 2681 2521 10116 2680 2520 10117 2682 2522 10118 2681 2521 10119 2679 2519 10120 2680 2520 10121 2683 2523 10122 2682 2522 10123 2684 2524 10124 2683 2523 10125 2681 2521 10126 2682 2522 10127 2685 2525 10128 2684 2524 10129 2686 2526 10130 2685 2525 10131 2683 2523 10132 2684 2524 10133 2687 2527 10134 2686 2526 10135 2688 2528 10136 2687 2527 10137 2685 2525 10138 2686 2526 10139 2689 2529 10140 2688 2528 10141 2690 2530 10142 2689 2529 10143 2687 2527 10144 2688 2528 10145 2691 2531 10146 2690 2530 10147 2692 2532 10148 2691 2531 10149 2689 2529 10150 2690 2530 10151 2693 2533 10152 2692 2532 10153 2694 2534 10154 2693 2533 10155 2691 2531 10156 2692 2532 10157 2695 2535 10158 2694 2534 10159 2696 2536 10160 2695 2535 10161 2693 2533 10162 2694 2534 10163 2697 2537 10164 2696 2536 10165 2698 2538 10166 2697 2537 10167 2695 2535 10168 2696 2536 10169 2697 2537 10170 2698 2538 10171 2699 2539 10172 2700 2540 10173 2699 2539 10174 2701 2541 10175 2700 2540 10176 2697 2537 10177 2699 2539 10178 2700 2540 10179 2701 2541 10180 2702 2542 10181 2703 2543 10182 2704 2544 10183 2705 2545 10184 2706 2546 10185 2700 2540 10186 2702 2542 10187 2707 2547 10188 2705 2545 10189 2708 2548 10190 2709 2549 10191 2703 2543 10192 2705 2545 10193 2707 2547 10194 2709 2549 10195 2705 2545 10196 2710 2550 10197 2708 2548 10198 2711 2551 10199 2712 2552 10200 2707 2547 10201 2708 2548 10202 2710 2550 10203 2712 2552 10204 2708 2548 10205 2713 2553 10206 2711 2551 10207 2714 2554 10208 2713 2553 10209 2710 2550 10210 2711 2551 10211 2715 2555 10212 2714 2554 10213 2716 2556 10214 2715 2555 10215 2713 2553 10216 2714 2554 10217 2717 2557 10218 2716 2556 10219 2718 2558 10220 2717 2557 10221 2715 2555 10222 2716 2556 10223 2719 2559 10224 2718 2558 10225 2720 2560 10226 2719 2559 10227 2717 2557 10228 2718 2558 10229 2721 2561 10230 2720 2560 10231 2722 2562 10232 2721 2561 10233 2719 2559 10234 2720 2560 10235 2723 2563 10236 2722 2562 10237 2724 2564 10238 2723 2563 10239 2721 2561 10240 2722 2562 10241 2725 2565 10242 2724 2564 10243 2726 2566 10244 2725 2565 10245 2723 2563 10246 2724 2564 10247 2727 2567 10248 2726 2566 10249 2728 2568 10250 2727 2567 10251 2725 2565 10252 2726 2566 10253 2729 2569 10254 2728 2568 10255 2730 2570 10256 2729 2569 10257 2727 2567 10258 2728 2568 10259 2731 2571 10260 2730 2570 10261 2732 2572 10262 2731 2571 10263 2729 2569 10264 2730 2570 10265 2733 2573 10266 2732 2572 10267 2734 2574 10268 2733 2573 10269 2731 2571 10270 2732 2572 10271 2735 2575 10272 2734 2574 10273 2736 2576 10274 2735 2575 10275 2733 2573 10276 2734 2574 10277 2737 2577 10278 2736 2576 10279 2738 2578 10280 2737 2577 10281 2735 2575 10282 2736 2576 10283 2739 2579 10284 2738 2578 10285 2740 2580 10286 2739 2579 10287 2737 2577 10288 2738 2578 10289 2741 2581 10290 2740 2580 10291 2742 2582 10292 2741 2581 10293 2739 2579 10294 2740 2580 10295 2743 2583 10296 2742 2582 10297 2744 2584 10298 2743 2583 10299 2741 2581 10300 2742 2582 10301 2745 2585 10302 2744 2584 10303 2746 2586 10304 2745 2585 10305 2743 2583 10306 2744 2584 10307 2747 2587 10308 2746 2586 10309 2748 2588 10310 2747 2587 10311 2745 2585 10312 2746 2586 10313 2747 2587 10314 2748 2588 10315 2749 2589 10316 2653 2493 10317 2749 2589 10318 2654 2494 10319 2653 2493 10320 2747 2587 10321 2749 2589 10322 2750 1068 10323 2751 1068 10324 2752 1068 10325 2750 1068 10326 2752 1068 10327 2753 1068 10328 2750 1068 10329 2753 1068 10330 2754 1068 10331 2755 1068 10332 2754 1068 10333 2756 1068 10334 2750 1068 10335 2754 1068 10336 2755 1068 10337 2757 1068 10338 2756 1068 10339 2758 1068 10340 2755 1068 10341 2756 1068 10342 2757 1068 10343 2759 1068 10344 2758 1068 10345 2760 1068 10346 2757 1068 10347 2758 1068 10348 2759 1068 10349 2761 1068 10350 2760 1068 10351 2762 1068 10352 2759 1068 10353 2760 1068 10354 2761 1068 10355 2763 2590 10356 2762 1068 10357 2764 2591 10358 2761 1068 10359 2762 1068 10360 2763 2590 10361 2765 2592 10362 2764 2591 10363 2766 2593 10364 2763 2590 10365 2764 2591 10366 2765 2592 10367 2767 2594 10368 2766 2593 10369 2768 2595 10370 2765 2592 10371 2766 2593 10372 2767 2594 10373 2769 2596 10374 2768 2595 10375 2770 2597 10376 2767 2594 10377 2768 2595 10378 2769 2596 10379 2771 2598 10380 2770 2597 10381 2772 2599 10382 2769 2596 10383 2770 2597 10384 2771 2598 10385 2773 2600 10386 2772 2599 10387 2774 2601 10388 2771 2598 10389 2772 2599 10390 2773 2600 10391 2775 2602 10392 2774 2601 10393 2776 2603 10394 2773 2600 10395 2774 2601 10396 2775 2602 10397 2777 2604 10398 2776 2603 10399 2778 2605 10400 2775 2602 10401 2776 2603 10402 2777 2604 10403 2779 2606 10404 2778 2605 10405 2780 2607 10406 2777 2604 10407 2778 2605 10408 2779 2606 10409 2781 2608 10410 2780 2607 10411 2782 2609 10412 2779 2606 10413 2780 2607 10414 2781 2608 10415 2783 2610 10416 2782 2609 10417 2784 2611 10418 2781 2608 10419 2782 2609 10420 2783 2610 10421 2785 1068 10422 2784 2611 10423 2786 1068 10424 2783 2610 10425 2784 2611 10426 2785 1068 10427 2787 1068 10428 2786 1068 10429 2788 1068 10430 2785 1068 10431 2786 1068 10432 2787 1068 10433 2789 1068 10434 2788 1068 10435 2790 1068 10436 2787 1068 10437 2788 1068 10438 2789 1068 10439 2791 1068 10440 2790 1068 10441 2792 1068 10442 2789 1068 10443 2790 1068 10444 2791 1068 10445 2793 1068 10446 2792 1068 10447 2794 1068 10448 2791 1068 10449 2792 1068 10450 2793 1068 10451 2795 1068 10452 2794 1068 10453 2796 1068 10454 2797 1068 10455 2794 1068 10456 2795 1068 10457 2793 1068 10458 2794 1068 10459 2797 1068 10460 2098 9 10461 2798 9 10462 831 9 10463 2098 9 10464 2799 9 10465 2798 9 10466 2098 9 10467 2800 9 10468 2799 9 10469 2801 9 10470 2802 9 10471 2800 9 10472 2098 9 10473 2801 9 10474 2800 9 10475 2803 9 10476 2804 9 10477 2802 9 10478 2801 9 10479 2803 9 10480 2802 9 10481 2805 9 10482 2806 9 10483 2804 9 10484 2803 9 10485 2805 9 10486 2804 9 10487 2807 9 10488 2808 9 10489 2806 9 10490 2805 9 10491 2807 9 10492 2806 9 10493 2809 9 10494 2810 9 10495 2154 9 10496 2153 9 10497 2809 9 10498 2154 9 10499 2811 9 10500 2812 9 10501 2810 9 10502 2809 9 10503 2811 9 10504 2810 9 10505 2813 9 10506 2814 9 10507 2812 9 10508 2811 9 10509 2813 9 10510 2812 9 10511 2815 9 10512 2816 9 10513 2814 9 10514 2813 9 10515 2815 9 10516 2814 9 10517 2815 9 10518 2817 9 10519 2816 9 10520 2818 9 10521 2197 9 10522 2199 9 10523 2819 9 10524 2818 9 10525 2199 9 10526 2820 9 10527 2819 9 10528 2199 9 10529 2821 9 10530 2820 9 10531 2199 9 10532 2821 9 10533 2822 9 10534 2820 9 10535 2823 9 10536 2824 9 10537 2822 9 10538 2821 9 10539 2823 9 10540 2822 9 10541 2825 9 10542 2826 9 10543 2824 9 10544 2823 9 10545 2825 9 10546 2824 9 10547 2827 9 10548 2828 9 10549 2826 9 10550 2825 9 10551 2827 9 10552 2826 9 10553 585 9 10554 2829 9 10555 538 9 10556 585 9 10557 2830 9 10558 2829 9 10559 585 9 10560 2831 9 10561 2830 9 10562 2832 9 10563 2833 9 10564 2831 9 10565 2834 9 10566 2832 9 10567 2831 9 10568 585 9 10569 2834 9 10570 2831 9 10571 2835 9 10572 2836 9 10573 2833 9 10574 2837 9 10575 2835 9 10576 2833 9 10577 2832 9 10578 2837 9 10579 2833 9 10580 2838 9 10581 2839 9 10582 2836 9 10583 2840 9 10584 2838 9 10585 2836 9 10586 2835 9 10587 2840 9 10588 2836 9 10589 2841 9 10590 2842 9 10591 2839 9 10592 2838 9 10593 2841 9 10594 2839 9 10595 2843 9 10596 2844 9 10597 1160 9 10598 1159 9 10599 2843 9 10600 1160 9 10601 2845 9 10602 2846 9 10603 2844 9 10604 2843 9 10605 2845 9 10606 2844 9 10607 2847 9 10608 2848 9 10609 2846 9 10610 2845 9 10611 2847 9 10612 2846 9 10613 2849 9 10614 2850 9 10615 1106 9 10616 1104 9 10617 2849 9 10618 1106 9 10619 2849 9 10620 2851 9 10621 2850 9 10622 2852 9 10623 2853 9 10624 2851 9 10625 2849 9 10626 2852 9 10627 2851 9 10628 2854 9 10629 2855 9 10630 2853 9 10631 2852 9 10632 2854 9 10633 2853 9 10634 2856 9 10635 2857 9 10636 2855 9 10637 2854 9 10638 2856 9 10639 2855 9 10640 2856 9 10641 2858 9 10642 2857 9 10643 2859 9 10644 2860 9 10645 2861 9 10646 2862 2612 10647 2861 9 10648 2863 2613 10649 2859 9 10650 2861 9 10651 2862 2612 10652 2864 2614 10653 2863 2613 10654 2865 2615 10655 2862 2612 10656 2863 2613 10657 2864 2614 10658 2866 9 10659 2865 2615 10660 2867 9 10661 2864 2614 10662 2865 2615 10663 2866 9 10664 2868 2616 10665 2867 9 10666 2869 2617 10667 2866 9 10668 2867 9 10669 2868 2616 10670 2870 2618 10671 2869 2617 10672 2871 9 10673 2868 2616 10674 2869 2617 10675 2870 2618 10676 2872 9 10677 2871 9 10678 2873 2619 10679 2870 2618 10680 2871 9 10681 2872 9 10682 2874 2620 10683 2873 2619 10684 2875 2621 10685 2872 9 10686 2873 2619 10687 2874 2620 10688 2876 9 10689 2875 2621 10690 2877 9 10691 2874 2620 10692 2875 2621 10693 2876 9 10694 2878 9 10695 2877 9 10696 2879 9 10697 2876 9 10698 2877 9 10699 2878 9 10700 2880 2622 10701 2879 9 10702 2881 2623 10703 2878 9 10704 2879 9 10705 2880 2622 10706 971 946 10707 2881 2623 10708 972 947 10709 2880 2622 10710 2881 2623 10711 971 946 10712 889 9 10713 972 947 10714 890 9 10715

+
+
+
+
+ + + + + 7.54969e-11 4.37108e-11 9.99987e-4 0 0 9.99987e-4 -4.37108e-11 -0.9174 -9.99987e-4 0 7.54969e-11 0 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl new file mode 100644 index 0000000000000000000000000000000000000000..4444aa42c7e156a8999386cf27ff8d0771d0c421 GIT binary patch literal 10284 zcmb7~d303e8OC2yWl>Xwpb}Y(9F~MYOhOQmxpPScg0fkl#iFuQP=pErB0-`dg;InH zib@e#0t%-t5FnsJojcdM;6Wi8trZYN*~Adp1r1xD_s*Tn^G*4uIVWd^yx;HLzvX_H z9#itiPb?TUGUcI(;~!1=&7Ve%8#!uXhwO~bT~bmfJ@&_x%ryDGezsxs=M_c4jvGsZ zFCHIbTdOw)zPWmlwWP3_rHb^swK~UoV0787yQ&&niA~1f@6{mMUxwgO)1NQsdhDxI z%jq%pGtOuCS6k6T+B)K8Y| zd8OKmqi62j*8ZBCt>x!BS~bHO!mD?oTeEu&h~w*Xt)Xq(Sl!a91GgW|v)&!o!fLtu zP=IZV90YM22>oOU+cRzG$Se?t@yQal$C^YIAxG-fXUG{#*sC1WdOT|W#Eh2fMYKCI zL4-iCM7u-tRu$QZ(H)~pu^sZdPrLbun!cTI;SLkTWB4w$Y+dgY3+r!Pej@0};nw z5S@L3C2e*d$nsZ)IIliJ9c~4I{&IN~(_0F@4n<=UDFdN>wFCr9ZeP7Iq&7+mn>nmW z1YPc?gV4{HAk|TKVl)%139A@Jb^vhC0WAuOdFVkuFmtb$TCaVE6f`wAM^YVP4<_2Gs+{5M`l#51hdx5 z^verN%UP4Rmbd}fScYy{?$;w5Gm8n+Mk%~%2ci%}dU>96CFXfj-B4isyzb6$%=49J z_61mzxB7Tq?F7NPm^O*XHdx~7C$F5m8}OtK|)+L%PGIKGoC8UsL6M|1)+tk^LZYLFh`&Hdrrf5;^L7wKvWN z>t#(Md;B@5E4D`O&s2*?F^%{7AB=yKeb>K6W8$4!|E@nJUeqk%eTjFU$oLo$ z+sSx0FjvtCQ(}kU6-#)H;*}_71H?v_@GRoF5+n2*OSlu`GooWl>?ejc&S42>;qsBs z8u~&GOE@O>R`rWqx-`wpE=$-$wjCkVtLjxxZeSZsn?$$7lHl@_J^V-dm_JJbVE>sL9m3+3>_-6t!anrSPKVtKzye`{2Ig*5G*-5E6=*( zp+kY}q0Jq(Em8-ge}&(PaW4O!at zp7%O9*WUG@6@Itvx))zfMHXV3M6`Np<1yG^T}+$A3J`ZBmV_sP(0V7;T^ovIH>Q{E zi7W$=3*vDQU%{)sLzcdyUR5Jk2@f3#bw;jOlgP^;(m-ehSr^kLq1nZ+tGR+l+KG;O z#iQ7s$dw?@AIWg1g79nLXl?gBdMNPDyga8ox4FZbu;ZZSjbKA7$hw#|2|LoeuI6g! z`aN05q~{fnVtXPjLA-KuoU6HFf=4xezbw!%^KR#k_cPFmy+I(u?gS7wcj^?V**(bF zbv)AMm(P`!GnM*)aTc$DmS zB9CHwA{Rhl4!T8g1dnR*(JhX(prLcqu}oz5Ef51i+^1emv7NF()gd|9&KXP$S z5W09@Ylm%%Tm*sM@+!!>m^KN_K{p4{Ydu)PHoCMP>9ko`QQl%sYk0K;#Qh*Na+YX+ zJ-zDna_xN9B%-xI6@!H!cofqU5Yu;A2Lk61leaRsSs-*}U`Z!rx?b&y8nY+T08!Uq zj;L2Ds6~dq8!*9|L|TE^4Wc-X;8FJ?>njIU2NIBV+)Vg3bT{DV0X~JZ?FjMnWo)qC zrjeRk&Agf?!NxHVYJ(+g&$Q7Uwa`^gv&(xQk75r+I)l)aG#>;%rSJ~NnndzJ%mwiw z2-d~4N$9^KKP4`EqJPshJ+f-^uD!o_TBj(%yCv^9N=A1gk)Mh$y%{575?*(CwTq06 z5-j1hgl8~Luf@}9ZLowpoO{~yisFd%D0gCfMxvgXx#BFCk*_{d+%XylOE@O>7G5PU z%ZU;!Vc$)!a<>oI7$w*S(+EooQEBekbpx!cl9HW1of911qj>KU*#{yY zL^24L@LoHitk6(BH}modJmBr=&%JBlE`MQ#}!xwqU;ZDbnfv2i@xitq5m=sJv~u z_t!cgP7Uwn^uT()3j}O9F&nb0zMa-G&(4T>WofSXeunRWL@IaIw=+S!0fHrbf91#L zX%hLQu&=!(?|S!^90%XeMdJ7X#N!}X;>Y3XH6tH6qB8jSw<&I;QE4{f z2>2DWP!G$mhn3vP3ba9Oe)RgQQ@<188OYUjAfU_fd)GqELw?Pz+_JNw?dXy!k3c87 z=&K;QJxXXC7W&G|Ci*o>1R}&2L%P@pN9P5<8JT7ySC-}jT@v-mLYG*>@T-6Sr)MJ! z{S6+;3vQY-!Dfl?yA|`orIBK)tI zSDr3EZ~iP|uiioA-)~ED%VJ)61kWgwZuNO{>)cw~Rj+sy&tQ|#`BDFoys*v>mhfDO z_{8(WUjJ5DE64<|3?}W*+OW=A9>p`*B(NLUjR&m=VmAo#8pVCgw8*pY=9=wE_K_yt zf;@_8Uin0dK(q#tlH4uGZ({g84r>xA_KD-L!Md0>3GAFMx+Ityi9>fUZ>_yd$9OBB z$mD_|uMm~42XxD!p{%+C65O3OUA5MJ?K#2v%5$f(ha!+Tnf zcPGOuCbTo6dpOe~<2HXB@=pLk9>tw#63vp6>>lfEcYegH+CA0JsGa~UrbTqNCT&l0 z4{6P57xruJWr1n$l%aj4r;KP{d84?O{)cdHh;(8Y5fb`ICZn;#y5 z`JuV0J#(VNyQJLkMh0pPEIDFC*(&#=$V>FG0it@ct;Q7w;&pW z;Cnc}9b`>-e-7dW5bZ#)E~ZUl$mphC9>umrPEI-(?tvX=9pd17 z7`~t3xgwI*??kW|XHk8Q;!foIGQN`&$@GaEL9m3My!?7N`jjEk9mFiyXb?y6D7Gzf zQ^bbd0t9yk-&6C`i%2^Vg*dk>!4mEa)`XS%^XATZoB*_Uc{SjBIKH35o6*YVj-DBm zUn;oWa)CW+$9{7$WHWbJ)D+ypm(`nx!d{PFGBohbY6HD2$pak zn_lURIs-yy6cap(ZHpupoD1jRi3O){mv6jy*7~%!cj>C?yAn@!Q-3Pt(9KEa0hTeIHHHkFEuGVLr zZ5Lyu=C|zp_T7x520Km@oMdoj2=kj /dev/null && pwd)" +else + _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_bash_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh script of this package +_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/package.sh" + +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts +COLCON_CURRENT_PREFIX="$_colcon_package_bash_COLCON_CURRENT_PREFIX" + +# source bash hooks +_colcon_package_bash_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.bash" + +unset COLCON_CURRENT_PREFIX + +unset _colcon_package_bash_source_script +unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv new file mode 100644 index 0000000000..760f04466e --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv @@ -0,0 +1,8 @@ +source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 +source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv +source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh +source;share/moveit_resources_prbt_support/local_setup.bash +source;share/moveit_resources_prbt_support/local_setup.dsv +source;share/moveit_resources_prbt_support/local_setup.ps1 +source;share/moveit_resources_prbt_support/local_setup.sh +source;share/moveit_resources_prbt_support/local_setup.zsh diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 new file mode 100644 index 0000000000..356c3c4dda --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 @@ -0,0 +1,116 @@ +# generated from colcon_powershell/shell/template/package.ps1.em + +# function to append a value to a variable +# which uses colons as separators +# duplicates as well as leading separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_append_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + $_duplicate="" + # start with no values + $_all_values="" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -eq $_value) { + $_duplicate="1" + } + if ($_all_values) { + $_all_values="${_all_values};$_" + } else { + $_all_values="$_" + } + } + } + } + # append only non-duplicates + if (!$_duplicate) { + # avoid leading separator + if ($_all_values) { + $_all_values="${_all_values};${_value}" + } else { + $_all_values="${_value}" + } + } + + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +function colcon_prepend_unique_value { + param ( + $_listname, + $_value + ) + + # get values from variable + if (Test-Path Env:$_listname) { + $_values=(Get-Item env:$_listname).Value + } else { + $_values="" + } + # start with the new value + $_all_values="$_value" + # iterate over existing values in the variable + if ($_values) { + $_values.Split(";") | ForEach { + # not an empty string + if ($_) { + # not a duplicate of _value + if ($_ -ne $_value) { + # keep non-duplicate values + $_all_values="${_all_values};$_" + } + } + } + } + # export the updated variable + Set-Item env:\$_listname -Value "$_all_values" +} + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +function colcon_package_source_powershell_script { + param ( + $_colcon_package_source_powershell_script + ) + # source script with conditional trace output + if (Test-Path $_colcon_package_source_powershell_script) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_package_source_powershell_script'" + } + . "$_colcon_package_source_powershell_script" + } else { + Write-Error "not found: '$_colcon_package_source_powershell_script'" + } +} + + +# a powershell script is able to determine its own path +# the prefix is two levels up from the package specific share directory +$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName + +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1" +colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_resources_prbt_support/local_setup.ps1" + +Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh new file mode 100644 index 0000000000..88c8fe8227 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh @@ -0,0 +1,87 @@ +# generated from colcon_core/shell/template/package.sh.em + +# This script extends the environment for this package. + +# function to prepend a value to a variable +# which uses colons as separators +# duplicates as well as trailing separators are avoided +# first argument: the name of the result variable +# second argument: the value to be prepended +_colcon_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + + # get values from variable + eval _values=\"\$$_listname\" + # backup the field separator + _colcon_prepend_unique_value_IFS=$IFS + IFS=":" + # start with the new value + _all_values="$_value" + # workaround SH_WORD_SPLIT not being set in zsh + if [ "$(command -v colcon_zsh_convert_to_array)" ]; then + colcon_zsh_convert_to_array _values + fi + # iterate over existing values in the variable + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + # ignore duplicates of _value + if [ "$_item" = "$_value" ]; then + continue + fi + # keep non-duplicate values + _all_values="$_all_values:$_item" + done + unset _item + # restore the field separator + IFS=$_colcon_prepend_unique_value_IFS + unset _colcon_prepend_unique_value_IFS + # export the updated variable + eval export $_listname=\"$_all_values\" + unset _all_values + unset _values + + unset _value + unset _listname +} + +# since a plain shell script can't determine its own path when being sourced +# either use the provided COLCON_CURRENT_PREFIX +# or fall back to the build time prefix (if it exists) +_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support" +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then + echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 + unset _colcon_package_sh_COLCON_CURRENT_PREFIX + return 1 + fi + COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" +fi +unset _colcon_package_sh_COLCON_CURRENT_PREFIX + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo "# . \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source sh hooks +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh" +_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.sh" + +unset _colcon_package_sh_source_script +unset COLCON_CURRENT_PREFIX + +# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml new file mode 100644 index 0000000000..4e77f0194c --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml @@ -0,0 +1,25 @@ + + moveit_resources_prbt_support + 2.5.1 + Mechanical, kinematic and visual description + of the Pilz light weight arm PRBT. + + Alexander Gutenkunst + Christian Henkel + Hagen Slusarek + Immanuel Martini + + Apache 2.0 + + http://moveit.ros.org + https://github.com/ros-planning/moveit-resources/issues + https://github.com/ros-planning/moveit-resources + + ament_cmake + + xacro + + + ament_cmake + + diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh new file mode 100644 index 0000000000..49f14e0f61 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh @@ -0,0 +1,50 @@ +# generated from colcon_zsh/shell/template/package.zsh.em + +# This script extends the environment for this package. + +# a zsh script is able to determine its own path if necessary +if [ -z "$COLCON_CURRENT_PREFIX" ]; then + # the prefix is two levels up from the package specific share directory + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" +else + _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +# additional arguments: arguments to the script +_colcon_package_zsh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$@" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# function to convert array-like strings into arrays +# to workaround SH_WORD_SPLIT not being set +colcon_zsh_convert_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# source sh script of this package +_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/package.sh" +unset convert_zsh_to_array + +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts +COLCON_CURRENT_PREFIX="$_colcon_package_zsh_COLCON_CURRENT_PREFIX" + +# source zsh hooks +_colcon_package_zsh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.zsh" + +unset COLCON_CURRENT_PREFIX + +unset _colcon_package_zsh_source_script +unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro new file mode 100644 index 0000000000..c76e60e75f --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro @@ -0,0 +1,101 @@ + + + + + + + + + fake_components/GenericSystem + ${fake_sensor_commands} + 0.0 + + + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_1']} + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_2']} + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_3']} + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_4']} + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_5']} + + + + -2.96706 + 2.96706 + + + -3.15 + 3.15 + + + + + ${initial_positions['joint_6']} + + + + diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro new file mode 100644 index 0000000000..6654dd97d7 --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro new file mode 100644 index 0000000000..82d9ff13bc --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro @@ -0,0 +1,465 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + + + + + prbt + gazebo_ros_control/DefaultRobotHWSim + false + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_1 + ${prefix}joint_1 + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_2 + ${prefix}joint_2 + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_3 + ${prefix}joint_3 + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_4 + ${prefix}joint_4 + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_5 + ${prefix}joint_5 + + + + + true + + + + + 100.0 + prbt/ft_sensor/joint_6 + ${prefix}joint_6 + + + + + + diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro new file mode 100644 index 0000000000..63236f59ab --- /dev/null +++ b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro @@ -0,0 +1,94 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/install/setup.bash b/install/setup.bash new file mode 100644 index 0000000000..4c55244159 --- /dev/null +++ b/install/setup.bash @@ -0,0 +1,31 @@ +# generated from colcon_bash/shell/template/prefix_chain.bash.em + +# This script extends the environment with the environment of other prefix +# paths which were sourced when this file was generated as well as all packages +# contained in this prefix path. + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_chain_bash_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source chained prefixes +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script +COLCON_CURRENT_PREFIX="/opt/ros/humble" +_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash" + +# source this prefix +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script +COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)" +_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash" + +unset COLCON_CURRENT_PREFIX +unset _colcon_prefix_chain_bash_source_script diff --git a/install/setup.ps1 b/install/setup.ps1 new file mode 100644 index 0000000000..558e9b9e62 --- /dev/null +++ b/install/setup.ps1 @@ -0,0 +1,29 @@ +# generated from colcon_powershell/shell/template/prefix_chain.ps1.em + +# This script extends the environment with the environment of other prefix +# paths which were sourced when this file was generated as well as all packages +# contained in this prefix path. + +# function to source another script with conditional trace output +# first argument: the path of the script +function _colcon_prefix_chain_powershell_source_script { + param ( + $_colcon_prefix_chain_powershell_source_script_param + ) + # source script with conditional trace output + if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) { + if ($env:COLCON_TRACE) { + echo ". '$_colcon_prefix_chain_powershell_source_script_param'" + } + . "$_colcon_prefix_chain_powershell_source_script_param" + } else { + Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'" + } +} + +# source chained prefixes +_colcon_prefix_chain_powershell_source_script "/opt/ros/humble\local_setup.ps1" + +# source this prefix +$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent) +_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1" diff --git a/install/setup.sh b/install/setup.sh new file mode 100644 index 0000000000..65cd424cec --- /dev/null +++ b/install/setup.sh @@ -0,0 +1,45 @@ +# generated from colcon_core/shell/template/prefix_chain.sh.em + +# This script extends the environment with the environment of other prefix +# paths which were sourced when this file was generated as well as all packages +# contained in this prefix path. + +# since a plain shell script can't determine its own path when being sourced +# either use the provided COLCON_CURRENT_PREFIX +# or fall back to the build time prefix (if it exists) +_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/henry/ws_moveit2/src/moveit2/install +if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then + _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" +elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then + echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 + unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX + return 1 +fi + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_chain_sh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo "# . \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source chained prefixes +# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script +COLCON_CURRENT_PREFIX="/opt/ros/humble" +_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh" + + +# source this prefix +# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script +COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" +_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh" + +unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX +unset _colcon_prefix_chain_sh_source_script +unset COLCON_CURRENT_PREFIX diff --git a/install/setup.zsh b/install/setup.zsh new file mode 100644 index 0000000000..990d17190a --- /dev/null +++ b/install/setup.zsh @@ -0,0 +1,31 @@ +# generated from colcon_zsh/shell/template/prefix_chain.zsh.em + +# This script extends the environment with the environment of other prefix +# paths which were sourced when this file was generated as well as all packages +# contained in this prefix path. + +# function to source another script with conditional trace output +# first argument: the path of the script +_colcon_prefix_chain_zsh_source_script() { + if [ -f "$1" ]; then + if [ -n "$COLCON_TRACE" ]; then + echo ". \"$1\"" + fi + . "$1" + else + echo "not found: \"$1\"" 1>&2 + fi +} + +# source chained prefixes +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script +COLCON_CURRENT_PREFIX="/opt/ros/humble" +_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh" + +# source this prefix +# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script +COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)" +_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh" + +unset COLCON_CURRENT_PREFIX +unset _colcon_prefix_chain_zsh_source_script diff --git a/log/COLCON_IGNORE b/log/COLCON_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/log/build_2022-06-08_12-52-32/events.log b/log/build_2022-06-08_12-52-32/events.log new file mode 100644 index 0000000000..41ae65df06 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/events.log @@ -0,0 +1,313 @@ +[0.000000] (-) TimerEvent: {} +[0.000915] (moveit_common) JobQueued: {'identifier': 'moveit_common', 'dependencies': OrderedDict()} +[0.000949] (moveit_configs_utils) JobQueued: {'identifier': 'moveit_configs_utils', 'dependencies': OrderedDict()} +[0.000964] (moveit_resources_prbt_support) JobQueued: {'identifier': 'moveit_resources_prbt_support', 'dependencies': OrderedDict()} +[0.000975] (moveit_core) JobQueued: {'identifier': 'moveit_core', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common')])} +[0.000989] (chomp_motion_planner) JobQueued: {'identifier': 'chomp_motion_planner', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} +[0.001002] (moveit_resources_prbt_ikfast_manipulator_plugin) JobQueued: {'identifier': 'moveit_resources_prbt_ikfast_manipulator_plugin', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} +[0.001014] (moveit_ros_occupancy_map_monitor) JobQueued: {'identifier': 'moveit_ros_occupancy_map_monitor', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} +[0.001026] (moveit_simple_controller_manager) JobQueued: {'identifier': 'moveit_simple_controller_manager', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} +[0.001038] (pilz_industrial_motion_planner_testutils) JobQueued: {'identifier': 'pilz_industrial_motion_planner_testutils', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} +[0.001049] (moveit_chomp_optimizer_adapter) JobQueued: {'identifier': 'moveit_chomp_optimizer_adapter', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('chomp_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner')])} +[0.001061] (moveit_planners_chomp) JobQueued: {'identifier': 'moveit_planners_chomp', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('chomp_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner')])} +[0.001072] (moveit_plugins) JobQueued: {'identifier': 'moveit_plugins', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager')])} +[0.001084] (moveit_ros_control_interface) JobQueued: {'identifier': 'moveit_ros_control_interface', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager')])} +[0.001095] (moveit_ros_planning) JobQueued: {'identifier': 'moveit_ros_planning', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor')])} +[0.001106] (moveit_kinematics) JobQueued: {'identifier': 'moveit_kinematics', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} +[0.001211] (moveit_planners_ompl) JobQueued: {'identifier': 'moveit_planners_ompl', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} +[0.001225] (moveit_ros_perception) JobQueued: {'identifier': 'moveit_ros_perception', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} +[0.001236] (moveit_ros_robot_interaction) JobQueued: {'identifier': 'moveit_ros_robot_interaction', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} +[0.001249] (moveit_ros_warehouse) JobQueued: {'identifier': 'moveit_ros_warehouse', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} +[0.001263] (moveit_ros_benchmarks) JobQueued: {'identifier': 'moveit_ros_benchmarks', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse')])} +[0.001276] (moveit_ros_move_group) JobQueued: {'identifier': 'moveit_ros_move_group', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics')])} +[0.001289] (moveit_resources_prbt_moveit_config) JobQueued: {'identifier': 'moveit_resources_prbt_moveit_config', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group')])} +[0.001312] (moveit_ros_planning_interface) JobQueued: {'identifier': 'moveit_ros_planning_interface', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group')])} +[0.001329] (moveit_hybrid_planning) JobQueued: {'identifier': 'moveit_hybrid_planning', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} +[0.001344] (moveit_resources_prbt_pg70_support) JobQueued: {'identifier': 'moveit_resources_prbt_pg70_support', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_resources_prbt_moveit_config', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config')])} +[0.001358] (moveit_ros_visualization) JobQueued: {'identifier': 'moveit_ros_visualization', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} +[0.001452] (moveit_servo) JobQueued: {'identifier': 'moveit_servo', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} +[0.001467] (moveit_ros) JobQueued: {'identifier': 'moveit_ros', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_benchmarks', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization')])} +[0.001483] (moveit_setup_assistant) JobQueued: {'identifier': 'moveit_setup_assistant', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization')])} +[0.001498] (pilz_industrial_motion_planner) JobQueued: {'identifier': 'pilz_industrial_motion_planner', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('pilz_industrial_motion_planner_testutils', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner_testutils'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_resources_prbt_moveit_config', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_resources_prbt_pg70_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_pg70_support')])} +[0.001528] (moveit_planners) JobQueued: {'identifier': 'moveit_planners', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner')])} +[0.001543] (moveit) JobQueued: {'identifier': 'moveit', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_plugins', '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_benchmarks', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization'), ('moveit_ros', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner'), ('moveit_planners', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners')])} +[0.001561] (moveit_runtime) JobQueued: {'identifier': 'moveit_runtime', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_plugins', '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner'), ('moveit_planners', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners')])} +[0.001585] (moveit_common) JobStarted: {'identifier': 'moveit_common'} +[0.006455] (moveit_configs_utils) JobStarted: {'identifier': 'moveit_configs_utils'} +[0.010670] (moveit_resources_prbt_support) JobStarted: {'identifier': 'moveit_resources_prbt_support'} +[0.013071] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'cmake'} +[0.013236] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_common', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.099844] (-) TimerEvent: {} +[0.179485] (moveit_common) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} +[0.179975] (moveit_common) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} +[0.180092] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'cmake'} +[0.180291] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.199936] (-) TimerEvent: {} +[0.243553] (moveit_common) StdoutLine: {'line': b'-- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake)\n'} +[0.249359] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- The C compiler identification is GNU 11.2.0\n'} +[0.288317] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- The CXX compiler identification is GNU 11.2.0\n'} +[0.295205] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compiler ABI info\n'} +[0.300014] (-) TimerEvent: {} +[0.303725] (moveit_common) StdoutLine: {'line': b"-- Added test 'copyright' to check source files copyright and LICENSE\n"} +[0.305287] (moveit_common) StdoutLine: {'line': b"-- Added test 'lint_cmake' to check CMake code style\n"} +[0.306266] (moveit_common) StdoutLine: {'line': b"-- Added test 'xmllint' to check XML markup files\n"} +[0.307667] (moveit_common) StdoutLine: {'line': b'-- Configuring done\n'} +[0.309479] (moveit_common) StdoutLine: {'line': b'-- Generating done\n'} +[0.309965] (moveit_common) StdoutLine: {'line': b'-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common\n'} +[0.311464] (moveit_common) CommandEnded: {'returncode': 0} +[0.311967] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'build'} +[0.312487] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '--build', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', '--', '-j8', '-l8'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.332509] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compiler ABI info - done\n'} +[0.333407] (moveit_common) CommandEnded: {'returncode': 0} +[0.337252] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Check for working C compiler: /usr/lib/ccache/cc - skipped\n'} +[0.337429] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compile features\n'} +[0.337639] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compile features - done\n'} +[0.339680] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info\n'} +[0.343763] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'install'} +[0.348811] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '--install', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.353226] (moveit_common) StdoutLine: {'line': b'-- Install configuration: "Release"\n'} +[0.353445] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common\n'} +[0.353511] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common\n'} +[0.353606] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh\n'} +[0.353695] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv\n'} +[0.353781] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh\n'} +[0.353865] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv\n'} +[0.353958] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash\n'} +[0.354022] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh\n'} +[0.354103] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh\n'} +[0.354163] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv\n'} +[0.354248] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv\n'} +[0.354345] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common\n'} +[0.354408] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake\n'} +[0.354503] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake\n'} +[0.354585] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake\n'} +[0.354639] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml\n'} +[0.354690] (moveit_common) StdoutLine: {'line': b'-- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake\n'} +[0.354744] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake\n'} +[0.355708] (moveit_common) CommandEnded: {'returncode': 0} +[0.381539] (moveit_common) JobEnded: {'identifier': 'moveit_common', 'rc': 0} +[0.382980] (moveit_core) JobStarted: {'identifier': 'moveit_core'} +[0.383355] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info - done\n'} +[0.387257] (moveit_core) JobProgress: {'identifier': 'moveit_core', 'progress': 'cmake'} +[0.387420] (moveit_core) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_core', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_core', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_core'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble')]), 'shell': False} +[0.392163] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped\n'} +[0.392416] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compile features\n'} +[0.392911] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compile features - done\n'} +[0.394724] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} +[0.400132] (-) TimerEvent: {} +[0.435787] (moveit_core) StdoutLine: {'line': b'-- The CXX compiler identification is GNU 11.2.0\n'} +[0.442190] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info\n'} +[0.483918] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info - done\n'} +[0.488983] (moveit_core) StdoutLine: {'line': b'-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped\n'} +[0.489143] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compile features\n'} +[0.489421] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compile features - done\n'} +[0.489996] (moveit_core) StdoutLine: {'line': b'-- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake)\n'} +[0.490919] (moveit_core) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} +[0.500228] (-) TimerEvent: {} +[0.515039] (moveit_configs_utils) Command: {'cmd': ['/usr/bin/python3', 'setup.py', 'egg_info', '--egg-base', '../build/moveit_configs_utils', 'build', '--build-base', '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build', 'install', '--prefix', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils', '--record', '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log', '--single-version-externally-managed'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils', 'env': {'LESSOPEN': '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s', 'ALTERNATE_EDITOR': '', 'USER': 'henry', 'BASHRC_NAME': 'TODO_GITHUB_USER_NAME', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'LESS': '-R', 'HOME': '/home/henry', 'OLDPWD': '/home/henry/ws_moveit2/src', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'PS1': '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$', 'MANAGERPID': '1489', 'SYSTEMD_EXEC_PID': '1823', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1000/bus', 'COLORTERM': 'truecolor', 'TERMINATOR_DBUS_NAME': 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3', 'GIO_LAUNCHED_DESKTOP_FILE_PID': '40701', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'ROS_DISTRO': 'humble', 'LOGNAME': 'henry', 'JOURNAL_STREAM': '8:37404', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'henry', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'ROS_LOCALHOST_ONLY': '1', 'PATH': '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677', 'INVOCATION_ID': '3e66bc62391b49bc94f6e6cf493d6504', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1000', 'DISPLAY': ':0', 'TERMINATOR_DBUS_PATH': '/net/tenshu/Terminator2', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'IBUS_DISABLE_SNOOPER': '1', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1000/.mutter-Xwaylandauth.VETXM1', 'BASHRC_ENV': 'default', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:', 'SSH_AGENT_LAUNCHER': 'gnome-keyring', 'SSH_AUTH_SOCK': '/run/user/1000/keyring/ssh', 'ROS_DOMAIN_ID': '44', 'AMENT_PREFIX_PATH': '/opt/ros/humble', 'ROSCONSOLE_FORMAT': '${logger}: ${message}', 'SHELL': '/bin/bash', 'TERMINATOR_UUID': 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'UBUNTU_VERSION': 'jammy', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1', 'VTE_VERSION': '6800', 'EDITOR': '/usr/bin/nano'}, 'shell': False} +[0.526486] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} +[0.600349] (-) TimerEvent: {} +[0.603527] (moveit_core) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} +[0.623968] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Configuring done\n'} +[0.625556] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Generating done\n'} +[0.626120] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support\n'} +[0.630819] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} +[0.631277] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'build'} +[0.631483] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '--build', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', '--', '-j8', '-l8'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.654855] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} +[0.665159] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'install'} +[0.665448] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '--install', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} +[0.667774] (moveit_configs_utils) StdoutLine: {'line': b'running egg_info\n'} +[0.668174] (moveit_configs_utils) StdoutLine: {'line': b'creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info\n'} +[0.668307] (moveit_configs_utils) StdoutLine: {'line': b'writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO\n'} +[0.668444] (moveit_configs_utils) StdoutLine: {'line': b'writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt\n'} +[0.668540] (moveit_configs_utils) StdoutLine: {'line': b'writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt\n'} +[0.668626] (moveit_configs_utils) StdoutLine: {'line': b'writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt\n'} +[0.668721] (moveit_configs_utils) StdoutLine: {'line': b'writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt\n'} +[0.668780] (moveit_configs_utils) StdoutLine: {'line': b"writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} +[0.669687] (moveit_configs_utils) StdoutLine: {'line': b"reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} +[0.670025] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Install configuration: "Release"\n'} +[0.670236] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support\n'} +[0.670349] (moveit_configs_utils) StdoutLine: {'line': b"writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} +[0.670470] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support\n'} +[0.670565] (moveit_configs_utils) StdoutLine: {'line': b'running build\n'} +[0.670671] (moveit_configs_utils) StdoutLine: {'line': b'running build_py\n'} +[0.670738] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build\n'} +[0.670836] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib\n'} +[0.670905] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} +[0.670971] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh\n'} +[0.671061] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} +[0.671130] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv\n'} +[0.671256] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh\n'} +[0.671325] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv\n'} +[0.671430] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash\n'} +[0.671525] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh\n'} +[0.671605] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} +[0.671680] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} +[0.671740] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} +[0.671813] (moveit_configs_utils) StdoutLine: {'line': b'running install\n'} +[0.671875] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh\n'} +[0.671970] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv\n'} +[0.672066] (moveit_configs_utils) StderrLine: {'line': b'/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools.\n'} +[0.672238] (moveit_configs_utils) StderrLine: {'line': b' warnings.warn(\n'} +[0.672313] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv\n'} +[0.672390] (moveit_configs_utils) StdoutLine: {'line': b'running install_lib\n'} +[0.672467] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support\n'} +[0.672536] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake\n'} +[0.672621] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake\n'} +[0.672684] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml\n'} +[0.672745] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} +[0.672787] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf\n'} +[0.672826] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro\n'} +[0.672887] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} +[0.672951] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro\n'} +[0.673015] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} +[0.673079] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} +[0.673143] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro\n'} +[0.673231] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} +[0.673290] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro\n'} +[0.673347] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes\n'} +[0.673419] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl\n'} +[0.673505] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl\n'} +[0.673544] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae\n'} +[0.673579] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc\n'} +[0.673618] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae\n'} +[0.673653] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc\n'} +[0.674627] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc\n'} +[0.674733] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc\n'} +[0.675001] (moveit_configs_utils) StdoutLine: {'line': b'running install_data\n'} +[0.675289] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index\n'} +[0.675370] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index\n'} +[0.675408] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages\n'} +[0.675467] (moveit_configs_utils) StdoutLine: {'line': b'copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages\n'} +[0.675573] (moveit_configs_utils) StdoutLine: {'line': b'copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils\n'} +[0.675661] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.675703] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae\n'} +[0.675746] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.675839] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.675898] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.675956] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.676008] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} +[0.676044] (moveit_configs_utils) StdoutLine: {'line': b'running install_egg_info\n'} +[0.676818] (moveit_configs_utils) StdoutLine: {'line': b'Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info\n'} +[0.676940] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl\n'} +[0.677034] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl\n'} +[0.677120] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl\n'} +[0.677206] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl\n'} +[0.677284] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl\n'} +[0.677371] (moveit_configs_utils) StdoutLine: {'line': b'running install_scripts\n'} +[0.677455] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae\n'} +[0.677981] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae\n'} +[0.678095] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae\n'} +[0.679330] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae\n'} +[0.680751] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config\n'} +[0.680856] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf\n'} +[0.680943] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml\n'} +[0.681027] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml\n'} +[0.682226] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} +[0.690535] (moveit_configs_utils) StdoutLine: {'line': b"writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log'\n"} +[0.700849] (-) TimerEvent: {} +[0.702434] (moveit_resources_prbt_support) JobEnded: {'identifier': 'moveit_resources_prbt_support', 'rc': 0} +[0.708287] (moveit_configs_utils) CommandEnded: {'returncode': 0} +[0.712395] (moveit_configs_utils) JobEnded: {'identifier': 'moveit_configs_utils', 'rc': 0} +[0.712895] (moveit_core) StdoutLine: {'line': b'-- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so \n'} +[0.716545] (moveit_core) StdoutLine: {'line': b'-- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) \n'} +[0.716596] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_UNWIND=1\n'} +[0.716631] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BACKTRACE=0\n'} +[0.716665] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BACKTRACE_SYMBOL=0\n'} +[0.716698] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_DW=1\n'} +[0.716732] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BFD=0\n'} +[0.717183] (moveit_core) StdoutLine: {'line': b'-- Found Backward: /opt/ros/humble/share/backward_ros/cmake \n'} +[0.719696] (moveit_core) StdoutLine: {'line': b'-- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake)\n'} +[0.768961] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake)\n'} +[0.773515] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake)\n'} +[0.781666] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake)\n'} +[0.796664] (moveit_core) StdoutLine: {'line': b'-- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c\n'} +[0.800941] (-) TimerEvent: {} +[0.814447] (moveit_core) StdoutLine: {'line': b'-- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp\n'} +[0.870574] (moveit_core) StdoutLine: {'line': b'-- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake)\n'} +[0.873441] (moveit_core) StdoutLine: {'line': b'-- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake)\n'} +[0.901043] (-) TimerEvent: {} +[0.938296] (moveit_core) StdoutLine: {'line': b'-- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") \n'} +[0.953175] (moveit_core) StdoutLine: {'line': b'-- Found FastRTPS: /opt/ros/humble/include \n'} +[0.979657] (moveit_core) StdoutLine: {'line': b"-- Using RMW implementation 'rmw_fastrtps_cpp' as default\n"} +[1.001142] (-) TimerEvent: {} +[1.087281] (moveit_core) StdoutLine: {'line': b'-- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake)\n'} +[1.092299] (moveit_core) StdoutLine: {'line': b'-- Found Eigen3: TRUE (found version "3.4.0") \n'} +[1.094707] (moveit_core) StdoutLine: {'line': b'-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") \n'} +[1.095049] (moveit_core) StdoutLine: {'line': b"-- Checking for module 'fcl>=0.5.0'\n"} +[1.101147] (moveit_core) StdoutLine: {'line': b'-- Found fcl, version 0.7.0\n'} +[1.101216] (-) TimerEvent: {} +[1.123782] (moveit_core) StdoutLine: {'line': b'-- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") \n'} +[1.125036] (moveit_core) StdoutLine: {'line': b'-- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake)\n'} +[1.136881] (moveit_core) StdoutLine: {'line': b'-- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake)\n'} +[1.158204] (moveit_core) StdoutLine: {'line': b'-- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake)\n'} +[1.201352] (-) TimerEvent: {} +[1.301594] (-) TimerEvent: {} +[1.401854] (-) TimerEvent: {} +[1.465100] (moveit_core) StdoutLine: {'line': b'-- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake)\n'} +[1.477530] (moveit_core) StdoutLine: {'line': b'-- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake)\n'} +[1.488819] (moveit_core) StdoutLine: {'line': b'-- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake)\n'} +[1.491189] (moveit_core) StdoutLine: {'line': b'-- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake)\n'} +[1.499324] (moveit_core) StdoutLine: {'line': b'-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem \n'} +[1.501926] (-) TimerEvent: {} +[1.547713] (moveit_core) StdoutLine: {'line': b'-- library: /usr/lib/x86_64-linux-gnu/libcurl.so\n'} +[1.602141] (-) TimerEvent: {} +[1.702487] (-) TimerEvent: {} +[1.737524] (moveit_core) StdoutLine: {'line': b'-- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake)\n'} +[1.740146] (moveit_core) StdoutLine: {'line': b'-- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake)\n'} +[1.802672] (-) TimerEvent: {} +[1.903022] (-) TimerEvent: {} +[2.003394] (-) TimerEvent: {} +[2.103064] (moveit_core) StderrLine: {'line': b'\x1b[31mCMake Error at CMakeLists.txt:43 (find_package):\n'} +[2.103240] (moveit_core) StderrLine: {'line': b' By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has\n'} +[2.103284] (moveit_core) StderrLine: {'line': b' asked CMake to find a package configuration file provided by "srdfdom", but\n'} +[2.103323] (moveit_core) StderrLine: {'line': b' CMake did not find one.\n'} +[2.103359] (moveit_core) StderrLine: {'line': b'\n'} +[2.103392] (-) TimerEvent: {} +[2.103465] (moveit_core) StderrLine: {'line': b' Could not find a package configuration file provided by "srdfdom" with any\n'} +[2.103505] (moveit_core) StderrLine: {'line': b' of the following names:\n'} +[2.103541] (moveit_core) StderrLine: {'line': b'\n'} +[2.103574] (moveit_core) StderrLine: {'line': b' srdfdomConfig.cmake\n'} +[2.103608] (moveit_core) StderrLine: {'line': b' srdfdom-config.cmake\n'} +[2.103642] (moveit_core) StderrLine: {'line': b'\n'} +[2.103674] (moveit_core) StderrLine: {'line': b' Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set\n'} +[2.103708] (moveit_core) StderrLine: {'line': b' "srdfdom_DIR" to a directory containing one of the above files. If\n'} +[2.103742] (moveit_core) StderrLine: {'line': b' "srdfdom" provides a separate development package or SDK, be sure it has\n'} +[2.103775] (moveit_core) StderrLine: {'line': b' been installed.\n'} +[2.103809] (moveit_core) StderrLine: {'line': b'\n'} +[2.103842] (moveit_core) StderrLine: {'line': b'\x1b[0m\n'} +[2.103876] (moveit_core) StdoutLine: {'line': b'-- Configuring incomplete, errors occurred!\n'} +[2.103914] (moveit_core) StdoutLine: {'line': b'See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log".\n'} +[2.110082] (moveit_core) CommandEnded: {'returncode': 1} +[2.119794] (moveit_core) JobEnded: {'identifier': 'moveit_core', 'rc': 1} +[2.130499] (chomp_motion_planner) JobSkipped: {'identifier': 'chomp_motion_planner'} +[2.130544] (moveit_resources_prbt_ikfast_manipulator_plugin) JobSkipped: {'identifier': 'moveit_resources_prbt_ikfast_manipulator_plugin'} +[2.130563] (moveit_ros_occupancy_map_monitor) JobSkipped: {'identifier': 'moveit_ros_occupancy_map_monitor'} +[2.130580] (moveit_simple_controller_manager) JobSkipped: {'identifier': 'moveit_simple_controller_manager'} +[2.130595] (pilz_industrial_motion_planner_testutils) JobSkipped: {'identifier': 'pilz_industrial_motion_planner_testutils'} +[2.130610] (moveit_chomp_optimizer_adapter) JobSkipped: {'identifier': 'moveit_chomp_optimizer_adapter'} +[2.130624] (moveit_planners_chomp) JobSkipped: {'identifier': 'moveit_planners_chomp'} +[2.130638] (moveit_plugins) JobSkipped: {'identifier': 'moveit_plugins'} +[2.130652] (moveit_ros_control_interface) JobSkipped: {'identifier': 'moveit_ros_control_interface'} +[2.130665] (moveit_ros_planning) JobSkipped: {'identifier': 'moveit_ros_planning'} +[2.130679] (moveit_kinematics) JobSkipped: {'identifier': 'moveit_kinematics'} +[2.130720] (moveit_planners_ompl) JobSkipped: {'identifier': 'moveit_planners_ompl'} +[2.130735] (moveit_ros_perception) JobSkipped: {'identifier': 'moveit_ros_perception'} +[2.130750] (moveit_ros_robot_interaction) JobSkipped: {'identifier': 'moveit_ros_robot_interaction'} +[2.130764] (moveit_ros_warehouse) JobSkipped: {'identifier': 'moveit_ros_warehouse'} +[2.130777] (moveit_ros_benchmarks) JobSkipped: {'identifier': 'moveit_ros_benchmarks'} +[2.130791] (moveit_ros_move_group) JobSkipped: {'identifier': 'moveit_ros_move_group'} +[2.130805] (moveit_resources_prbt_moveit_config) JobSkipped: {'identifier': 'moveit_resources_prbt_moveit_config'} +[2.130819] (moveit_ros_planning_interface) JobSkipped: {'identifier': 'moveit_ros_planning_interface'} +[2.130833] (moveit_hybrid_planning) JobSkipped: {'identifier': 'moveit_hybrid_planning'} +[2.130846] (moveit_resources_prbt_pg70_support) JobSkipped: {'identifier': 'moveit_resources_prbt_pg70_support'} +[2.130860] (moveit_ros_visualization) JobSkipped: {'identifier': 'moveit_ros_visualization'} +[2.130874] (moveit_servo) JobSkipped: {'identifier': 'moveit_servo'} +[2.130887] (moveit_ros) JobSkipped: {'identifier': 'moveit_ros'} +[2.130901] (moveit_setup_assistant) JobSkipped: {'identifier': 'moveit_setup_assistant'} +[2.130915] (pilz_industrial_motion_planner) JobSkipped: {'identifier': 'pilz_industrial_motion_planner'} +[2.130925] (moveit_planners) JobSkipped: {'identifier': 'moveit_planners'} +[2.130936] (moveit) JobSkipped: {'identifier': 'moveit'} +[2.130946] (moveit_runtime) JobSkipped: {'identifier': 'moveit_runtime'} +[2.130957] (-) EventReactorShutdown: {} diff --git a/log/build_2022-06-08_12-52-32/logger_all.log b/log/build_2022-06-08_12-52-32/logger_all.log new file mode 100644 index 0000000000..d4c7af7b3d --- /dev/null +++ b/log/build_2022-06-08_12-52-32/logger_all.log @@ -0,0 +1,986 @@ +[0.181s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--mixin', 'release'] +[0.181s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=['-DCMAKE_BUILD_TYPE=Release'], cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=['release'], verb_parser=, verb_extension=, main=>, mixin_verb=('build',)) +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover +[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover +[0.199s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/henry/ws_moveit2/src/moveit2' +[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install'] +[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore' +[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install' +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg'] +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg' +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta'] +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta' +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros'] +[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros' +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python'] +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake' +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python' +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py'] +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py' +[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['ignore', 'ignore_ament_install'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ignore' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ignore_ament_install' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['colcon_pkg'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'colcon_pkg' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['colcon_meta'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'colcon_meta' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['ros'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ros' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['cmake', 'python'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'cmake' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'python' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['python_setup_py'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'python_setup_py' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['ignore', 'ignore_ament_install'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ignore' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ignore_ament_install' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['colcon_pkg'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'colcon_pkg' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['colcon_meta'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'colcon_meta' +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['ros'] +[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ros' +[0.215s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit' with type 'ros.ament_cmake' and name 'moveit' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) by extensions ['ignore', 'ignore_ament_install'] +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) by extension 'ignore' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) ignored +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['ignore', 'ignore_ament_install'] +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ignore' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ignore_ament_install' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['colcon_pkg'] +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'colcon_pkg' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['colcon_meta'] +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'colcon_meta' +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['ros'] +[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ros' +[0.216s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_common' with type 'ros.ament_cmake' and name 'moveit_common' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['ignore', 'ignore_ament_install'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ignore' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ignore_ament_install' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['colcon_pkg'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'colcon_pkg' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['colcon_meta'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'colcon_meta' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['ros'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ros' +[0.216s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_configs_utils' with type 'ros.ament_python' and name 'moveit_configs_utils' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['ignore', 'ignore_ament_install'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ignore' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ignore_ament_install' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['colcon_pkg'] +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'colcon_pkg' +[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['colcon_meta'] +[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'colcon_meta' +[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['ros'] +[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ros' +[0.219s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_core' with type 'ros.ament_cmake' and name 'moveit_core' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) by extensions ['ignore', 'ignore_ament_install'] +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) by extension 'ignore' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) ignored +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['ignore', 'ignore_ament_install'] +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ignore' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ignore_ament_install' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['colcon_pkg'] +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'colcon_pkg' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['colcon_meta'] +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'colcon_meta' +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['ros'] +[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ros' +[0.220s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_kinematics' with type 'ros.ament_cmake' and name 'moveit_kinematics' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['ignore', 'ignore_ament_install'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ignore' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ignore_ament_install' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['colcon_pkg'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'colcon_pkg' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['colcon_meta'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'colcon_meta' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['ros'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ros' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['cmake', 'python'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'cmake' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'python' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['python_setup_py'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'python_setup_py' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['ignore', 'ignore_ament_install'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ignore' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ignore_ament_install' +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['colcon_pkg'] +[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'colcon_pkg' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['colcon_meta'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'colcon_meta' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['ros'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ros' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['cmake', 'python'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'cmake' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'python' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['python_setup_py'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'python_setup_py' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['ignore', 'ignore_ament_install'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ignore' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ignore_ament_install' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['colcon_pkg'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'colcon_pkg' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['colcon_meta'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'colcon_meta' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['ros'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ros' +[0.221s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_interface' with type 'ros.ament_cmake' and name 'moveit_planners_chomp' +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['ignore', 'ignore_ament_install'] +[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ignore' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ignore_ament_install' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['colcon_pkg'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'colcon_pkg' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['colcon_meta'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'colcon_meta' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['ros'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ros' +[0.222s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_motion_planner' with type 'ros.ament_cmake' and name 'chomp_motion_planner' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['ignore', 'ignore_ament_install'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ignore' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ignore_ament_install' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['colcon_pkg'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'colcon_pkg' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['colcon_meta'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'colcon_meta' +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['ros'] +[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ros' +[0.223s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_optimizer_adapter' with type 'ros.ament_cmake' and name 'moveit_chomp_optimizer_adapter' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['ignore', 'ignore_ament_install'] +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ignore' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ignore_ament_install' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['colcon_pkg'] +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'colcon_pkg' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['colcon_meta'] +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'colcon_meta' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['ros'] +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ros' +[0.223s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/moveit_planners' with type 'ros.ament_cmake' and name 'moveit_planners' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['ignore', 'ignore_ament_install'] +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ignore' +[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ignore_ament_install' +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['colcon_pkg'] +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'colcon_pkg' +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['colcon_meta'] +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'colcon_meta' +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['ros'] +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ros' +[0.224s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/ompl' with type 'ros.ament_cmake' and name 'moveit_planners_ompl' +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['ignore', 'ignore_ament_install'] +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ignore' +[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ignore_ament_install' +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['colcon_pkg'] +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'colcon_pkg' +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['colcon_meta'] +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'colcon_meta' +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['ros'] +[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ros' +[0.226s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/pilz_industrial_motion_planner' with type 'ros.ament_cmake' and name 'pilz_industrial_motion_planner' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['ignore', 'ignore_ament_install'] +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ignore' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ignore_ament_install' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['colcon_pkg'] +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'colcon_pkg' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['colcon_meta'] +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'colcon_meta' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['ros'] +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ros' +[0.226s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/pilz_industrial_motion_planner_testutils' with type 'ros.ament_cmake' and name 'pilz_industrial_motion_planner_testutils' +[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['ignore', 'ignore_ament_install'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ignore' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ignore_ament_install' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['colcon_pkg'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'colcon_pkg' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['colcon_meta'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'colcon_meta' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['ros'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ros' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['cmake', 'python'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'cmake' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'python' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['python_setup_py'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'python_setup_py' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['ignore', 'ignore_ament_install'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ignore' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ignore_ament_install' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['colcon_pkg'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'colcon_pkg' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['colcon_meta'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'colcon_meta' +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['ros'] +[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ros' +[0.228s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_ikfast_manipulator_plugin' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_ikfast_manipulator_plugin' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['ignore', 'ignore_ament_install'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ignore' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ignore_ament_install' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['colcon_pkg'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'colcon_pkg' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['colcon_meta'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'colcon_meta' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['ros'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ros' +[0.228s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_moveit_config' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_moveit_config' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['ignore', 'ignore_ament_install'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ignore' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ignore_ament_install' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['colcon_pkg'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'colcon_pkg' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['colcon_meta'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'colcon_meta' +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['ros'] +[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ros' +[0.229s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_pg70_support' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_pg70_support' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['ignore', 'ignore_ament_install'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ignore' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ignore_ament_install' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['colcon_pkg'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'colcon_pkg' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['colcon_meta'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'colcon_meta' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['ros'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ros' +[0.229s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_support' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_support' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) by extensions ['ignore', 'ignore_ament_install'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) by extension 'ignore' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) ignored +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['ignore', 'ignore_ament_install'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ignore' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ignore_ament_install' +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['colcon_pkg'] +[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'colcon_pkg' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['colcon_meta'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'colcon_meta' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['ros'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ros' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['cmake', 'python'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'cmake' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'python' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['python_setup_py'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'python_setup_py' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) by extensions ['ignore', 'ignore_ament_install'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) by extension 'ignore' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) ignored +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['ignore', 'ignore_ament_install'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ignore' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ignore_ament_install' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['colcon_pkg'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'colcon_pkg' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['colcon_meta'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'colcon_meta' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['ros'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ros' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['cmake', 'python'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'cmake' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'python' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['python_setup_py'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'python_setup_py' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['ignore', 'ignore_ament_install'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ignore' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ignore_ament_install' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['colcon_pkg'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'colcon_pkg' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['colcon_meta'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'colcon_meta' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['ros'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ros' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['cmake', 'python'] +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'cmake' +[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'python' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['python_setup_py'] +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'python_setup_py' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['ignore', 'ignore_ament_install'] +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ignore' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ignore_ament_install' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['colcon_pkg'] +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'colcon_pkg' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['colcon_meta'] +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'colcon_meta' +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['ros'] +[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ros' +[0.232s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_plugins' with type 'ros.ament_cmake' and name 'moveit_plugins' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['ignore', 'ignore_ament_install'] +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ignore' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ignore_ament_install' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['colcon_pkg'] +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'colcon_pkg' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['colcon_meta'] +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'colcon_meta' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['ros'] +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ros' +[0.232s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_ros_control_interface' with type 'ros.ament_cmake' and name 'moveit_ros_control_interface' +[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['ignore', 'ignore_ament_install'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ignore' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ignore_ament_install' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['colcon_pkg'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'colcon_pkg' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['colcon_meta'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'colcon_meta' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['ros'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ros' +[0.233s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_simple_controller_manager' with type 'ros.ament_cmake' and name 'moveit_simple_controller_manager' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['ignore', 'ignore_ament_install'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ignore' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ignore_ament_install' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['colcon_pkg'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'colcon_pkg' +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['colcon_meta'] +[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'colcon_meta' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['ros'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ros' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['cmake', 'python'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'cmake' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'python' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['python_setup_py'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'python_setup_py' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['ignore', 'ignore_ament_install'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ignore' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ignore_ament_install' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['colcon_pkg'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'colcon_pkg' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['colcon_meta'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'colcon_meta' +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['ros'] +[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ros' +[0.235s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/benchmarks' with type 'ros.ament_cmake' and name 'moveit_ros_benchmarks' +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['ignore', 'ignore_ament_install'] +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ignore' +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ignore_ament_install' +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['colcon_pkg'] +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'colcon_pkg' +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['colcon_meta'] +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'colcon_meta' +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['ros'] +[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ros' +[0.236s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/hybrid_planning' with type 'ros.ament_cmake' and name 'moveit_hybrid_planning' +[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) by extensions ['ignore', 'ignore_ament_install'] +[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) by extension 'ignore' +[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) ignored +[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['ignore', 'ignore_ament_install'] +[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ignore' +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ignore_ament_install' +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['colcon_pkg'] +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'colcon_pkg' +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['colcon_meta'] +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'colcon_meta' +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['ros'] +[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ros' +[0.238s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/move_group' with type 'ros.ament_cmake' and name 'moveit_ros_move_group' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['ignore', 'ignore_ament_install'] +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ignore' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ignore_ament_install' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['colcon_pkg'] +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'colcon_pkg' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['colcon_meta'] +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'colcon_meta' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['ros'] +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ros' +[0.238s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/moveit_ros' with type 'ros.ament_cmake' and name 'moveit_ros' +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['ignore', 'ignore_ament_install'] +[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ignore' +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ignore_ament_install' +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['colcon_pkg'] +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'colcon_pkg' +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['colcon_meta'] +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'colcon_meta' +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['ros'] +[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ros' +[0.240s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/moveit_servo' with type 'ros.ament_cmake' and name 'moveit_servo' +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['ignore', 'ignore_ament_install'] +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ignore' +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ignore_ament_install' +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['colcon_pkg'] +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'colcon_pkg' +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['colcon_meta'] +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'colcon_meta' +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['ros'] +[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ros' +[0.241s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/occupancy_map_monitor' with type 'ros.ament_cmake' and name 'moveit_ros_occupancy_map_monitor' +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['ignore', 'ignore_ament_install'] +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ignore' +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ignore_ament_install' +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['colcon_pkg'] +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'colcon_pkg' +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['colcon_meta'] +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'colcon_meta' +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['ros'] +[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ros' +[0.242s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/perception' with type 'ros.ament_cmake' and name 'moveit_ros_perception' +[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['ignore', 'ignore_ament_install'] +[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ignore' +[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ignore_ament_install' +[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['colcon_pkg'] +[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'colcon_pkg' +[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['colcon_meta'] +[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'colcon_meta' +[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['ros'] +[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ros' +[0.244s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/planning' with type 'ros.ament_cmake' and name 'moveit_ros_planning' +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['ignore', 'ignore_ament_install'] +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ignore' +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ignore_ament_install' +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['colcon_pkg'] +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'colcon_pkg' +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['colcon_meta'] +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'colcon_meta' +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['ros'] +[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ros' +[0.245s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/planning_interface' with type 'ros.ament_cmake' and name 'moveit_ros_planning_interface' +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['ignore', 'ignore_ament_install'] +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ignore' +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ignore_ament_install' +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['colcon_pkg'] +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'colcon_pkg' +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['colcon_meta'] +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'colcon_meta' +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['ros'] +[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ros' +[0.246s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/robot_interaction' with type 'ros.ament_cmake' and name 'moveit_ros_robot_interaction' +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['ignore', 'ignore_ament_install'] +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ignore' +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ignore_ament_install' +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['colcon_pkg'] +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'colcon_pkg' +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['colcon_meta'] +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'colcon_meta' +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['ros'] +[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ros' +[0.247s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/visualization' with type 'ros.ament_cmake' and name 'moveit_ros_visualization' +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['ignore', 'ignore_ament_install'] +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ignore' +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ignore_ament_install' +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['colcon_pkg'] +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'colcon_pkg' +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['colcon_meta'] +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'colcon_meta' +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['ros'] +[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ros' +[0.248s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/warehouse' with type 'ros.ament_cmake' and name 'moveit_ros_warehouse' +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['ignore', 'ignore_ament_install'] +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ignore' +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ignore_ament_install' +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['colcon_pkg'] +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'colcon_pkg' +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['colcon_meta'] +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'colcon_meta' +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['ros'] +[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ros' +[0.249s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_runtime' with type 'ros.ament_cmake' and name 'moveit_runtime' +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['ignore', 'ignore_ament_install'] +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ignore' +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ignore_ament_install' +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['colcon_pkg'] +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'colcon_pkg' +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['colcon_meta'] +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'colcon_meta' +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['ros'] +[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ros' +[0.250s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_setup_assistant' with type 'ros.ament_cmake' and name 'moveit_setup_assistant' +[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults +[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover +[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults +[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover +[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults +[0.267s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters +[0.267s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover +[0.268s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 304 installed packages in /opt/ros/humble +[0.269s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_target' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_clean_cache' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_clean_first' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_force_configure' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'ament_cmake_args' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'catkin_cmake_args' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.305s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_common' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_common', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_common', 'symlink_install': False, 'test_result_base': None} +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_target' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_clean_cache' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_clean_first' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_force_configure' from command line to 'False' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'ament_cmake_args' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'catkin_cmake_args' from command line to 'None' +[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.305s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_configs_utils' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils', 'symlink_install': False, 'test_result_base': None} +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_target' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_clean_cache' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_clean_first' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_force_configure' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'ament_cmake_args' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'catkin_cmake_args' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.306s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_support' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support', 'symlink_install': False, 'test_result_base': None} +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_target' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_clean_cache' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_clean_first' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_force_configure' from command line to 'False' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'ament_cmake_args' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'catkin_cmake_args' from command line to 'None' +[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.306s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_core' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_core', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_core', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_core', 'symlink_install': False, 'test_result_base': None} +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_target' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_clean_cache' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_clean_first' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_force_configure' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'ament_cmake_args' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'catkin_cmake_args' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.307s] DEBUG:colcon.colcon_core.verb:Building package 'chomp_motion_planner' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/chomp_motion_planner', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_motion_planner', 'symlink_install': False, 'test_result_base': None} +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_target' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_clean_cache' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_clean_first' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_force_configure' from command line to 'False' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'ament_cmake_args' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'catkin_cmake_args' from command line to 'None' +[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.307s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_ikfast_manipulator_plugin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_ikfast_manipulator_plugin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin', 'symlink_install': False, 'test_result_base': None} +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_target' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_clean_cache' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_clean_first' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_force_configure' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'ament_cmake_args' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'catkin_cmake_args' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.308s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_occupancy_map_monitor' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_occupancy_map_monitor', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/occupancy_map_monitor', 'symlink_install': False, 'test_result_base': None} +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_target' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_clean_cache' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_clean_first' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_force_configure' from command line to 'False' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'ament_cmake_args' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'catkin_cmake_args' from command line to 'None' +[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.308s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_simple_controller_manager' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_simple_controller_manager', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_simple_controller_manager', 'symlink_install': False, 'test_result_base': None} +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_target' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_clean_cache' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_clean_first' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_force_configure' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'ament_cmake_args' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'catkin_cmake_args' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.309s] DEBUG:colcon.colcon_core.verb:Building package 'pilz_industrial_motion_planner_testutils' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/pilz_industrial_motion_planner_testutils', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner_testutils', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner_testutils', 'symlink_install': False, 'test_result_base': None} +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_target' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_clean_cache' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_clean_first' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_force_configure' from command line to 'False' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'ament_cmake_args' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'catkin_cmake_args' from command line to 'None' +[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.309s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_chomp_optimizer_adapter' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_chomp_optimizer_adapter', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_chomp_optimizer_adapter', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_optimizer_adapter', 'symlink_install': False, 'test_result_base': None} +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_target' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_clean_cache' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_clean_first' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_force_configure' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'ament_cmake_args' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'catkin_cmake_args' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.310s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners_chomp' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners_chomp', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_chomp', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_interface', 'symlink_install': False, 'test_result_base': None} +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_target' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_clean_cache' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_clean_first' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_force_configure' from command line to 'False' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'ament_cmake_args' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'catkin_cmake_args' from command line to 'None' +[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.310s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_plugins' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_plugins', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_plugins', 'symlink_install': False, 'test_result_base': None} +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_target' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_clean_cache' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_clean_first' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_force_configure' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'ament_cmake_args' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'catkin_cmake_args' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.311s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_control_interface' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_control_interface', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_control_interface', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_ros_control_interface', 'symlink_install': False, 'test_result_base': None} +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_target' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_clean_cache' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_clean_first' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_force_configure' from command line to 'False' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'ament_cmake_args' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'catkin_cmake_args' from command line to 'None' +[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.311s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_planning' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_planning', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/planning', 'symlink_install': False, 'test_result_base': None} +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_target' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_clean_cache' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_clean_first' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_force_configure' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'ament_cmake_args' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'catkin_cmake_args' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.312s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_kinematics' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_kinematics', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_kinematics', 'symlink_install': False, 'test_result_base': None} +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_target' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_clean_cache' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_clean_first' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_force_configure' from command line to 'False' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'ament_cmake_args' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'catkin_cmake_args' from command line to 'None' +[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.312s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners_ompl' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners_ompl', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/ompl', 'symlink_install': False, 'test_result_base': None} +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_target' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_clean_cache' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_clean_first' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_force_configure' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'ament_cmake_args' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'catkin_cmake_args' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.313s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_perception' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_perception', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_perception', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/perception', 'symlink_install': False, 'test_result_base': None} +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_target' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_clean_cache' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_clean_first' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_force_configure' from command line to 'False' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'ament_cmake_args' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'catkin_cmake_args' from command line to 'None' +[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.313s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_robot_interaction' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_robot_interaction', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/robot_interaction', 'symlink_install': False, 'test_result_base': None} +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_target' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_clean_cache' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_clean_first' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_force_configure' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'ament_cmake_args' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'catkin_cmake_args' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.314s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_warehouse' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_warehouse', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/warehouse', 'symlink_install': False, 'test_result_base': None} +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_target' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_clean_cache' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_clean_first' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_force_configure' from command line to 'False' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'ament_cmake_args' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'catkin_cmake_args' from command line to 'None' +[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.314s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_benchmarks' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_benchmarks', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/benchmarks', 'symlink_install': False, 'test_result_base': None} +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_target' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_clean_cache' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_clean_first' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_force_configure' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'ament_cmake_args' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'catkin_cmake_args' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.315s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_move_group' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_move_group', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/move_group', 'symlink_install': False, 'test_result_base': None} +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_target' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_clean_cache' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_clean_first' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_force_configure' from command line to 'False' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'ament_cmake_args' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'catkin_cmake_args' from command line to 'None' +[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.315s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_moveit_config' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_moveit_config', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_moveit_config', 'symlink_install': False, 'test_result_base': None} +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_target' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_clean_cache' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_clean_first' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_force_configure' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'ament_cmake_args' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'catkin_cmake_args' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.316s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_planning_interface' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_planning_interface', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/planning_interface', 'symlink_install': False, 'test_result_base': None} +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_target' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_clean_cache' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_clean_first' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_force_configure' from command line to 'False' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'ament_cmake_args' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'catkin_cmake_args' from command line to 'None' +[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.316s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_hybrid_planning' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_hybrid_planning', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_hybrid_planning', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/hybrid_planning', 'symlink_install': False, 'test_result_base': None} +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_target' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_clean_cache' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_clean_first' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_force_configure' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'ament_cmake_args' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'catkin_cmake_args' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.317s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_pg70_support' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_pg70_support', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_pg70_support', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_pg70_support', 'symlink_install': False, 'test_result_base': None} +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_target' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_clean_cache' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_clean_first' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_force_configure' from command line to 'False' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'ament_cmake_args' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'catkin_cmake_args' from command line to 'None' +[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.317s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_visualization' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_visualization', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/visualization', 'symlink_install': False, 'test_result_base': None} +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_target' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_clean_cache' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_clean_first' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_force_configure' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'ament_cmake_args' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'catkin_cmake_args' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.318s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_servo' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_servo', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_servo', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/moveit_servo', 'symlink_install': False, 'test_result_base': None} +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_target' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_clean_cache' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_clean_first' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_force_configure' from command line to 'False' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'ament_cmake_args' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'catkin_cmake_args' from command line to 'None' +[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.318s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/moveit_ros', 'symlink_install': False, 'test_result_base': None} +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_target' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_clean_cache' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_clean_first' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_force_configure' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'ament_cmake_args' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'catkin_cmake_args' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.319s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_setup_assistant' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_setup_assistant', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_setup_assistant', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_setup_assistant', 'symlink_install': False, 'test_result_base': None} +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_target' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_clean_cache' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_clean_first' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_force_configure' from command line to 'False' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'ament_cmake_args' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'catkin_cmake_args' from command line to 'None' +[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.319s] DEBUG:colcon.colcon_core.verb:Building package 'pilz_industrial_motion_planner' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/pilz_industrial_motion_planner', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner', 'symlink_install': False, 'test_result_base': None} +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_target' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_clean_cache' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_clean_first' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_force_configure' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'ament_cmake_args' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'catkin_cmake_args' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.320s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/moveit_planners', 'symlink_install': False, 'test_result_base': None} +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_target' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_clean_cache' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_clean_first' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_force_configure' from command line to 'False' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'ament_cmake_args' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'catkin_cmake_args' from command line to 'None' +[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.320s] DEBUG:colcon.colcon_core.verb:Building package 'moveit' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit', 'symlink_install': False, 'test_result_base': None} +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_target' from command line to 'None' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_target_skip_unavailable' from command line to 'False' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_clean_cache' from command line to 'False' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_clean_first' from command line to 'False' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_force_configure' from command line to 'False' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'ament_cmake_args' from command line to 'None' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'catkin_cmake_args' from command line to 'None' +[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'catkin_skip_building_tests' from command line to 'False' +[0.321s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_runtime' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_runtime', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_runtime', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_runtime', 'symlink_install': False, 'test_result_base': None} +[0.321s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor +[0.322s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete +[0.323s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_common' with build type 'ament_cmake' +[0.323s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_common' +[0.326s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems +[0.326s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell +[0.326s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment +[0.328s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' with build type 'ament_python' +[0.328s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_configs_utils', 'ament_prefix_path') +[0.329s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1' +[0.329s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv' +[0.330s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh' +[0.330s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell +[0.331s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment +[0.332s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support' with build type 'ament_cmake' +[0.332s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support' +[0.332s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell +[0.332s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment +[0.340s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +[0.499s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' +[0.499s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell +[0.499s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment +[0.504s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +[0.634s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +[0.636s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +[0.656s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +[0.672s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common +[0.678s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_common) +[0.679s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common +[0.681s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake module files +[0.681s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake config files +[0.682s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_common', 'cmake_prefix_path') +[0.682s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1' +[0.682s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv' +[0.682s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh' +[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' +[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/pkgconfig/moveit_common.pc' +[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/python3.10/site-packages' +[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' +[0.684s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.ps1' +[0.684s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv' +[0.684s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.sh' +[0.685s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.bash' +[0.685s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.zsh' +[0.686s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/colcon-core/packages/moveit_common) +[0.697s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_common) +[0.698s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake module files +[0.698s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake config files +[0.699s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_common', 'cmake_prefix_path') +[0.699s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1' +[0.700s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv' +[0.700s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh' +[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' +[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/pkgconfig/moveit_common.pc' +[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/python3.10/site-packages' +[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' +[0.702s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.ps1' +[0.702s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv' +[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.sh' +[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.bash' +[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.zsh' +[0.703s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/colcon-core/packages/moveit_common) +[0.704s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_core' with build type 'ament_cmake' +[0.704s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_core' +[0.705s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell +[0.705s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment +[0.711s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core +[0.838s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed +[0.953s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +[0.954s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +[0.977s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +[0.988s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +[1.004s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_resources_prbt_support) +[1.005s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake module files +[1.005s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +[1.006s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake config files +[1.006s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_resources_prbt_support', 'cmake_prefix_path') +[1.006s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1' +[1.006s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv' +[1.007s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh' +[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' +[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/pkgconfig/moveit_resources_prbt_support.pc' +[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/python3.10/site-packages' +[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' +[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1' +[1.008s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv' +[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh' +[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash' +[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh' +[1.009s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support) +[1.020s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_resources_prbt_support) +[1.020s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake module files +[1.021s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake config files +[1.021s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_resources_prbt_support', 'cmake_prefix_path') +[1.021s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1' +[1.022s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv' +[1.022s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh' +[1.022s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' +[1.022s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/pkgconfig/moveit_resources_prbt_support.pc' +[1.023s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/python3.10/site-packages' +[1.023s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' +[1.023s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1' +[1.024s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv' +[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh' +[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash' +[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh' +[1.025s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support) +[1.030s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils' for CMake module files +[1.031s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed +[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils' for CMake config files +[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib' +[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/bin' +[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/pkgconfig/moveit_configs_utils.pc' +[1.032s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages' +[1.032s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_configs_utils', 'pythonpath') +[1.032s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1' +[1.032s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv' +[1.033s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh' +[1.033s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/bin' +[1.033s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_configs_utils) +[1.033s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1' +[1.034s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv' +[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.sh' +[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.bash' +[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh' +[1.034s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils) +[2.433s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core +[2.439s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_core) +[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core' for CMake module files +[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core' for CMake config files +[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/bin' +[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/lib/pkgconfig/moveit_core.pc' +[2.441s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/lib/python3.10/site-packages' +[2.441s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/bin' +[2.441s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.ps1' +[2.441s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.dsv' +[2.441s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.sh' +[2.442s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.bash' +[2.442s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.zsh' +[2.442s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/colcon-core/packages/moveit_core) +[2.452s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop +[2.452s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed +[2.453s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '1' +[2.453s] DEBUG:colcon.colcon_core.event_reactor:joining thread +[2.457s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems +[2.457s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems +[2.457s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2' +[2.467s] DEBUG:colcon.colcon_core.event_reactor:joined thread +[2.468s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.ps1' +[2.469s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/henry/ws_moveit2/src/moveit2/install/_local_setup_util_ps1.py' +[2.469s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.ps1' +[2.470s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.sh' +[2.471s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/henry/ws_moveit2/src/moveit2/install/_local_setup_util_sh.py' +[2.471s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.sh' +[2.472s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.bash' +[2.473s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.bash' +[2.473s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.zsh' +[2.474s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.zsh' diff --git a/log/build_2022-06-08_12-52-32/moveit_common/command.log b/log/build_2022-06-08_12-52-32/moveit_common/command.log new file mode 100644 index 0000000000..81f689bf6b --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_common/command.log @@ -0,0 +1,6 @@ +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stderr.log b/log/build_2022-06-08_12-52-32/moveit_common/stderr.log new file mode 100644 index 0000000000..e69de29bb2 diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stdout.log b/log/build_2022-06-08_12-52-32/moveit_common/stdout.log new file mode 100644 index 0000000000..c29c3332f0 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_common/stdout.log @@ -0,0 +1,28 @@ +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) +-- Added test 'copyright' to check source files copyright and LICENSE +-- Added test 'lint_cmake' to check CMake code style +-- Added test 'xmllint' to check XML markup files +-- Configuring done +-- Generating done +-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common +-- Install configuration: "Release" +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml +-- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log new file mode 100644 index 0000000000..c29c3332f0 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log @@ -0,0 +1,28 @@ +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) +-- Added test 'copyright' to check source files copyright and LICENSE +-- Added test 'lint_cmake' to check CMake code style +-- Added test 'xmllint' to check XML markup files +-- Configuring done +-- Generating done +-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common +-- Install configuration: "Release" +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml +-- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake diff --git a/log/build_2022-06-08_12-52-32/moveit_common/streams.log b/log/build_2022-06-08_12-52-32/moveit_common/streams.log new file mode 100644 index 0000000000..999e9e267a --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_common/streams.log @@ -0,0 +1,34 @@ +[0.016s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +[0.178s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +[0.178s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +[0.242s] -- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) +[0.302s] -- Added test 'copyright' to check source files copyright and LICENSE +[0.304s] -- Added test 'lint_cmake' to check CMake code style +[0.305s] -- Added test 'xmllint' to check XML markup files +[0.306s] -- Configuring done +[0.308s] -- Generating done +[0.308s] -- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common +[0.310s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common +[0.311s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +[0.332s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 +[0.348s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common +[0.352s] -- Install configuration: "Release" +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash +[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml +[0.353s] -- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake +[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake +[0.355s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log new file mode 100644 index 0000000000..8659525b8a --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log @@ -0,0 +1,2 @@ +Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed +Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log new file mode 100644 index 0000000000..89805d747e --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log @@ -0,0 +1,2 @@ +/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. + warnings.warn( diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log new file mode 100644 index 0000000000..6e86d07a99 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log @@ -0,0 +1,46 @@ +running egg_info +creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info +writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO +writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt +writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt +writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt +writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt +writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +running build +running build_py +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +running install +running install_lib +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc +running install_data +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +running install_egg_info +Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info +running install_scripts +writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log new file mode 100644 index 0000000000..514c7258cb --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log @@ -0,0 +1,48 @@ +running egg_info +creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info +writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO +writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt +writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt +writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt +writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt +writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +running build +running build_py +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib +creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +running install +/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. + warnings.warn( +running install_lib +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc +byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc +running install_data +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils +creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +running install_egg_info +Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info +running install_scripts +writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log new file mode 100644 index 0000000000..afef0f1b6f --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log @@ -0,0 +1,50 @@ +[0.509s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed +[0.661s] running egg_info +[0.662s] creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info +[0.662s] writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO +[0.662s] writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt +[0.662s] writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt +[0.662s] writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt +[0.662s] writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt +[0.662s] writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +[0.663s] reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +[0.664s] writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' +[0.664s] running build +[0.664s] running build_py +[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build +[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib +[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +[0.665s] copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +[0.665s] copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +[0.665s] copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +[0.665s] copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils +[0.665s] running install +[0.666s] /usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. +[0.666s] warnings.warn( +[0.666s] running install_lib +[0.666s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +[0.666s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils +[0.667s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc +[0.667s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc +[0.668s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc +[0.668s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc +[0.669s] running install_data +[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index +[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index +[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +[0.669s] copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages +[0.669s] copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils +[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.669s] copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.669s] copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.669s] copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.670s] copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.670s] copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs +[0.670s] running install_egg_info +[0.670s] Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info +[0.671s] running install_scripts +[0.684s] writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' +[0.702s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed diff --git a/log/build_2022-06-08_12-52-32/moveit_core/command.log b/log/build_2022-06-08_12-52-32/moveit_core/command.log new file mode 100644 index 0000000000..263b877f02 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_core/command.log @@ -0,0 +1,2 @@ +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stderr.log b/log/build_2022-06-08_12-52-32/moveit_core/stderr.log new file mode 100644 index 0000000000..e23dc64dc5 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_core/stderr.log @@ -0,0 +1,17 @@ +CMake Error at CMakeLists.txt:43 (find_package): + By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has + asked CMake to find a package configuration file provided by "srdfdom", but + CMake did not find one. + + Could not find a package configuration file provided by "srdfdom" with any + of the following names: + + srdfdomConfig.cmake + srdfdom-config.cmake + + Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set + "srdfdom_DIR" to a directory containing one of the above files. If + "srdfdom" provides a separate development package or SDK, be sure it has + been installed. + + diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stdout.log b/log/build_2022-06-08_12-52-32/moveit_core/stdout.log new file mode 100644 index 0000000000..47ae7f06b6 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_core/stdout.log @@ -0,0 +1,47 @@ +-- The CXX compiler identification is GNU 11.2.0 +-- Detecting CXX compiler ABI info +-- Detecting CXX compiler ABI info - done +-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +-- Detecting CXX compile features +-- Detecting CXX compile features - done +-- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so +-- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) +-- BACKWARD_HAS_UNWIND=1 +-- BACKWARD_HAS_BACKTRACE=0 +-- BACKWARD_HAS_BACKTRACE_SYMBOL=0 +-- BACKWARD_HAS_DW=1 +-- BACKWARD_HAS_BFD=0 +-- Found Backward: /opt/ros/humble/share/backward_ros/cmake +-- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) +-- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) +-- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) +-- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) +-- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c +-- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp +-- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) +-- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) +-- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") +-- Found FastRTPS: /opt/ros/humble/include +-- Using RMW implementation 'rmw_fastrtps_cpp' as default +-- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) +-- Found Eigen3: TRUE (found version "3.4.0") +-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") +-- Checking for module 'fcl>=0.5.0' +-- Found fcl, version 0.7.0 +-- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") +-- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) +-- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) +-- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) +-- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) +-- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) +-- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) +-- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) +-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem +-- library: /usr/lib/x86_64-linux-gnu/libcurl.so +-- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) +-- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) +-- Configuring incomplete, errors occurred! +See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log new file mode 100644 index 0000000000..eb621a2b67 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log @@ -0,0 +1,64 @@ +-- The CXX compiler identification is GNU 11.2.0 +-- Detecting CXX compiler ABI info +-- Detecting CXX compiler ABI info - done +-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +-- Detecting CXX compile features +-- Detecting CXX compile features - done +-- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so +-- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) +-- BACKWARD_HAS_UNWIND=1 +-- BACKWARD_HAS_BACKTRACE=0 +-- BACKWARD_HAS_BACKTRACE_SYMBOL=0 +-- BACKWARD_HAS_DW=1 +-- BACKWARD_HAS_BFD=0 +-- Found Backward: /opt/ros/humble/share/backward_ros/cmake +-- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) +-- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) +-- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) +-- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) +-- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c +-- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp +-- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) +-- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) +-- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") +-- Found FastRTPS: /opt/ros/humble/include +-- Using RMW implementation 'rmw_fastrtps_cpp' as default +-- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) +-- Found Eigen3: TRUE (found version "3.4.0") +-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") +-- Checking for module 'fcl>=0.5.0' +-- Found fcl, version 0.7.0 +-- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") +-- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) +-- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) +-- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) +-- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) +-- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) +-- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) +-- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) +-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem +-- library: /usr/lib/x86_64-linux-gnu/libcurl.so +-- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) +-- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) +CMake Error at CMakeLists.txt:43 (find_package): + By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has + asked CMake to find a package configuration file provided by "srdfdom", but + CMake did not find one. + + Could not find a package configuration file provided by "srdfdom" with any + of the following names: + + srdfdomConfig.cmake + srdfdom-config.cmake + + Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set + "srdfdom_DIR" to a directory containing one of the above files. If + "srdfdom" provides a separate development package or SDK, be sure it has + been installed. + + +-- Configuring incomplete, errors occurred! +See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". diff --git a/log/build_2022-06-08_12-52-32/moveit_core/streams.log b/log/build_2022-06-08_12-52-32/moveit_core/streams.log new file mode 100644 index 0000000000..45601f0c62 --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_core/streams.log @@ -0,0 +1,66 @@ +[0.005s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core +[0.053s] -- The CXX compiler identification is GNU 11.2.0 +[0.059s] -- Detecting CXX compiler ABI info +[0.101s] -- Detecting CXX compiler ABI info - done +[0.106s] -- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +[0.106s] -- Detecting CXX compile features +[0.106s] -- Detecting CXX compile features - done +[0.107s] -- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) +[0.108s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +[0.220s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +[0.330s] -- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so +[0.333s] -- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) +[0.333s] -- BACKWARD_HAS_UNWIND=1 +[0.333s] -- BACKWARD_HAS_BACKTRACE=0 +[0.333s] -- BACKWARD_HAS_BACKTRACE_SYMBOL=0 +[0.333s] -- BACKWARD_HAS_DW=1 +[0.333s] -- BACKWARD_HAS_BFD=0 +[0.334s] -- Found Backward: /opt/ros/humble/share/backward_ros/cmake +[0.336s] -- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) +[0.386s] -- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) +[0.390s] -- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) +[0.398s] -- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) +[0.413s] -- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c +[0.431s] -- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp +[0.487s] -- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) +[0.490s] -- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) +[0.555s] -- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") +[0.570s] -- Found FastRTPS: /opt/ros/humble/include +[0.596s] -- Using RMW implementation 'rmw_fastrtps_cpp' as default +[0.704s] -- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) +[0.709s] -- Found Eigen3: TRUE (found version "3.4.0") +[0.711s] -- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") +[0.712s] -- Checking for module 'fcl>=0.5.0' +[0.718s] -- Found fcl, version 0.7.0 +[0.741s] -- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") +[0.742s] -- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) +[0.754s] -- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) +[0.775s] -- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) +[1.082s] -- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) +[1.094s] -- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) +[1.106s] -- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) +[1.108s] -- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) +[1.116s] -- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem +[1.165s] -- library: /usr/lib/x86_64-linux-gnu/libcurl.so +[1.354s] -- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) +[1.357s] -- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) +[1.720s] CMake Error at CMakeLists.txt:43 (find_package): +[1.720s] By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has +[1.720s] asked CMake to find a package configuration file provided by "srdfdom", but +[1.720s] CMake did not find one. +[1.720s] +[1.720s] Could not find a package configuration file provided by "srdfdom" with any +[1.720s] of the following names: +[1.720s] +[1.720s] srdfdomConfig.cmake +[1.720s] srdfdom-config.cmake +[1.720s] +[1.720s] Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set +[1.720s] "srdfdom_DIR" to a directory containing one of the above files. If +[1.720s] "srdfdom" provides a separate development package or SDK, be sure it has +[1.721s] been installed. +[1.721s] +[1.721s]  +[1.721s] -- Configuring incomplete, errors occurred! +[1.721s] See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". +[1.727s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log new file mode 100644 index 0000000000..114f84f6ae --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log @@ -0,0 +1,6 @@ +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log new file mode 100644 index 0000000000..e69de29bb2 diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log new file mode 100644 index 0000000000..09c37a964b --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log @@ -0,0 +1,57 @@ +-- The C compiler identification is GNU 11.2.0 +-- The CXX compiler identification is GNU 11.2.0 +-- Detecting C compiler ABI info +-- Detecting C compiler ABI info - done +-- Check for working C compiler: /usr/lib/ccache/cc - skipped +-- Detecting C compile features +-- Detecting C compile features - done +-- Detecting CXX compiler ABI info +-- Detecting CXX compiler ABI info - done +-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +-- Detecting CXX compile features +-- Detecting CXX compile features - done +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Configuring done +-- Generating done +-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +-- Install configuration: "Release" +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log new file mode 100644 index 0000000000..09c37a964b --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log @@ -0,0 +1,57 @@ +-- The C compiler identification is GNU 11.2.0 +-- The CXX compiler identification is GNU 11.2.0 +-- Detecting C compiler ABI info +-- Detecting C compiler ABI info - done +-- Check for working C compiler: /usr/lib/ccache/cc - skipped +-- Detecting C compile features +-- Detecting C compile features - done +-- Detecting CXX compiler ABI info +-- Detecting CXX compiler ABI info - done +-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +-- Detecting CXX compile features +-- Detecting CXX compile features - done +-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +-- Configuring done +-- Generating done +-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +-- Install configuration: "Release" +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml +-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log new file mode 100644 index 0000000000..2f5d32631e --- /dev/null +++ b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log @@ -0,0 +1,63 @@ +[0.171s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +[0.239s] -- The C compiler identification is GNU 11.2.0 +[0.278s] -- The CXX compiler identification is GNU 11.2.0 +[0.285s] -- Detecting C compiler ABI info +[0.322s] -- Detecting C compiler ABI info - done +[0.327s] -- Check for working C compiler: /usr/lib/ccache/cc - skipped +[0.327s] -- Detecting C compile features +[0.327s] -- Detecting C compile features - done +[0.329s] -- Detecting CXX compiler ABI info +[0.373s] -- Detecting CXX compiler ABI info - done +[0.382s] -- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped +[0.382s] -- Detecting CXX compile features +[0.382s] -- Detecting CXX compile features - done +[0.384s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) +[0.516s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter +[0.613s] -- Configuring done +[0.615s] -- Generating done +[0.615s] -- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +[0.620s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support +[0.621s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +[0.644s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 +[0.655s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support +[0.659s] -- Install configuration: "Release" +[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support +[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support +[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh +[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro +[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae +[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae +[0.665s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae +[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl +[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl +[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl +[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl +[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl +[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae +[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae +[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae +[0.669s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae +[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config +[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf +[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml +[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml +[0.672s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support diff --git a/log/latest b/log/latest new file mode 120000 index 0000000000..b57d247c77 --- /dev/null +++ b/log/latest @@ -0,0 +1 @@ +latest_build \ No newline at end of file diff --git a/log/latest_build b/log/latest_build new file mode 120000 index 0000000000..2886a6fca1 --- /dev/null +++ b/log/latest_build @@ -0,0 +1 @@ +build_2022-06-08_12-52-32 \ No newline at end of file diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 6837e3f6cc..adbab5e77d 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -44,6 +44,7 @@ #include #include +#include namespace collision_detection { diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 063d6eab36..ffa868135f 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -43,6 +43,7 @@ #include #include #include +#include namespace moveit { diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index a3e5c14c1b..76d5999f97 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -46,6 +46,7 @@ #include #include #include +#include namespace cached_ik_kinematics_plugin { diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index ee8257563b..03518e9aed 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -73,7 +73,7 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr // use mutex lock for rest of initialization std::lock_guard slock(lock_); // determine cache file name - std::filesystem::path prefix(!cached_ik_path.empty() ? cached_ik_path : std::filesystem::current_path()); + std::filesystem::path prefix(!cached_ik_path.empty() ? std::filesystem::path(cached_ik_path) : std::filesystem::current_path()); // create cache directory if necessary std::filesystem::create_directories(prefix); @@ -87,7 +87,7 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr if (std::filesystem::exists(cache_file_name_)) { // read cache - boost::filesystem::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in); + std::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in); cache_file.read((char*)&last_saved_cache_size_, sizeof(unsigned int)); unsigned int num_dofs; cache_file.read((char*)&num_dofs, sizeof(unsigned int)); @@ -219,7 +219,7 @@ void IKCache::saveCache() const RCLCPP_INFO(LOGGER, "writing %ld IK solutions to %s", ik_cache_.size(), cache_file_name_.string().c_str()); - boost::filesystem::ofstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::out); + std::ofstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::out); unsigned int position_size = 3 * sizeof(tf2Scalar); unsigned int orientation_size = 4 * sizeof(tf2Scalar); unsigned int pose_size = position_size + orientation_size; diff --git a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp index fdb0752a32..1b368462cf 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp +++ b/moveit_kinematics/kdl_kinematics_plugin/src/kdl_kinematics_plugin.cpp @@ -406,7 +406,7 @@ bool KDLKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_po continue; Eigen::Map(solution.data(), solution.size()) = jnt_pos_out.data; - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); if (error_code.val != error_code.SUCCESS) diff --git a/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp b/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp index 6bcd6b3ae0..6ee31892af 100644 --- a/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp +++ b/moveit_kinematics/lma_kinematics_plugin/src/lma_kinematics_plugin.cpp @@ -292,7 +292,7 @@ bool LMAKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_po continue; Eigen::Map(solution.data(), solution.size()) = jnt_pos_out.data; - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); if (error_code.val != error_code.SUCCESS) diff --git a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp index 42ed2615a2..1ea85b1355 100644 --- a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp +++ b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp @@ -342,7 +342,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vectorcopyJointGroupPositions(joint_model_group_, solution); // Run the solution callback (i.e. collision checker) if available - if (!solution_callback.empty()) + if (solution_callback) { RCLCPP_DEBUG(LOGGER, "Calling solution callback on IK solution"); diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp index a04b600d03..124009e361 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include #include @@ -369,7 +370,7 @@ void ompl_interface::ConstraintsLibrary::saveConstraintApproximations(const std: (unsigned int)constraint_approximations_.size(), path.c_str()); try { - boost::filesystem::create_directories(path); + std::filesystem::create_directory(path); } catch (...) { diff --git a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp index 7479184c92..515bdf6afd 100644 --- a/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp +++ b/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin/src/prbt_manipulator_ikfast_moveit_plugin.cpp @@ -896,7 +896,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); // check for collisions if a callback is provided - if (!solution_callback.empty()) + if (solution_callback) { for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) { @@ -1024,7 +1024,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik getSolution(solutions, ik_seed_state, s, solution); // This solution is within joint limits, now check if in collision (if callback provided) - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); } diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index fd0a70261e..91760fc02b 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -54,6 +54,7 @@ #include #include #include +#include #ifndef _WIN32 #include #else @@ -1100,7 +1101,7 @@ void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std: filename.append("/"); // Ensure directories exist - boost::filesystem::create_directories(filename); + std::filesystem::create_directories(filename); filename += (options_.getBenchmarkName().empty() ? "" : options_.getBenchmarkName() + "_") + brequest.name + "_" + getHostname() + "_" + start_time + ".log"; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index a647e2e219..4b71a8e9a1 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -105,7 +105,7 @@ class ManipulationPipeline std::vector failed_; std::vector processing_threads_; - boost::condition_variable queue_access_cond_; + std::condition_variable queue_access_cond_; std::mutex queue_access_lock_; std::mutex result_lock_; diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index f0e6bc3b55..30fd775408 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -87,7 +87,7 @@ class PickPlacePlanBase double last_plan_time_; bool done_; bool pushed_all_poses_; - boost::condition_variable done_condition_; + std::condition_variable done_condition_; std::mutex done_mutex_; moveit_msgs::msg::MoveItErrorCodes error_code_; }; diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 32153a8780..219bc82640 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -244,7 +244,7 @@ class OccupancyMapMonitor * * @param[in] update_callback The update callback function */ - void setUpdateCallback(const boost::function& update_callback) + void setUpdateCallback(const std::function& update_callback) { tree_->setUpdateCallback(update_callback); } diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index 03a49567d9..ae9b5dceb3 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -54,7 +54,7 @@ namespace occupancy_map_monitor using ShapeHandle = unsigned int; using ShapeTransformCache = std::map, Eigen::aligned_allocator > >; -using TransformCacheProvider = boost::function; +using TransformCacheProvider = std::function; class OccupancyMapMonitor; diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index ac64d64d24..9e1663ae1a 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -40,6 +40,8 @@ #include #include #include +#include +#include namespace occupancy_map_monitor { @@ -75,16 +77,16 @@ class LazyFreeSpaceUpdater std::deque occupied_cells_sets_; std::deque model_cells_sets_; std::deque sensor_origins_; - boost::condition_variable update_condition_; - boost::mutex update_cell_sets_lock_; + std::condition_variable update_condition_; + std::mutex update_cell_sets_lock_; OcTreeKeyCountMap* process_occupied_cells_set_; octomap::KeySet* process_model_cells_set_; octomap::point3d process_sensor_origin_; - boost::condition_variable process_condition_; - boost::mutex cell_process_lock_; + std::condition_variable process_condition_; + std::mutex cell_process_lock_; - boost::thread update_thread_; - boost::thread process_thread_; + std::thread update_thread_; + std::thread process_thread_; }; } // namespace occupancy_map_monitor diff --git a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp index 503c5610ea..8d63097070 100644 --- a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp +++ b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp @@ -58,11 +58,11 @@ LazyFreeSpaceUpdater::~LazyFreeSpaceUpdater() { running_ = false; { - boost::unique_lock _(update_cell_sets_lock_); + boost::unique_lock _(update_cell_sets_lock_); update_condition_.notify_one(); } { - boost::unique_lock _(cell_process_lock_); + boost::unique_lock _(cell_process_lock_); process_condition_.notify_one(); } update_thread_.join(); @@ -74,7 +74,7 @@ void LazyFreeSpaceUpdater::pushLazyUpdate(octomap::KeySet* occupied_cells, octom { RCLCPP_DEBUG(LOGGER, "Pushing %lu occupied cells and %lu model cells for lazy updating...", (long unsigned int)occupied_cells->size(), (long unsigned int)model_cells->size()); - boost::mutex::scoped_lock _(update_cell_sets_lock_); + std::scoped_lock _(update_cell_sets_lock_); occupied_cells_sets_.push_back(occupied_cells); model_cells_sets_.push_back(model_cells); sensor_origins_.push_back(sensor_origin); @@ -116,7 +116,7 @@ void LazyFreeSpaceUpdater::processThread() free_cells1.clear(); free_cells2.clear(); - boost::unique_lock ulock(cell_process_lock_); + std::unique_lock ulock(cell_process_lock_); while (!process_occupied_cells_set_ && running_) process_condition_.wait(ulock); @@ -207,7 +207,7 @@ void LazyFreeSpaceUpdater::lazyUpdateThread() while (running_) { - boost::unique_lock ulock(update_cell_sets_lock_); + std::unique_lock ulock(update_cell_sets_lock_); while (occupied_cells_sets_.empty() && running_) update_condition_.wait(ulock); diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index e1d81fc713..3f45c7b074 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -61,7 +61,7 @@ class ShapeMask CLIP = 2 }; - typedef boost::function TransformCallback; + typedef std::function TransformCallback; /** \brief Construct the filter */ ShapeMask(const TransformCallback& transform_callback = TransformCallback()); @@ -117,7 +117,7 @@ class ShapeMask TransformCallback transform_callback_; /** \brief Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration. */ - mutable boost::mutex shapes_lock_; + mutable std::mutex shapes_lock_; std::set bodies_; std::vector bspheres_; diff --git a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp index 1b75cefcae..9abd0c300c 100644 --- a/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp +++ b/moveit_ros/perception/point_containment_filter/src/shape_mask.cpp @@ -60,14 +60,14 @@ void point_containment_filter::ShapeMask::freeMemory() void point_containment_filter::ShapeMask::setTransformCallback(const TransformCallback& transform_callback) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); transform_callback_ = transform_callback; } point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addShape(const shapes::ShapeConstPtr& shape, double scale, double padding) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); SeeShape ss; ss.body = bodies::createEmptyBodyFromShapeType(shape->type); if (ss.body) @@ -101,7 +101,7 @@ point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addSh void point_containment_filter::ShapeMask::removeShape(ShapeHandle handle) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); std::map::iterator>::iterator it = used_handles_.find(handle); if (it != used_handles_.end()) { @@ -119,7 +119,7 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::msg const double min_sensor_dist, const double max_sensor_dist, std::vector& mask) { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); const unsigned int np = data_in.data.size() / data_in.point_step; mask.resize(np); @@ -178,7 +178,7 @@ void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::msg int point_containment_filter::ShapeMask::getMaskContainment(const Eigen::Vector3d& pt) const { - boost::mutex::scoped_lock _(shapes_lock_); + std::scoped_lock _(shapes_lock_); int out = OUTSIDE; for (std::set::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it) diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 537fdd3063..5985d2e637 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -61,7 +61,7 @@ class SemanticWorld { public: /** @brief The signature for a callback on receiving table messages*/ - typedef boost::function TableCallbackFn; + typedef std::function TableCallbackFn; /** * @brief A (simple) semantic world representation for pick and place and other tasks. diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index 626e06eb99..a7fd9ed107 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -173,7 +173,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl jmg->getParentModel().getModelFrame(); // just to be sure, do not call the same pluginlib instance allocation function in parallel - boost::mutex::scoped_lock slock(lock_); + std::scoped_lock slock(lock_); for (std::size_t i = 0; !result && i < it->second.size(); ++i) { try @@ -223,7 +223,7 @@ class KinematicsPluginLoader::KinematicsLoaderImpl // second call in JointModelGroup::setSolverAllocators() is to actually retrieve the instance for use kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup* jmg) { - boost::mutex::scoped_lock slock(cache_lock_); + std::scoped_lock slock(cache_lock_); kinematics::KinematicsBasePtr& cached = instances_[jmg]; if (cached.unique()) return std::move(cached); // pass on unique instance @@ -255,8 +255,8 @@ class KinematicsPluginLoader::KinematicsLoaderImpl // of custom-specified tip link(s) std::shared_ptr> kinematics_loader_; std::map instances_; - boost::mutex lock_; - boost::mutex cache_lock_; + std::mutex lock_; + std::mutex cache_lock_; }; void KinematicsPluginLoader::status() const diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index 8fcffd370d..53ef5c223c 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -82,12 +82,12 @@ class PlanExecution /// one is the index of the last trajectory being executed (from the sequence of trajectories specified in the /// ExecutableMotionPlan) and the second /// one is the index of the closest waypoint along that trajectory. - boost::function& trajectory_index)> + std::function& trajectory_index)> repair_plan_callback_; - boost::function before_plan_callback_; - boost::function before_execution_callback_; - boost::function done_callback_; + std::function before_plan_callback_; + std::function before_execution_callback_; + std::function done_callback_; }; PlanExecution(const rclcpp::Node::SharedPtr& node, diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 1b47eeee37..a810571c6f 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -65,7 +65,7 @@ struct ExecutableTrajectory std::string description_; bool trajectory_monitoring_; collision_detection::AllowedCollisionMatrixConstPtr allowed_collision_matrix_; - boost::function effect_on_success_; + std::function effect_on_success_; std::vector controller_names_; }; @@ -85,5 +85,5 @@ struct ExecutableMotionPlan }; /// The signature of a function that can compute a motion plan -using ExecutableMotionPlanComputationFn = boost::function; +using ExecutableMotionPlanComputationFn = std::function; } // namespace plan_execution diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h index d29fbb79ec..d10e15e239 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h @@ -105,7 +105,7 @@ class PlanWithSensing discard_overlapping_cost_sources_ = value; } - void setBeforeLookCallback(const boost::function& callback) + void setBeforeLookCallback(const std::function& callback) { before_look_callback_ = callback; } @@ -129,7 +129,7 @@ class PlanWithSensing bool display_cost_sources_; rclcpp::Publisher::SharedPtr cost_sources_publisher_; - boost::function before_look_callback_; + std::function before_look_callback_; // class DynamicReconfigureImpl; // DynamicReconfigureImpl* reconfigure_impl_; diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index 4aae4144cf..4b0285b5a2 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -122,10 +122,10 @@ int main(int argc, char** argv) states.push_back(moveit::core::RobotStatePtr(state)); } - std::vector threads; + std::vector threads; runCollisionDetection(10, trials, *psm.getPlanningScene(), *states[0]); for (unsigned int i = 0; i < states.size(); ++i) - threads.push_back(new boost::thread([i, trials, &scene = *psm.getPlanningScene(), &state = *states[i]] { + threads.push_back(new std::thread([i, trials, &scene = *psm.getPlanningScene(), &state = *states[i]] { return runCollisionDetection(i, trials, scene, state); })); diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 8a67220ef0..d2724c8c5d 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -378,7 +378,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: void stopWorldGeometryMonitor(); /** @brief Add a function to be called when an update to the scene is received */ - void addUpdateCallback(const boost::function& fn); + void addUpdateCallback(const std::function& fn); /** @brief Clear the functions to be called when an update to the scene is received */ void clearUpdateCallbacks(); @@ -476,7 +476,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: planning_scene::PlanningScenePtr scene_; planning_scene::PlanningSceneConstPtr scene_const_; planning_scene::PlanningScenePtr parent_scene_; /// if diffs are monitored, this is the pointer to the parent scene - boost::shared_mutex scene_update_mutex_; /// mutex for stored scene + std::shared_mutex scene_update_mutex_; /// mutex for stored scene rclcpp::Time last_update_time_; /// Last time the state was updated rclcpp::Time last_robot_motion_time_; /// Last time the robot has moved @@ -509,11 +509,11 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: // variables for planning scene publishing rclcpp::Publisher::SharedPtr planning_scene_publisher_; - std::unique_ptr publish_planning_scene_; + std::unique_ptr publish_planning_scene_; double publish_planning_scene_frequency_; SceneUpdateType publish_update_types_; std::atomic new_scene_update_; - boost::condition_variable_any new_scene_update_condition_; + std::condition_variable_any new_scene_update_condition_; // subscribe to various sources of data rclcpp::Subscription::SharedPtr planning_scene_subscriber_; @@ -543,11 +543,11 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: LinkShapeHandles link_shape_handles_; AttachedBodyShapeHandles attached_body_shape_handles_; CollisionBodyShapeHandles collision_body_shape_handles_; - mutable boost::recursive_mutex shape_handles_lock_; + mutable std::recursive_mutex shape_handles_lock_; /// lock access to update_callbacks_ - boost::recursive_mutex update_lock_; - std::vector > update_callbacks_; /// List of callbacks to trigger when updates + std::recursive_mutex update_lock_; + std::vector > update_callbacks_; /// List of callbacks to trigger when updates /// are received private: diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index b870ae7d70..f5afa3f512 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -138,7 +138,7 @@ class TrajectoryMonitor rclcpp::Time trajectory_start_time_; rclcpp::Time last_recorded_state_time_; - std::unique_ptr record_states_thread_; + std::unique_ptr record_states_thread_; TrajectoryStateAddedCallback state_add_callback_; }; } // namespace planning_scene_monitor diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index d7181f8e72..60b1276243 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -437,7 +437,7 @@ void PlanningSceneMonitor::scenePublishingThread() msg.robot_state.is_diff = true; } } - std::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the + std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the // transform cache to // update while we are // potentially changing @@ -527,7 +527,7 @@ bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConst void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type) { // do not modify update functions while we are calling them - std::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); for (std::function& update_callback : update_callbacks_) update_callback(update_type); @@ -666,7 +666,7 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann { std::unique_lock ulock(scene_update_mutex_); // we don't want the transform cache to update while we are potentially changing attached bodies - std::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); + std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); last_update_time_ = rclcpp::Clock().now(); last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp; @@ -794,7 +794,7 @@ void PlanningSceneMonitor::excludeRobotLinksFromOctree() if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); includeRobotLinksInOctree(); const std::vector& links = getRobotModel()->getLinkModelsWithCollisionGeometry(); @@ -831,7 +831,7 @@ void PlanningSceneMonitor::includeRobotLinksInOctree() if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); for (std::pair>>& link_shape_handle : @@ -846,7 +846,7 @@ void PlanningSceneMonitor::includeAttachedBodiesInOctree() if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); // clear information about any attached body, without referring to the AttachedBody* ptr (could be invalid) for (std::pair>>& @@ -887,7 +887,7 @@ void PlanningSceneMonitor::includeWorldObjectsInOctree() void PlanningSceneMonitor::excludeWorldObjectsFromOctree() { - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); includeWorldObjectsInOctree(); for (const std::pair& it : *scene_->getWorld()) @@ -899,7 +899,7 @@ void PlanningSceneMonitor::excludeAttachedBodyFromOctree(const moveit::core::Att if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i) { @@ -921,7 +921,7 @@ void PlanningSceneMonitor::includeAttachedBodyInOctree(const moveit::core::Attac if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body); if (it != attached_body_shape_handles_.end()) @@ -938,7 +938,7 @@ void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detectio if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); bool found = false; for (std::size_t i = 0; i < obj->shapes_.size(); ++i) @@ -961,7 +961,7 @@ void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection: if (!octomap_monitor_) return; - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_); if (it != collision_body_shape_handles_.end()) @@ -1116,7 +1116,7 @@ bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_fram { try { - std::recursive_mutex::scoped_lock _(shape_handles_lock_); + std::scoped_lock _(shape_handles_lock_); for (const std::pair>>& link_shape_handle : @@ -1427,14 +1427,14 @@ void PlanningSceneMonitor::updateSceneWithCurrentState() void PlanningSceneMonitor::addUpdateCallback(const std::function& fn) { - std::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); if (fn) update_callbacks_.push_back(fn); } void PlanningSceneMonitor::clearUpdateCallbacks() { - std::recursive_mutex::scoped_lock lock(update_lock_); + std::scoped_lock lock(update_lock_); update_callbacks_.clear(); } diff --git a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp index 8d423b15b9..5242bf54a0 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp +++ b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp @@ -88,8 +88,8 @@ struct InitProxy static void roscpp_init_or_stop(bool init) { // ensure we do not accidentally initialize ROS multiple times per process - static boost::mutex lock; - boost::mutex::scoped_lock slock(lock); + static std::mutex lock; + std::mutex::scoped_lock slock(lock); // once per process, we start a spinner static bool once = true; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 62cfe88fe8..79ee5dded8 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -199,7 +199,7 @@ class RobotInteraction std::unique_ptr processing_thread_; bool run_processing_thread_; - boost::condition_variable new_feedback_condition_; + std::condition_variable new_feedback_condition_; std::map feedback_map_; moveit::core::RobotModelConstPtr robot_model_; diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 180c61fdc1..7252672ca6 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -559,7 +559,7 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce boost::thread_group bgroup; // create a group of threads std::mutex lock; // used for sharing the same data structures - int num_threads = boost::thread::hardware_concurrency(); // how many cores does this computer have? + int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have? // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " << // num_threads << " threads..."); From 90f9e0033b3b291050e38ae44da385fad1d84e2b Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 8 Jun 2022 16:56:19 -0600 Subject: [PATCH 04/43] got everything to build and fixed locked robot state test --- .../robot_interaction/test/locked_robot_state_test.cpp | 2 +- .../src/motion_planning_display.cpp | 2 +- .../planning_scene_rviz_plugin/background_processing.hpp | 2 ++ moveit_setup_assistant/src/tools/moveit_config_data.cpp | 7 ++++--- 4 files changed, 8 insertions(+), 5 deletions(-) diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index 1f467d5437..254c87744c 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -533,8 +533,8 @@ static void runThreads(int ncheck, int nset, int nmod) for (int i = 0; i < p; ++i) { threads[i]->join(); - wthread.join(); } + wthread.join(); // clean up for (int i = 0; i < p; ++i) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index 19d4c6e32d..39ac0c0613 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -482,7 +482,7 @@ void MotionPlanningDisplay::computeMetrics(bool start, const std::string& group, const std::vector& eef = robot_interaction_->getActiveEndEffectors(); if (eef.empty()) return; - std::mutex::scoped_lock slock(update_metrics_lock_); + std::scoped_lock slock(update_metrics_lock_); moveit::core::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState(); for (const robot_interaction::EndEffectorInteraction& ee : eef) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp index f1de5cc56c..3f056371f5 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp @@ -42,6 +42,8 @@ #include #include #include +#include +#include namespace moveit { diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 19d106bbc1..238b1fde9b 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -43,6 +43,7 @@ #include #include #include +#include // ROS #include @@ -1604,11 +1605,11 @@ bool MoveItConfigData::extractPackageNameFromPath(const std::string& path, std:: RCLCPP_DEBUG_STREAM(LOGGER, "Found package.xml in " << sub_path.make_preferred().string()); package_found = true; relative_filepath = relative_path.string(); - package_name = sub_path.leaf().string(); + package_name = sub_path.filename(); break; } - relative_path = sub_path.leaf() / relative_path; - sub_path.remove_leaf(); + relative_path = sub_path.filename() / relative_path; + sub_path.remove_filename(); } // Assign data to moveit_config_data From 245cad5566af4ee0e367028773ac73d3974e3a67 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 8 Jun 2022 16:58:33 -0600 Subject: [PATCH 05/43] made thread joining safer --- moveit_ros/robot_interaction/test/locked_robot_state_test.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index 254c87744c..608f648456 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -532,9 +532,9 @@ static void runThreads(int ncheck, int nset, int nmod) // wait for all threads to finish for (int i = 0; i < p; ++i) { - threads[i]->join(); + if (threads[i]->joinable()) {threads[i]->join();} } - wthread.join(); + if (wthread.joinable()) {wthread.join();} // clean up for (int i = 0; i < p; ++i) From 05ebbb65ec6faf68e9d9fec0fde59a4cdbe1e501 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 9 Jun 2022 14:39:35 -0600 Subject: [PATCH 06/43] remove install and log --- install/.colcon_install_layout | 1 - install/COLCON_IGNORE | 0 install/_local_setup_util_ps1.py | 404 ---- install/_local_setup_util_sh.py | 404 ---- install/local_setup.bash | 107 - install/local_setup.ps1 | 55 - install/local_setup.sh | 137 -- install/local_setup.zsh | 120 - .../package_run_dependencies/moveit_common | 1 - .../resource_index/packages/moveit_common | 0 .../parent_prefix_path/moveit_common | 1 - .../share/colcon-core/packages/moveit_common | 1 - .../cmake/moveit_common-extras.cmake | 30 - .../cmake/moveit_commonConfig-version.cmake | 14 - .../cmake/moveit_commonConfig.cmake | 42 - .../moveit_common/cmake/moveit_package.cmake | 81 - .../environment/ament_prefix_path.dsv | 1 - .../environment/ament_prefix_path.sh | 4 - .../share/moveit_common/environment/path.dsv | 1 - .../share/moveit_common/environment/path.sh | 5 - .../moveit_common/hook/cmake_prefix_path.dsv | 1 - .../moveit_common/hook/cmake_prefix_path.ps1 | 3 - .../moveit_common/hook/cmake_prefix_path.sh | 3 - .../share/moveit_common/local_setup.bash | 46 - .../share/moveit_common/local_setup.dsv | 2 - .../share/moveit_common/local_setup.sh | 184 -- .../share/moveit_common/local_setup.zsh | 59 - .../share/moveit_common/package.bash | 39 - .../share/moveit_common/package.dsv | 8 - .../share/moveit_common/package.ps1 | 116 - .../share/moveit_common/package.sh | 87 - .../share/moveit_common/package.xml | 29 - .../share/moveit_common/package.zsh | 50 - .../packages/moveit_configs_utils | 0 .../colcon-core/packages/moveit_configs_utils | 1 - .../default_configs/chomp_planning.yaml | 12 - .../default_configs/ompl_defaults.yaml | 129 -- .../default_configs/ompl_planning.yaml | 10 - ...lz_industrial_motion_planner_planning.yaml | 6 - .../default_configs/trajopt_planning.yaml | 9 - .../hook/ament_prefix_path.dsv | 1 - .../hook/ament_prefix_path.ps1 | 3 - .../hook/ament_prefix_path.sh | 3 - .../moveit_configs_utils/hook/pythonpath.dsv | 1 - .../moveit_configs_utils/hook/pythonpath.ps1 | 3 - .../moveit_configs_utils/hook/pythonpath.sh | 3 - .../share/moveit_configs_utils/package.bash | 31 - .../share/moveit_configs_utils/package.dsv | 6 - .../share/moveit_configs_utils/package.ps1 | 116 - .../share/moveit_configs_utils/package.sh | 87 - .../share/moveit_configs_utils/package.xml | 24 - .../share/moveit_configs_utils/package.zsh | 42 - .../share/colcon-core/packages/moveit_core | 1 - .../share/moveit_core/package.bash | 31 - .../moveit_core/share/moveit_core/package.dsv | 0 .../moveit_core/share/moveit_core/package.ps1 | 108 - .../moveit_core/share/moveit_core/package.sh | 52 - .../moveit_core/share/moveit_core/package.zsh | 42 - .../moveit_resources_prbt_support | 1 - .../packages/moveit_resources_prbt_support | 0 .../moveit_resources_prbt_support | 1 - .../packages/moveit_resources_prbt_support | 1 - ...resources_prbt_supportConfig-version.cmake | 14 - .../moveit_resources_prbt_supportConfig.cmake | 42 - .../config/manipulator_controller.yaml | 77 - .../config/manipulator_driver.yaml | 52 - .../config/prbt_0_1.dcf | 2052 ----------------- .../environment/ament_prefix_path.dsv | 1 - .../environment/ament_prefix_path.sh | 4 - .../environment/path.dsv | 1 - .../environment/path.sh | 5 - .../hook/cmake_prefix_path.dsv | 1 - .../hook/cmake_prefix_path.ps1 | 3 - .../hook/cmake_prefix_path.sh | 3 - .../local_setup.bash | 46 - .../local_setup.dsv | 2 - .../local_setup.sh | 184 -- .../local_setup.zsh | 59 - .../meshes/flange.dae | 109 - .../meshes/flange.stl | Bin 2284 -> 0 bytes .../meshes/foot.dae | 145 -- .../meshes/foot.stl | Bin 6284 -> 0 bytes .../meshes/link_1.dae | 109 - .../meshes/link_1.stl | Bin 17884 -> 0 bytes .../meshes/link_2.dae | 181 -- .../meshes/link_2.stl | Bin 4284 -> 0 bytes .../meshes/link_3.dae | 109 - .../meshes/link_3.stl | Bin 18184 -> 0 bytes .../meshes/link_4.dae | 145 -- .../meshes/link_4.stl | Bin 6884 -> 0 bytes .../meshes/link_5.dae | 109 - .../meshes/link_5.stl | Bin 10284 -> 0 bytes .../package.bash | 39 - .../moveit_resources_prbt_support/package.dsv | 8 - .../moveit_resources_prbt_support/package.ps1 | 116 - .../moveit_resources_prbt_support/package.sh | 87 - .../moveit_resources_prbt_support/package.xml | 25 - .../moveit_resources_prbt_support/package.zsh | 50 - .../urdf/prbt.ros2_control.xacro | 101 - .../urdf/prbt.xacro | 73 - .../urdf/prbt_macro.xacro | 465 ---- .../urdf/simple_gripper_brackets.urdf.xacro | 94 - install/setup.bash | 31 - install/setup.ps1 | 29 - install/setup.sh | 45 - install/setup.zsh | 31 - log/COLCON_IGNORE | 0 log/build_2022-06-08_12-52-32/events.log | 313 --- log/build_2022-06-08_12-52-32/logger_all.log | 986 -------- .../moveit_common/command.log | 6 - .../moveit_common/stderr.log | 0 .../moveit_common/stdout.log | 28 - .../moveit_common/stdout_stderr.log | 28 - .../moveit_common/streams.log | 34 - .../moveit_configs_utils/command.log | 2 - .../moveit_configs_utils/stderr.log | 2 - .../moveit_configs_utils/stdout.log | 46 - .../moveit_configs_utils/stdout_stderr.log | 48 - .../moveit_configs_utils/streams.log | 50 - .../moveit_core/command.log | 2 - .../moveit_core/stderr.log | 17 - .../moveit_core/stdout.log | 47 - .../moveit_core/stdout_stderr.log | 64 - .../moveit_core/streams.log | 66 - .../moveit_resources_prbt_support/command.log | 6 - .../moveit_resources_prbt_support/stderr.log | 0 .../moveit_resources_prbt_support/stdout.log | 57 - .../stdout_stderr.log | 57 - .../moveit_resources_prbt_support/streams.log | 63 - log/latest | 1 - log/latest_build | 1 - 131 files changed, 9331 deletions(-) delete mode 100644 install/.colcon_install_layout delete mode 100644 install/COLCON_IGNORE delete mode 100644 install/_local_setup_util_ps1.py delete mode 100644 install/_local_setup_util_sh.py delete mode 100644 install/local_setup.bash delete mode 100644 install/local_setup.ps1 delete mode 100644 install/local_setup.sh delete mode 100644 install/local_setup.zsh delete mode 100644 install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common delete mode 100644 install/moveit_common/share/ament_index/resource_index/packages/moveit_common delete mode 100644 install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common delete mode 100644 install/moveit_common/share/colcon-core/packages/moveit_common delete mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake delete mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake delete mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake delete mode 100644 install/moveit_common/share/moveit_common/cmake/moveit_package.cmake delete mode 100644 install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv delete mode 100644 install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh delete mode 100644 install/moveit_common/share/moveit_common/environment/path.dsv delete mode 100644 install/moveit_common/share/moveit_common/environment/path.sh delete mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv delete mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 delete mode 100644 install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh delete mode 100644 install/moveit_common/share/moveit_common/local_setup.bash delete mode 100644 install/moveit_common/share/moveit_common/local_setup.dsv delete mode 100644 install/moveit_common/share/moveit_common/local_setup.sh delete mode 100644 install/moveit_common/share/moveit_common/local_setup.zsh delete mode 100644 install/moveit_common/share/moveit_common/package.bash delete mode 100644 install/moveit_common/share/moveit_common/package.dsv delete mode 100644 install/moveit_common/share/moveit_common/package.ps1 delete mode 100644 install/moveit_common/share/moveit_common/package.sh delete mode 100644 install/moveit_common/share/moveit_common/package.xml delete mode 100644 install/moveit_common/share/moveit_common/package.zsh delete mode 100644 install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils delete mode 100644 install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.bash delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.dsv delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.sh delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.xml delete mode 100644 install/moveit_configs_utils/share/moveit_configs_utils/package.zsh delete mode 100644 install/moveit_core/share/colcon-core/packages/moveit_core delete mode 100644 install/moveit_core/share/moveit_core/package.bash delete mode 100644 install/moveit_core/share/moveit_core/package.dsv delete mode 100644 install/moveit_core/share/moveit_core/package.ps1 delete mode 100644 install/moveit_core/share/moveit_core/package.sh delete mode 100644 install/moveit_core/share/moveit_core/package.zsh delete mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support delete mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support delete mode 100644 install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support delete mode 100644 install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro delete mode 100644 install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro delete mode 100644 install/setup.bash delete mode 100644 install/setup.ps1 delete mode 100644 install/setup.sh delete mode 100644 install/setup.zsh delete mode 100644 log/COLCON_IGNORE delete mode 100644 log/build_2022-06-08_12-52-32/events.log delete mode 100644 log/build_2022-06-08_12-52-32/logger_all.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_common/command.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stdout.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_common/streams.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_core/command.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stdout.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_core/streams.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log delete mode 100644 log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log delete mode 120000 log/latest delete mode 120000 log/latest_build diff --git a/install/.colcon_install_layout b/install/.colcon_install_layout deleted file mode 100644 index 3aad5336af..0000000000 --- a/install/.colcon_install_layout +++ /dev/null @@ -1 +0,0 @@ -isolated diff --git a/install/COLCON_IGNORE b/install/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/install/_local_setup_util_ps1.py b/install/_local_setup_util_ps1.py deleted file mode 100644 index 98348eebcf..0000000000 --- a/install/_local_setup_util_ps1.py +++ /dev/null @@ -1,404 +0,0 @@ -# Copyright 2016-2019 Dirk Thomas -# Licensed under the Apache License, Version 2.0 - -import argparse -from collections import OrderedDict -import os -from pathlib import Path -import sys - - -FORMAT_STR_COMMENT_LINE = '# {comment}' -FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"' -FORMAT_STR_USE_ENV_VAR = '$env:{name}' -FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"' -FORMAT_STR_REMOVE_LEADING_SEPARATOR = '' -FORMAT_STR_REMOVE_TRAILING_SEPARATOR = '' - -DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate' -DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate' -DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists' -DSV_TYPE_SET = 'set' -DSV_TYPE_SET_IF_UNSET = 'set-if-unset' -DSV_TYPE_SOURCE = 'source' - - -def main(argv=sys.argv[1:]): # noqa: D103 - parser = argparse.ArgumentParser( - description='Output shell commands for the packages in topological ' - 'order') - parser.add_argument( - 'primary_extension', - help='The file extension of the primary shell') - parser.add_argument( - 'additional_extension', nargs='?', - help='The additional file extension to be considered') - parser.add_argument( - '--merged-install', action='store_true', - help='All install prefixes are merged into a single location') - args = parser.parse_args(argv) - - packages = get_packages(Path(__file__).parent, args.merged_install) - - ordered_packages = order_packages(packages) - for pkg_name in ordered_packages: - if _include_comments(): - print( - FORMAT_STR_COMMENT_LINE.format_map( - {'comment': 'Package: ' + pkg_name})) - prefix = os.path.abspath(os.path.dirname(__file__)) - if not args.merged_install: - prefix = os.path.join(prefix, pkg_name) - for line in get_commands( - pkg_name, prefix, args.primary_extension, - args.additional_extension - ): - print(line) - - for line in _remove_ending_separators(): - print(line) - - -def get_packages(prefix_path, merged_install): - """ - Find packages based on colcon-specific files created during installation. - - :param Path prefix_path: The install prefix path of all packages - :param bool merged_install: The flag if the packages are all installed - directly in the prefix or if each package is installed in a subdirectory - named after the package - :returns: A mapping from the package name to the set of runtime - dependencies - :rtype: dict - """ - packages = {} - # since importing colcon_core isn't feasible here the following constant - # must match colcon_core.location.get_relative_package_index_path() - subdirectory = 'share/colcon-core/packages' - if merged_install: - # return if workspace is empty - if not (prefix_path / subdirectory).is_dir(): - return packages - # find all files in the subdirectory - for p in (prefix_path / subdirectory).iterdir(): - if not p.is_file(): - continue - if p.name.startswith('.'): - continue - add_package_runtime_dependencies(p, packages) - else: - # for each subdirectory look for the package specific file - for p in prefix_path.iterdir(): - if not p.is_dir(): - continue - if p.name.startswith('.'): - continue - p = p / subdirectory / p.name - if p.is_file(): - add_package_runtime_dependencies(p, packages) - - # remove unknown dependencies - pkg_names = set(packages.keys()) - for k in packages.keys(): - packages[k] = {d for d in packages[k] if d in pkg_names} - - return packages - - -def add_package_runtime_dependencies(path, packages): - """ - Check the path and if it exists extract the packages runtime dependencies. - - :param Path path: The resource file containing the runtime dependencies - :param dict packages: A mapping from package names to the sets of runtime - dependencies to add to - """ - content = path.read_text() - dependencies = set(content.split(os.pathsep) if content else []) - packages[path.name] = dependencies - - -def order_packages(packages): - """ - Order packages topologically. - - :param dict packages: A mapping from package name to the set of runtime - dependencies - :returns: The package names - :rtype: list - """ - # select packages with no dependencies in alphabetical order - to_be_ordered = list(packages.keys()) - ordered = [] - while to_be_ordered: - pkg_names_without_deps = [ - name for name in to_be_ordered if not packages[name]] - if not pkg_names_without_deps: - reduce_cycle_set(packages) - raise RuntimeError( - 'Circular dependency between: ' + ', '.join(sorted(packages))) - pkg_names_without_deps.sort() - pkg_name = pkg_names_without_deps[0] - to_be_ordered.remove(pkg_name) - ordered.append(pkg_name) - # remove item from dependency lists - for k in list(packages.keys()): - if pkg_name in packages[k]: - packages[k].remove(pkg_name) - return ordered - - -def reduce_cycle_set(packages): - """ - Reduce the set of packages to the ones part of the circular dependency. - - :param dict packages: A mapping from package name to the set of runtime - dependencies which is modified in place - """ - last_depended = None - while len(packages) > 0: - # get all remaining dependencies - depended = set() - for pkg_name, dependencies in packages.items(): - depended = depended.union(dependencies) - # remove all packages which are not dependent on - for name in list(packages.keys()): - if name not in depended: - del packages[name] - if last_depended: - # if remaining packages haven't changed return them - if last_depended == depended: - return packages.keys() - # otherwise reduce again - last_depended = depended - - -def _include_comments(): - # skipping comment lines when COLCON_TRACE is not set speeds up the - # processing especially on Windows - return bool(os.environ.get('COLCON_TRACE')) - - -def get_commands(pkg_name, prefix, primary_extension, additional_extension): - commands = [] - package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv') - if os.path.exists(package_dsv_path): - commands += process_dsv_file( - package_dsv_path, prefix, primary_extension, additional_extension) - return commands - - -def process_dsv_file( - dsv_path, prefix, primary_extension=None, additional_extension=None -): - commands = [] - if _include_comments(): - commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path})) - with open(dsv_path, 'r') as h: - content = h.read() - lines = content.splitlines() - - basenames = OrderedDict() - for i, line in enumerate(lines): - # skip over empty or whitespace-only lines - if not line.strip(): - continue - try: - type_, remainder = line.split(';', 1) - except ValueError: - raise RuntimeError( - "Line %d in '%s' doesn't contain a semicolon separating the " - 'type from the arguments' % (i + 1, dsv_path)) - if type_ != DSV_TYPE_SOURCE: - # handle non-source lines - try: - commands += handle_dsv_types_except_source( - type_, remainder, prefix) - except RuntimeError as e: - raise RuntimeError( - "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e - else: - # group remaining source lines by basename - path_without_ext, ext = os.path.splitext(remainder) - if path_without_ext not in basenames: - basenames[path_without_ext] = set() - assert ext.startswith('.') - ext = ext[1:] - if ext in (primary_extension, additional_extension): - basenames[path_without_ext].add(ext) - - # add the dsv extension to each basename if the file exists - for basename, extensions in basenames.items(): - if not os.path.isabs(basename): - basename = os.path.join(prefix, basename) - if os.path.exists(basename + '.dsv'): - extensions.add('dsv') - - for basename, extensions in basenames.items(): - if not os.path.isabs(basename): - basename = os.path.join(prefix, basename) - if 'dsv' in extensions: - # process dsv files recursively - commands += process_dsv_file( - basename + '.dsv', prefix, primary_extension=primary_extension, - additional_extension=additional_extension) - elif primary_extension in extensions and len(extensions) == 1: - # source primary-only files - commands += [ - FORMAT_STR_INVOKE_SCRIPT.format_map({ - 'prefix': prefix, - 'script_path': basename + '.' + primary_extension})] - elif additional_extension in extensions: - # source non-primary files - commands += [ - FORMAT_STR_INVOKE_SCRIPT.format_map({ - 'prefix': prefix, - 'script_path': basename + '.' + additional_extension})] - - return commands - - -def handle_dsv_types_except_source(type_, remainder, prefix): - commands = [] - if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET): - try: - env_name, value = remainder.split(';', 1) - except ValueError: - raise RuntimeError( - "doesn't contain a semicolon separating the environment name " - 'from the value') - try_prefixed_value = os.path.join(prefix, value) if value else prefix - if os.path.exists(try_prefixed_value): - value = try_prefixed_value - if type_ == DSV_TYPE_SET: - commands += _set(env_name, value) - elif type_ == DSV_TYPE_SET_IF_UNSET: - commands += _set_if_unset(env_name, value) - else: - assert False - elif type_ in ( - DSV_TYPE_APPEND_NON_DUPLICATE, - DSV_TYPE_PREPEND_NON_DUPLICATE, - DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS - ): - try: - env_name_and_values = remainder.split(';') - except ValueError: - raise RuntimeError( - "doesn't contain a semicolon separating the environment name " - 'from the values') - env_name = env_name_and_values[0] - values = env_name_and_values[1:] - for value in values: - if not value: - value = prefix - elif not os.path.isabs(value): - value = os.path.join(prefix, value) - if ( - type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and - not os.path.exists(value) - ): - comment = f'skip extending {env_name} with not existing ' \ - f'path: {value}' - if _include_comments(): - commands.append( - FORMAT_STR_COMMENT_LINE.format_map({'comment': comment})) - elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE: - commands += _append_unique_value(env_name, value) - else: - commands += _prepend_unique_value(env_name, value) - else: - raise RuntimeError( - 'contains an unknown environment hook type: ' + type_) - return commands - - -env_state = {} - - -def _append_unique_value(name, value): - global env_state - if name not in env_state: - if os.environ.get(name): - env_state[name] = set(os.environ[name].split(os.pathsep)) - else: - env_state[name] = set() - # append even if the variable has not been set yet, in case a shell script sets the - # same variable without the knowledge of this Python script. - # later _remove_ending_separators() will cleanup any unintentional leading separator - extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': extend + value}) - if value not in env_state[name]: - env_state[name].add(value) - else: - if not _include_comments(): - return [] - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -def _prepend_unique_value(name, value): - global env_state - if name not in env_state: - if os.environ.get(name): - env_state[name] = set(os.environ[name].split(os.pathsep)) - else: - env_state[name] = set() - # prepend even if the variable has not been set yet, in case a shell script sets the - # same variable without the knowledge of this Python script. - # later _remove_ending_separators() will cleanup any unintentional trailing separator - extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value + extend}) - if value not in env_state[name]: - env_state[name].add(value) - else: - if not _include_comments(): - return [] - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -# generate commands for removing prepended underscores -def _remove_ending_separators(): - # do nothing if the shell extension does not implement the logic - if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None: - return [] - - global env_state - commands = [] - for name in env_state: - # skip variables that already had values before this script started prepending - if name in os.environ: - continue - commands += [ - FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}), - FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})] - return commands - - -def _set(name, value): - global env_state - env_state[name] = value - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value}) - return [line] - - -def _set_if_unset(name, value): - global env_state - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value}) - if env_state.get(name, os.environ.get(name)): - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -if __name__ == '__main__': # pragma: no cover - try: - rc = main() - except RuntimeError as e: - print(str(e), file=sys.stderr) - rc = 1 - sys.exit(rc) diff --git a/install/_local_setup_util_sh.py b/install/_local_setup_util_sh.py deleted file mode 100644 index 35c017b255..0000000000 --- a/install/_local_setup_util_sh.py +++ /dev/null @@ -1,404 +0,0 @@ -# Copyright 2016-2019 Dirk Thomas -# Licensed under the Apache License, Version 2.0 - -import argparse -from collections import OrderedDict -import os -from pathlib import Path -import sys - - -FORMAT_STR_COMMENT_LINE = '# {comment}' -FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"' -FORMAT_STR_USE_ENV_VAR = '${name}' -FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"' -FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi' -FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi' - -DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate' -DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate' -DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists' -DSV_TYPE_SET = 'set' -DSV_TYPE_SET_IF_UNSET = 'set-if-unset' -DSV_TYPE_SOURCE = 'source' - - -def main(argv=sys.argv[1:]): # noqa: D103 - parser = argparse.ArgumentParser( - description='Output shell commands for the packages in topological ' - 'order') - parser.add_argument( - 'primary_extension', - help='The file extension of the primary shell') - parser.add_argument( - 'additional_extension', nargs='?', - help='The additional file extension to be considered') - parser.add_argument( - '--merged-install', action='store_true', - help='All install prefixes are merged into a single location') - args = parser.parse_args(argv) - - packages = get_packages(Path(__file__).parent, args.merged_install) - - ordered_packages = order_packages(packages) - for pkg_name in ordered_packages: - if _include_comments(): - print( - FORMAT_STR_COMMENT_LINE.format_map( - {'comment': 'Package: ' + pkg_name})) - prefix = os.path.abspath(os.path.dirname(__file__)) - if not args.merged_install: - prefix = os.path.join(prefix, pkg_name) - for line in get_commands( - pkg_name, prefix, args.primary_extension, - args.additional_extension - ): - print(line) - - for line in _remove_ending_separators(): - print(line) - - -def get_packages(prefix_path, merged_install): - """ - Find packages based on colcon-specific files created during installation. - - :param Path prefix_path: The install prefix path of all packages - :param bool merged_install: The flag if the packages are all installed - directly in the prefix or if each package is installed in a subdirectory - named after the package - :returns: A mapping from the package name to the set of runtime - dependencies - :rtype: dict - """ - packages = {} - # since importing colcon_core isn't feasible here the following constant - # must match colcon_core.location.get_relative_package_index_path() - subdirectory = 'share/colcon-core/packages' - if merged_install: - # return if workspace is empty - if not (prefix_path / subdirectory).is_dir(): - return packages - # find all files in the subdirectory - for p in (prefix_path / subdirectory).iterdir(): - if not p.is_file(): - continue - if p.name.startswith('.'): - continue - add_package_runtime_dependencies(p, packages) - else: - # for each subdirectory look for the package specific file - for p in prefix_path.iterdir(): - if not p.is_dir(): - continue - if p.name.startswith('.'): - continue - p = p / subdirectory / p.name - if p.is_file(): - add_package_runtime_dependencies(p, packages) - - # remove unknown dependencies - pkg_names = set(packages.keys()) - for k in packages.keys(): - packages[k] = {d for d in packages[k] if d in pkg_names} - - return packages - - -def add_package_runtime_dependencies(path, packages): - """ - Check the path and if it exists extract the packages runtime dependencies. - - :param Path path: The resource file containing the runtime dependencies - :param dict packages: A mapping from package names to the sets of runtime - dependencies to add to - """ - content = path.read_text() - dependencies = set(content.split(os.pathsep) if content else []) - packages[path.name] = dependencies - - -def order_packages(packages): - """ - Order packages topologically. - - :param dict packages: A mapping from package name to the set of runtime - dependencies - :returns: The package names - :rtype: list - """ - # select packages with no dependencies in alphabetical order - to_be_ordered = list(packages.keys()) - ordered = [] - while to_be_ordered: - pkg_names_without_deps = [ - name for name in to_be_ordered if not packages[name]] - if not pkg_names_without_deps: - reduce_cycle_set(packages) - raise RuntimeError( - 'Circular dependency between: ' + ', '.join(sorted(packages))) - pkg_names_without_deps.sort() - pkg_name = pkg_names_without_deps[0] - to_be_ordered.remove(pkg_name) - ordered.append(pkg_name) - # remove item from dependency lists - for k in list(packages.keys()): - if pkg_name in packages[k]: - packages[k].remove(pkg_name) - return ordered - - -def reduce_cycle_set(packages): - """ - Reduce the set of packages to the ones part of the circular dependency. - - :param dict packages: A mapping from package name to the set of runtime - dependencies which is modified in place - """ - last_depended = None - while len(packages) > 0: - # get all remaining dependencies - depended = set() - for pkg_name, dependencies in packages.items(): - depended = depended.union(dependencies) - # remove all packages which are not dependent on - for name in list(packages.keys()): - if name not in depended: - del packages[name] - if last_depended: - # if remaining packages haven't changed return them - if last_depended == depended: - return packages.keys() - # otherwise reduce again - last_depended = depended - - -def _include_comments(): - # skipping comment lines when COLCON_TRACE is not set speeds up the - # processing especially on Windows - return bool(os.environ.get('COLCON_TRACE')) - - -def get_commands(pkg_name, prefix, primary_extension, additional_extension): - commands = [] - package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv') - if os.path.exists(package_dsv_path): - commands += process_dsv_file( - package_dsv_path, prefix, primary_extension, additional_extension) - return commands - - -def process_dsv_file( - dsv_path, prefix, primary_extension=None, additional_extension=None -): - commands = [] - if _include_comments(): - commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path})) - with open(dsv_path, 'r') as h: - content = h.read() - lines = content.splitlines() - - basenames = OrderedDict() - for i, line in enumerate(lines): - # skip over empty or whitespace-only lines - if not line.strip(): - continue - try: - type_, remainder = line.split(';', 1) - except ValueError: - raise RuntimeError( - "Line %d in '%s' doesn't contain a semicolon separating the " - 'type from the arguments' % (i + 1, dsv_path)) - if type_ != DSV_TYPE_SOURCE: - # handle non-source lines - try: - commands += handle_dsv_types_except_source( - type_, remainder, prefix) - except RuntimeError as e: - raise RuntimeError( - "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e - else: - # group remaining source lines by basename - path_without_ext, ext = os.path.splitext(remainder) - if path_without_ext not in basenames: - basenames[path_without_ext] = set() - assert ext.startswith('.') - ext = ext[1:] - if ext in (primary_extension, additional_extension): - basenames[path_without_ext].add(ext) - - # add the dsv extension to each basename if the file exists - for basename, extensions in basenames.items(): - if not os.path.isabs(basename): - basename = os.path.join(prefix, basename) - if os.path.exists(basename + '.dsv'): - extensions.add('dsv') - - for basename, extensions in basenames.items(): - if not os.path.isabs(basename): - basename = os.path.join(prefix, basename) - if 'dsv' in extensions: - # process dsv files recursively - commands += process_dsv_file( - basename + '.dsv', prefix, primary_extension=primary_extension, - additional_extension=additional_extension) - elif primary_extension in extensions and len(extensions) == 1: - # source primary-only files - commands += [ - FORMAT_STR_INVOKE_SCRIPT.format_map({ - 'prefix': prefix, - 'script_path': basename + '.' + primary_extension})] - elif additional_extension in extensions: - # source non-primary files - commands += [ - FORMAT_STR_INVOKE_SCRIPT.format_map({ - 'prefix': prefix, - 'script_path': basename + '.' + additional_extension})] - - return commands - - -def handle_dsv_types_except_source(type_, remainder, prefix): - commands = [] - if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET): - try: - env_name, value = remainder.split(';', 1) - except ValueError: - raise RuntimeError( - "doesn't contain a semicolon separating the environment name " - 'from the value') - try_prefixed_value = os.path.join(prefix, value) if value else prefix - if os.path.exists(try_prefixed_value): - value = try_prefixed_value - if type_ == DSV_TYPE_SET: - commands += _set(env_name, value) - elif type_ == DSV_TYPE_SET_IF_UNSET: - commands += _set_if_unset(env_name, value) - else: - assert False - elif type_ in ( - DSV_TYPE_APPEND_NON_DUPLICATE, - DSV_TYPE_PREPEND_NON_DUPLICATE, - DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS - ): - try: - env_name_and_values = remainder.split(';') - except ValueError: - raise RuntimeError( - "doesn't contain a semicolon separating the environment name " - 'from the values') - env_name = env_name_and_values[0] - values = env_name_and_values[1:] - for value in values: - if not value: - value = prefix - elif not os.path.isabs(value): - value = os.path.join(prefix, value) - if ( - type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and - not os.path.exists(value) - ): - comment = f'skip extending {env_name} with not existing ' \ - f'path: {value}' - if _include_comments(): - commands.append( - FORMAT_STR_COMMENT_LINE.format_map({'comment': comment})) - elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE: - commands += _append_unique_value(env_name, value) - else: - commands += _prepend_unique_value(env_name, value) - else: - raise RuntimeError( - 'contains an unknown environment hook type: ' + type_) - return commands - - -env_state = {} - - -def _append_unique_value(name, value): - global env_state - if name not in env_state: - if os.environ.get(name): - env_state[name] = set(os.environ[name].split(os.pathsep)) - else: - env_state[name] = set() - # append even if the variable has not been set yet, in case a shell script sets the - # same variable without the knowledge of this Python script. - # later _remove_ending_separators() will cleanup any unintentional leading separator - extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': extend + value}) - if value not in env_state[name]: - env_state[name].add(value) - else: - if not _include_comments(): - return [] - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -def _prepend_unique_value(name, value): - global env_state - if name not in env_state: - if os.environ.get(name): - env_state[name] = set(os.environ[name].split(os.pathsep)) - else: - env_state[name] = set() - # prepend even if the variable has not been set yet, in case a shell script sets the - # same variable without the knowledge of this Python script. - # later _remove_ending_separators() will cleanup any unintentional trailing separator - extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value + extend}) - if value not in env_state[name]: - env_state[name].add(value) - else: - if not _include_comments(): - return [] - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -# generate commands for removing prepended underscores -def _remove_ending_separators(): - # do nothing if the shell extension does not implement the logic - if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None: - return [] - - global env_state - commands = [] - for name in env_state: - # skip variables that already had values before this script started prepending - if name in os.environ: - continue - commands += [ - FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}), - FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})] - return commands - - -def _set(name, value): - global env_state - env_state[name] = value - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value}) - return [line] - - -def _set_if_unset(name, value): - global env_state - line = FORMAT_STR_SET_ENV_VAR.format_map( - {'name': name, 'value': value}) - if env_state.get(name, os.environ.get(name)): - line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line}) - return [line] - - -if __name__ == '__main__': # pragma: no cover - try: - rc = main() - except RuntimeError as e: - print(str(e), file=sys.stderr) - rc = 1 - sys.exit(rc) diff --git a/install/local_setup.bash b/install/local_setup.bash deleted file mode 100644 index efd5f8c9e2..0000000000 --- a/install/local_setup.bash +++ /dev/null @@ -1,107 +0,0 @@ -# generated from colcon_bash/shell/template/prefix.bash.em - -# This script extends the environment with all packages contained in this -# prefix path. - -# a bash script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)" -else - _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prefix_bash_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prefix_bash_prepend_unique_value_IFS="$IFS" - IFS=":" - # start with the new value - _all_values="$_value" - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS="$_colcon_prefix_bash_prepend_unique_value_IFS" - unset _colcon_prefix_bash_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# add this prefix to the COLCON_PREFIX_PATH -_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX" -unset _colcon_prefix_bash_prepend_unique_value - -# check environment variable for custom Python executable -if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then - if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then - echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" - return 1 - fi - _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" -else - # try the Python executable known at configure time - _colcon_python_executable="/usr/bin/python3" - # if it doesn't exist try a fall back - if [ ! -f "$_colcon_python_executable" ]; then - if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then - echo "error: unable to find python3 executable" - return 1 - fi - _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` - fi -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# get all commands in topological order -_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)" -unset _colcon_python_executable -if [ -n "$COLCON_TRACE" ]; then - echo "Execute generated script:" - echo "<<<" - echo "${_colcon_ordered_commands}" - echo ">>>" -fi -eval "${_colcon_ordered_commands}" -unset _colcon_ordered_commands - -unset _colcon_prefix_sh_source_script - -unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX diff --git a/install/local_setup.ps1 b/install/local_setup.ps1 deleted file mode 100644 index 6f68c8dede..0000000000 --- a/install/local_setup.ps1 +++ /dev/null @@ -1,55 +0,0 @@ -# generated from colcon_powershell/shell/template/prefix.ps1.em - -# This script extends the environment with all packages contained in this -# prefix path. - -# check environment variable for custom Python executable -if ($env:COLCON_PYTHON_EXECUTABLE) { - if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) { - echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist" - exit 1 - } - $_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE" -} else { - # use the Python executable known at configure time - $_colcon_python_executable="/usr/bin/python3" - # if it doesn't exist try a fall back - if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) { - if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) { - echo "error: unable to find python3 executable" - exit 1 - } - $_colcon_python_executable="python3" - } -} - -# function to source another script with conditional trace output -# first argument: the path of the script -function _colcon_prefix_powershell_source_script { - param ( - $_colcon_prefix_powershell_source_script_param - ) - # source script with conditional trace output - if (Test-Path $_colcon_prefix_powershell_source_script_param) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_prefix_powershell_source_script_param'" - } - . "$_colcon_prefix_powershell_source_script_param" - } else { - Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'" - } -} - -# get all commands in topological order -$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1 - -# execute all commands in topological order -if ($env:COLCON_TRACE) { - echo "Execute generated script:" - echo "<<<" - $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output - echo ">>>" -} -if ($_colcon_ordered_commands) { - $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression -} diff --git a/install/local_setup.sh b/install/local_setup.sh deleted file mode 100644 index 8e04206e84..0000000000 --- a/install/local_setup.sh +++ /dev/null @@ -1,137 +0,0 @@ -# generated from colcon_core/shell/template/prefix.sh.em - -# This script extends the environment with all packages contained in this -# prefix path. - -# since a plain shell script can't determine its own path when being sourced -# either use the provided COLCON_CURRENT_PREFIX -# or fall back to the build time prefix (if it exists) -_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install" -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then - echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 - unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX - return 1 - fi -else - _colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prefix_sh_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prefix_sh_prepend_unique_value_IFS="$IFS" - IFS=":" - # start with the new value - _all_values="$_value" - _contained_value="" - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - _contained_value=1 - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - if [ -z "$_contained_value" ]; then - if [ -n "$COLCON_TRACE" ]; then - if [ "$_all_values" = "$_value" ]; then - echo "export $_listname=$_value" - else - echo "export $_listname=$_value:\$$_listname" - fi - fi - fi - unset _contained_value - # restore the field separator - IFS="$_colcon_prefix_sh_prepend_unique_value_IFS" - unset _colcon_prefix_sh_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# add this prefix to the COLCON_PREFIX_PATH -_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" -unset _colcon_prefix_sh_prepend_unique_value - -# check environment variable for custom Python executable -if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then - if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then - echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" - return 1 - fi - _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" -else - # try the Python executable known at configure time - _colcon_python_executable="/usr/bin/python3" - # if it doesn't exist try a fall back - if [ ! -f "$_colcon_python_executable" ]; then - if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then - echo "error: unable to find python3 executable" - return 1 - fi - _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` - fi -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo "# . \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# get all commands in topological order -_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)" -unset _colcon_python_executable -if [ -n "$COLCON_TRACE" ]; then - echo "_colcon_prefix_sh_source_script() { - if [ -f \"\$1\" ]; then - if [ -n \"\$COLCON_TRACE\" ]; then - echo \"# . \\\"\$1\\\"\" - fi - . \"\$1\" - else - echo \"not found: \\\"\$1\\\"\" 1>&2 - fi - }" - echo "# Execute generated script:" - echo "# <<<" - echo "${_colcon_ordered_commands}" - echo "# >>>" - echo "unset _colcon_prefix_sh_source_script" -fi -eval "${_colcon_ordered_commands}" -unset _colcon_ordered_commands - -unset _colcon_prefix_sh_source_script - -unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX diff --git a/install/local_setup.zsh b/install/local_setup.zsh deleted file mode 100644 index f7a8d904f2..0000000000 --- a/install/local_setup.zsh +++ /dev/null @@ -1,120 +0,0 @@ -# generated from colcon_zsh/shell/template/prefix.zsh.em - -# This script extends the environment with all packages contained in this -# prefix path. - -# a zsh script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)" -else - _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to convert array-like strings into arrays -# to workaround SH_WORD_SPLIT not being set -_colcon_prefix_zsh_convert_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prefix_zsh_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prefix_zsh_prepend_unique_value_IFS="$IFS" - IFS=":" - # start with the new value - _all_values="$_value" - # workaround SH_WORD_SPLIT not being set - _colcon_prefix_zsh_convert_to_array _values - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS" - unset _colcon_prefix_zsh_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# add this prefix to the COLCON_PREFIX_PATH -_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX" -unset _colcon_prefix_zsh_prepend_unique_value -unset _colcon_prefix_zsh_convert_to_array - -# check environment variable for custom Python executable -if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then - if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then - echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist" - return 1 - fi - _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE" -else - # try the Python executable known at configure time - _colcon_python_executable="/usr/bin/python3" - # if it doesn't exist try a fall back - if [ ! -f "$_colcon_python_executable" ]; then - if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then - echo "error: unable to find python3 executable" - return 1 - fi - _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"` - fi -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# get all commands in topological order -_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)" -unset _colcon_python_executable -if [ -n "$COLCON_TRACE" ]; then - echo "Execute generated script:" - echo "<<<" - echo "${_colcon_ordered_commands}" - echo ">>>" -fi -eval "${_colcon_ordered_commands}" -unset _colcon_ordered_commands - -unset _colcon_prefix_sh_source_script - -unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common b/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common deleted file mode 100644 index cb50e1c622..0000000000 --- a/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common +++ /dev/null @@ -1 +0,0 @@ -backward_ros;ament_lint_auto;ament_lint_common \ No newline at end of file diff --git a/install/moveit_common/share/ament_index/resource_index/packages/moveit_common b/install/moveit_common/share/ament_index/resource_index/packages/moveit_common deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common b/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common deleted file mode 100644 index 6350bc15a2..0000000000 --- a/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common +++ /dev/null @@ -1 +0,0 @@ -/opt/ros/humble \ No newline at end of file diff --git a/install/moveit_common/share/colcon-core/packages/moveit_common b/install/moveit_common/share/colcon-core/packages/moveit_common deleted file mode 100644 index 64e2ddc3bc..0000000000 --- a/install/moveit_common/share/colcon-core/packages/moveit_common +++ /dev/null @@ -1 +0,0 @@ -backward_ros \ No newline at end of file diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake deleted file mode 100644 index b2fc2d01a0..0000000000 --- a/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake +++ /dev/null @@ -1,30 +0,0 @@ -# Copyright 2021 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -include("${moveit_common_DIR}/moveit_package.cmake") diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake deleted file mode 100644 index 0f7d27f124..0000000000 --- a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake +++ /dev/null @@ -1,14 +0,0 @@ -# generated from ament/cmake/core/templates/nameConfig-version.cmake.in -set(PACKAGE_VERSION "2.5.1") - -set(PACKAGE_VERSION_EXACT False) -set(PACKAGE_VERSION_COMPATIBLE False) - -if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") - set(PACKAGE_VERSION_EXACT True) - set(PACKAGE_VERSION_COMPATIBLE True) -endif() - -if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") - set(PACKAGE_VERSION_COMPATIBLE True) -endif() diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake deleted file mode 100644 index 9ff6072903..0000000000 --- a/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake +++ /dev/null @@ -1,42 +0,0 @@ -# generated from ament/cmake/core/templates/nameConfig.cmake.in - -# prevent multiple inclusion -if(_moveit_common_CONFIG_INCLUDED) - # ensure to keep the found flag the same - if(NOT DEFINED moveit_common_FOUND) - # explicitly set it to FALSE, otherwise CMake will set it to TRUE - set(moveit_common_FOUND FALSE) - elseif(NOT moveit_common_FOUND) - # use separate condition to avoid uninitialized variable warning - set(moveit_common_FOUND FALSE) - endif() - return() -endif() -set(_moveit_common_CONFIG_INCLUDED TRUE) - -# output package information -if(NOT moveit_common_FIND_QUIETLY) - message(STATUS "Found moveit_common: 2.5.1 (${moveit_common_DIR})") -endif() - -# warn when using a deprecated package -if(NOT "" STREQUAL "") - set(_msg "Package 'moveit_common' is deprecated") - # append custom deprecation text if available - if(NOT "" STREQUAL "TRUE") - set(_msg "${_msg} ()") - endif() - # optionally quiet the deprecation message - if(NOT ${moveit_common_DEPRECATED_QUIET}) - message(DEPRECATION "${_msg}") - endif() -endif() - -# flag package as ament-based to distinguish it after being find_package()-ed -set(moveit_common_FOUND_AMENT_PACKAGE TRUE) - -# include all config extra files -set(_extras "moveit_common-extras.cmake") -foreach(_extra ${_extras}) - include("${moveit_common_DIR}/${_extra}") -endforeach() diff --git a/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake b/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake deleted file mode 100644 index 1fed492e2d..0000000000 --- a/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake +++ /dev/null @@ -1,81 +0,0 @@ -# Copyright 2021 PickNik Inc. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the name of the PickNik Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - - -macro(moveit_package) - # Set ${PROJECT_NAME}_VERSION - find_package(ament_cmake REQUIRED) - ament_package_xml() - - # Enable backward_ros on every moveit package - find_package(backward_ros QUIET) - - if(NOT "${CMAKE_CXX_STANDARD}") - set(CMAKE_CXX_STANDARD 17) - endif() - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_EXTENSIONS OFF) - - if(NOT CMAKE_CXX_COMPILER_ID STREQUAL "MSVC") - # Enable warnings - add_compile_options(-Wall -Wextra - -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual - -Wno-unused-parameter -Wno-unused-function) - else() - # Defaults for Microsoft C++ compiler - add_compile_options(/W3 /wd4251 /wd4068 /wd4275) - - # https://blog.kitware.com/create-dlls-on-windows-without-declspec-using-new-cmake-export-all-feature/ - set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) - - # Enable Math Constants - # https://docs.microsoft.com/en-us/cpp/c-runtime-library/math-constants?view=vs-2019 - add_compile_definitions( - _USE_MATH_DEFINES - ) - endif() - - option(MOVEIT_CI_WARNINGS "Enable all warnings used by CI" ON) - if(MOVEIT_CI_WARNINGS) - if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - add_compile_options(-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual) - # This too often has false-positives - add_compile_options(-Wno-maybe-uninitialized) - endif() - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") - add_compile_options(-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wcast-qual) - endif() - endif() - - set(CMAKE_EXPORT_COMPILE_COMMANDS ON) - - if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) - message("${PROJECT_NAME}: You did not request a specific build type: Choosing 'Release' for maximum performance") - set(CMAKE_BUILD_TYPE Release) - endif() -endmacro() diff --git a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv deleted file mode 100644 index 79d4c95b55..0000000000 --- a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh b/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh deleted file mode 100644 index 02e441b753..0000000000 --- a/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh +++ /dev/null @@ -1,4 +0,0 @@ -# copied from -# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh - -ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/environment/path.dsv b/install/moveit_common/share/moveit_common/environment/path.dsv deleted file mode 100644 index b94426af08..0000000000 --- a/install/moveit_common/share/moveit_common/environment/path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate-if-exists;PATH;bin diff --git a/install/moveit_common/share/moveit_common/environment/path.sh b/install/moveit_common/share/moveit_common/environment/path.sh deleted file mode 100644 index e59b749a89..0000000000 --- a/install/moveit_common/share/moveit_common/environment/path.sh +++ /dev/null @@ -1,5 +0,0 @@ -# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh - -if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then - ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin" -fi diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv deleted file mode 100644 index e119f32cba..0000000000 --- a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;CMAKE_PREFIX_PATH; diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 deleted file mode 100644 index d03facc1a4..0000000000 --- a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1 +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em - -colcon_prepend_unique_value CMAKE_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh b/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh deleted file mode 100644 index a948e685ba..0000000000 --- a/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_core/shell/template/hook_prepend_value.sh.em - -_colcon_prepend_unique_value CMAKE_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_common/share/moveit_common/local_setup.bash b/install/moveit_common/share/moveit_common/local_setup.bash deleted file mode 100644 index 49782f2461..0000000000 --- a/install/moveit_common/share/moveit_common/local_setup.bash +++ /dev/null @@ -1,46 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.bash.in - -# source local_setup.sh from same directory as this file -_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd) -# provide AMENT_CURRENT_PREFIX to shell script -AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd) -# store AMENT_CURRENT_PREFIX to restore it before each environment hook -_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX - -# trace output -if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_this_path/local_setup.sh\"" -fi -. "$_this_path/local_setup.sh" -unset _this_path - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks -AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX -# list all environment hooks of this package - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - # restore AMENT_CURRENT_PREFIX for each environment hook - AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - . "$_hook" - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -unset _package_local_setup_AMENT_CURRENT_PREFIX -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/local_setup.dsv b/install/moveit_common/share/moveit_common/local_setup.dsv deleted file mode 100644 index 6aaf2a9457..0000000000 --- a/install/moveit_common/share/moveit_common/local_setup.dsv +++ /dev/null @@ -1,2 +0,0 @@ -source;share/moveit_common/environment/ament_prefix_path.sh -source;share/moveit_common/environment/path.sh diff --git a/install/moveit_common/share/moveit_common/local_setup.sh b/install/moveit_common/share/moveit_common/local_setup.sh deleted file mode 100644 index 818849912a..0000000000 --- a/install/moveit_common/share/moveit_common/local_setup.sh +++ /dev/null @@ -1,184 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.sh.in - -# since this file is sourced use either the provided AMENT_CURRENT_PREFIX -# or fall back to the destination set at configure time -: ${AMENT_CURRENT_PREFIX:="/home/henry/ws_moveit2/src/moveit2/install/moveit_common"} -if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then - if [ -z "$COLCON_CURRENT_PREFIX" ]; then - echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \ - "exist. Consider sourcing a different extension than '.sh'." 1>&2 - else - AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" - fi -fi - -# function to append values to environment variables -# using colons as separators and avoiding leading separators -ament_append_value() { - # arguments - _listname="$1" - _value="$2" - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # avoid leading separator - eval _values=\"\$$_listname\" - if [ -z "$_values" ]; then - eval export $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - _ament_append_value_IFS=$IFS - unset IFS - eval export $_listname=\"\$$_listname:$_value\" - #eval echo "append list \$$_listname" - IFS=$_ament_append_value_IFS - unset _ament_append_value_IFS - fi - unset _values - - unset _value - unset _listname -} - -# function to append non-duplicate values to environment variables -# using colons as separators and avoiding leading separators -ament_append_unique_value() { - # arguments - _listname=$1 - _value=$2 - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # check if the list contains the value - eval _values=\$$_listname - _duplicate= - _ament_append_unique_value_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array _values - fi - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - if [ $_item = $_value ]; then - _duplicate=1 - fi - done - unset _item - - # append only non-duplicates - if [ -z "$_duplicate" ]; then - # avoid leading separator - if [ -z "$_values" ]; then - eval $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - unset IFS - eval $_listname=\"\$$_listname:$_value\" - #eval echo "append list \$$_listname" - fi - fi - IFS=$_ament_append_unique_value_IFS - unset _ament_append_unique_value_IFS - unset _duplicate - unset _values - - unset _value - unset _listname -} - -# function to prepend non-duplicate values to environment variables -# using colons as separators and avoiding trailing separators -ament_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # check if the list contains the value - eval _values=\"\$$_listname\" - _duplicate= - _ament_prepend_unique_value_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array _values - fi - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - if [ "$_item" = "$_value" ]; then - _duplicate=1 - fi - done - unset _item - - # prepend only non-duplicates - if [ -z "$_duplicate" ]; then - # avoid trailing separator - if [ -z "$_values" ]; then - eval export $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - unset IFS - eval export $_listname=\"$_value:\$$_listname\" - #eval echo "prepend list \$$_listname" - fi - fi - IFS=$_ament_prepend_unique_value_IFS - unset _ament_prepend_unique_value_IFS - unset _duplicate - unset _values - - unset _value - unset _listname -} - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# list all environment hooks of this package -ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_common/environment/ament_prefix_path.sh" -ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_common/environment/path.sh" - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS - fi - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - if [ -f "$_hook" ]; then - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - # trace output - if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_hook\"" - fi - . "$_hook" - fi - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -# reset AMENT_CURRENT_PREFIX after each package -# allowing to source multiple package-level setup files -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/local_setup.zsh b/install/moveit_common/share/moveit_common/local_setup.zsh deleted file mode 100644 index fe161be53d..0000000000 --- a/install/moveit_common/share/moveit_common/local_setup.zsh +++ /dev/null @@ -1,59 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.zsh.in - -AMENT_SHELL=zsh - -# source local_setup.sh from same directory as this file -_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd) -# provide AMENT_CURRENT_PREFIX to shell script -AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd) -# store AMENT_CURRENT_PREFIX to restore it before each environment hook -_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX - -# function to convert array-like strings into arrays -# to wordaround SH_WORD_SPLIT not being set -ament_zsh_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# trace output -if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_this_path/local_setup.sh\"" -fi -# the package-level local_setup file unsets AMENT_CURRENT_PREFIX -. "$_this_path/local_setup.sh" -unset _this_path - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks -AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX -# list all environment hooks of this package - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - # restore AMENT_CURRENT_PREFIX for each environment hook - AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - . "$_hook" - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -unset _package_local_setup_AMENT_CURRENT_PREFIX -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.bash b/install/moveit_common/share/moveit_common/package.bash deleted file mode 100644 index 15d140b8ae..0000000000 --- a/install/moveit_common/share/moveit_common/package.bash +++ /dev/null @@ -1,39 +0,0 @@ -# generated from colcon_bash/shell/template/package.bash.em - -# This script extends the environment for this package. - -# a bash script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" -else - _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_bash_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh script of this package -_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_common/package.sh" - -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts -COLCON_CURRENT_PREFIX="$_colcon_package_bash_COLCON_CURRENT_PREFIX" - -# source bash hooks -_colcon_package_bash_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.bash" - -unset COLCON_CURRENT_PREFIX - -unset _colcon_package_bash_source_script -unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.dsv b/install/moveit_common/share/moveit_common/package.dsv deleted file mode 100644 index 73d9cbcd41..0000000000 --- a/install/moveit_common/share/moveit_common/package.dsv +++ /dev/null @@ -1,8 +0,0 @@ -source;share/moveit_common/hook/cmake_prefix_path.ps1 -source;share/moveit_common/hook/cmake_prefix_path.dsv -source;share/moveit_common/hook/cmake_prefix_path.sh -source;share/moveit_common/local_setup.bash -source;share/moveit_common/local_setup.dsv -source;share/moveit_common/local_setup.ps1 -source;share/moveit_common/local_setup.sh -source;share/moveit_common/local_setup.zsh diff --git a/install/moveit_common/share/moveit_common/package.ps1 b/install/moveit_common/share/moveit_common/package.ps1 deleted file mode 100644 index 47a325104f..0000000000 --- a/install/moveit_common/share/moveit_common/package.ps1 +++ /dev/null @@ -1,116 +0,0 @@ -# generated from colcon_powershell/shell/template/package.ps1.em - -# function to append a value to a variable -# which uses colons as separators -# duplicates as well as leading separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_append_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - $_duplicate="" - # start with no values - $_all_values="" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -eq $_value) { - $_duplicate="1" - } - if ($_all_values) { - $_all_values="${_all_values};$_" - } else { - $_all_values="$_" - } - } - } - } - # append only non-duplicates - if (!$_duplicate) { - # avoid leading separator - if ($_all_values) { - $_all_values="${_all_values};${_value}" - } else { - $_all_values="${_value}" - } - } - - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_prepend_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - # start with the new value - $_all_values="$_value" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -ne $_value) { - # keep non-duplicate values - $_all_values="${_all_values};$_" - } - } - } - } - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -function colcon_package_source_powershell_script { - param ( - $_colcon_package_source_powershell_script - ) - # source script with conditional trace output - if (Test-Path $_colcon_package_source_powershell_script) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_package_source_powershell_script'" - } - . "$_colcon_package_source_powershell_script" - } else { - Write-Error "not found: '$_colcon_package_source_powershell_script'" - } -} - - -# a powershell script is able to determine its own path -# the prefix is two levels up from the package specific share directory -$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName - -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_common/hook/cmake_prefix_path.ps1" -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_common/local_setup.ps1" - -Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_common/share/moveit_common/package.sh b/install/moveit_common/share/moveit_common/package.sh deleted file mode 100644 index ea7c7d2c99..0000000000 --- a/install/moveit_common/share/moveit_common/package.sh +++ /dev/null @@ -1,87 +0,0 @@ -# generated from colcon_core/shell/template/package.sh.em - -# This script extends the environment for this package. - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prepend_unique_value_IFS=$IFS - IFS=":" - # start with the new value - _all_values="$_value" - # workaround SH_WORD_SPLIT not being set in zsh - if [ "$(command -v colcon_zsh_convert_to_array)" ]; then - colcon_zsh_convert_to_array _values - fi - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS=$_colcon_prepend_unique_value_IFS - unset _colcon_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# since a plain shell script can't determine its own path when being sourced -# either use the provided COLCON_CURRENT_PREFIX -# or fall back to the build time prefix (if it exists) -_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_common" -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then - echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 - unset _colcon_package_sh_COLCON_CURRENT_PREFIX - return 1 - fi - COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" -fi -unset _colcon_package_sh_COLCON_CURRENT_PREFIX - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo "# . \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh hooks -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/hook/cmake_prefix_path.sh" -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.sh" - -unset _colcon_package_sh_source_script -unset COLCON_CURRENT_PREFIX - -# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_common/share/moveit_common/package.xml b/install/moveit_common/share/moveit_common/package.xml deleted file mode 100644 index a015632281..0000000000 --- a/install/moveit_common/share/moveit_common/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - moveit_common - 2.5.1 - Common support functionality used throughout MoveIt - Henning Kayser - Tyler Weaver - MoveIt Release Team - - BSD - - http://moveit.ros.org - https://github.com/ros-planning/moveit2/issues - https://github.com/ros-planning/moveit2 - - Lior Lustgarten - - ament_cmake - - backward_ros - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/install/moveit_common/share/moveit_common/package.zsh b/install/moveit_common/share/moveit_common/package.zsh deleted file mode 100644 index 2534236587..0000000000 --- a/install/moveit_common/share/moveit_common/package.zsh +++ /dev/null @@ -1,50 +0,0 @@ -# generated from colcon_zsh/shell/template/package.zsh.em - -# This script extends the environment for this package. - -# a zsh script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" -else - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_zsh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# function to convert array-like strings into arrays -# to workaround SH_WORD_SPLIT not being set -colcon_zsh_convert_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# source sh script of this package -_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_common/package.sh" -unset convert_zsh_to_array - -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts -COLCON_CURRENT_PREFIX="$_colcon_package_zsh_COLCON_CURRENT_PREFIX" - -# source zsh hooks -_colcon_package_zsh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_common/local_setup.zsh" - -unset COLCON_CURRENT_PREFIX - -unset _colcon_package_zsh_source_script -unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils b/install/moveit_configs_utils/share/ament_index/resource_index/packages/moveit_configs_utils deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils b/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils deleted file mode 100644 index c4b091727f..0000000000 --- a/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils +++ /dev/null @@ -1 +0,0 @@ -ament_index_python:launch:launch_param_builder:launch_ros:srdfdom \ No newline at end of file diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml deleted file mode 100644 index 47002cc036..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/chomp_planning.yaml +++ /dev/null @@ -1,12 +0,0 @@ -planning_plugin: chomp_interface/CHOMPPlanner -enable_failure_recovery: true -jiggle_fraction: 0.05 -request_adapters: >- - default_planner_request_adapters/AddTimeParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints -ridge_factor: 0.01 -start_state_max_bounds_error: 0.1 diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml deleted file mode 100644 index dda05494b7..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_defaults.yaml +++ /dev/null @@ -1,129 +0,0 @@ -planner_configs: - AnytimePathShortening: - type: geometric::AnytimePathShortening - shortcut: true # Attempt to shortcut all new solution paths - hybridize: true # Compute hybrid solution trajectories - max_hybrid_paths: 24 # Number of hybrid paths generated per iteration - num_planners: 4 # The number of default planners to use for planning - planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" - SBL: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - EST: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECE: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECE: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECE: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRT: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnect: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstar: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRT: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() - PRM: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstar: - type: geometric::PRMstar - FMT: - type: geometric::FMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 - nearest_k: 1 # use Knearest strategy. default: 1 - cache_cc: 1 # use collision checking cache. default: 1 - heuristics: 0 # activate cost to go heuristics. default: 0 - extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - BFMT: - type: geometric::BFMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 - nearest_k: 1 # use the Knearest strategy. default: 1 - balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 - optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 - heuristics: 1 # activates cost to go heuristics. default: 1 - cache_cc: 1 # use the collision checking cache. default: 1 - extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - PDST: - type: geometric::PDST - STRIDE: - type: geometric::STRIDE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 - degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 - max_degree: 18 # max degree of a node in the GNAT. default: 12 - min_degree: 12 # min degree of a node in the GNAT. default: 12 - max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 - estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 - min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 - BiTRRT: - type: geometric::BiTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 - init_temperature: 100 # initial temperature. default: 100 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf - LBTRRT: - type: geometric::LBTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - epsilon: 0.4 # optimality approximation factor. default: 0.4 - BiEST: - type: geometric::BiEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ProjEST: - type: geometric::ProjEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LazyPRM: - type: geometric::LazyPRM - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - LazyPRMstar: - type: geometric::LazyPRMstar - SPARS: - type: geometric::SPARS - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 1000 # maximum consecutive failure limit. default: 1000 - SPARStwo: - type: geometric::SPARStwo - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 5000 # maximum consecutive failure limit. default: 5000 diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml deleted file mode 100644 index a5d0ea8522..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/ompl_planning.yaml +++ /dev/null @@ -1,10 +0,0 @@ -planning_plugin: ompl_interface/OMPLPlanner -start_state_max_bounds_error: 0.1 -jiggle_fraction: 0.05 -request_adapters: >- - default_planner_request_adapters/AddTimeParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml deleted file mode 100644 index 92fd5907be..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/pilz_industrial_motion_planner_planning.yaml +++ /dev/null @@ -1,6 +0,0 @@ -planning_plugin: pilz_industrial_motion_planner/CommandPlanner -request_adapters: "" -default_planner_config: PTP -capabilities: >- - pilz_industrial_motion_planner/MoveGroupSequenceAction - pilz_industrial_motion_planner/MoveGroupSequenceService diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml b/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml deleted file mode 100644 index 6565e256d4..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/trajopt_planning.yaml +++ /dev/null @@ -1,9 +0,0 @@ -planning_plugin: trajopt_interface/TrajOptPlanner -start_state_max_bounds_error: 0.1 -jiggle_fraction: 0.05 -request_adapters: >- - default_planner_request_adapters/AddTimeParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv deleted file mode 100644 index 79d4c95b55..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 deleted file mode 100644 index 26b9997579..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1 +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em - -colcon_prepend_unique_value AMENT_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh b/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh deleted file mode 100644 index f3041f688a..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_core/shell/template/hook_prepend_value.sh.em - -_colcon_prepend_unique_value AMENT_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv deleted file mode 100644 index 257067d44d..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;PYTHONPATH;lib/python3.10/site-packages diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 deleted file mode 100644 index caffe83fd5..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1 +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em - -colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\lib/python3.10/site-packages" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh b/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh deleted file mode 100644 index 660c34836d..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_core/shell/template/hook_prepend_value.sh.em - -_colcon_prepend_unique_value PYTHONPATH "$COLCON_CURRENT_PREFIX/lib/python3.10/site-packages" diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.bash b/install/moveit_configs_utils/share/moveit_configs_utils/package.bash deleted file mode 100644 index 48f4f92f22..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.bash +++ /dev/null @@ -1,31 +0,0 @@ -# generated from colcon_bash/shell/template/package.bash.em - -# This script extends the environment for this package. - -# a bash script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" -else - _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_bash_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh script of this package -_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_configs_utils/package.sh" - -unset _colcon_package_bash_source_script -unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv b/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv deleted file mode 100644 index 358282cdc6..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv +++ /dev/null @@ -1,6 +0,0 @@ -source;share/moveit_configs_utils/hook/pythonpath.ps1 -source;share/moveit_configs_utils/hook/pythonpath.dsv -source;share/moveit_configs_utils/hook/pythonpath.sh -source;share/moveit_configs_utils/hook/ament_prefix_path.ps1 -source;share/moveit_configs_utils/hook/ament_prefix_path.dsv -source;share/moveit_configs_utils/hook/ament_prefix_path.sh diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 b/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 deleted file mode 100644 index 11c9459d60..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1 +++ /dev/null @@ -1,116 +0,0 @@ -# generated from colcon_powershell/shell/template/package.ps1.em - -# function to append a value to a variable -# which uses colons as separators -# duplicates as well as leading separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_append_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - $_duplicate="" - # start with no values - $_all_values="" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -eq $_value) { - $_duplicate="1" - } - if ($_all_values) { - $_all_values="${_all_values};$_" - } else { - $_all_values="$_" - } - } - } - } - # append only non-duplicates - if (!$_duplicate) { - # avoid leading separator - if ($_all_values) { - $_all_values="${_all_values};${_value}" - } else { - $_all_values="${_value}" - } - } - - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_prepend_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - # start with the new value - $_all_values="$_value" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -ne $_value) { - # keep non-duplicate values - $_all_values="${_all_values};$_" - } - } - } - } - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -function colcon_package_source_powershell_script { - param ( - $_colcon_package_source_powershell_script - ) - # source script with conditional trace output - if (Test-Path $_colcon_package_source_powershell_script) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_package_source_powershell_script'" - } - . "$_colcon_package_source_powershell_script" - } else { - Write-Error "not found: '$_colcon_package_source_powershell_script'" - } -} - - -# a powershell script is able to determine its own path -# the prefix is two levels up from the package specific share directory -$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName - -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_configs_utils/hook/pythonpath.ps1" -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_configs_utils/hook/ament_prefix_path.ps1" - -Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.sh b/install/moveit_configs_utils/share/moveit_configs_utils/package.sh deleted file mode 100644 index 964075e3fb..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.sh +++ /dev/null @@ -1,87 +0,0 @@ -# generated from colcon_core/shell/template/package.sh.em - -# This script extends the environment for this package. - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prepend_unique_value_IFS=$IFS - IFS=":" - # start with the new value - _all_values="$_value" - # workaround SH_WORD_SPLIT not being set in zsh - if [ "$(command -v colcon_zsh_convert_to_array)" ]; then - colcon_zsh_convert_to_array _values - fi - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS=$_colcon_prepend_unique_value_IFS - unset _colcon_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# since a plain shell script can't determine its own path when being sourced -# either use the provided COLCON_CURRENT_PREFIX -# or fall back to the build time prefix (if it exists) -_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils" -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then - echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 - unset _colcon_package_sh_COLCON_CURRENT_PREFIX - return 1 - fi - COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" -fi -unset _colcon_package_sh_COLCON_CURRENT_PREFIX - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo "# . \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh hooks -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_configs_utils/hook/pythonpath.sh" -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_configs_utils/hook/ament_prefix_path.sh" - -unset _colcon_package_sh_source_script -unset COLCON_CURRENT_PREFIX - -# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.xml b/install/moveit_configs_utils/share/moveit_configs_utils/package.xml deleted file mode 100644 index 8847721002..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - moveit_configs_utils - 2.5.1 - Python library for loading moveit config parameters in launch files - MoveIt Release Team - BSD - Jafar Abdi - David V. Lu!! - - ament_index_python - launch_param_builder - launch - launch_ros - srdfdom - - ament_lint_auto - ament_lint_common - - - ament_python - - diff --git a/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh b/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh deleted file mode 100644 index 5938d0b95e..0000000000 --- a/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh +++ /dev/null @@ -1,42 +0,0 @@ -# generated from colcon_zsh/shell/template/package.zsh.em - -# This script extends the environment for this package. - -# a zsh script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" -else - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_zsh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# function to convert array-like strings into arrays -# to workaround SH_WORD_SPLIT not being set -colcon_zsh_convert_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# source sh script of this package -_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_configs_utils/package.sh" -unset convert_zsh_to_array - -unset _colcon_package_zsh_source_script -unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_core/share/colcon-core/packages/moveit_core b/install/moveit_core/share/colcon-core/packages/moveit_core deleted file mode 100644 index 3dbf09e4b0..0000000000 --- a/install/moveit_core/share/colcon-core/packages/moveit_core +++ /dev/null @@ -1 +0,0 @@ -angles:assimp:boost:bullet:common_interfaces:eigen:eigen3_cmake_module:eigen_stl_containers:geometric_shapes:geometry_msgs:kdl_parser:libfcl-dev:moveit_common:moveit_msgs:octomap:octomap_msgs:pluginlib:pybind11_vendor:random_numbers:rclcpp:ruckig:sensor_msgs:shape_msgs:srdfdom:std_msgs:tf2:tf2_eigen:tf2_geometry_msgs:trajectory_msgs:urdf:urdfdom:urdfdom_headers:visualization_msgs \ No newline at end of file diff --git a/install/moveit_core/share/moveit_core/package.bash b/install/moveit_core/share/moveit_core/package.bash deleted file mode 100644 index fb242794b1..0000000000 --- a/install/moveit_core/share/moveit_core/package.bash +++ /dev/null @@ -1,31 +0,0 @@ -# generated from colcon_bash/shell/template/package.bash.em - -# This script extends the environment for this package. - -# a bash script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)" -else - _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_bash_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh script of this package -_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_core/package.sh" - -unset _colcon_package_bash_source_script -unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_core/share/moveit_core/package.dsv b/install/moveit_core/share/moveit_core/package.dsv deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/install/moveit_core/share/moveit_core/package.ps1 b/install/moveit_core/share/moveit_core/package.ps1 deleted file mode 100644 index 4198e42ecf..0000000000 --- a/install/moveit_core/share/moveit_core/package.ps1 +++ /dev/null @@ -1,108 +0,0 @@ -# generated from colcon_powershell/shell/template/package.ps1.em - -# function to append a value to a variable -# which uses colons as separators -# duplicates as well as leading separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_append_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - $_duplicate="" - # start with no values - $_all_values="" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -eq $_value) { - $_duplicate="1" - } - if ($_all_values) { - $_all_values="${_all_values};$_" - } else { - $_all_values="$_" - } - } - } - } - # append only non-duplicates - if (!$_duplicate) { - # avoid leading separator - if ($_all_values) { - $_all_values="${_all_values};${_value}" - } else { - $_all_values="${_value}" - } - } - - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_prepend_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - # start with the new value - $_all_values="$_value" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -ne $_value) { - # keep non-duplicate values - $_all_values="${_all_values};$_" - } - } - } - } - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -function colcon_package_source_powershell_script { - param ( - $_colcon_package_source_powershell_script - ) - # source script with conditional trace output - if (Test-Path $_colcon_package_source_powershell_script) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_package_source_powershell_script'" - } - . "$_colcon_package_source_powershell_script" - } else { - Write-Error "not found: '$_colcon_package_source_powershell_script'" - } -} - - diff --git a/install/moveit_core/share/moveit_core/package.sh b/install/moveit_core/share/moveit_core/package.sh deleted file mode 100644 index 7d7278e5f0..0000000000 --- a/install/moveit_core/share/moveit_core/package.sh +++ /dev/null @@ -1,52 +0,0 @@ -# generated from colcon_core/shell/template/package.sh.em - -# This script extends the environment for this package. - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prepend_unique_value_IFS=$IFS - IFS=":" - # start with the new value - _all_values="$_value" - # workaround SH_WORD_SPLIT not being set in zsh - if [ "$(command -v colcon_zsh_convert_to_array)" ]; then - colcon_zsh_convert_to_array _values - fi - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS=$_colcon_prepend_unique_value_IFS - unset _colcon_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_core/share/moveit_core/package.zsh b/install/moveit_core/share/moveit_core/package.zsh deleted file mode 100644 index 82fdae26eb..0000000000 --- a/install/moveit_core/share/moveit_core/package.zsh +++ /dev/null @@ -1,42 +0,0 @@ -# generated from colcon_zsh/shell/template/package.zsh.em - -# This script extends the environment for this package. - -# a zsh script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" -else - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_zsh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# function to convert array-like strings into arrays -# to workaround SH_WORD_SPLIT not being set -colcon_zsh_convert_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# source sh script of this package -_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_core/package.sh" -unset convert_zsh_to_array - -unset _colcon_package_zsh_source_script -unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support deleted file mode 100644 index 476e71c3f8..0000000000 --- a/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support +++ /dev/null @@ -1 +0,0 @@ -xacro \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support deleted file mode 100644 index 6350bc15a2..0000000000 --- a/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support +++ /dev/null @@ -1 +0,0 @@ -/opt/ros/humble \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support b/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support deleted file mode 100644 index 476e71c3f8..0000000000 --- a/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support +++ /dev/null @@ -1 +0,0 @@ -xacro \ No newline at end of file diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake deleted file mode 100644 index 0f7d27f124..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake +++ /dev/null @@ -1,14 +0,0 @@ -# generated from ament/cmake/core/templates/nameConfig-version.cmake.in -set(PACKAGE_VERSION "2.5.1") - -set(PACKAGE_VERSION_EXACT False) -set(PACKAGE_VERSION_COMPATIBLE False) - -if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") - set(PACKAGE_VERSION_EXACT True) - set(PACKAGE_VERSION_COMPATIBLE True) -endif() - -if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") - set(PACKAGE_VERSION_COMPATIBLE True) -endif() diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake deleted file mode 100644 index fbcf5ca572..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake +++ /dev/null @@ -1,42 +0,0 @@ -# generated from ament/cmake/core/templates/nameConfig.cmake.in - -# prevent multiple inclusion -if(_moveit_resources_prbt_support_CONFIG_INCLUDED) - # ensure to keep the found flag the same - if(NOT DEFINED moveit_resources_prbt_support_FOUND) - # explicitly set it to FALSE, otherwise CMake will set it to TRUE - set(moveit_resources_prbt_support_FOUND FALSE) - elseif(NOT moveit_resources_prbt_support_FOUND) - # use separate condition to avoid uninitialized variable warning - set(moveit_resources_prbt_support_FOUND FALSE) - endif() - return() -endif() -set(_moveit_resources_prbt_support_CONFIG_INCLUDED TRUE) - -# output package information -if(NOT moveit_resources_prbt_support_FIND_QUIETLY) - message(STATUS "Found moveit_resources_prbt_support: 2.5.1 (${moveit_resources_prbt_support_DIR})") -endif() - -# warn when using a deprecated package -if(NOT "" STREQUAL "") - set(_msg "Package 'moveit_resources_prbt_support' is deprecated") - # append custom deprecation text if available - if(NOT "" STREQUAL "TRUE") - set(_msg "${_msg} ()") - endif() - # optionally quiet the deprecation message - if(NOT ${moveit_resources_prbt_support_DEPRECATED_QUIET}) - message(DEPRECATION "${_msg}") - endif() -endif() - -# flag package as ament-based to distinguish it after being find_package()-ed -set(moveit_resources_prbt_support_FOUND_AMENT_PACKAGE TRUE) - -# include all config extra files -set(_extras "") -foreach(_extra ${_extras}) - include("${moveit_resources_prbt_support_DIR}/${_extra}") -endforeach() diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml deleted file mode 100644 index 9ad1cdf941..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml +++ /dev/null @@ -1,77 +0,0 @@ -# -# Copyright © 2018 Pilz GmbH & Co. KG -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -# FILE DESCRIPTION: -# -# This file declares the different controller types which can then be -# instantiated by the controller manager. In this file only controllers -# for the manipulator are declared (no gripper). -# -# See also: http://wiki.ros.org/joint_trajectory_controller?distro=lunar -# - -## joint_names -joint_names: [prbt_joint_1, prbt_joint_2, prbt_joint_3, prbt_joint_4, prbt_joint_5, prbt_joint_6] - -## control_mode_adapter -max_command_silence: 0.5 - -## joint_state_controller (needed to obtain /joint_states) -manipulator_joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 50 - -## joint trajectory controller -manipulator_joint_trajectory_controller: - type: position_controllers/PilzJointTrajectoryController - joints: - - prbt_joint_1 - - prbt_joint_2 - - prbt_joint_3 - - prbt_joint_4 - - prbt_joint_5 - - prbt_joint_6 - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - prbt_joint_1: {trajectory: 0.157, goal: 0.01} - prbt_joint_2: {trajectory: 0.157, goal: 0.01} - prbt_joint_3: {trajectory: 0.157, goal: 0.01} - prbt_joint_4: {trajectory: 0.157, goal: 0.01} - prbt_joint_5: {trajectory: 0.157, goal: 0.01} - prbt_joint_6: {trajectory: 0.157, goal: 0.01} - stop_trajectory_duration: 0.2 - state_publish_rate: 25 - action_monitor_rate: 10 - required_drive_mode: 7 - limits: - prbt_joint_1: - has_acceleration_limits: true - max_acceleration: 6.0 - prbt_joint_2: - has_acceleration_limits: true - max_acceleration: 6.0 - prbt_joint_3: - has_acceleration_limits: true - max_acceleration: 6.0 - prbt_joint_4: - has_acceleration_limits: true - max_acceleration: 6.0 - prbt_joint_5: - has_acceleration_limits: true - max_acceleration: 6.0 - prbt_joint_6: - has_acceleration_limits: true - max_acceleration: 6.0 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml deleted file mode 100644 index 4e196d3087..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml +++ /dev/null @@ -1,52 +0,0 @@ -# -# Copyright © 2018 Pilz GmbH & Co. KG -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -# FILE DESCRIPTION: -# -# This file mappes the robot joints to the corresponding CAN-IDs. In this file -# only the robot joints are considered (no gripper joint). -# - -name: manipulator - -bus: - device: can0 -sync: - interval_ms: 10 - overflow: 0 - -defaults: - eds_pkg: moveit_resources_prbt_support - eds_file: "config/prbt_0_1.dcf" - -nodes: - prbt_joint_1: - id: 3 - braketest_required: true - prbt_joint_2: - id: 4 - braketest_required: true - prbt_joint_3: - id: 5 - braketest_required: true - prbt_joint_4: - id: 6 - braketest_required: true - prbt_joint_5: - id: 7 - braketest_required: true - prbt_joint_6: - id: 8 - braketest_required: true diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf deleted file mode 100644 index 090290b13c..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf +++ /dev/null @@ -1,2052 +0,0 @@ -[FileInfo] -CreatedBy=Dirk Osswald, SCHUNK GmbH & Co. KG -ModifiedBy=Pilz GmbH & Co. KG -Description=PRBT Electronic Data Sheet -CreationTime=01:33PM -CreationDate=05-23-2013 -ModificationTime=00:00PM -ModificationDate=09-07-2018 -FileName=prbt_0_1.dcf -FileVersion=0x03 -FileRevision=0x01 -EDSVersion=4.0 - -[DeviceInfo] -VendorName=Pilz GmbH & Co. KG -OrderCode=0 -BaudRate_10=0 -BaudRate_20=0 -BaudRate_50=1 -BaudRate_125=1 -BaudRate_250=1 -BaudRate_500=1 -BaudRate_800=0 -BaudRate_1000=1 -SimpleBootUpMaster=0 -SimpleBootUpSlave=1 -Granularity=8 -DynamicChannelsSupported=0 -CompactPDO=0 -GroupMessaging=0 -NrOfRXPDO=2 -NrOfTXPDO=4 -LSS_Supported=1 - -[DummyUsage] -Dummy0001=0 -Dummy0002=1 -Dummy0003=1 -Dummy0004=1 -Dummy0005=1 -Dummy0006=1 -Dummy0007=1 - -[Comments] -Lines=0 - -[MandatoryObjects] -SupportedObjects=3 -1=0x1000 -2=0x1001 -3=0x1018 - -[1000] -ParameterName=Device type -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 -ObjFlags=0x0 - -[1001] -ParameterName=Error register -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -PDOMapping=0 -ObjFlags=0x0 - -[1018] -ParameterName=Identity Object -ObjectType=0x9 -SubNumber=5 -ObjFlags=0x0 - -[1018sub0] -ParameterName=number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=4 -PDOMapping=0 -LowLimit=1 -HighLimit=4 -ObjFlags=0 - -[1018sub1] -ParameterName=Vendor ID -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 -ObjFlags=0 - -[1018sub2] -ParameterName=Product code -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 -ObjFlags=0 - -[1018sub3] -ParameterName=Revision number -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 -ObjFlags=0 - -[1018sub4] -ParameterName=Serial number -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 -ObjFlags=0 - -[OptionalObjects] -SupportedObjects=62 -1=0x1002 -2=0x1003 -3=0x1005 -4=0x1008 -5=0x1009 -6=0x100A -7=0x100C -8=0x100D -9=0x1014 -10=0x1016 -11=0x1017 -12=0x1200 -13=0x1400 -14=0x1401 -15=0x1600 -16=0x1601 -17=0x1800 -18=0x1801 -19=0x1802 -20=0x1803 -21=0x1A00 -22=0x1A01 -23=0x1A02 -24=0x1A03 -25=0x20A0 -26=0x6040 -27=0x6041 -28=0x6042 -29=0x6043 -30=0x6044 -31=0x6046 -32=0x6048 -33=0x6049 -34=0x604C -35=0x6060 -36=0x6061 -37=0x6062 -38=0x6064 -39=0x6065 -40=0x606B -41=0x606C -42=0x6073 -43=0x6075 -44=0x6077 -45=0x607A -46=0x607C -47=0x607D -48=0x6081 -49=0x6083 -50=0x6086 -51=0x6098 -52=0x60B2 -53=0x60C0 -54=0x60C1 -55=0x60C2 -56=0x60C3 -57=0x60C4 -58=0x60F4 -59=0x60FD -60=0x60FE -61=0x6502 -62=0x2060 - -[1002] -ParameterName=Manufacturer Status Register -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=0 - -[1003] -ParameterName=Pre-defined Error Field -ObjectType=0x8 -SubNumber=3 -ObjFlags=0x0 - -[1003sub0] -ParameterName=Number of Errors -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0 - -[1003sub1] -ParameterName=Standard Error Field -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=0 -PDOMapping=0 -ObjFlags=2 - -[1003sub2] -ParameterName=Standard Error Field -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=0 -PDOMapping=0 -ObjFlags=2 - -[1005] -ParameterName=COB-ID SYNC message -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x00000080 -PDOMapping=0 -ObjFlags=0x0 - -[1008] -ParameterName=Manufacturer device name -ObjectType=0x7 -DataType=0x0009 -AccessType=const -PDOMapping=0 -ObjFlags=0x0 - -[1009] -ParameterName=Manufacturer hardware version -ObjectType=0x7 -DataType=0x0009 -AccessType=const -PDOMapping=0 -ObjFlags=0x0 - -[100A] -ParameterName=Manufacturer software version -ObjectType=0x7 -DataType=0x0009 -AccessType=const -PDOMapping=0 -ObjFlags=0x0 - -[100C] -ParameterName=Guard time -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0x00000000 -PDOMapping=0 -ObjFlags=0x0 - -[100D] -ParameterName=Life time factor -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0x00000000 -PDOMapping=0 -ObjFlags=0x0 - -[1014] -ParameterName=COB-ID EMCY message -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x80 -PDOMapping=0 -ObjFlags=0x0 - -[1016] -ParameterName=Consumer Heartbeat Time -ObjectType=0x8 -SubNumber=4 -ObjFlags=0x0 - -[1016sub0] -ParameterName=Number of Entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=3 -PDOMapping=0 -LowLimit=1 -HighLimit=127 -ObjFlags=0 - -[1016sub1] -ParameterName=Consumer Heartbeat Time of Node-ID 1 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0 - -[1016sub2] -ParameterName=Consumer Heartbeat Time of Node-ID 2 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0 - -[1016sub3] -ParameterName=Consumer Heartbeat Time of Node-ID 3 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0 - -[1017] -ParameterName=Producer heartbeat time -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0x00000000 -PDOMapping=0 -LowLimit=0 -HighLimit=32767 -ObjFlags=0x0 -ParameterValue=100 - -[1200] -ParameterName=1. Server SDO parameter -ObjectType=0x9 -SubNumber=3 -ObjFlags=0x0 - -[1200sub0] -ParameterName=Number of supported Entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=2 -PDOMapping=0 -ObjFlags=0 - -[1200sub1] -ParameterName=COB-ID Client -> Server (rx) -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=$NodeID + 0x600 -PDOMapping=0 -ObjFlags=0 - -[1200sub2] -ParameterName=COB-ID Server -> Client (tx) -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=$NodeID + 0x580 -PDOMapping=0 -ObjFlags=0 - -[1400] -ParameterName=1. Receive PDO parameter -ObjectType=0x9 -SubNumber=3 -ObjFlags=0x0 - -[1400sub0] -ParameterName=Largest Sub-Index supported -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=2 -PDOMapping=0 -ObjFlags=0 - -[1400sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x200 -PDOMapping=0 -ObjFlags=0 -ParameterValue=$NODEID+0x200 - -[1400sub2] -ParameterName=Transmission Type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=255 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x1 - -[1401] -ParameterName=2. Receive PDO Parameter -ObjectType=0x9 -SubNumber=3 -ObjFlags=0x0 - -[1401sub0] -ParameterName=Largest Sub-Index supported -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=2 -PDOMapping=0 -ObjFlags=0 - -[1401sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x300 -PDOMapping=0 -ObjFlags=0 -ParameterValue=$NODEID+0x300 - -[1401sub2] -ParameterName=Transmission Type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=255 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x1 - -[1600] -ParameterName=1. Receive PDO Mapping -ObjectType=0x9 -SubNumber=9 -ObjFlags=0x0 - -[1600sub0] -ParameterName=Number of mapped Application Objects -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=2 -PDOMapping=0 -LowLimit=0 -HighLimit=8 -ObjFlags=0 -ParameterValue=3 - -[1600sub1] -ParameterName=1. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x60400010 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60400010 - -[1600sub2] -ParameterName=2. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x60c10120 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60420010 - -[1600sub3] -ParameterName=3. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60c10120 - -[1600sub4] -ParameterName=4. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1600sub5] -ParameterName=5. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1600sub6] -ParameterName=6. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1600sub7] -ParameterName=7. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1600sub8] -ParameterName=8. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601] -ParameterName=2. Receive PDO mapping -ObjectType=0x9 -SubNumber=9 -ObjFlags=0x0 - -[1601sub0] -ParameterName=Number of mapped Application Objects -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=0 -HighLimit=8 -ObjFlags=0 -ParameterValue=2 - -[1601sub1] -ParameterName=1. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x607a0020 - -[1601sub2] -ParameterName=2. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60810020 - -[1601sub3] -ParameterName=3. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601sub4] -ParameterName=4. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601sub5] -ParameterName=5. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601sub6] -ParameterName=6. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601sub7] -ParameterName=7. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1601sub8] -ParameterName=8. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1800] -ParameterName=1. Transmit PDO Parameter -ObjectType=0x9 -SubNumber=4 -ObjFlags=0x0 - -[1800sub0] -ParameterName=Largest Sub-Index supported -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=5 -PDOMapping=0 -ObjFlags=0 - -[1800sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x180 -PDOMapping=0 -ObjFlags=0 -ParameterValue=$NODEID+0x180 - -[1800sub2] -ParameterName=transmission type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=1 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x1 - -[1800sub5] -ParameterName=event timer -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=0 -HighLimit=32767 -ObjFlags=0 - -[1801] -ParameterName=2. Transmit PDO Parameter -ObjectType=0x9 -SubNumber=4 -ObjFlags=0x0 - -[1801sub0] -ParameterName=Largest Sub-Index supported -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=5 -PDOMapping=0 -ObjFlags=0 - -[1801sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x280 -PDOMapping=0 -ObjFlags=0 - -[1801sub2] -ParameterName=Transmission Type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=1 -PDOMapping=0 -ObjFlags=0 - -[1801sub5] -ParameterName=event timer -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0 - -[1802] -ParameterName=3. Transmit PDO Parameter -ObjectType=0x9 -SubNumber=4 - -[1802sub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=5 -PDOMapping=0 -LowLimit=0x02 -HighLimit=0x06 - -[1802sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x380 -PDOMapping=0 -ObjFlags=0 -ParameterValue=$NODEID+0x380 - -[1802sub2] -ParameterName=Transmission Type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=1 -PDOMapping=0 -ParameterValue=0x1 - -[1802sub5] -ParameterName=Event Timer -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[1803] -ParameterName=4. Transmit PDO Parameter -ObjectType=0x9 -SubNumber=4 - -[1803sub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=5 -PDOMapping=0 -LowLimit=0x02 -HighLimit=0x06 - -[1803sub1] -ParameterName=COB-ID used by PDO -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=$NodeID + 0x480 -PDOMapping=0 -ObjFlags=0 - -[1803sub2] -ParameterName=Transmission Type -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=254 -PDOMapping=0 - -[1803sub5] -ParameterName=Event Timer -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[1A00] -ParameterName=1. Transmit PDO Mapping -ObjectType=0x9 -SubNumber=9 -ObjFlags=0x0 - -[1A00sub0] -ParameterName=Number of mapped Application Objects -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=3 -PDOMapping=0 -LowLimit=0 -HighLimit=8 -ObjFlags=0 -ParameterValue=2 - -[1A00sub1] -ParameterName=1. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x60410010 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60410010 - -[1A00sub2] -ParameterName=2. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x60770010 -PDOMapping=0 -ObjFlags=0 -ParameterValue=0x60610008 - -[1A00sub3] -ParameterName=3. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x60640020 -PDOMapping=0 -ObjFlags=0 - -[1A00sub4] -ParameterName=4. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A00sub5] -ParameterName=5. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A00sub6] -ParameterName=6. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A00sub7] -ParameterName=7. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A00sub8] -ParameterName=8. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01] -ParameterName=2. Transmit PDO Mapping -ObjectType=0x9 -SubNumber=9 -ObjFlags=0x0 - -[1A01sub0] -ParameterName=Number of mapped Application Objects -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=2 -PDOMapping=0 -LowLimit=0 -HighLimit=8 -ObjFlags=0 - -[1A01sub1] -ParameterName=1. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x606b0020 -PDOMapping=0 -ObjFlags=0 - -[1A01sub2] -ParameterName=2. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0x606c0020 -PDOMapping=0 -ObjFlags=0 - -[1A01sub3] -ParameterName=3. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01sub4] -ParameterName=4. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01sub5] -ParameterName=5. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01sub6] -ParameterName=6. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01sub7] -ParameterName=7. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A01sub8] -ParameterName=8. mapped Object -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ObjFlags=0 - -[1A02] -ParameterName=3. Transmit PDO Mapping -ObjectType=0x9 -SubNumber=9 - -[1A02sub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=0 -HighLimit=8 -ParameterValue=2 - -[1A02sub1] -ParameterName=PDO Mapping Entry -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ParameterValue=0x60640020 - -[1A02sub2] -ParameterName=PDO Mapping Entry_2 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 -ParameterValue=0x606c0020 - -[1A02sub3] -ParameterName=PDO Mapping Entry_3 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A02sub4] -ParameterName=PDO Mapping Entry_4 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A02sub5] -ParameterName=PDO Mapping Entry_5 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A02sub6] -ParameterName=PDO Mapping Entry_6 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A02sub7] -ParameterName=PDO Mapping Entry_7 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A02sub8] -ParameterName=PDO Mapping Entry_8 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03] -ParameterName=4. Transmit PDO Mapping -ObjectType=0x9 -SubNumber=9 - -[1A03sub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=0 -HighLimit=8 - -[1A03sub1] -ParameterName=PDO Mapping Entry -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub2] -ParameterName=PDO Mapping Entry_2 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub3] -ParameterName=PDO Mapping Entry_3 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub4] -ParameterName=PDO Mapping Entry_4 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub5] -ParameterName=PDO Mapping Entry_5 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub6] -ParameterName=PDO Mapping Entry_6 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub7] -ParameterName=PDO Mapping Entry_7 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[1A03sub8] -ParameterName=PDO Mapping Entry_8 -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[6040] -ParameterName=controlword -ObjectType=0x7 -DataType=0x0006 -AccessType=rww -PDOMapping=1 - -[6041] -ParameterName=statusword -ObjectType=0x7 -DataType=0x0006 -AccessType=ro -PDOMapping=1 - -[6042] -ParameterName=vl_target_velocity -ObjectType=0x7 -DataType=0x0003 -AccessType=rww -DefaultValue=0 -PDOMapping=1 - -[6043] -ParameterName=vl_velocity_demand -ObjectType=0x7 -DataType=0x0003 -AccessType=ro -PDOMapping=1 - -[6044] -ParameterName=vl_velocity_actual_value -ObjectType=0x7 -DataType=0x0003 -AccessType=ro -PDOMapping=1 - -[6046] -ParameterName=vl_velocity_min_max_amount -ObjectType=0x8 -SubNumber=3 - -[6046sub0] -ParameterName=vl_velocity_min_max_amount_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[6046sub1] -ParameterName=vl_velocity_min_max_amount_vl_velocity_min_amount -ObjectType=0x7 -DataType=0x0007 -AccessType=rww -PDOMapping=1 - -[6046sub2] -ParameterName=vl_velocity_min_max_amount_vl_velocity_max_amount -ObjectType=0x7 -DataType=0x0007 -AccessType=rww -PDOMapping=1 - -[6048] -ParameterName=vl_velocity_acceleration -ObjectType=0x9 -SubNumber=3 - -[6048sub0] -ParameterName=vl_velocity_acceleration_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[6048sub1] -ParameterName=vl_velocity_acceleration_delta_speed -ObjectType=0x7 -DataType=0x0007 -AccessType=rww -PDOMapping=1 - -[6048sub2] -ParameterName=vl_velocity_acceleration_delta_time -ObjectType=0x7 -DataType=0x0006 -AccessType=rww -PDOMapping=1 - -[6049] -ParameterName=vl_velocity_deceleration -ObjectType=0x9 -SubNumber=3 - -[6049sub0] -ParameterName=vl_velocity_deceleration_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[6049sub1] -ParameterName=vl_velocity_deceleration_delta_speed -ObjectType=0x7 -DataType=0x0007 -AccessType=rww -PDOMapping=1 - -[6049sub2] -ParameterName=vl_velocity_deceleration_delta_time -ObjectType=0x7 -DataType=0x0006 -AccessType=rww -PDOMapping=1 - -[604C] -ParameterName=vl_dimension_factor -ObjectType=0x8 -SubNumber=3 - -[604Csub0] -ParameterName=vl_dimension_factor_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[604Csub1] -ParameterName=vl_dimension_factor_numerator -ObjectType=0x7 -DataType=0x0004 -AccessType=rw -DefaultValue=1 -PDOMapping=0 - -[604Csub2] -ParameterName=vl_dimension_factor_denominator -ObjectType=0x7 -DataType=0x0004 -AccessType=rw -DefaultValue=6000 -PDOMapping=0 - -[6060] -ParameterName=modes_of_operation -ObjectType=0x7 -DataType=0x0002 -AccessType=rw -PDOMapping=1 -ParameterValue=7 - -[6061] -ParameterName=modes_of_operation_display -ObjectType=0x7 -DataType=0x0002 -AccessType=ro -PDOMapping=1 -ObjFlags=0x1 - -[6062] -ParameterName=position_demand_value -ObjectType=0x7 -DataType=0x0004 -AccessType=ro -PDOMapping=1 - -[6064] -ParameterName=position_actual_value -ObjectType=0x7 -DataType=0x0004 -AccessType=ro -PDOMapping=1 - -[6065] -ParameterName=following_error_window -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[606B] -ParameterName=velocity_demand_value -ObjectType=0x7 -DataType=0x0004 -AccessType=ro -PDOMapping=1 - -[606C] -ParameterName=velocity_actual_value -ObjectType=0x7 -DataType=0x0004 -AccessType=ro -PDOMapping=1 - -[6073] -ParameterName=max_current -ObjectType=0x7 -DataType=0x0006 -AccessType=rww -PDOMapping=1 - -[6075] -ParameterName=motor_rated_current -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[6077] -ParameterName=torque_actual_value -ObjectType=0x7 -DataType=0x0003 -AccessType=ro -PDOMapping=1 - -[607A] -ParameterName=target_position -ObjectType=0x7 -DataType=0x0004 -AccessType=rw -PDOMapping=1 - -[607C] -ParameterName=home_offset -ObjectType=0x7 -DataType=0x0004 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[607D] -ParameterName=software_position_limit -ObjectType=0x8 -SubNumber=3 - -[607Dsub0] -ParameterName=software_position_limit_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[607Dsub1] -ParameterName=software_position_limit_min_position_limit -ObjectType=0x7 -DataType=0x0004 -AccessType=rw - -[607Dsub2] -ParameterName=software_position_limit_max_position_limit -ObjectType=0x7 -DataType=0x0004 -AccessType=rw - -[6081] -ParameterName=profile_velocity -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=1 -DefaultValue=0x2710 - -[6083] -ParameterName=profile_acceleration -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=1 - -[6086] -ParameterName=motion_profile_type -ObjectType=0x7 -DataType=0x0003 -AccessType=rw -PDOMapping=0 - -[6098] -ParameterName=homing_method -ObjectType=0x7 -DataType=0x0002 -AccessType=const -DefaultValue=0 -PDOMapping=0 -LowLimit=-128 -HighLimit=35 -ParameterValue=0 - -[60B2] -ParameterName=torque_offset -ObjectType=0x7 -DataType=0x0003 -AccessType=rww -PDOMapping=1 - -[60C0] -ParameterName=interpolation_sub_mode_select -ObjectType=0x7 -DataType=0x0003 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=-1 -HighLimit=0 -ParameterValue=0 - -[60C1] -ParameterName=interpolation_data_record -ObjectType=0x8 -SubNumber=2 - -[60C1sub0] -ParameterName=interpolation_data_record_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=1 -PDOMapping=0 - -[60C1sub1] -ParameterName=interpolation_data_record_setpoint_1 -ObjectType=0x7 -DataType=0x0004 -AccessType=rww -PDOMapping=1 - -[60C2] -ParameterName=interpolation_time_period -ObjectType=0x9 -SubNumber=3 - -[60C2sub0] -ParameterName=interpolation_time_period_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[60C2sub1] -ParameterName=interpolation_time_period_value -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=8 -PDOMapping=0 -ParameterValue=10 - -[60C2sub2] -ParameterName=interpolation_time_period_index -ObjectType=0x7 -DataType=0x0002 -AccessType=rw -DefaultValue=-3 -PDOMapping=0 - -[60C3] -ParameterName=interpolation_sync_definition -ObjectType=0x8 -SubNumber=3 - -[60C3sub0] -ParameterName=interpolation_sync_definition_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[60C3sub1] -ParameterName=syncronize_on_group -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[60C3sub2] -ParameterName=ip_sync_every_n_event -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=1 -PDOMapping=0 -LowLimit=0 -HighLimit=255 - -[60C4] -ParameterName=interpolation_data_configuration -ObjectType=0x9 -SubNumber=7 - -[60C4sub0] -ParameterName=interpolation_data_configuration_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=6 -PDOMapping=0 - -[60C4sub1] -ParameterName=interpolation_data_configuration_maximum_buffer_size -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=1 -PDOMapping=0 - -[60C4sub2] -ParameterName=interpolation_data_configuration_actual_buffer_size -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[60C4sub3] -ParameterName=interpolation_data_configuration_buffer_organization -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -LowLimit=0 -HighLimit=1 - -[60C4sub4] -ParameterName=interpolation_data_configuration_buffer_position -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0 -PDOMapping=0 - -[60C4sub5] -ParameterName=interpolation_data_configuration_size_of_data_record -ObjectType=0x7 -DataType=0x0005 -AccessType=wo -DefaultValue=1 -PDOMapping=0 - -[60C4sub6] -ParameterName=interpolation_data_configuration_buffer_clear -ObjectType=0x7 -DataType=0x0005 -AccessType=wo -DefaultValue=0 -PDOMapping=0 - -[60F4] -ParameterName=following_error_actual_value -ObjectType=0x7 -DataType=0x0004 -AccessType=ro -PDOMapping=1 -ObjFlags=0x0 - -[60FD] -ParameterName=digital_inputs -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -PDOMapping=1 -ObjFlags=0x2 - -[60FE] -ParameterName=digital_outputs -ObjectType=0x8 -SubNumber=3 - -[60FEsub0] -ParameterName=digital_outputs_highest_subindex -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 - -[60FEsub1] -ParameterName=digital_outputs_physical_outputs -ObjectType=0x7 -DataType=0x0007 -AccessType=rww -PDOMapping=1 -ObjFlags=2 - -[60FEsub2] -ParameterName=digital_outputs_bit_mask -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -PDOMapping=0 - -[6502] -ParameterName=supported_drive_modes -ObjectType=0x7 -DataType=0x0007 -AccessType=ro -DefaultValue=0x00000043 -PDOMapping=0 - -[ManufacturerObjects] -SupportedObjects=29 -1=0x2000 -2=0x2001 -3=0x2002 -4=0x2003 -5=0x2004 -6=0x2007 -7=0x2008 -8=0x2009 -9=0x200A -10=0x200B -11=0x200C -12=0x200D -13=0x200E -14=0x2010 -15=0x2011 -16=0x2012 -17=0x2013 -18=0x2020 -19=0x2021 -20=0x2022 -21=0x2023 -22=0x2024 -23=0x2030 -24=0x2031 -25=0x2032 -26=0x2033 -27=0x2034 -28=0x2041 -29=0x2050 - -[2000] -ParameterName=manufacturer_debug_flags -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ObjFlags=0x0 - -[2001] -ParameterName=debug_values_int32 -ObjectType=0x8 -SubNumber=5 - -[2001sub0] -ParameterName=nb_debug_values_int32 -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=4 -PDOMapping=0 - -[2001sub1] -ParameterName=debug_value_int32_1 -ObjectType=0x7 -DataType=0x0004 -AccessType=rwr -PDOMapping=1 - -[2001sub2] -ParameterName=debug_value_int32_2 -ObjectType=0x7 -DataType=0x0004 -AccessType=rwr -PDOMapping=1 - -[2001sub3] -ParameterName=debug_value_int32_3 -ObjectType=0x7 -DataType=0x0004 -AccessType=rwr -PDOMapping=1 - -[2001sub4] -ParameterName=debug_value_int32_4 -ObjectType=0x7 -DataType=0x0004 -AccessType=rwr -PDOMapping=1 - -[2002] -ParameterName=debug_values_float -ObjectType=0x8 -SubNumber=5 - -[2002sub0] -ParameterName=nb_debug_values_float -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=4 -PDOMapping=0 - -[2002sub1] -ParameterName=debug_value_float_1 -ObjectType=0x7 -DataType=0x0008 -AccessType=rwr -PDOMapping=1 - -[2002sub2] -ParameterName=debug_value_float_2 -ObjectType=0x7 -DataType=0x0008 -AccessType=rwr -PDOMapping=1 - -[2002sub3] -ParameterName=debug_value_float_3 -ObjectType=0x7 -DataType=0x0008 -AccessType=rwr -PDOMapping=1 - -[2002sub4] -ParameterName=debug_value_float_4 -ObjectType=0x7 -DataType=0x0008 -AccessType=rwr -PDOMapping=1 - -[2003] -ParameterName=debug_message -ObjectType=0x7 -DataType=0x0009 -AccessType=ro -PDOMapping=1 - -[2004] -ParameterName=logging -ObjectType=0x9 -SubNumber=3 -ObjFlags=0x3 - -[2004sub0] -ParameterName=nb_logging -ObjectType=0x7 -DataType=0x0005 -AccessType=const -DefaultValue=2 -PDOMapping=0 -ObjFlags=3 - -[2004sub1] -ParameterName=logging_state -ObjectType=0x7 -DataType=0x0006 -AccessType=rw -DefaultValue=0x8001 -PDOMapping=0 -ObjFlags=3 - -[2004sub2] -ParameterName=logging_trigger_time -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 -ObjFlags=3 - -[2007] -ParameterName=EEPROM_Parameters -ObjectType=0x9 -SubNumber=2 - -[2007sub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=1 -PDOMapping=0 - -[2007sub1] -ParameterName=SECT_CONFIG -ObjectType=0x7 -DataType=0x000a -AccessType=ro -PDOMapping=0 -ObjFlags=3 - -[2008] -ParameterName=Password -ObjectType=0x7 -DataType=0x0009 -AccessType=wo -PDOMapping=0 -ObjFlags=0x1 - -[2009] -ParameterName=User -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=0 -PDOMapping=0 - -[200A] -ParameterName=Disconnect_Reset -ObjectType=0x7 -DataType=0x0005 -AccessType=wo -PDOMapping=0 -ObjFlags=0x3 - -[200B] -ParameterName=error_details -ObjectType=0x9 -SubNumber=4 -DataType=0x0008 -AccessType=ro - -[200Bsub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=3 -PDOMapping=0 - -[200Bsub1] -ParameterName=detail -ObjectType=0x7 -DataType=0x0008 -AccessType=ro -PDOMapping=0 - -[200Bsub2] -ParameterName=file -ObjectType=0x7 -DataType=0x0009 -AccessType=ro -PDOMapping=0 -ObjFlags=2 - -[200Bsub3] -ParameterName=line -ObjectType=0x7 -DataType=0x0006 -AccessType=ro -PDOMapping=0 - -[200C] -ParameterName=communication_mode -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -PDOMapping=0 - -[200D] -ParameterName=pcb_temperature -ObjectType=0x9 -SubNumber=3 - -[200Dsub0] -ParameterName=Number of entries -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=2 -PDOMapping=0 - -[200Dsub1] -ParameterName=actual_pcb_temperature -ObjectType=0x7 -DataType=0x0008 -AccessType=ro -PDOMapping=1 - -[200Dsub2] -ParameterName=pcb_temperature_update_period_ms -ObjectType=0x7 -DataType=0x0007 -AccessType=rw -DefaultValue=20000 -PDOMapping=0 -LowLimit=1000 -HighLimit=3600000 - -[200E] -ParameterName=sync_timeout_factor -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=6 -PDOMapping=0 - -[2010] -ParameterName=KR_Current -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2011] -ParameterName=TN_Current -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2012] -ParameterName=TD_Current -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2013] -ParameterName=KC_Current -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2020] -ParameterName=KR_Speed -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2021] -ParameterName=TN_Speed -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2022] -ParameterName=TD_Speed -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2023] -ParameterName=KC_Speed -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2024] -ParameterName=KS_FeedForward -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2030] -ParameterName=KR_Pos -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2031] -ParameterName=TN_Pos -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2032] -ParameterName=TD_Pos -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2033] -ParameterName=KC_Pos -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2034] -ParameterName=KP_FeedForward -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2041] -ParameterName=Delta_Position -ObjectType=0x7 -DataType=0x0008 -AccessType=rw -PDOMapping=0 - -[2050] -ParameterName=extended_status -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=0 -PDOMapping=1 -ObjFlags=0x1 - -[20A0] -ParameterName=vendor_parameters_and_status -ObjectType=0x9 -SubNumber=8 - -[20A0sub7] -ParameterName=run_permitted_status -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=0 -PDOMapping=1 -ObjFlags=0x1 - -[2060] -ParameterName=brake_test -ObjectType=0x9 -SubNumber=4 - -[2060sub1] -ParameterName=brake_test_duration -ObjectType=0x7 -DataType=0x0006 -AccessType=ro -DefaultValue=2500 -PDOMapping=0 -ObjFlags=1 -ParameterValue=2500 - - -[2060sub2] -ParameterName=start_brake_test -ObjectType=0x7 -DataType=0x0005 -AccessType=rw -DefaultValue=0 -PDOMapping=0 -ParameterValue=0 - -[2060sub3] -ParameterName=brake_test_status -ObjectType=0x7 -DataType=0x0005 -AccessType=ro -DefaultValue=0 -PDOMapping=0 -ParameterValue=0 diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv deleted file mode 100644 index 79d4c95b55..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh deleted file mode 100644 index 02e441b753..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh +++ /dev/null @@ -1,4 +0,0 @@ -# copied from -# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh - -ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv deleted file mode 100644 index b94426af08..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate-if-exists;PATH;bin diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh deleted file mode 100644 index e59b749a89..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh +++ /dev/null @@ -1,5 +0,0 @@ -# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh - -if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then - ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin" -fi diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv deleted file mode 100644 index e119f32cba..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv +++ /dev/null @@ -1 +0,0 @@ -prepend-non-duplicate;CMAKE_PREFIX_PATH; diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 deleted file mode 100644 index d03facc1a4..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em - -colcon_prepend_unique_value CMAKE_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh deleted file mode 100644 index a948e685ba..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh +++ /dev/null @@ -1,3 +0,0 @@ -# generated from colcon_core/shell/template/hook_prepend_value.sh.em - -_colcon_prepend_unique_value CMAKE_PREFIX_PATH "$COLCON_CURRENT_PREFIX" diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash deleted file mode 100644 index 49782f2461..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash +++ /dev/null @@ -1,46 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.bash.in - -# source local_setup.sh from same directory as this file -_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd) -# provide AMENT_CURRENT_PREFIX to shell script -AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd) -# store AMENT_CURRENT_PREFIX to restore it before each environment hook -_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX - -# trace output -if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_this_path/local_setup.sh\"" -fi -. "$_this_path/local_setup.sh" -unset _this_path - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks -AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX -# list all environment hooks of this package - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - # restore AMENT_CURRENT_PREFIX for each environment hook - AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - . "$_hook" - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -unset _package_local_setup_AMENT_CURRENT_PREFIX -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv deleted file mode 100644 index 36167c5b9a..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv +++ /dev/null @@ -1,2 +0,0 @@ -source;share/moveit_resources_prbt_support/environment/ament_prefix_path.sh -source;share/moveit_resources_prbt_support/environment/path.sh diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh deleted file mode 100644 index cce3209152..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh +++ /dev/null @@ -1,184 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.sh.in - -# since this file is sourced use either the provided AMENT_CURRENT_PREFIX -# or fall back to the destination set at configure time -: ${AMENT_CURRENT_PREFIX:="/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support"} -if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then - if [ -z "$COLCON_CURRENT_PREFIX" ]; then - echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \ - "exist. Consider sourcing a different extension than '.sh'." 1>&2 - else - AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" - fi -fi - -# function to append values to environment variables -# using colons as separators and avoiding leading separators -ament_append_value() { - # arguments - _listname="$1" - _value="$2" - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # avoid leading separator - eval _values=\"\$$_listname\" - if [ -z "$_values" ]; then - eval export $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - _ament_append_value_IFS=$IFS - unset IFS - eval export $_listname=\"\$$_listname:$_value\" - #eval echo "append list \$$_listname" - IFS=$_ament_append_value_IFS - unset _ament_append_value_IFS - fi - unset _values - - unset _value - unset _listname -} - -# function to append non-duplicate values to environment variables -# using colons as separators and avoiding leading separators -ament_append_unique_value() { - # arguments - _listname=$1 - _value=$2 - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # check if the list contains the value - eval _values=\$$_listname - _duplicate= - _ament_append_unique_value_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array _values - fi - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - if [ $_item = $_value ]; then - _duplicate=1 - fi - done - unset _item - - # append only non-duplicates - if [ -z "$_duplicate" ]; then - # avoid leading separator - if [ -z "$_values" ]; then - eval $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - unset IFS - eval $_listname=\"\$$_listname:$_value\" - #eval echo "append list \$$_listname" - fi - fi - IFS=$_ament_append_unique_value_IFS - unset _ament_append_unique_value_IFS - unset _duplicate - unset _values - - unset _value - unset _listname -} - -# function to prepend non-duplicate values to environment variables -# using colons as separators and avoiding trailing separators -ament_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - #echo "listname $_listname" - #eval echo "list value \$$_listname" - #echo "value $_value" - - # check if the list contains the value - eval _values=\"\$$_listname\" - _duplicate= - _ament_prepend_unique_value_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array _values - fi - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - if [ "$_item" = "$_value" ]; then - _duplicate=1 - fi - done - unset _item - - # prepend only non-duplicates - if [ -z "$_duplicate" ]; then - # avoid trailing separator - if [ -z "$_values" ]; then - eval export $_listname=\"$_value\" - #eval echo "set list \$$_listname" - else - # field separator must not be a colon - unset IFS - eval export $_listname=\"$_value:\$$_listname\" - #eval echo "prepend list \$$_listname" - fi - fi - IFS=$_ament_prepend_unique_value_IFS - unset _ament_prepend_unique_value_IFS - unset _duplicate - unset _values - - unset _value - unset _listname -} - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# list all environment hooks of this package -ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh" -ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/moveit_resources_prbt_support/environment/path.sh" - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - if [ "$AMENT_SHELL" = "zsh" ]; then - ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS - fi - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - if [ -f "$_hook" ]; then - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - # trace output - if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_hook\"" - fi - . "$_hook" - fi - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -# reset AMENT_CURRENT_PREFIX after each package -# allowing to source multiple package-level setup files -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh deleted file mode 100644 index fe161be53d..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh +++ /dev/null @@ -1,59 +0,0 @@ -# generated from ament_package/template/package_level/local_setup.zsh.in - -AMENT_SHELL=zsh - -# source local_setup.sh from same directory as this file -_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd) -# provide AMENT_CURRENT_PREFIX to shell script -AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd) -# store AMENT_CURRENT_PREFIX to restore it before each environment hook -_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX - -# function to convert array-like strings into arrays -# to wordaround SH_WORD_SPLIT not being set -ament_zsh_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# trace output -if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then - echo "# . \"$_this_path/local_setup.sh\"" -fi -# the package-level local_setup file unsets AMENT_CURRENT_PREFIX -. "$_this_path/local_setup.sh" -unset _this_path - -# unset AMENT_ENVIRONMENT_HOOKS -# if not appending to them for return -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - unset AMENT_ENVIRONMENT_HOOKS -fi - -# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks -AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX -# list all environment hooks of this package - -# source all shell-specific environment hooks of this package -# if not returning them -if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then - _package_local_setup_IFS=$IFS - IFS=":" - for _hook in $AMENT_ENVIRONMENT_HOOKS; do - # restore AMENT_CURRENT_PREFIX for each environment hook - AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX - # restore IFS before sourcing other files - IFS=$_package_local_setup_IFS - . "$_hook" - done - unset _hook - IFS=$_package_local_setup_IFS - unset _package_local_setup_IFS - unset AMENT_ENVIRONMENT_HOOKS -fi - -unset _package_local_setup_AMENT_CURRENT_PREFIX -unset AMENT_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae deleted file mode 100644 index 48d7f2088b..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae +++ /dev/null @@ -1,109 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T14:46:40 - 2019-01-15T14:46:40 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - -25.4994 1001.4 -2.59834 -31.78964 1001.4 -6.756204 -32.5 1001.4 0 -32.5 998.9 0 -32.5 1001.4 0 -31.78964 1001.4 -6.756204 -26.99976 1001.4 0 -31.78964 1001.4 6.756204 -31.7898 998.9 6.75713 -31.78964 1001.4 6.756204 -32.5 1001.4 0 -26.59765 1001.4 -1.500361 -32.5 998.9 0 29.68938 1001.4 -13.22047 -29.68938 1001.4 -13.22047 -31.7898 998.9 -6.75713 -29.68938 1001.4 -13.22047 31.78964 1001.4 -6.756204 -24 1001.4 -3 26.29395 1001.4 -19.10152 -26.29395 1001.4 -19.10152 -29.69023 998.9 -13.21894 -26.29395 1001.4 -19.10152 21.74586 1001.4 -24.15253 -21.74586 1001.4 -24.15253 -26.29305 998.9 -19.10302 -21.74586 1001.4 -24.15253 16.25 1001.4 -28.14583 -16.25 1001.4 -28.14583 -21.74674 998.9 -24.15221 -16.25 1001.4 -28.14583 10.04377 1001.4 -30.90873 -10.04377 1001.4 -30.90873 -16.25 998.9 -28.14583 -10.04377 1001.4 -30.90873 3.395426 1001.4 -32.32199 -3.395426 1001.4 -32.32199 -10.04305 998.9 -30.90934 -3.395426 1001.4 -32.32199 -3.397175 998.9 -32.32196 3.395426 1001.4 -32.32199 3.397175 998.9 -32.32196 10.04377 1001.4 -30.90873 10.04305 998.9 -30.90934 16.25 1001.4 -28.14583 16.25 998.9 -28.14583 21.74586 1001.4 -24.15253 21.74674 998.9 -24.15221 26.29395 1001.4 -19.10152 26.29305 998.9 -19.10302 29.68938 1001.4 -13.22047 29.69023 998.9 -13.21894 31.78964 1001.4 -6.756204 -21.00024 1001.4 0 32.5 1001.4 0 31.7898 998.9 -6.75713 32.5 1001.4 0 -22.50061 1001.4 -2.59834 -21.40235 1001.4 -1.500361 31.78964 1001.4 6.756204 32.5 998.9 0 32.5 1001.4 0 31.78964 1001.4 6.756204 -24 1001.4 3 -22.50061 1001.4 2.59834 -21.40235 1001.4 1.500361 32.5 998.9 0 -29.68938 1001.4 13.22047 29.68938 1001.4 13.22047 31.7898 998.9 6.75713 29.68938 1001.4 13.22047 -26.29395 1001.4 19.10152 26.29395 1001.4 19.10152 29.69023 998.9 13.21894 26.29395 1001.4 19.10152 -21.74586 1001.4 24.15253 21.74586 1001.4 24.15253 26.29305 998.9 19.10302 21.74586 1001.4 24.15253 -16.25 1001.4 28.14583 16.25 1001.4 28.14583 21.74674 998.9 24.15221 16.25 1001.4 28.14583 -10.04377 1001.4 30.90873 10.04377 1001.4 30.90873 16.25 998.9 28.14583 10.04377 1001.4 30.90873 -3.395426 1001.4 32.32199 3.395426 1001.4 32.32199 10.04305 998.9 30.90934 3.395426 1001.4 32.32199 3.397175 998.9 32.32196 -3.395426 1001.4 32.32199 -3.397175 998.9 32.32196 -10.04377 1001.4 30.90873 -10.04305 998.9 30.90934 -16.25 1001.4 28.14583 -16.25 998.9 28.14583 -21.74586 1001.4 24.15253 -21.74674 998.9 24.15221 -26.29395 1001.4 19.10152 -26.29305 998.9 19.10302 -29.68938 1001.4 13.22047 -29.69023 998.9 13.21894 -26.59765 1001.4 1.500361 -25.4994 1001.4 2.59834 -24 1007.9 -3 -24 1001.4 -3 -25.4994 1001.4 -2.59834 -22.5 1007.9 -2.598076 -22.50061 1001.4 -2.59834 -24 1001.4 -3 -24 1007.9 -3 -25.5 1007.9 -2.598076 -26.59765 1001.4 -1.500361 -26.59808 1007.9 -1.5 -26.99976 1001.4 0 -27 1007.9 0 -26.59765 1001.4 1.500361 -26.59808 1007.9 1.5 -25.4994 1001.4 2.59834 -25.5 1007.9 2.598076 -24 1001.4 3 -24 1007.9 3 -24 1001.4 3 -22.50061 1001.4 2.59834 -24 1007.9 3 -22.5 1007.9 2.598076 -21.40235 1001.4 1.500361 -21.40192 1007.9 1.5 -21.00024 1001.4 0 -21 1007.9 0 -21.40235 1001.4 -1.500361 -21.40192 1007.9 -1.5 -28.5 994.4 0 -32.5 998.9 0 -31.7898 998.9 -6.75713 -27.78544 994.4 6.341847 -32.5 998.9 0 -28.5 994.4 0 -31.7898 998.9 6.75713 -27.78544 994.4 -6.341847 -29.69023 998.9 -13.21894 -25.67761 994.4 -12.36569 -26.29305 998.9 -19.10302 -22.2822 994.4 -17.76946 -21.74674 998.9 -24.15221 -17.76946 994.4 -22.2822 -16.25 998.9 -28.14583 -12.36569 994.4 -25.67761 -10.04305 998.9 -30.90934 -6.341847 994.4 -27.78544 -3.397175 998.9 -32.32196 0 994.4 -28.5 3.397175 998.9 -32.32196 6.341847 994.4 -27.78544 10.04305 998.9 -30.90934 12.36569 994.4 -25.67761 16.25 998.9 -28.14583 17.76946 994.4 -22.2822 21.74674 998.9 -24.15221 22.2822 994.4 -17.76946 26.29305 998.9 -19.10302 25.67761 994.4 -12.36569 29.69023 998.9 -13.21894 27.78544 994.4 -6.341847 31.7898 998.9 -6.75713 32.5 998.9 0 28.5 994.4 0 31.7898 998.9 6.75713 28.5 994.4 0 32.5 998.9 0 -28.5 991.9 0 -28.5 994.4 0 -27.78544 994.4 -6.341847 -27.78535 991.9 6.340377 -28.5 994.4 0 -28.5 991.9 0 -27.78544 994.4 6.341847 -27.78535 991.9 -6.340377 -25.67761 994.4 -12.36569 -25.6765 991.9 -12.36724 -22.2822 994.4 -17.76946 -22.28293 991.9 -17.76848 -17.76946 994.4 -22.2822 -17.76975 991.9 -22.28136 -12.36569 994.4 -25.67761 -12.36372 991.9 -25.67831 -6.341847 994.4 -27.78544 -6.343652 991.9 -27.78491 0 994.4 -28.5 0 991.9 -28.4995 6.341847 994.4 -27.78544 6.343652 991.9 -27.78491 12.36569 994.4 -25.67761 12.36372 991.9 -25.67831 17.76946 994.4 -22.2822 17.76975 991.9 -22.28136 22.2822 994.4 -17.76946 22.28293 991.9 -17.76848 25.67761 994.4 -12.36569 25.6765 991.9 -12.36724 27.78544 994.4 -6.341847 27.78535 991.9 -6.340377 28.5 994.4 0 28.5 991.9 0 27.78544 994.4 6.341847 28.5 991.9 0 28.5 994.4 0 27.78544 994.4 6.341847 28.5 991.9 0 -28.5 991.9 0 -27.78535 991.9 -6.340377 27.78535 991.9 6.340377 -27.78535 991.9 6.340377 27.78535 991.9 -6.340377 -25.6765 991.9 -12.36724 25.6765 991.9 -12.36724 -22.28293 991.9 -17.76848 22.28293 991.9 -17.76848 -17.76975 991.9 -22.28136 17.76975 991.9 -22.28136 -12.36372 991.9 -25.67831 12.36372 991.9 -25.67831 -6.343652 991.9 -27.78491 6.343652 991.9 -27.78491 0 991.9 -28.4995 27.78535 991.9 6.340377 25.6765 991.9 12.36724 -25.6765 991.9 12.36724 -25.6765 991.9 12.36724 22.28293 991.9 17.76848 -22.28293 991.9 17.76848 -25.67761 994.4 12.36569 -22.28293 991.9 17.76848 17.76975 991.9 22.28136 -17.76975 991.9 22.28136 -22.2822 994.4 17.76946 -17.76975 991.9 22.28136 12.36372 991.9 25.67831 -12.36372 991.9 25.67831 -17.76946 994.4 22.2822 -12.36372 991.9 25.67831 6.343652 991.9 27.78491 -6.343652 991.9 27.78491 -12.36569 994.4 25.67761 -6.343652 991.9 27.78491 0 991.9 28.4995 -6.341847 994.4 27.78544 0 991.9 28.4995 0 994.4 28.5 6.343652 991.9 27.78491 6.341847 994.4 27.78544 12.36372 991.9 25.67831 12.36569 994.4 25.67761 17.76975 991.9 22.28136 17.76946 994.4 22.2822 22.28293 991.9 17.76848 22.2822 994.4 17.76946 25.6765 991.9 12.36724 25.67761 994.4 12.36569 29.69023 998.9 13.21894 25.67761 994.4 12.36569 26.29305 998.9 19.10302 22.2822 994.4 17.76946 21.74674 998.9 24.15221 17.76946 994.4 22.2822 16.25 998.9 28.14583 12.36569 994.4 25.67761 10.04305 998.9 30.90934 6.341847 994.4 27.78544 3.397175 998.9 32.32196 0 994.4 28.5 -3.397175 998.9 32.32196 -6.341847 994.4 27.78544 -10.04305 998.9 30.90934 -12.36569 994.4 25.67761 -16.25 998.9 28.14583 -17.76946 994.4 22.2822 -21.74674 998.9 24.15221 -22.2822 994.4 17.76946 -26.29305 998.9 19.10302 -25.67761 994.4 12.36569 -29.69023 998.9 13.21894 -22.5 1007.9 2.598076 -22.5 1007.9 -2.598076 -24 1007.9 -3 -24 1007.9 3 -25.5 1007.9 -2.598076 -21.40192 1007.9 1.5 -21.40192 1007.9 -1.5 -21 1007.9 0 -25.5 1007.9 2.598076 -26.59808 1007.9 -1.5 -26.59808 1007.9 1.5 -27 1007.9 0 - - - - - - - - - - 0 1 2.68571e-6 -0.9945221 0 -0.1045275 -0.9945189 0 -0.1045576 -0.9781579 1.22075e-4 -0.2078635 0 1 -3.28492e-6 -0.9781441 1.22077e-4 0.2079281 -0.9781517 1.22074e-4 0.2078927 -0.9945221 0 0.1045275 0 1 0 0 1 -1.18338e-4 0 1 2.54419e-5 -0.9781441 1.22077e-4 -0.2079281 -0.9135232 6.10379e-5 -0.4067869 0 1 -1.90088e-5 0 1 -3.27134e-5 0 1 -1.11469e-4 0 1 1.10517e-5 -0.9135622 6.10384e-5 -0.4066991 -0.8090448 6.10393e-5 -0.587747 0 1 -2.2372e-5 0 1 4.44544e-6 -0.8089907 6.10375e-5 -0.5878214 -0.6691013 1.22077e-4 -0.7431712 0 1 4.51477e-5 -0.6691334 1.22077e-4 -0.7431423 -0.4999665 0 -0.8660449 0 1 -4.49833e-5 0 1 -3.51915e-5 -0.3090316 1.22074e-4 -0.9510518 0 1 1.01754e-4 -0.3089764 1.22077e-4 -0.9510697 -0.1044671 6.10383e-5 -0.9945284 0 1 6.87988e-5 -0.1045576 3.05189e-5 -0.9945189 0.1044671 3.05192e-5 -0.9945284 0.1045576 6.10378e-5 -0.9945189 0.309004 1.22076e-4 -0.9510608 0.3089764 1.22077e-4 -0.9510697 0.4999893 0 -0.8660317 0.6691013 1.22077e-4 -0.7431712 0.6691334 1.22077e-4 -0.7431423 0.8090303 6.10382e-5 -0.587767 0.8089802 6.1039e-5 -0.5878359 0.9135345 6.10386e-5 -0.4067614 0.9135735 6.10392e-5 -0.4066736 0.9781517 1.22074e-4 -0.2078927 0 1 -7.76747e-6 0.9781441 1.22077e-4 -0.2079281 0.9945221 0 -0.1045275 0 1 9.53667e-5 0 1 1.21736e-4 0 1 6.53611e-6 0.9945221 0 0.1045275 0.9945189 0 0.1045576 0.9781579 1.22075e-4 0.2078635 0 1 -9.73282e-5 0 1 -2.54419e-5 0.9781441 1.22077e-4 0.2079281 0.9135232 6.10379e-5 0.4067869 0 1 1.90088e-5 0 1 -1.10517e-5 0.9135622 6.10384e-5 0.4066991 0.8090448 6.10393e-5 0.587747 0 1 2.2372e-5 0 1 -4.44544e-6 0.8089907 6.10375e-5 0.5878214 0.6691013 1.22077e-4 0.7431712 0 1 -4.51477e-5 0.6691334 1.22077e-4 0.7431423 0.4999665 0 0.8660449 0 1 4.49833e-5 0 1 3.51915e-5 0.3090316 1.22074e-4 0.9510518 0 1 -1.01754e-4 0.3089764 1.22077e-4 0.9510697 0.1044671 6.10383e-5 0.9945284 0 1 -6.87988e-5 0.1045576 3.05189e-5 0.9945189 -0.1044671 3.05192e-5 0.9945284 -0.1045576 6.10378e-5 0.9945189 -0.309004 1.22076e-4 0.9510608 -0.3089764 1.22077e-4 0.9510697 -0.4999893 0 0.8660317 -0.6691013 1.22077e-4 0.7431712 -0.6691334 1.22077e-4 0.7431423 -0.8090303 6.10382e-5 0.587767 -0.8089802 6.1039e-5 0.5878359 -0.9135345 6.10386e-5 0.4067614 -0.9135735 6.10392e-5 0.4066736 0 1 1.11469e-4 -0.2588022 0 -0.9659304 -0.2587376 0 -0.9659477 -0.4999074 0 -0.8660789 0.5000025 0 -0.866024 0.4999074 0 -0.8660789 0.2587453 0 -0.9659456 0.2588022 0 -0.9659304 -0.5000025 0 -0.866024 -0.8659768 -3.0519e-5 -0.5000844 -0.8660317 0 -0.4999893 -1 -3.05185e-5 0 -0.8659768 0 0.5000844 -0.8660317 -3.05188e-5 0.4999893 -0.4999074 0 0.8660789 -0.5000025 0 0.866024 -0.2587737 0 0.965938 0.2588022 0 0.9659304 0.2587376 0 0.9659477 0.4999074 0 0.8660789 -0.2588022 0 0.9659304 0.5000025 0 0.866024 0.8659768 -3.0519e-5 0.5000844 0.8660317 0 0.4999893 1 -3.05185e-5 0 0.8659768 0 -0.5000844 0.8660317 -3.05188e-5 -0.4999893 -0.7430429 -0.6643653 -0.08066135 -0.7451192 -0.6623214 -0.07828098 -0.7320972 -0.6636424 -0.1536647 -0.7272366 -0.6665344 0.1638869 -0.7430528 -0.6643131 0.08099812 -0.7447675 -0.6620292 0.08389812 -0.7313593 -0.6648277 0.152046 -0.7260594 -0.6674925 -0.1652022 -0.6853744 -0.6622712 -0.3027525 -0.6695508 -0.6690015 -0.3227052 -0.6081908 -0.6612336 -0.4391744 -0.5799239 -0.6700773 -0.4633409 -0.5038744 -0.6604997 -0.5566424 -0.4617599 -0.6708183 -0.5803281 -0.3770033 -0.6600076 -0.6498143 -0.3209741 -0.671308 -0.6680729 -0.2331983 -0.6597061 -0.7144273 -0.1645012 -0.6715557 -0.7224626 -0.07889223 -0.6595514 -0.7475079 0 -0.6716346 -0.7408825 0.07889223 -0.6595514 -0.7475079 0.1645012 -0.6715557 -0.7224626 0.2331983 -0.6597061 -0.7144273 0.3209675 -0.6712943 -0.6680898 0.3770033 -0.6600076 -0.6498143 0.4617599 -0.6708183 -0.5803281 0.5038744 -0.6604997 -0.5566424 0.5799239 -0.6700773 -0.4633409 0.6081908 -0.6612336 -0.4391744 0.6695508 -0.6690015 -0.3227052 0.6853744 -0.6622712 -0.3027525 0.7272366 -0.6665344 -0.1638869 0.7313593 -0.6648277 -0.152046 0.7430528 -0.6643131 -0.08099812 0.7447675 -0.6620292 -0.08389812 0.7320972 -0.6636424 0.1536647 0.7430429 -0.6643653 0.08066135 0.7451174 -0.6623198 0.07831132 -0.993711 0 -0.1119756 -0.9937145 0 -0.1119455 -0.9749163 -1.52593e-4 -0.222572 -0.9749362 -1.52596e-4 0.222485 -0.993711 0 0.1119756 -0.9937075 0 0.1120057 -0.974923 -1.52594e-4 0.2225431 -0.9749362 -1.52596e-4 -0.222485 -0.9009933 -1.22078e-4 -0.4338331 -0.9009518 -9.1557e-5 -0.4339193 -0.7818266 0 -0.6234959 -0.7818683 0 -0.6234438 -0.6234437 -1.52595e-4 -0.7818682 -0.6234773 -1.83115e-4 -0.7818415 -0.4339441 -9.15558e-5 -0.9009398 -0.4338331 -6.10388e-5 -0.9009933 -0.222456 -3.05194e-5 -0.9749428 -0.2225431 -3.05188e-5 -0.974923 0 -1.83111e-4 -1 0.222456 -3.05194e-5 -0.9749428 0.2225431 -3.05188e-5 -0.974923 0.4339193 -6.1038e-5 -0.9009518 0.4338331 -9.15582e-5 -0.9009933 0.6234773 -1.83115e-4 -0.7818415 0.6235108 -1.52597e-4 -0.7818148 0.7818148 0 -0.6235108 0.7818415 0 -0.6234773 0.9009933 -9.15582e-5 -0.4338331 0.9009518 -1.22076e-4 -0.4339193 0.974923 -1.52594e-4 -0.2225431 0.9749362 -1.52596e-4 -0.222485 0.993711 0 -0.1119756 0.9937075 0 -0.1120057 0.9749163 -1.52593e-4 0.222572 0.993711 0 0.1119756 0.9937145 0 0.1119455 0.7260594 -0.6674925 0.1652022 0 -1 -6.41762e-6 0 -1 0 0 -1 6.58268e-6 0 -1 4.37375e-6 0 -1 1.94224e-5 0 -1 8.08909e-6 0 -1 3.74946e-5 0 -1 -7.30767e-5 0.9749362 -1.52596e-4 0.222485 0 -1 -4.73297e-6 -0.9009518 -1.22076e-4 0.4339193 -0.9009933 -9.15582e-5 0.4338331 -0.7818415 0 0.6234773 0 -1 2.43554e-5 -0.7817999 0 0.6235294 -0.6235108 -1.52597e-4 0.7818148 0 -1 -3.88449e-5 0 -1 -1.1626e-5 -0.6234773 -1.83115e-4 0.7818415 -0.4338331 -9.15582e-5 0.9009933 0 -1 7.30767e-5 -0.4339441 -6.10372e-5 0.9009398 -0.2225431 -3.05188e-5 0.974923 0 -1 -7.49892e-5 -0.222456 -3.05194e-5 0.9749428 0 -1.83111e-4 1 0.222572 -3.05186e-5 0.9749163 0.222456 -3.05194e-5 0.9749428 0.4338331 -6.10388e-5 0.9009933 0.4339193 -9.1557e-5 0.9009518 0.6234773 -1.83115e-4 0.7818415 0.6234586 -1.52599e-4 0.7818564 0.7818683 0 0.6234438 0.7818415 0 0.6234773 0.9009518 -9.1557e-5 0.4339193 0.9009933 -1.22078e-4 0.4338331 0.6853744 -0.6622712 0.3027525 0.6695508 -0.6690015 0.3227052 0.6081908 -0.6612336 0.4391744 0.5799239 -0.6700773 0.4633409 0.5038744 -0.6604997 0.5566424 0.4617599 -0.6708183 0.5803281 0.3770033 -0.6600076 0.6498143 0.3209741 -0.671308 0.6680729 0.2331983 -0.6597061 0.7144273 0.1645012 -0.6715557 0.7224626 0.07889223 -0.6595514 0.7475079 0 -0.6716346 0.7408825 -0.07889223 -0.6595514 0.7475079 -0.1645012 -0.6715557 0.7224626 -0.2331983 -0.6597061 0.7144273 -0.3209675 -0.6712943 0.6680898 -0.3770033 -0.6600076 0.6498143 -0.4617599 -0.6708183 0.5803281 -0.5038744 -0.6604997 0.5566424 -0.5799239 -0.6700773 0.4633409 -0.6081908 -0.6612336 0.4391744 -0.6695508 -0.6690015 0.3227052 -0.6853744 -0.6622712 0.3027525 - - - - - - - - - - 0.05798298 0.02975195 0.06425899 0.02560299 0.06496697 0.03234595 0.06504899 0.03234595 0.06496697 0.03234595 0.06425899 0.02560299 0.05947995 0.03234595 0.06496697 0.03234595 0.06425899 0.03908896 0.06433796 0.03910696 0.06425899 0.03908896 0.06496697 0.03234595 0.05907899 0.0308479 0.05798298 0.02975195 0.06496697 0.03234595 0.05947995 0.03234595 0.05907899 0.0308479 0.06496697 0.03234595 0.06433796 0.03910696 0.06496697 0.03234595 0.06504899 0.03234595 0.002884984 0.01915097 0.06216388 0.01915097 0.06425899 0.02560299 0.06433796 0.02558499 0.06425899 0.02560299 0.06216388 0.01915097 7.9e-4 0.02560299 0.002884984 0.01915097 0.06425899 0.02560299 0.05648595 0.02935099 7.9e-4 0.02560299 0.06425899 0.02560299 0.05798298 0.02975195 0.05648595 0.02935099 0.06425899 0.02560299 0.06433796 0.02558499 0.06504899 0.03234595 0.06425899 0.02560299 0.006272971 0.01327997 0.05877488 0.01327997 0.06216388 0.01915097 0.06223791 0.01911896 0.06216388 0.01915097 0.05877488 0.01327997 0.002884984 0.01915097 0.006272971 0.01327997 0.06216388 0.01915097 0.06223791 0.01911896 0.06433796 0.02558499 0.06216388 0.01915097 0.01081198 0.008237957 0.05423599 0.008237957 0.05877488 0.01327997 0.05883991 0.01323091 0.05877488 0.01327997 0.05423599 0.008237957 0.006272971 0.01327997 0.01081198 0.008237957 0.05877488 0.01327997 0.05883991 0.01323091 0.06223791 0.01911896 0.05877488 0.01327997 0.01629799 0.004250943 0.04874998 0.004250943 0.05423599 0.008237957 0.05429196 0.008177995 0.05423599 0.008237957 0.04874998 0.004250943 0.01081198 0.008237957 0.01629799 0.004250943 0.05423599 0.008237957 0.05429196 0.008177995 0.05883991 0.01323091 0.05423599 0.008237957 0.02249497 0.001491904 0.04255396 0.001491904 0.04874998 0.004250943 0.04879099 0.004179954 0.04874998 0.004250943 0.04255396 0.001491904 0.01629799 0.004250943 0.02249497 0.001491904 0.04874998 0.004250943 0.04879099 0.004179954 0.05429196 0.008177995 0.04874998 0.004250943 0.02913397 8.1e-5 0.03591489 8.1e-5 0.04255396 0.001491904 0.04257798 0.001413941 0.04255396 0.001491904 0.03591489 8.1e-5 0.02249497 0.001491904 0.02913397 8.1e-5 0.04255396 0.001491904 0.04257798 0.001413941 0.04879099 0.004179954 0.04255396 0.001491904 0.03592497 0 0.03591489 8.1e-5 0.02913397 8.1e-5 0.03592497 0 0.04257798 0.001413941 0.03591489 8.1e-5 0.02912288 0 0.02913397 8.1e-5 0.02249497 0.001491904 0.02912288 0 0.03592497 0 0.02913397 8.1e-5 0.02247095 0.001413941 0.02249497 0.001491904 0.01629799 0.004250943 0.02247095 0.001413941 0.02912288 0 0.02249497 0.001491904 0.016258 0.004179954 0.01629799 0.004250943 0.01081198 0.008237957 0.016258 0.004179954 0.02247095 0.001413941 0.01629799 0.004250943 0.0107569 0.008177995 0.01081198 0.008237957 0.006272971 0.01327997 0.0107569 0.008177995 0.016258 0.004179954 0.01081198 0.008237957 0.006207883 0.01323091 0.006272971 0.01327997 0.002884984 0.01915097 0.006207883 0.01323091 0.0107569 0.008177995 0.006272971 0.01327997 0.002809882 0.01911896 0.002884984 0.01915097 7.9e-4 0.02560299 0.002809882 0.01911896 0.006207883 0.01323091 0.002884984 0.01915097 0.05349195 0.03234595 8.1e-5 0.03234595 7.9e-4 0.02560299 7.1e-4 0.02558499 7.9e-4 0.02560299 8.1e-5 0.03234595 0.05498999 0.02975195 7.9e-4 0.02560299 0.05648595 0.02935099 0.05389297 0.0308479 0.05349195 0.03234595 7.9e-4 0.02560299 0.05498999 0.02975195 0.05389297 0.0308479 7.9e-4 0.02560299 7.1e-4 0.02558499 0.002809882 0.01911896 7.9e-4 0.02560299 0.06425899 0.03908896 7.9e-4 0.03908896 8.1e-5 0.03234595 0 0.03234595 8.1e-5 0.03234595 7.9e-4 0.03908896 0.05648595 0.03534096 0.06425899 0.03908896 8.1e-5 0.03234595 0.05498999 0.03494 0.05648595 0.03534096 8.1e-5 0.03234595 0.05389297 0.03384399 0.05498999 0.03494 8.1e-5 0.03234595 0.05349195 0.03234595 0.05389297 0.03384399 8.1e-5 0.03234595 0 0.03234595 7.1e-4 0.02558499 8.1e-5 0.03234595 0.06216388 0.045542 0.002884984 0.045542 7.9e-4 0.03908896 7.1e-4 0.03910696 7.9e-4 0.03908896 0.002884984 0.045542 0.06425899 0.03908896 0.06216388 0.045542 7.9e-4 0.03908896 7.1e-4 0.03910696 0 0.03234595 7.9e-4 0.03908896 0.05877488 0.05141192 0.006272971 0.05141192 0.002884984 0.045542 0.002809882 0.04557293 0.002884984 0.045542 0.006272971 0.05141192 0.06216388 0.045542 0.05877488 0.05141192 0.002884984 0.045542 0.002809882 0.04557293 7.1e-4 0.03910696 0.002884984 0.045542 0.05423599 0.056454 0.01081198 0.056454 0.006272971 0.05141192 0.006207883 0.05146098 0.006272971 0.05141192 0.01081198 0.056454 0.05877488 0.05141192 0.05423599 0.056454 0.006272971 0.05141192 0.006207883 0.05146098 0.002809882 0.04557293 0.006272971 0.05141192 0.04874998 0.06044089 0.01629799 0.06044089 0.01081198 0.056454 0.0107569 0.05651396 0.01081198 0.056454 0.01629799 0.06044089 0.05423599 0.056454 0.04874998 0.06044089 0.01081198 0.056454 0.0107569 0.05651396 0.006207883 0.05146098 0.01081198 0.056454 0.04255396 0.06319999 0.02249497 0.06319999 0.01629799 0.06044089 0.016258 0.06051188 0.01629799 0.06044089 0.02249497 0.06319999 0.04874998 0.06044089 0.04255396 0.06319999 0.01629799 0.06044089 0.016258 0.06051188 0.0107569 0.05651396 0.01629799 0.06044089 0.03591489 0.06461095 0.02913397 0.06461095 0.02249497 0.06319999 0.02247095 0.06327795 0.02249497 0.06319999 0.02913397 0.06461095 0.04255396 0.06319999 0.03591489 0.06461095 0.02249497 0.06319999 0.02247095 0.06327795 0.016258 0.06051188 0.02249497 0.06319999 0.02912288 0.06469196 0.02913397 0.06461095 0.03591489 0.06461095 0.02912288 0.06469196 0.02247095 0.06327795 0.02913397 0.06461095 0.03592497 0.06469196 0.03591489 0.06461095 0.04255396 0.06319999 0.03592497 0.06469196 0.02912288 0.06469196 0.03591489 0.06461095 0.04257798 0.06327795 0.04255396 0.06319999 0.04874998 0.06044089 0.04257798 0.06327795 0.03592497 0.06469196 0.04255396 0.06319999 0.04879099 0.06051188 0.04874998 0.06044089 0.05423599 0.056454 0.04879099 0.06051188 0.04257798 0.06327795 0.04874998 0.06044089 0.05429196 0.05651396 0.05423599 0.056454 0.05877488 0.05141192 0.05429196 0.05651396 0.04879099 0.06051188 0.05423599 0.056454 0.05883991 0.05146098 0.05877488 0.05141192 0.06216388 0.045542 0.05883991 0.05146098 0.05429196 0.05651396 0.05877488 0.05141192 0.06223791 0.04557293 0.06216388 0.045542 0.06425899 0.03908896 0.06223791 0.04557293 0.05883991 0.05146098 0.06216388 0.045542 0.05907899 0.03384399 0.05947995 0.03234595 0.06425899 0.03908896 0.05798298 0.03494 0.05907899 0.03384399 0.06425899 0.03908896 0.05648595 0.03534096 0.05798298 0.03494 0.06425899 0.03908896 0.06433796 0.03910696 0.06223791 0.04557293 0.06425899 0.03908896 0.05633199 0.02936995 0.05648595 0.02935099 0.05798298 0.02975195 0.05484396 0.029769 0.05498999 0.02975195 0.05648595 0.02935099 0.05484396 0.029769 0.05648595 0.02935099 0.05633199 0.02936995 0.05781888 0.029769 0.05798298 0.02975195 0.05907899 0.0308479 0.05781888 0.029769 0.05633199 0.02936995 0.05798298 0.02975195 0.05890792 0.03085798 0.05907899 0.0308479 0.05947995 0.03234595 0.05781888 0.029769 0.05907899 0.0308479 0.05890792 0.03085798 0.0593059 0.03234595 0.05947995 0.03234595 0.05907899 0.03384399 0.05890792 0.03085798 0.05947995 0.03234595 0.0593059 0.03234595 0.05890792 0.03383398 0.05907899 0.03384399 0.05798298 0.03494 0.0593059 0.03234595 0.05907899 0.03384399 0.05890792 0.03383398 0.05781888 0.03492289 0.05798298 0.03494 0.05648595 0.03534096 0.05890792 0.03383398 0.05798298 0.03494 0.05781888 0.03492289 0.05633199 0.03532195 0.05648595 0.03534096 0.05498999 0.03494 0.05781888 0.03492289 0.05648595 0.03534096 0.05633199 0.03532195 0.05484396 0.03492289 0.05498999 0.03494 0.05389297 0.03384399 0.05633199 0.03532195 0.05498999 0.03494 0.05484396 0.03492289 0.05375498 0.03383398 0.05389297 0.03384399 0.05349195 0.03234595 0.05484396 0.03492289 0.05389297 0.03384399 0.05375498 0.03383398 0.053357 0.03234595 0.05349195 0.03234595 0.05389297 0.0308479 0.05375498 0.03383398 0.05349195 0.03234595 0.053357 0.03234595 0.05375498 0.03085798 0.05389297 0.0308479 0.05498999 0.02975195 0.053357 0.03234595 0.05389297 0.0308479 0.05375498 0.03085798 0.05375498 0.03085798 0.05498999 0.02975195 0.05484396 0.029769 0.06117689 0.03234595 0.06504899 0.03234595 0.06433796 0.02558499 0.06045889 0.03872096 0.06504899 0.03234595 0.06117689 0.03234595 0.06045889 0.03872096 0.06433796 0.03910696 0.06504899 0.03234595 0.06045889 0.02597099 0.06433796 0.02558499 0.06223791 0.01911896 0.06045889 0.02597099 0.06117689 0.03234595 0.06433796 0.02558499 0.0583409 0.01991593 0.06223791 0.01911896 0.05883991 0.01323091 0.0583409 0.01991593 0.06045889 0.02597099 0.06223791 0.01911896 0.054928 0.01448297 0.05883991 0.01323091 0.05429196 0.008177995 0.054928 0.01448297 0.0583409 0.01991593 0.05883991 0.01323091 0.05039197 0.009945988 0.05429196 0.008177995 0.04879099 0.004179954 0.05039197 0.009945988 0.054928 0.01448297 0.05429196 0.008177995 0.04495888 0.006531894 0.04879099 0.004179954 0.04257798 0.001413941 0.04495888 0.006531894 0.05039197 0.009945988 0.04879099 0.004179954 0.03890198 0.004411995 0.04257798 0.001413941 0.03592497 0 0.03890198 0.004411995 0.04495888 0.006531894 0.04257798 0.001413941 0.03252393 0.003692984 0.03592497 0 0.02912288 0 0.03252393 0.003692984 0.03890198 0.004411995 0.03592497 0 0.02614688 0.004411995 0.02912288 0 0.02247095 0.001413941 0.02614688 0.004411995 0.03252393 0.003692984 0.02912288 0 0.02008998 0.006531894 0.02247095 0.001413941 0.016258 0.004179954 0.02008998 0.006531894 0.02614688 0.004411995 0.02247095 0.001413941 0.01465696 0.009945988 0.016258 0.004179954 0.0107569 0.008177995 0.01465696 0.009945988 0.02008998 0.006531894 0.016258 0.004179954 0.01011997 0.01448297 0.0107569 0.008177995 0.006207883 0.01323091 0.01011997 0.01448297 0.01465696 0.009945988 0.0107569 0.008177995 0.006707966 0.01991593 0.006207883 0.01323091 0.002809882 0.01911896 0.006707966 0.01991593 0.01011997 0.01448297 0.006207883 0.01323091 0.004589915 0.02597099 0.002809882 0.01911896 7.1e-4 0.02558499 0.004589915 0.02597099 0.006707966 0.01991593 0.002809882 0.01911896 0.004589915 0.02597099 7.1e-4 0.02558499 0 0.03234595 0.003871977 0.03234595 0.004589915 0.02597099 0 0.03234595 7.1e-4 0.03910696 0.003871977 0.03234595 0 0.03234595 0.06124889 0.03234595 0.06117689 0.03234595 0.06045889 0.02597099 0.06052899 0.03873592 0.06117689 0.03234595 0.06124889 0.03234595 0.06045889 0.03872096 0.06117689 0.03234595 0.06052899 0.03873592 0.06052899 0.02595692 0.06045889 0.02597099 0.0583409 0.01991593 0.06052899 0.02595692 0.06124889 0.03234595 0.06045889 0.02597099 0.05840498 0.01988291 0.0583409 0.01991593 0.054928 0.01448297 0.05840498 0.01988291 0.06052899 0.02595692 0.0583409 0.01991593 0.05498492 0.01443892 0.054928 0.01448297 0.05039197 0.009945988 0.05498492 0.01443892 0.05840498 0.01988291 0.054928 0.01448297 0.05043697 0.00988996 0.05039197 0.009945988 0.04495888 0.006531894 0.05043697 0.00988996 0.05498492 0.01443892 0.05039197 0.009945988 0.04498791 0.006465971 0.04495888 0.006531894 0.03890198 0.004411995 0.04498791 0.006465971 0.05043697 0.00988996 0.04495888 0.006531894 0.03891998 0.0043419 0.03890198 0.004411995 0.03252393 0.003692984 0.03891998 0.0043419 0.04498791 0.006465971 0.03890198 0.004411995 0.03252393 0.003621995 0.03252393 0.003692984 0.02614688 0.004411995 0.03252393 0.003621995 0.03891998 0.0043419 0.03252393 0.003692984 0.02612888 0.0043419 0.02614688 0.004411995 0.02008998 0.006531894 0.02612888 0.0043419 0.03252393 0.003621995 0.02614688 0.004411995 0.02006 0.006465971 0.02008998 0.006531894 0.01465696 0.009945988 0.02006 0.006465971 0.02612888 0.0043419 0.02008998 0.006531894 0.01461088 0.00988996 0.01465696 0.009945988 0.01011997 0.01448297 0.01461088 0.00988996 0.02006 0.006465971 0.01465696 0.009945988 0.01006299 0.01443892 0.01011997 0.01448297 0.006707966 0.01991593 0.01006299 0.01443892 0.01461088 0.00988996 0.01011997 0.01448297 0.006643891 0.01988291 0.006707966 0.01991593 0.004589915 0.02597099 0.006643891 0.01988291 0.01006299 0.01443892 0.006707966 0.01991593 0.004518926 0.02595692 0.004589915 0.02597099 0.003871977 0.03234595 0.004518926 0.02595692 0.006643891 0.01988291 0.004589915 0.02597099 0.003798902 0.03234595 0.004518926 0.02595692 0.003871977 0.03234595 0.004589915 0.03872096 0.003798902 0.03234595 0.003871977 0.03234595 0.004589915 0.03872096 0.003871977 0.03234595 7.1e-4 0.03910696 0.003798902 0.03234595 0.06124889 0.03234595 0.06052899 0.02595692 0.004518926 0.03873592 0.06124889 0.03234595 0.003798902 0.03234595 0.004518926 0.03873592 0.06052899 0.03873592 0.06124889 0.03234595 0.004518926 0.02595692 0.06052899 0.02595692 0.05840498 0.01988291 0.003798902 0.03234595 0.06052899 0.02595692 0.004518926 0.02595692 0.006643891 0.01988291 0.05840498 0.01988291 0.05498492 0.01443892 0.004518926 0.02595692 0.05840498 0.01988291 0.006643891 0.01988291 0.01006299 0.01443892 0.05498492 0.01443892 0.05043697 0.00988996 0.006643891 0.01988291 0.05498492 0.01443892 0.01006299 0.01443892 0.01461088 0.00988996 0.05043697 0.00988996 0.04498791 0.006465971 0.01006299 0.01443892 0.05043697 0.00988996 0.01461088 0.00988996 0.02006 0.006465971 0.04498791 0.006465971 0.03891998 0.0043419 0.01461088 0.00988996 0.04498791 0.006465971 0.02006 0.006465971 0.02612888 0.0043419 0.03891998 0.0043419 0.03252393 0.003621995 0.02006 0.006465971 0.03891998 0.0043419 0.02612888 0.0043419 0.004589915 0.03872096 0.004518926 0.03873592 0.003798902 0.03234595 0.006643891 0.04480898 0.05840498 0.04480898 0.06052899 0.03873592 0.06045889 0.03872096 0.06052899 0.03873592 0.05840498 0.04480898 0.004518926 0.03873592 0.006643891 0.04480898 0.06052899 0.03873592 0.01006299 0.05025297 0.05498492 0.05025297 0.05840498 0.04480898 0.0583409 0.04477691 0.05840498 0.04480898 0.05498492 0.05025297 0.006643891 0.04480898 0.01006299 0.05025297 0.05840498 0.04480898 0.06045889 0.03872096 0.05840498 0.04480898 0.0583409 0.04477691 0.01461088 0.054802 0.05043697 0.054802 0.05498492 0.05025297 0.054928 0.05020892 0.05498492 0.05025297 0.05043697 0.054802 0.01006299 0.05025297 0.01461088 0.054802 0.05498492 0.05025297 0.0583409 0.04477691 0.05498492 0.05025297 0.054928 0.05020892 0.02006 0.05822592 0.04498791 0.05822592 0.05043697 0.054802 0.05039197 0.05474597 0.05043697 0.054802 0.04498791 0.05822592 0.01461088 0.054802 0.02006 0.05822592 0.05043697 0.054802 0.054928 0.05020892 0.05043697 0.054802 0.05039197 0.05474597 0.02612888 0.06035 0.03891998 0.06035 0.04498791 0.05822592 0.04495888 0.05816096 0.04498791 0.05822592 0.03891998 0.06035 0.02006 0.05822592 0.02612888 0.06035 0.04498791 0.05822592 0.05039197 0.05474597 0.04498791 0.05822592 0.04495888 0.05816096 0.02612888 0.06035 0.03252393 0.06106996 0.03891998 0.06035 0.03890198 0.06027996 0.03891998 0.06035 0.03252393 0.06106996 0.04495888 0.05816096 0.03891998 0.06035 0.03890198 0.06027996 0.03252393 0.06099891 0.03252393 0.06106996 0.02612888 0.06035 0.03890198 0.06027996 0.03252393 0.06106996 0.03252393 0.06099891 0.02614688 0.06027996 0.02612888 0.06035 0.02006 0.05822592 0.03252393 0.06099891 0.02612888 0.06035 0.02614688 0.06027996 0.02008998 0.05816096 0.02006 0.05822592 0.01461088 0.054802 0.02614688 0.06027996 0.02006 0.05822592 0.02008998 0.05816096 0.01465696 0.05474597 0.01461088 0.054802 0.01006299 0.05025297 0.02008998 0.05816096 0.01461088 0.054802 0.01465696 0.05474597 0.01011997 0.05020892 0.01006299 0.05025297 0.006643891 0.04480898 0.01465696 0.05474597 0.01006299 0.05025297 0.01011997 0.05020892 0.006707966 0.04477691 0.006643891 0.04480898 0.004518926 0.03873592 0.01011997 0.05020892 0.006643891 0.04480898 0.006707966 0.04477691 0.006707966 0.04477691 0.004518926 0.03873592 0.004589915 0.03872096 0.004589915 0.03872096 7.1e-4 0.03910696 0.002809882 0.04557293 0.006707966 0.04477691 0.002809882 0.04557293 0.006207883 0.05146098 0.006707966 0.04477691 0.004589915 0.03872096 0.002809882 0.04557293 0.01011997 0.05020892 0.006207883 0.05146098 0.0107569 0.05651396 0.01011997 0.05020892 0.006707966 0.04477691 0.006207883 0.05146098 0.01465696 0.05474597 0.0107569 0.05651396 0.016258 0.06051188 0.01465696 0.05474597 0.01011997 0.05020892 0.0107569 0.05651396 0.02008998 0.05816096 0.016258 0.06051188 0.02247095 0.06327795 0.02008998 0.05816096 0.01465696 0.05474597 0.016258 0.06051188 0.02614688 0.06027996 0.02247095 0.06327795 0.02912288 0.06469196 0.02614688 0.06027996 0.02008998 0.05816096 0.02247095 0.06327795 0.03252393 0.06099891 0.02912288 0.06469196 0.03592497 0.06469196 0.03252393 0.06099891 0.02614688 0.06027996 0.02912288 0.06469196 0.03890198 0.06027996 0.03592497 0.06469196 0.04257798 0.06327795 0.03890198 0.06027996 0.03252393 0.06099891 0.03592497 0.06469196 0.04495888 0.05816096 0.04257798 0.06327795 0.04879099 0.06051188 0.04495888 0.05816096 0.03890198 0.06027996 0.04257798 0.06327795 0.05039197 0.05474597 0.04879099 0.06051188 0.05429196 0.05651396 0.05039197 0.05474597 0.04495888 0.05816096 0.04879099 0.06051188 0.054928 0.05020892 0.05429196 0.05651396 0.05883991 0.05146098 0.054928 0.05020892 0.05039197 0.05474597 0.05429196 0.05651396 0.0583409 0.04477691 0.05883991 0.05146098 0.06223791 0.04557293 0.0583409 0.04477691 0.054928 0.05020892 0.05883991 0.05146098 0.06045889 0.03872096 0.06223791 0.04557293 0.06433796 0.03910696 0.06045889 0.03872096 0.0583409 0.04477691 0.06223791 0.04557293 0.05484396 0.03492289 0.05484396 0.029769 0.05633199 0.02936995 0.05633199 0.03532195 0.05484396 0.03492289 0.05633199 0.02936995 0.05781888 0.029769 0.05633199 0.03532195 0.05633199 0.02936995 0.05375498 0.03383398 0.05375498 0.03085798 0.05484396 0.029769 0.05484396 0.03492289 0.05375498 0.03383398 0.05484396 0.029769 0.05375498 0.03383398 0.053357 0.03234595 0.05375498 0.03085798 0.05781888 0.029769 0.05781888 0.03492289 0.05633199 0.03532195 0.05890792 0.03085798 0.05890792 0.03383398 0.05781888 0.03492289 0.05781888 0.029769 0.05890792 0.03085798 0.05781888 0.03492289 0.05890792 0.03085798 0.0593059 0.03234595 0.05890792 0.03383398 - - - - - - - - - - - - - - -

0 0 0 1 0 1 2 0 2 3 1 3 4 2 4 5 3 5 6 4 6 2 4 7 7 4 8 8 5 9 9 6 10 10 7 11 11 8 12 0 8 13 2 8 14 6 9 15 11 9 16 2 9 17 8 5 18 10 7 19 12 7 20 13 10 21 14 10 22 1 10 23 15 11 24 5 3 25 16 12 26 17 13 27 13 13 28 1 13 29 18 14 30 17 14 31 1 14 32 0 15 33 18 15 34 1 15 35 15 11 36 3 1 37 5 3 38 19 16 39 20 16 40 14 16 41 21 17 42 16 12 43 22 18 44 13 19 45 19 19 46 14 19 47 21 17 48 15 11 49 16 12 50 23 20 51 24 20 52 20 20 53 25 21 54 22 18 55 26 22 56 19 8 57 23 8 58 20 8 59 25 21 60 21 17 61 22 18 62 27 23 63 28 23 64 24 23 65 29 24 66 26 22 67 30 25 68 23 26 69 27 26 70 24 26 71 29 24 72 25 21 73 26 22 74 31 27 75 32 27 76 28 27 77 33 25 78 30 25 79 34 28 80 27 8 81 31 8 82 28 8 83 33 25 84 29 24 85 30 25 86 35 29 87 36 29 88 32 29 89 37 30 90 34 28 91 38 31 92 31 32 93 35 32 94 32 32 95 37 30 96 33 25 97 34 28 98 39 33 99 38 31 100 40 34 101 39 33 102 37 30 103 38 31 104 41 35 105 40 34 106 42 36 107 41 35 108 39 33 109 40 34 110 43 37 111 42 36 112 44 38 113 43 37 114 41 35 115 42 36 116 45 38 117 44 38 118 46 39 119 45 38 120 43 37 121 44 38 122 47 40 123 46 39 124 48 41 125 47 40 126 45 38 127 46 39 128 49 42 129 48 41 130 50 43 131 49 42 132 47 40 133 48 41 134 51 44 135 50 43 136 52 45 137 51 44 138 49 42 139 50 43 140 53 46 141 54 46 142 17 46 143 55 47 144 52 45 145 56 48 146 57 8 147 17 8 148 18 8 149 58 49 150 53 49 151 17 49 152 57 50 153 58 50 154 17 50 155 55 47 156 51 44 157 52 45 158 7 51 159 59 51 160 54 51 161 60 52 162 61 53 163 62 54 164 63 8 165 7 8 166 54 8 167 64 8 168 63 8 169 54 8 170 65 8 171 64 8 172 54 8 173 53 55 174 65 55 175 54 55 176 66 48 177 55 47 178 56 48 179 67 56 180 68 56 181 59 56 182 69 57 183 62 54 184 70 58 185 7 59 186 67 59 187 59 59 188 69 57 189 60 52 190 62 54 191 71 60 192 72 60 193 68 60 194 73 61 195 70 58 196 74 62 197 67 63 198 71 63 199 68 63 200 73 61 201 69 57 202 70 58 203 75 64 204 76 64 205 72 64 206 77 65 207 74 62 208 78 66 209 71 8 210 75 8 211 72 8 212 77 65 213 73 61 214 74 62 215 79 67 216 80 67 217 76 67 218 81 68 219 78 66 220 82 69 221 75 70 222 79 70 223 76 70 224 81 68 225 77 65 226 78 66 227 83 71 228 84 71 229 80 71 230 85 69 231 82 69 232 86 72 233 79 8 234 83 8 235 80 8 236 85 69 237 81 68 238 82 69 239 87 73 240 88 73 241 84 73 242 89 74 243 86 72 244 90 75 245 83 76 246 87 76 247 84 76 248 89 74 249 85 69 250 86 72 251 91 77 252 90 75 253 92 78 254 91 77 255 89 74 256 90 75 257 93 79 258 92 78 259 94 80 260 93 79 261 91 77 262 92 78 263 95 81 264 94 80 265 96 82 266 95 81 267 93 79 268 94 80 269 97 82 270 96 82 271 98 83 272 97 82 273 95 81 274 96 82 275 99 84 276 98 83 277 100 85 278 99 84 279 97 82 280 98 83 281 101 86 282 100 85 283 102 87 284 101 86 285 99 84 286 100 85 287 103 88 288 102 87 289 9 6 290 103 88 291 101 86 292 102 87 293 104 8 294 6 8 295 7 8 296 105 8 297 104 8 298 7 8 299 63 89 300 105 89 301 7 89 302 8 5 303 103 88 304 9 6 305 106 90 306 107 91 307 108 92 308 109 93 309 110 94 310 111 95 311 109 93 312 111 95 313 112 96 314 113 97 315 108 92 316 114 98 317 113 97 318 106 90 319 108 92 320 115 99 321 114 98 322 116 100 323 113 97 324 114 98 325 115 99 326 117 100 327 116 100 328 118 101 329 115 99 330 116 100 331 117 100 332 119 102 333 118 101 334 120 103 335 117 100 336 118 101 337 119 102 338 121 104 339 120 103 340 122 105 341 119 102 342 120 103 343 121 104 344 123 106 345 124 107 346 125 108 347 121 104 348 122 105 349 126 109 350 127 110 351 125 108 352 128 111 353 123 106 354 125 108 355 127 110 356 129 112 357 128 111 358 130 113 359 127 110 360 128 111 361 129 112 362 131 113 363 130 113 364 132 114 365 129 112 366 130 113 367 131 113 368 133 115 369 132 114 370 110 94 371 131 113 372 132 114 373 133 115 374 133 115 375 110 94 376 109 93 377 134 116 378 135 117 379 136 118 380 137 119 381 138 120 382 139 121 383 137 119 384 140 122 385 138 120 386 141 123 387 136 118 388 142 124 389 141 123 390 134 116 391 136 118 392 143 125 393 142 124 394 144 126 395 143 125 396 141 123 397 142 124 398 145 127 399 144 126 400 146 128 401 145 127 402 143 125 403 144 126 404 147 129 405 146 128 406 148 130 407 147 129 408 145 127 409 146 128 410 149 131 411 148 130 412 150 132 413 149 131 414 147 129 415 148 130 416 151 133 417 150 132 418 152 134 419 151 133 420 149 131 421 150 132 422 153 135 423 152 134 424 154 136 425 153 135 426 151 133 427 152 134 428 155 137 429 154 136 430 156 138 431 155 137 432 153 135 433 154 136 434 157 139 435 156 138 436 158 140 437 157 139 438 155 137 439 156 138 440 159 141 441 158 140 442 160 142 443 159 141 444 157 139 445 158 140 446 161 143 447 160 142 448 162 144 449 161 143 450 159 141 451 160 142 452 163 145 453 162 144 454 164 146 455 163 145 456 161 143 457 162 144 458 165 147 459 164 146 460 166 148 461 165 147 462 163 145 463 164 146 464 165 147 465 166 148 466 167 149 467 168 150 468 165 147 469 167 149 470 169 151 471 170 152 472 171 153 473 172 154 474 173 155 475 174 156 476 175 157 477 176 158 478 177 159 479 178 160 480 176 158 481 175 157 482 179 161 483 174 156 484 180 162 485 179 161 486 172 154 487 174 156 488 181 163 489 180 162 490 182 164 491 181 163 492 179 161 493 180 162 494 183 165 495 182 164 496 184 166 497 183 165 498 181 163 499 182 164 500 185 167 501 184 166 502 186 168 503 185 167 504 183 165 505 184 166 506 187 169 507 186 168 508 188 170 509 187 169 510 185 167 511 186 168 512 189 171 513 188 170 514 190 172 515 189 171 516 187 169 517 188 170 518 191 172 519 190 172 520 192 173 521 191 172 522 189 171 523 190 172 524 193 174 525 192 173 526 194 175 527 193 174 528 191 172 529 192 173 530 195 176 531 194 175 532 196 177 533 195 176 534 193 174 535 194 175 536 197 178 537 196 177 538 198 179 539 197 178 540 195 176 541 196 177 542 199 180 543 198 179 544 200 181 545 199 180 546 197 178 547 198 179 548 201 182 549 200 181 550 202 183 551 201 182 552 199 180 553 200 181 554 203 184 555 202 183 556 204 185 557 203 184 558 201 182 559 202 183 560 205 186 561 203 184 562 204 185 563 206 187 564 207 188 565 208 189 566 209 190 567 170 152 568 169 151 569 210 191 570 211 191 571 212 191 572 213 192 573 211 192 574 210 192 575 213 193 576 214 193 577 211 193 578 215 194 579 212 194 580 216 194 581 210 192 582 212 192 583 215 192 584 217 192 585 216 192 586 218 192 587 215 192 588 216 192 589 217 192 590 219 195 591 218 195 592 220 195 593 217 192 594 218 192 595 219 192 596 221 196 597 220 196 598 222 196 599 219 192 600 220 192 601 221 192 602 223 197 603 222 197 604 224 197 605 221 192 606 222 192 607 223 192 608 225 192 609 224 192 610 226 192 611 223 198 612 224 198 613 225 198 614 206 187 615 227 199 616 207 188 617 228 200 618 229 200 619 214 200 620 178 160 621 175 157 622 230 201 623 213 192 624 228 192 625 214 192 626 231 192 627 232 192 628 229 192 629 233 202 630 230 201 631 234 203 632 228 192 633 231 192 634 229 192 635 178 160 636 230 201 637 233 202 638 235 204 639 236 204 640 232 204 641 237 205 642 234 203 643 238 206 644 231 207 645 235 207 646 232 207 647 233 202 648 234 203 649 237 205 650 239 208 651 240 208 652 236 208 653 241 209 654 238 206 655 242 210 656 235 192 657 239 192 658 236 192 659 237 205 660 238 206 661 241 209 662 243 211 663 244 211 664 240 211 665 245 212 666 242 210 667 246 213 668 239 214 669 243 214 670 240 214 671 241 209 672 242 210 673 245 212 674 243 192 675 247 192 676 244 192 677 248 215 678 246 213 679 249 216 680 245 212 681 246 213 682 248 215 683 250 216 684 249 216 685 251 217 686 248 215 687 249 216 688 250 216 689 252 218 690 251 217 691 253 219 692 250 216 693 251 217 694 252 218 695 254 220 696 253 219 697 255 221 698 252 218 699 253 219 700 254 220 701 256 222 702 255 221 703 257 223 704 254 220 705 255 221 706 256 222 707 258 224 708 257 223 709 259 225 710 256 222 711 257 223 712 258 224 713 260 226 714 259 225 715 227 199 716 258 224 717 259 225 718 260 226 719 260 226 720 227 199 721 206 187 722 209 190 723 169 151 724 261 227 725 262 228 726 261 227 727 263 229 728 262 228 729 209 190 730 261 227 731 264 230 732 263 229 733 265 231 734 264 230 735 262 228 736 263 229 737 266 232 738 265 231 739 267 233 740 266 232 741 264 230 742 265 231 743 268 234 744 267 233 745 269 235 746 268 234 747 266 232 748 267 233 749 270 236 750 269 235 751 271 237 752 270 236 753 268 234 754 269 235 755 272 238 756 271 237 757 273 239 758 272 238 759 270 236 760 271 237 761 274 240 762 273 239 763 275 241 764 274 240 765 272 238 766 273 239 767 276 242 768 275 241 769 277 243 770 276 242 771 274 240 772 275 241 773 278 244 774 277 243 775 279 245 776 278 244 777 276 242 778 277 243 779 280 246 780 279 245 781 281 247 782 280 246 783 278 244 784 279 245 785 282 248 786 281 247 787 283 249 788 282 248 789 280 246 790 281 247 791 137 119 792 283 249 793 140 122 794 137 119 795 282 248 796 283 249 797 284 8 798 285 8 799 286 8 800 287 8 801 284 8 802 286 8 803 288 8 804 287 8 805 286 8 806 289 8 807 290 8 808 285 8 809 284 8 810 289 8 811 285 8 812 289 8 813 291 8 814 290 8 815 288 8 816 292 8 817 287 8 818 293 8 819 294 8 820 292 8 821 288 8 822 293 8 823 292 8 824 293 8 825 295 8 826 294 8 827

-
-
-
-
- - - - - -4.37108e-11 1.62919e-10 9.99987e-4 0 9.99987e-4 -2.98019e-11 4.37108e-11 0 2.98019e-11 9.99987e-4 -1.62919e-10 -1.0014 0 0 0 1 - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl deleted file mode 100644 index 7c86d6e49b328ba00517a57b80c70b5823081360..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2284 zcmb7_PfJu`6vkhojeUv;r_;%2cMJmX{m?w=IW0KqN|;1%Wxc zAc*h}7-fqV6;`Hc5lTdz=brbu_j#2T4d@(w&hI?uocFymXKsv+G_N)WYnPfMmusho z8pDH)=8@i`{U>YPSFT;G9qS4I^*U_X-^N;}zMQ?D5nO3^4NTrWG>g9x4;?&EUulom zXD+PQ5r?oLger`c_IPW5U-rX(yr$QJLIQOkS^YQW;~vQV9tl+#EA1YiZH9I03?7=r z*yrdPxU=;9zI&`0@jeomlnP_iC7pQ8`5aDoCl!r7y={-rCLRT$3S*_+15?}d9e8LK zW7M_!IFINNcU2IoFh*U{?h(&CA)t_e$LhJM~J>`V#|&0>tY zuWV0`%Q-;UnG}R7j8T`gdu-aCe#TvC7Groku=?-H^VqQL?MSG?7-j6x)IKR_jFhI54WK6g|PYTPcKvus_0DGt>^mhJX1wGOuK5g z?oE?W52aJ$m)-QW_$f*Pw}CPCqo)~y5~?s(+V9nl-SpL6-yhsNc7-gZLr_8$#!55h zzVZ&U+}+OuF~3Xr|B6tB`*EWB1P{TUj}vjb9o`IN@jMXoj_vhOh3A1R-eV``#X}X| z5@eZo`TTPRyyxhuRCt0Qc5j4Kx+~p+&KJVIo40wdlF4-@?UwbuD^;|^e|M$sN~gqM DKkB`Q diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae deleted file mode 100644 index 3fd9152677..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae +++ /dev/null @@ -1,145 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T14:47:26 - 2019-01-15T14:47:26 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.31 0.33 0.33 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - - - - 26.12602 99.69651 66.13459 42.55324 95 58 34.5009 97.64975 62.5895 32.92695 129.5 57.02968 34.5009 97.64975 62.5895 42.55324 95 58 17.52961 101.1482 68.64896 8.79768 102.0146 70.14962 0 102.3025 70.64831 -8.797612 102.0146 70.14963 37.09656 129.5 54.40962 41.05839 129.5 51.4856 50.89944 65.33378 58 60.35892 28.24008 58 50.89944 65.33378 58 42.55324 95 58 -17.52952 101.1482 68.64897 -26.12594 99.69652 66.13462 -34.50087 97.64976 62.58951 -42.55324 95 58 -20.17238 90.05471 58 -42.55324 95 58 -20 85.97177 58 28.5724 129.5 59.33119 26.12602 99.69651 66.13459 19.40983 129.5 62.9271 17.52961 101.1482 68.64896 24.05798 129.5 61.30075 9.815401 129.5 65.11697 8.79768 102.0146 70.14962 14.65357 129.5 64.20149 0 129.5 65.85266 0 102.3025 70.64831 4.922456 129.5 65.66841 -4.922456 129.5 65.66841 0 102.3025 70.64831 0 129.5 65.85266 -8.797612 102.0146 70.14963 0 129.5 61.5 0 129.5 65.85266 4.922456 129.5 65.66841 -9.621398 129.5 60.74267 -4.922456 129.5 65.66841 9.621398 129.5 60.74267 9.815401 129.5 65.11697 14.65357 129.5 64.20149 19.00452 129.5 58.48989 19.40983 129.5 62.9271 24.05798 129.5 61.30075 27.91977 129.5 54.79717 28.5724 129.5 59.33119 32.92695 129.5 57.02968 36.14879 129.5 49.75454 37.09656 129.5 54.40962 41.05839 129.5 51.4856 44.79069 129.5 48.27375 43.48752 129.5 43.48654 44.79069 129.5 48.27375 60.29818 28.47987 58 48.27289 129.5 44.7917 48.27289 129.5 44.7917 64.28165 28.47987 53.55129 51.48568 129.5 41.05846 49.75447 129.5 36.14874 51.48568 129.5 41.05846 58.44707 101.1704 40.04206 54.4104 129.5 37.0955 54.4104 129.5 37.0955 58.50773 99.33776 40.52366 58.5972 97.30286 41.02306 58.71929 95.04547 41.54118 58.87856 92.54319 42.07857 59.0805 89.76996 42.63568 59.33171 86.69617 43.21257 59.64018 83.28813 43.80873 60.01565 79.50714 44.4229 60.4699 75.3105 45.05237 61.01741 70.64891 45.69291 61.67665 65.46395 46.33765 62.47172 59.68569 46.97561 63.43516 53.22743 47.58906 59.64444 112.3794 34.43574 57.0303 129.5 32.92578 54.79654 129.5 27.92101 57.0303 129.5 32.92578 59.45811 112.327 34.77478 59.27178 112.1529 35.15167 59.10295 111.8574 35.53603 58.95536 111.4522 35.91783 58.82619 110.9408 36.30103 58.71517 110.3289 36.68436 58.62092 109.6142 37.07111 58.54294 108.7934 37.46332 58.48117 107.8602 37.86329 58.43608 106.8069 38.2729 58.40855 105.6228 38.69424 58.39995 104.2973 39.12866 58.41205 102.8183 39.57741 63.48478 102.8041 30.79572 59.3311 129.5 28.57235 58.48997 129.5 19.00455 59.3311 129.5 28.57235 63.08979 104.2849 31.00957 62.71754 105.6121 31.23422 62.3661 106.7978 31.46875 62.03363 107.8526 31.71264 61.71778 108.7874 31.96623 61.4167 109.6097 32.23007 61.12855 110.3256 32.50528 60.85177 110.9386 32.7933 60.58418 111.4509 33.09705 60.32679 111.857 33.41637 60.07841 112.1526 33.75463 59.84508 112.3269 34.10456 68.485 79.47608 29.76399 61.30022 129.5 24.0592 60.74289 129.5 9.620025 61.30022 129.5 24.0592 67.76525 83.25878 29.74548 67.09452 86.66883 29.77605 66.46907 89.74466 29.84662 65.88543 92.5197 29.94999 65.34017 95.02383 30.08051 64.83016 97.28314 30.23363 64.35267 99.31984 30.40568 63.90499 101.1544 30.59381 79.85744 28.47987 24.95315 62.92676 129.5 19.4111 61.4999 129.5 0 62.92676 129.5 19.4111 71.92422 59.64659 30.61713 70.97407 65.42729 30.24676 70.08599 70.6142 29.99756 69.2574 75.27765 29.84313 62.92676 129.5 -19.4111 64.20159 129.5 14.65359 82.2877 28.47987 15.11971 64.20159 129.5 14.65359 61.30022 129.5 -24.0592 64.20159 129.5 -14.65359 65.11721 129.5 9.814099 65.11721 129.5 9.814099 65.11721 129.5 -9.814099 65.66848 129.5 4.920582 83.51181 28.47987 5.064649 65.66848 129.5 4.920582 65.66848 129.5 -4.920582 65.85256 129.5 0 65.85256 129.5 0 83.51181 28.47987 -5.064649 65.66848 129.5 -4.920582 82.2877 28.47987 -15.11971 65.11721 129.5 -9.814099 64.20159 129.5 -14.65359 79.85744 28.47987 -24.95315 62.92676 129.5 -19.4111 61.30022 129.5 -24.0592 63.90098 101.1704 -30.59562 59.3311 129.5 -28.57235 60.74289 129.5 -9.620025 59.3311 129.5 -28.57235 64.34839 99.33776 -30.40735 64.82563 97.30286 -30.23513 65.33538 95.04547 -30.08181 65.8804 92.54319 -29.95104 66.46384 89.76996 -29.84738 67.08905 86.69617 -29.77649 67.75957 83.28813 -29.74555 68.47919 79.50714 -29.76363 69.25145 75.3105 -29.84229 70.07994 70.64891 -29.99617 70.96791 65.46395 -30.24472 71.91793 59.68569 -30.61429 72.93093 53.22743 -31.14193 59.64444 112.3794 -34.43574 57.0303 129.5 -32.92578 58.48997 129.5 -19.00455 57.0303 129.5 -32.92578 59.8449 112.327 -34.10485 60.07813 112.1529 -33.75503 60.32658 111.8574 -33.41664 60.58344 111.4522 -33.09793 60.85071 110.9408 -32.79446 61.12717 110.3289 -32.50665 61.41498 109.6142 -32.23165 61.71566 108.7934 -31.96801 62.03116 107.8602 -31.71454 62.36334 106.8069 -31.47068 62.71448 105.6228 -31.23617 63.08639 104.2973 -31.01151 63.48107 102.8183 -30.79761 58.41226 102.8041 -39.58157 54.4104 129.5 -37.0955 54.79654 129.5 -27.92101 54.4104 129.5 -37.0955 58.39997 104.2849 -39.13258 58.4084 105.6121 -38.69787 58.43579 106.7978 -38.27625 58.48076 107.8526 -37.86638 58.54246 108.7874 -37.46606 58.62041 109.6097 -37.07339 58.71467 110.3256 -36.68623 58.82572 110.9386 -36.30252 58.95497 111.4509 -35.91892 59.10282 111.857 -35.53635 59.27157 112.1526 -35.15211 59.45796 112.3269 -34.77508 60.01887 79.47608 -44.42775 51.48568 129.5 -41.05846 51.48568 129.5 -41.05846 59.64296 83.25878 -43.81369 59.33407 86.66883 -43.21752 59.08246 89.74466 -42.64059 58.88017 92.5197 -42.08345 58.72057 95.02383 -41.54599 58.59817 97.28314 -41.02774 58.50842 99.31984 -40.5282 58.44751 101.1544 -40.04644 61.53878 28.47987 -56.68199 48.27289 129.5 -44.7917 49.75447 129.5 -36.14874 48.27289 129.5 -44.7917 62.47731 59.64659 -46.97964 61.68149 65.42729 -46.34197 61.02164 70.6142 -45.69746 60.4736 75.27765 -45.05709 54.2379 28.47987 -63.70338 44.79069 129.5 -48.27375 44.79069 129.5 -48.27375 41.05839 129.5 -51.4856 43.48752 129.5 -43.48654 41.05839 129.5 -51.4856 46.14201 28.47987 -69.79101 37.09656 129.5 -54.40962 37.09656 129.5 -54.40962 32.92695 129.5 -57.02968 36.14879 129.5 -49.75454 32.92695 129.5 -57.02968 37.36978 28.47987 -74.85566 28.5724 129.5 -59.33119 28.5724 129.5 -59.33119 28.04979 28.47987 -78.82309 24.05798 129.5 -61.30075 27.91977 129.5 -54.79717 24.05798 129.5 -61.30075 19.40983 129.5 -62.9271 19.40983 129.5 -62.9271 18.31866 28.47987 -81.63515 14.65357 129.5 -64.20149 19.00452 129.5 -58.48989 14.65357 129.5 -64.20149 9.815401 129.5 -65.11697 9.815401 129.5 -65.11697 5.453908 101.1704 -70.63769 4.922456 129.5 -65.66841 9.621398 129.5 -60.74267 4.922456 129.5 -65.66841 5.840654 99.33776 -70.93103 6.228416 97.30286 -71.2582 6.616074 95.04547 -71.623 7.001833 92.54319 -72.02962 7.383331 89.76996 -72.48307 7.757323 86.69617 -72.98906 8.119386 83.28813 -73.55429 8.463538 79.50714 -74.18653 8.781544 75.3105 -74.89466 9.062521 70.64891 -75.68908 9.291265 65.46395 -76.58237 9.446212 59.68569 -77.5899 9.495759 53.22743 -78.73101 0 112.3794 -68.87149 0 129.5 -65.85266 0 129.5 -65.85266 0.386784 112.327 -68.87963 0.80635 112.1529 -68.90671 1.223627 111.8574 -68.95269 1.628072 111.4522 -69.01576 2.024522 110.9408 -69.09549 2.412002 110.3289 -69.19101 2.794067 109.6142 -69.30276 3.172716 108.7934 -69.43135 3.549988 107.8602 -69.57783 3.927262 106.8069 -69.74359 4.305922 105.6228 -69.93041 4.686441 104.2973 -70.14019 5.069021 102.8183 -70.37503 -0.387123 112.3269 -68.87965 0 129.5 -65.85266 0 112.3794 -68.87149 -4.689824 104.2849 -70.14215 -5.072514 102.8041 -70.37729 -4.922456 129.5 -65.66841 -4.309144 105.6121 -69.9321 -3.930311 106.7978 -69.74501 -3.552864 107.8526 -69.57902 -3.17533 108.7874 -69.43228 -2.796289 109.6097 -69.30346 -2.413873 110.3256 -69.19152 -2.026049 110.9386 -69.09584 -1.629207 111.4509 -69.01597 -1.22397 111.857 -68.95272 -0.806836 112.1526 -68.90676 0 129.5 -61.5 -4.922456 129.5 -65.66841 0 12 -71.5 0 112.3794 -68.87149 0.386784 112.327 -68.87963 -1.329693 12 -71.60466 -0.387123 112.3269 -68.87965 0 112.3794 -68.87149 0 12 -71.5 0.80635 112.1529 -68.90671 1.223627 111.8574 -68.95269 1.628072 111.4522 -69.01576 1.329693 12 -71.60466 2.024522 110.9408 -69.09549 2.412002 110.3289 -69.19101 2.794067 109.6142 -69.30276 3.172716 108.7934 -69.43135 2.626644 12 -71.91603 3.549988 107.8602 -69.57783 3.927262 106.8069 -69.74359 4.305922 105.6228 -69.93041 4.686441 104.2973 -70.14019 3.858919 12 -72.42646 5.069021 102.8183 -70.37503 5.453908 101.1704 -70.63769 5.840654 99.33776 -70.93103 6.228416 97.30286 -71.2582 4.996175 12 -73.12336 6.616074 95.04547 -71.623 7.001833 92.54319 -72.02962 7.383331 89.76996 -72.48307 6.010408 12 -73.9896 7.757323 86.69617 -72.98906 8.119386 83.28813 -73.55429 6.876644 12 -75.00382 8.463538 79.50714 -74.18653 8.781544 75.3105 -74.89466 7.573555 12 -76.14109 9.062521 70.64891 -75.68908 9.291265 65.46395 -76.58237 8.08398 12 -77.37336 9.446212 59.68569 -77.5899 8.395353 12 -78.67031 9.495759 53.22743 -78.73101 9.391167 45.9834 -80.02976 8.5 12 -80 9.391167 45.9834 -80.02976 9.050388 37.79684 -81.52156 8.395353 12 -81.3297 9.050388 37.79684 -81.52156 8.31901 28.47987 -83.25061 8.08398 12 -82.62664 8.31901 28.47987 -83.25061 17.95494 24.46426 -82.89403 8.31901 28.47987 -83.25061 18.31866 28.47987 -81.63515 7.828858 25.33502 -84.12519 7.573555 12 -83.85892 7.828858 25.33502 -84.12519 28.07899 24.46426 -80.03356 28.04979 28.47987 -78.82309 37.77103 24.46426 -75.94175 37.36978 28.47987 -74.85566 46.14201 28.47987 -69.79101 46.88196 24.46426 -70.68155 54.2379 28.47987 -63.70338 55.2716 24.46426 -64.3339 61.53878 28.47987 -56.68199 66.07898 37.77328 -48.59962 67.93764 28.47987 -48.82978 62.81087 24.46426 -56.99645 67.93764 28.47987 -48.82978 64.61872 45.94526 -48.15041 63.44156 53.18627 -47.59262 67.5148 12 -48.31425 67.93764 28.47987 -48.82978 66.07898 37.77328 -48.59962 68.94012 25.33501 -48.84258 68.83718 12 -48.48835 68.94012 25.33501 -48.84258 66.23591 12 -47.93543 64.61872 45.94526 -48.15041 65.03203 12 -47.36122 63.44156 53.18627 -47.59262 63.93281 12 -46.60574 62.47731 59.64659 -46.97964 62.9653 12 -45.68761 61.68149 65.42729 -46.34197 61.02164 70.6142 -45.69746 62.15333 12 -44.62943 60.4736 75.27765 -45.05709 60.01887 79.47608 -44.42775 61.51689 12 -43.45726 59.64296 83.25878 -43.81369 59.33407 86.66883 -43.21752 61.07166 12 -42.19996 59.08246 89.74466 -42.64059 58.88017 92.5197 -42.08345 58.72057 95.02383 -41.54599 60.82859 12 -40.88849 58.59817 97.28314 -41.02774 58.50842 99.31984 -40.5282 58.44751 101.1544 -40.04644 58.41226 102.8041 -39.58157 60.79368 12 -39.55514 58.39997 104.2849 -39.13258 58.4084 105.6121 -38.69787 58.43579 106.7978 -38.27625 58.48076 107.8526 -37.86638 60.96778 12 -38.23275 58.54246 108.7874 -37.46606 58.62041 109.6097 -37.07339 58.71467 110.3256 -36.68623 58.82572 110.9386 -36.30252 61.3466 12 -36.95387 58.95497 111.4509 -35.91892 59.10282 111.857 -35.53635 59.27157 112.1526 -35.15211 59.45796 112.3269 -34.77508 59.64444 112.3794 -34.43574 61.92081 12 -35.75 59.64444 112.3794 -34.43574 59.8449 112.327 -34.10485 61.92081 12 -35.75 60.07813 112.1529 -33.75503 60.32658 111.8574 -33.41664 60.58344 111.4522 -33.09793 62.67629 12 -34.65077 60.85071 110.9408 -32.79446 61.12717 110.3289 -32.50665 61.41498 109.6142 -32.23165 61.71566 108.7934 -31.96801 63.59442 12 -33.68327 62.03116 107.8602 -31.71454 62.36334 106.8069 -31.47068 62.71448 105.6228 -31.23617 63.08639 104.2973 -31.01151 64.65261 12 -32.8713 63.48107 102.8183 -30.79761 63.90098 101.1704 -30.59562 64.34839 99.33776 -30.40735 64.82563 97.30286 -30.23513 65.82477 12 -32.23486 65.33538 95.04547 -30.08181 65.8804 92.54319 -29.95104 66.46384 89.76996 -29.84738 67.08207 12 -31.78963 67.08905 86.69617 -29.77649 67.75957 83.28813 -29.74555 68.39354 12 -31.54656 68.47919 79.50714 -29.76363 69.25145 75.3105 -29.84229 69.72689 12 -31.51165 70.07994 70.64891 -29.99617 70.96791 65.46395 -30.24472 71.04928 12 -31.68575 71.91793 59.68569 -30.61429 72.32817 12 -32.06457 72.93093 53.22743 -31.14193 74.00339 45.9834 -31.88189 73.53203 12 -32.63878 74.00339 45.9834 -31.88189 75.12493 37.79684 -32.92291 74.63127 12 -33.39426 75.12493 37.79684 -32.92291 76.25666 28.47987 -34.42083 75.59877 12 -34.31239 76.25666 28.47987 -34.42083 80.7658 24.46426 -25.89758 76.25666 28.47987 -34.42083 79.85744 28.47987 -24.95315 76.76898 25.33502 -35.2826 76.41073 12 -35.37057 76.76898 25.33502 -35.2826 83.3506 24.46426 -15.69966 82.2877 28.47987 -15.11971 84.653 24.46426 -5.260197 83.51181 28.47987 -5.064649 83.51181 28.47987 5.064649 84.653 24.46426 5.260197 82.2877 28.47987 15.11971 83.3506 24.46426 15.69966 79.85744 28.47987 24.95315 75.128 37.77328 32.92626 76.25666 28.47987 34.42083 80.7658 24.46426 25.89758 76.25666 28.47987 34.42083 74.00885 45.94526 31.88624 72.93721 53.18627 31.1457 75.59877 12 34.31239 76.25666 28.47987 34.42083 75.128 37.77328 32.92626 76.76898 25.33501 35.2826 76.41073 12 35.37057 76.76898 25.33501 35.2826 74.63127 12 33.39426 74.00885 45.94526 31.88624 73.53203 12 32.63878 72.93721 53.18627 31.1457 72.32817 12 32.06457 71.92422 59.64659 30.61713 71.04928 12 31.68575 70.97407 65.42729 30.24676 70.08599 70.6142 29.99756 69.72689 12 31.51165 69.2574 75.27765 29.84313 68.485 79.47608 29.76399 68.39354 12 31.54656 67.76525 83.25878 29.74548 67.09452 86.66883 29.77605 67.08207 12 31.78963 66.46907 89.74466 29.84662 65.88543 92.5197 29.94999 65.34017 95.02383 30.08051 65.82477 12 32.23486 64.83016 97.28314 30.23363 64.35267 99.31984 30.40568 63.90499 101.1544 30.59381 63.48478 102.8041 30.79572 64.65261 12 32.8713 63.08979 104.2849 31.00957 62.71754 105.6121 31.23422 62.3661 106.7978 31.46875 62.03363 107.8526 31.71264 63.59442 12 33.68327 61.71778 108.7874 31.96623 61.4167 109.6097 32.23007 61.12855 110.3256 32.50528 60.85177 110.9386 32.7933 62.67629 12 34.65077 60.58418 111.4509 33.09705 60.32679 111.857 33.41637 60.07841 112.1526 33.75463 59.84508 112.3269 34.10456 59.64444 112.3794 34.43574 61.92081 12 35.75 59.64444 112.3794 34.43574 59.45811 112.327 34.77478 61.92081 12 35.75 59.27178 112.1529 35.15167 59.10295 111.8574 35.53603 58.95536 111.4522 35.91783 61.3466 12 36.95387 58.82619 110.9408 36.30103 58.71517 110.3289 36.68436 58.62092 109.6142 37.07111 58.54294 108.7934 37.46332 60.96778 12 38.23275 58.48117 107.8602 37.86329 58.43608 106.8069 38.2729 58.40855 105.6228 38.69424 58.39995 104.2973 39.12866 60.79368 12 39.55514 58.41205 102.8183 39.57741 58.44707 101.1704 40.04206 58.50773 99.33776 40.52366 58.5972 97.30286 41.02306 60.82859 12 40.88849 58.71929 95.04547 41.54118 58.87856 92.54319 42.07857 59.0805 89.76996 42.63568 61.07166 12 42.19996 59.33171 86.69617 43.21257 59.64018 83.28813 43.80873 61.51689 12 43.45726 60.01565 79.50714 44.4229 60.4699 75.3105 45.05237 62.15333 12 44.62943 61.01741 70.64891 45.69291 61.67665 65.46395 46.33765 62.9653 12 45.68761 62.47172 59.68569 46.97561 63.93281 12 46.60574 63.43516 53.22743 47.58906 64.61222 45.9834 48.14787 65.03203 12 47.36122 64.61222 45.9834 48.14787 66.07455 37.79684 48.59864 66.23591 12 47.93543 66.07455 37.79684 48.59864 67.93764 28.47987 48.82978 67.5148 12 48.31425 67.93764 28.47987 48.82978 68.94012 25.33502 48.84258 67.93764 28.47987 48.82978 64.28165 28.47987 53.55129 68.83718 12 48.48835 68.94012 25.33502 48.84258 62.57725 24.46426 57.25284 60.29818 28.47987 58 69.38591 24.39945 48.82408 60.29818 28.47987 58 60.35892 28.24008 58 60.42392 28 58 12.1063 15 -91.95652 12.10664 0 -91.95637 0 0 -92.75 -12.10664 0 -91.95637 0 0 -92.75 12.10664 0 -91.95637 0 15 -92.75 -12.10664 0 -91.95637 0 15 -92.75 0 0 -92.75 24.00547 15 -89.58963 24.00468 0 -89.5898 24.00468 0 -89.5898 35.49389 15 -85.68983 35.49462 0 -85.68946 -24.00468 0 -89.5898 35.49462 0 -85.68946 46.375 15 -80.32386 46.3744 0 -80.32411 0 0 -84.25 46.3744 0 -80.32411 -35.49462 0 -85.68946 56.46262 15 -73.58352 56.46306 0 -73.58319 4.185433 0 -79.262 56.46306 0 -73.58319 1.453586 0 -83.99369 2.731847 0 -83.25569 3.680608 0 -82.125 4.185433 0 -80.73801 65.58415 15 -65.58415 65.58409 0 -65.58409 23.33038 0 -73.15058 65.58409 0 -65.58409 3.680608 0 -77.875 19.49515 0 -75.96544 21.09926 0 -75.53565 22.43872 0 -74.55274 73.58352 15 -56.46262 73.58319 0 -56.46306 34.91143 0 -65.24713 73.58319 0 -56.46306 23.65241 0 -71.52102 23.82219 0 -70.73329 24.28907 0 -70.0765 24.97726 0 -69.65728 30.02434 0 -67.63536 80.32386 15 -46.375 80.32411 0 -46.3744 48.34083 0 -56.02815 80.32411 0 -46.3744 39.61006 0 -62.50629 44.09458 0 -59.42776 85.68983 15 -35.49389 85.68946 0 -35.49462 70.73562 0 -43.99369 85.68946 0 -35.49462 69.28203 0 -44.25 56.02824 0 -48.34072 52.3259 0 -52.3258 89.58963 15 -24.00547 89.5898 0 -24.00468 65.24717 0 -34.91135 89.5898 0 -24.00468 73.46747 0 -40.73801 72.96264 0 -42.125 72.01388 0 -43.25569 73.46747 0 -39.26199 72.96264 0 -37.875 72.01388 0 -36.74431 70.73562 0 -36.0063 69.28203 0 -35.75 91.95652 15 -12.1063 91.95637 0 -12.10664 73.15052 0 -23.33041 91.95637 0 -12.10664 67.63537 0 -30.0243 69.65728 0 -24.97726 70.0765 0 -24.28907 70.73329 0 -23.82219 92.75 15 0 92.75 0 0 73.58609 0 -7.815966 92.75 0 0 74.55265 0 -22.43881 75.53559 0 -21.09942 75.96543 0 -19.49533 75.78392 0 -17.84387 75.01544 0 -16.37059 73.76522 0 -15.27692 73.16793 0 -14.73602 72.83258 0 -14.0033 72.81361 0 -13.1977 91.95652 15 12.1063 91.95637 0 12.10664 85.18923 0 0.694593 91.95637 0 12.10664 83.82115 0 -3.064178 82.61808 0 -3.75877 84.71411 0 -2 85.18923 0 -0.694593 89.58963 15 24.00547 89.5898 0 24.00468 72.69229 0 13.84998 89.5898 0 24.00468 84.71411 0 2 83.82115 0 3.064178 82.61808 0 3.75877 81.25 0 4 73.51329 0 8.472822 85.68983 15 35.49389 85.68946 0 35.49462 69.87854 0 24.35123 85.68946 0 35.49462 71.47851 0 19.15234 80.32386 15 46.375 80.32411 0 46.3744 72.01388 0 36.74431 80.32411 0 46.3744 70.73562 0 36.0063 69.28203 0 35.75 65.55654 0 34.32689 67.90097 0 29.41852 73.58352 15 56.46262 73.58319 0 56.46306 56.45958 0 47.83634 73.58319 0 56.46306 72.01388 0 43.25569 72.96264 0 42.125 73.46747 0 40.73801 70.73562 0 43.99369 69.28203 0 44.25 59.81955 0 43.56171 72.96264 0 37.875 73.46747 0 39.26199 65.58415 15 65.58415 65.58409 0 65.58409 53.3452 0 56.70886 65.58409 0 65.58409 56.0732 0 48.54349 55.99727 0 49.34572 56.24409 0 50.11281 56.77998 0 51.685 56.7089 0 53.34508 56.04042 0 54.86601 54.86616 0 56.04032 56.46262 15 73.58352 56.46306 0 73.58319 29.41893 0 67.90081 56.46306 0 73.58319 51.68506 0 56.77999 43.56184 0 59.81946 39.05011 0 62.85765 34.32722 0 65.55636 46.375 15 80.32386 46.3744 0 80.32411 3.050353 0 73.93708 46.3744 0 80.32411 24.3517 0 69.87836 19.15286 0 71.47837 13.85052 0 72.69219 8.473347 0 73.51322 35.49389 15 85.68983 35.49462 0 85.68946 -46.3744 0 80.32411 35.49462 0 85.68946 -56.46306 0 73.58319 -19.49515 0 75.96544 -2.389251 0 73.96141 -16.37053 0 75.01541 -17.84374 0 75.78388 24.00547 15 89.58963 24.00468 0 89.5898 -35.49462 0 85.68946 24.00468 0 89.5898 12.1063 15 91.95652 12.10664 0 91.95637 -24.00468 0 89.5898 12.10664 0 91.95637 0 15 92.75 0 0 92.75 -12.10664 0 91.95637 0 0 92.75 -12.1063 15 91.95652 0 0 92.75 0 15 92.75 -12.10664 0 91.95637 0 17.32252 89.72489 0 15 92.75 12.1063 15 91.95652 -11.21306 17.56821 88.7605 -12.1063 15 91.95652 0 15 92.75 0 17.32252 89.72489 22.24928 17.56821 86.65523 24.00547 15 89.58963 11.21306 17.56821 88.7605 0 17.56821 89.46598 32.93462 17.56821 83.18335 35.49389 15 85.68983 43.10056 17.56821 78.39963 46.375 15 80.32386 52.58678 17.56821 72.3795 56.46262 15 73.58352 61.24367 17.56821 65.21788 65.58415 15 65.58415 68.93473 17.56821 57.02775 73.58352 15 56.46262 75.53861 17.56821 47.93826 80.32386 15 46.375 80.95124 17.56821 38.09275 85.68983 15 35.49389 85.08719 17.56821 27.6465 89.58963 15 24.00547 87.88128 17.56821 16.76425 91.95652 15 12.1063 89.28943 17.56821 5.617614 92.75 15 0 89.28943 17.56821 -5.617614 91.95652 15 -12.1063 87.88128 17.56821 -16.76425 89.58963 15 -24.00547 85.08719 17.56821 -27.6465 85.68983 15 -35.49389 80.95124 17.56821 -38.09275 80.32386 15 -46.375 75.53861 17.56821 -47.93826 73.58352 15 -56.46262 68.93473 17.56821 -57.02775 65.58415 15 -65.58415 61.24367 17.56821 -65.21788 56.46262 15 -73.58352 52.58678 17.56821 -72.3795 46.375 15 -80.32386 43.10056 17.56821 -78.39963 35.49389 15 -85.68983 32.93462 17.56821 -83.18335 24.00547 15 -89.58963 22.24928 17.56821 -86.65523 12.1063 15 -91.95652 11.21306 17.56821 -88.7605 0 15 -92.75 -12.1063 15 -91.95652 0 16.55666 -90.5959 0 15 -92.75 -12.1063 15 -91.95652 0 16.55666 -90.5959 -48.27289 129.5 44.7917 -64.28165 28.47987 53.55129 -60.29818 28.47987 58 -60.35892 28.24008 58 -60.29818 28.47987 58 -64.28165 28.47987 53.55129 -44.79069 129.5 48.27375 -50.89953 65.33341 58 -56.43347 39.79531 58 -50.89953 65.33341 58 -60.29818 28.47987 58 -60.35892 28.24008 58 60.42392 28 58 -52.41174 32.82986 58 -56.75 38 58 -56.43347 36.20468 58 -55.52194 34.62569 58 -54.12522 33.45357 58 -66.07898 37.77328 48.59962 -67.93764 28.47987 48.82978 -62.57725 24.46426 57.25284 -67.93764 28.47987 48.82978 -64.61872 45.94526 48.15041 -63.44156 53.18627 47.59262 -62.47731 59.64659 46.97964 -51.48568 129.5 41.05846 -60.42392 28 58 -67.5148 12 48.31425 -67.93764 28.47987 48.82978 -66.07898 37.77328 48.59962 -68.94012 25.33501 48.84258 -68.83718 12 48.48835 -68.94012 25.33501 48.84258 -66.23591 12 47.93543 -64.61872 45.94526 48.15041 -65.03203 12 47.36122 -63.44156 53.18627 47.59262 -63.93281 12 46.60574 -62.47731 59.64659 46.97964 -61.68149 65.42729 46.34197 -62.9653 12 45.68761 -61.68149 65.42729 46.34197 -61.02164 70.6142 45.69746 -61.02164 70.6142 45.69746 -60.4736 75.27765 45.05709 -62.15333 12 44.62943 -60.4736 75.27765 45.05709 -60.01887 79.47608 44.42775 -60.01887 79.47608 44.42775 -54.4104 129.5 37.0955 -59.64296 83.25878 43.81369 -61.51689 12 43.45726 -59.64296 83.25878 43.81369 -59.33407 86.66883 43.21752 -59.33407 86.66883 43.21752 -59.08246 89.74466 42.64059 -61.07166 12 42.19996 -59.08246 89.74466 42.64059 -58.88017 92.5197 42.08345 -58.88017 92.5197 42.08345 -58.72057 95.02383 41.54599 -58.72057 95.02383 41.54599 -58.59817 97.28314 41.02774 -60.82859 12 40.88849 -58.59817 97.28314 41.02774 -58.50842 99.31984 40.5282 -58.50842 99.31984 40.5282 -58.44751 101.1544 40.04644 -58.44751 101.1544 40.04644 -58.41226 102.8041 39.58157 -58.41226 102.8041 39.58157 -57.0303 129.5 32.92578 -58.39997 104.2849 39.13258 -60.79368 12 39.55514 -58.39997 104.2849 39.13258 -58.4084 105.6121 38.69787 -58.4084 105.6121 38.69787 -58.43579 106.7978 38.27625 -58.43579 106.7978 38.27625 -58.48076 107.8526 37.86638 -58.48076 107.8526 37.86638 -58.54246 108.7874 37.46606 -60.96778 12 38.23275 -58.54246 108.7874 37.46606 -58.62041 109.6097 37.07339 -58.62041 109.6097 37.07339 -58.71467 110.3256 36.68623 -58.71467 110.3256 36.68623 -58.82572 110.9386 36.30252 -58.82572 110.9386 36.30252 -58.95497 111.4509 35.91892 -61.3466 12 36.95387 -58.95497 111.4509 35.91892 -59.10282 111.857 35.53635 -59.10282 111.857 35.53635 -59.27157 112.1526 35.15211 -59.27157 112.1526 35.15211 -59.45796 112.3269 34.77508 -59.45796 112.3269 34.77508 -59.64444 112.3794 34.43574 -59.64444 112.3794 34.43574 -59.3311 129.5 28.57235 -59.8449 112.327 34.10485 -61.92081 12 35.75 -59.64444 112.3794 34.43574 -59.8449 112.327 34.10485 -61.92081 12 35.75 -60.07813 112.1529 33.75503 -60.07813 112.1529 33.75503 -60.32658 111.8574 33.41664 -60.32658 111.8574 33.41664 -60.58344 111.4522 33.09793 -60.58344 111.4522 33.09793 -60.85071 110.9408 32.79446 -62.67629 12 34.65077 -60.85071 110.9408 32.79446 -61.12717 110.3289 32.50665 -61.12717 110.3289 32.50665 -61.41498 109.6142 32.23165 -61.41498 109.6142 32.23165 -61.71566 108.7934 31.96801 -61.71566 108.7934 31.96801 -62.03116 107.8602 31.71454 -63.59442 12 33.68327 -62.03116 107.8602 31.71454 -62.36334 106.8069 31.47068 -62.36334 106.8069 31.47068 -62.71448 105.6228 31.23617 -62.71448 105.6228 31.23617 -63.08639 104.2973 31.01151 -63.08639 104.2973 31.01151 -63.48107 102.8183 30.79761 -64.65261 12 32.8713 -63.48107 102.8183 30.79761 -63.90098 101.1704 30.59562 -63.90098 101.1704 30.59562 -61.30022 129.5 24.0592 -64.34839 99.33776 30.40735 -64.34839 99.33776 30.40735 -64.82563 97.30286 30.23513 -64.82563 97.30286 30.23513 -65.33538 95.04547 30.08181 -65.82477 12 32.23486 -65.33538 95.04547 30.08181 -65.8804 92.54319 29.95104 -65.8804 92.54319 29.95104 -66.46384 89.76996 29.84738 -66.46384 89.76996 29.84738 -67.08905 86.69617 29.77649 -67.08207 12 31.78963 -67.08905 86.69617 29.77649 -67.75957 83.28813 29.74555 -67.75957 83.28813 29.74555 -68.47919 79.50714 29.76363 -68.39354 12 31.54656 -68.47919 79.50714 29.76363 -69.25145 75.3105 29.84229 -69.25145 75.3105 29.84229 -70.07994 70.64891 29.99617 -69.72689 12 31.51165 -70.07994 70.64891 29.99617 -70.96791 65.46395 30.24472 -70.96791 65.46395 30.24472 -71.91793 59.68569 30.61429 -71.04928 12 31.68575 -71.91793 59.68569 30.61429 -72.93093 53.22743 31.14193 -72.32817 12 32.06457 -72.93093 53.22743 31.14193 -79.85744 28.47987 24.95315 -74.00339 45.9834 31.88189 -73.53203 12 32.63878 -74.00339 45.9834 31.88189 -75.12493 37.79684 32.92291 -74.63127 12 33.39426 -75.12493 37.79684 32.92291 -76.25666 28.47987 34.42083 -75.59877 12 34.31239 -76.25666 28.47987 34.42083 -80.7658 24.46426 25.89758 -76.25666 28.47987 34.42083 -79.85744 28.47987 24.95315 -76.76898 25.33502 35.2826 -76.41073 12 35.37057 -76.76898 25.33502 35.2826 -64.20159 129.5 14.65359 -82.2877 28.47987 15.11971 -83.3506 24.46426 15.69966 -82.2877 28.47987 15.11971 -62.92676 129.5 19.4111 -65.66848 129.5 4.920582 -83.51181 28.47987 5.064649 -84.653 24.46426 5.260197 -83.51181 28.47987 5.064649 -65.11721 129.5 9.814099 -65.85256 129.5 0 -83.51181 28.47987 -5.064649 -83.51181 28.47987 -5.064649 -65.11721 129.5 -9.814099 -82.2877 28.47987 -15.11971 -84.653 24.46426 -5.260197 -82.2877 28.47987 -15.11971 -65.66848 129.5 -4.920582 -62.92676 129.5 -19.4111 -79.85744 28.47987 -24.95315 -83.3506 24.46426 -15.69966 -79.85744 28.47987 -24.95315 -64.20159 129.5 -14.65359 -75.128 37.77328 -32.92626 -76.25666 28.47987 -34.42083 -80.7658 24.46426 -25.89758 -76.25666 28.47987 -34.42083 -74.00885 45.94526 -31.88624 -72.93721 53.18627 -31.1457 -71.92422 59.64659 -30.61713 -61.30022 129.5 -24.0592 -75.59877 12 -34.31239 -76.25666 28.47987 -34.42083 -75.128 37.77328 -32.92626 -76.76898 25.33501 -35.2826 -76.41073 12 -35.37057 -76.76898 25.33501 -35.2826 -74.63127 12 -33.39426 -74.00885 45.94526 -31.88624 -73.53203 12 -32.63878 -72.93721 53.18627 -31.1457 -72.32817 12 -32.06457 -71.92422 59.64659 -30.61713 -70.97407 65.42729 -30.24676 -71.04928 12 -31.68575 -70.97407 65.42729 -30.24676 -70.08599 70.6142 -29.99756 -70.08599 70.6142 -29.99756 -69.2574 75.27765 -29.84313 -69.72689 12 -31.51165 -69.2574 75.27765 -29.84313 -68.485 79.47608 -29.76399 -68.485 79.47608 -29.76399 -59.3311 129.5 -28.57235 -67.76525 83.25878 -29.74548 -68.39354 12 -31.54656 -67.76525 83.25878 -29.74548 -67.09452 86.66883 -29.77605 -67.09452 86.66883 -29.77605 -66.46907 89.74466 -29.84662 -67.08207 12 -31.78963 -66.46907 89.74466 -29.84662 -65.88543 92.5197 -29.94999 -65.88543 92.5197 -29.94999 -65.34017 95.02383 -30.08051 -65.34017 95.02383 -30.08051 -64.83016 97.28314 -30.23363 -65.82477 12 -32.23486 -64.83016 97.28314 -30.23363 -64.35267 99.31984 -30.40568 -64.35267 99.31984 -30.40568 -63.90499 101.1544 -30.59381 -63.90499 101.1544 -30.59381 -63.48478 102.8041 -30.79572 -63.48478 102.8041 -30.79572 -57.0303 129.5 -32.92578 -63.08979 104.2849 -31.00957 -64.65261 12 -32.8713 -63.08979 104.2849 -31.00957 -62.71754 105.6121 -31.23422 -62.71754 105.6121 -31.23422 -62.3661 106.7978 -31.46875 -62.3661 106.7978 -31.46875 -62.03363 107.8526 -31.71264 -62.03363 107.8526 -31.71264 -61.71778 108.7874 -31.96623 -63.59442 12 -33.68327 -61.71778 108.7874 -31.96623 -61.4167 109.6097 -32.23007 -61.4167 109.6097 -32.23007 -61.12855 110.3256 -32.50528 -61.12855 110.3256 -32.50528 -60.85177 110.9386 -32.7933 -60.85177 110.9386 -32.7933 -60.58418 111.4509 -33.09705 -62.67629 12 -34.65077 -60.58418 111.4509 -33.09705 -60.32679 111.857 -33.41637 -60.32679 111.857 -33.41637 -60.07841 112.1526 -33.75463 -60.07841 112.1526 -33.75463 -59.84508 112.3269 -34.10456 -59.84508 112.3269 -34.10456 -59.64444 112.3794 -34.43574 -59.64444 112.3794 -34.43574 -54.4104 129.5 -37.0955 -59.45811 112.327 -34.77478 -61.92081 12 -35.75 -59.64444 112.3794 -34.43574 -59.45811 112.327 -34.77478 -61.92081 12 -35.75 -59.27178 112.1529 -35.15167 -59.27178 112.1529 -35.15167 -59.10295 111.8574 -35.53603 -59.10295 111.8574 -35.53603 -58.95536 111.4522 -35.91783 -58.95536 111.4522 -35.91783 -58.82619 110.9408 -36.30103 -61.3466 12 -36.95387 -58.82619 110.9408 -36.30103 -58.71517 110.3289 -36.68436 -58.71517 110.3289 -36.68436 -58.62092 109.6142 -37.07111 -58.62092 109.6142 -37.07111 -58.54294 108.7934 -37.46332 -58.54294 108.7934 -37.46332 -58.48117 107.8602 -37.86329 -60.96778 12 -38.23275 -58.48117 107.8602 -37.86329 -58.43608 106.8069 -38.2729 -58.43608 106.8069 -38.2729 -58.40855 105.6228 -38.69424 -58.40855 105.6228 -38.69424 -58.39995 104.2973 -39.12866 -58.39995 104.2973 -39.12866 -58.41205 102.8183 -39.57741 -60.79368 12 -39.55514 -58.41205 102.8183 -39.57741 -58.44707 101.1704 -40.04206 -58.44707 101.1704 -40.04206 -51.48568 129.5 -41.05846 -58.50773 99.33776 -40.52366 -58.50773 99.33776 -40.52366 -58.5972 97.30286 -41.02306 -58.5972 97.30286 -41.02306 -58.71929 95.04547 -41.54118 -60.82859 12 -40.88849 -58.71929 95.04547 -41.54118 -58.87856 92.54319 -42.07857 -58.87856 92.54319 -42.07857 -59.0805 89.76996 -42.63568 -59.0805 89.76996 -42.63568 -59.33171 86.69617 -43.21257 -61.07166 12 -42.19996 -59.33171 86.69617 -43.21257 -59.64018 83.28813 -43.80873 -59.64018 83.28813 -43.80873 -60.01565 79.50714 -44.4229 -61.51689 12 -43.45726 -60.01565 79.50714 -44.4229 -60.4699 75.3105 -45.05237 -60.4699 75.3105 -45.05237 -61.01741 70.64891 -45.69291 -62.15333 12 -44.62943 -61.01741 70.64891 -45.69291 -61.67665 65.46395 -46.33765 -61.67665 65.46395 -46.33765 -62.47172 59.68569 -46.97561 -62.9653 12 -45.68761 -62.47172 59.68569 -46.97561 -63.43516 53.22743 -47.58906 -63.93281 12 -46.60574 -63.43516 53.22743 -47.58906 -61.53878 28.47987 -56.68199 -64.61222 45.9834 -48.14787 -65.03203 12 -47.36122 -64.61222 45.9834 -48.14787 -66.07455 37.79684 -48.59864 -66.23591 12 -47.93543 -66.07455 37.79684 -48.59864 -67.93764 28.47987 -48.82978 -67.5148 12 -48.31425 -67.93764 28.47987 -48.82978 -62.81087 24.46426 -56.99645 -67.93764 28.47987 -48.82978 -61.53878 28.47987 -56.68199 -68.94012 25.33502 -48.84258 -68.83718 12 -48.48835 -68.94012 25.33502 -48.84258 -44.79069 129.5 -48.27375 -54.2379 28.47987 -63.70338 -55.2716 24.46426 -64.3339 -54.2379 28.47987 -63.70338 -48.27289 129.5 -44.7917 -37.09656 129.5 -54.40962 -46.14201 28.47987 -69.79101 -46.88196 24.46426 -70.68155 -46.14201 28.47987 -69.79101 -41.05839 129.5 -51.4856 -32.92695 129.5 -57.02968 -37.36978 28.47987 -74.85566 -37.36978 28.47987 -74.85566 -24.05798 129.5 -61.30075 -28.04979 28.47987 -78.82309 -37.77103 24.46426 -75.94175 -28.04979 28.47987 -78.82309 -28.5724 129.5 -59.33119 -14.65357 129.5 -64.20149 -18.31866 28.47987 -81.63515 -28.07899 24.46426 -80.03356 -18.31866 28.47987 -81.63515 -19.40983 129.5 -62.9271 -9.049017 37.77328 -81.52589 -8.31901 28.47987 -83.25061 -17.95494 24.46426 -82.89403 -8.31901 28.47987 -83.25061 -9.390129 45.94526 -80.03665 -9.495635 53.18627 -78.73831 -9.446903 59.64659 -77.59677 -9.815401 129.5 -65.11697 -8.08398 12 -82.62664 -8.31901 28.47987 -83.25061 -9.049017 37.77328 -81.52589 -7.828857 25.33501 -84.12519 -7.573555 12 -83.85892 -7.828857 25.33501 -84.12519 -8.395353 12 -81.3297 -9.390129 45.94526 -80.03665 -8.5 12 -80 -9.495635 53.18627 -78.73831 -8.395353 12 -78.67031 -9.446903 59.64659 -77.59677 -9.292576 65.42729 -76.58872 -8.08398 12 -77.37336 -9.292576 65.42729 -76.58872 -9.06434 70.6142 -75.69503 -9.06434 70.6142 -75.69503 -8.783785 75.27765 -74.90023 -7.573555 12 -76.14109 -8.783785 75.27765 -74.90023 -8.466131 79.47608 -74.19174 -8.466131 79.47608 -74.19174 -8.122282 83.25878 -73.55918 -6.876644 12 -75.00382 -8.122282 83.25878 -73.55918 -7.760439 86.66883 -72.99359 -7.760439 86.66883 -72.99359 -7.386609 89.74466 -72.48722 -6.010408 12 -73.9896 -7.386609 89.74466 -72.48722 -7.005258 92.5197 -72.03345 -7.005258 92.5197 -72.03345 -6.619599 95.02383 -71.62651 -6.619599 95.02383 -71.62651 -6.231984 97.28314 -71.26139 -4.996175 12 -73.12336 -6.231984 97.28314 -71.26139 -5.844246 99.31984 -70.93389 -5.844246 99.31984 -70.93389 -5.457476 101.1544 -70.64025 -5.457476 101.1544 -70.64025 -5.072514 102.8041 -70.37729 -3.858919 12 -72.42646 -4.689824 104.2849 -70.14215 -4.309144 105.6121 -69.9321 -3.930311 106.7978 -69.74501 -3.552864 107.8526 -69.57902 -2.626644 12 -71.91603 -3.17533 108.7874 -69.43228 -2.796289 109.6097 -69.30346 -2.413873 110.3256 -69.19152 -2.026049 110.9386 -69.09584 -1.629207 111.4509 -69.01597 -1.22397 111.857 -68.95272 -0.806836 112.1526 -68.90676 -9.621398 129.5 -60.74267 -9.815401 129.5 -65.11697 -14.65357 129.5 -64.20149 -19.00452 129.5 -58.48989 -19.40983 129.5 -62.9271 -24.05798 129.5 -61.30075 -27.91977 129.5 -54.79717 -28.5724 129.5 -59.33119 -32.92695 129.5 -57.02968 -36.14879 129.5 -49.75454 -37.09656 129.5 -54.40962 -41.05839 129.5 -51.4856 -43.48752 129.5 -43.48654 -44.79069 129.5 -48.27375 -48.27289 129.5 -44.7917 -49.75447 129.5 -36.14874 -51.48568 129.5 -41.05846 -54.4104 129.5 -37.0955 -54.79654 129.5 -27.92101 -57.0303 129.5 -32.92578 -58.48997 129.5 -19.00455 -59.3311 129.5 -28.57235 -60.74289 129.5 -9.620025 -61.30022 129.5 -24.0592 -61.4999 129.5 0 -62.92676 129.5 -19.4111 -62.92676 129.5 19.4111 -64.20159 129.5 -14.65359 -61.30022 129.5 24.0592 -64.20159 129.5 14.65359 -65.11721 129.5 -9.814099 -65.11721 129.5 9.814099 -65.66848 129.5 -4.920582 -65.66848 129.5 4.920582 -65.85256 129.5 0 -60.74289 129.5 9.620025 -59.3311 129.5 28.57235 -58.48997 129.5 19.00455 -57.0303 129.5 32.92578 -54.79654 129.5 27.92101 -54.4104 129.5 37.0955 -51.48568 129.5 41.05846 -49.75447 129.5 36.14874 -48.27289 129.5 44.7917 -44.79069 129.5 48.27375 -41.05839 129.5 51.4856 -43.48752 129.5 43.48654 -41.05839 129.5 51.4856 -42.55324 95 58 -37.09656 129.5 54.40962 -37.09656 129.5 54.40962 -34.50087 97.64976 62.58951 -32.92695 129.5 57.02968 -36.14879 129.5 49.75454 -32.92695 129.5 57.02968 -28.5724 129.5 59.33119 -28.5724 129.5 59.33119 -26.12594 99.69652 66.13462 -24.05798 129.5 61.30075 -27.91977 129.5 54.79717 -24.05798 129.5 61.30075 -17.52952 101.1482 68.64897 -19.40983 129.5 62.9271 -19.40983 129.5 62.9271 -14.65357 129.5 64.20149 -19.00452 129.5 58.48989 -14.65357 129.5 64.20149 -9.815401 129.5 65.11697 -9.815401 129.5 65.11697 -46.25 38 58 -37.5 85 58 -37.5 90.05471 58 -33.44577 90.05471 58 -32.74585 89.89495 58 -31.25827 90.05471 58 -30.13828 90.05471 58 -29.23825 90.05471 58 -28.17565 90.05471 58 -25.41853 90.05471 58 -46.56652 39.79531 58 -47.47806 41.37431 58 -48.87478 42.54642 58 -50.58826 43.17013 58 -52.41174 43.17013 58 -54.12522 42.54642 58 -55.52194 41.37431 58 -24.00547 15 89.58963 -24.00468 0 89.5898 -35.49389 15 85.68983 -35.49462 0 85.68946 -46.375 15 80.32386 -46.3744 0 80.32411 -56.46262 15 73.58352 -56.46306 0 73.58319 -65.58415 15 65.58415 -65.58409 0 65.58409 -23.33038 0 73.15058 -65.58409 0 65.58409 -21.09926 0 75.53565 -22.43872 0 74.55274 -73.58352 15 56.46262 -73.58319 0 56.46306 -34.91125 0 65.24723 -73.58319 0 56.46306 -23.65241 0 71.52102 -23.82219 0 70.73329 -24.28907 0 70.0765 -24.97726 0 69.65728 -30.02424 0 67.63539 -80.32386 15 46.375 -80.32411 0 46.3744 -48.34053 0 56.02841 -80.32411 0 46.3744 -39.60983 0 62.50645 -44.09431 0 59.42797 -85.68983 15 35.49389 -85.68946 0 35.49462 -70.73562 0 43.99369 -85.68946 0 35.49462 -69.28203 0 44.25 -56.02798 0 48.34104 -52.32561 0 52.32609 -89.58963 15 24.00547 -89.5898 0 24.00468 -65.24707 0 34.91158 -89.5898 0 24.00468 -73.46747 0 40.73801 -72.96264 0 42.125 -72.01388 0 43.25569 -73.46747 0 39.26199 -72.96264 0 37.875 -72.01388 0 36.74431 -70.73562 0 36.0063 -69.28203 0 35.75 -91.95652 15 12.1063 -91.95637 0 12.10664 -73.15052 0 23.33041 -91.95637 0 12.10664 -70.73329 0 23.82219 -67.6353 0 30.02444 -69.65728 0 24.97726 -70.0765 0 24.28907 -92.75 15 0 -92.75 0 0 -73.58609 0 7.81595 -92.75 0 0 -74.55265 0 22.43881 -75.53559 0 21.09942 -75.96543 0 19.49533 -75.78392 0 17.84387 -75.01544 0 16.37059 -73.76522 0 15.27692 -73.16793 0 14.73602 -72.83258 0 14.0033 -72.81361 0 13.1977 -91.95652 15 -12.1063 -91.95637 0 -12.10664 -73.93708 0 -3.049872 -91.95637 0 -12.10664 -73.96138 0 2.389604 -89.58963 15 -24.00547 -89.5898 0 -24.00468 -72.6923 0 -13.8499 -89.5898 0 -24.00468 -73.51329 0 -8.472777 -85.68983 15 -35.49389 -85.68946 0 -35.49462 -69.87857 0 -24.3511 -85.68946 0 -35.49462 -71.47854 0 -19.15223 -80.32386 15 -46.375 -80.32411 0 -46.3744 -72.01388 0 -36.74431 -80.32411 0 -46.3744 -70.73562 0 -36.0063 -69.28203 0 -35.75 -65.55659 0 -34.32678 -67.90103 0 -29.41839 -73.58352 15 -56.46262 -73.58319 0 -56.46306 -56.45958 0 -47.83634 -73.58319 0 -56.46306 -72.01388 0 -43.25569 -72.96264 0 -42.125 -73.46747 0 -40.73801 -70.73562 0 -43.99369 -69.28203 0 -44.25 -59.81959 0 -43.56166 -72.96264 0 -37.875 -73.46747 0 -39.26199 -65.58415 15 -65.58415 -65.58409 0 -65.58409 -53.3452 0 -56.70886 -65.58409 0 -65.58409 -56.0732 0 -48.54349 -55.99727 0 -49.34572 -56.24409 0 -50.11281 -56.77998 0 -51.685 -56.7089 0 -53.34508 -56.04042 0 -54.86601 -54.86616 0 -56.04032 -56.46262 15 -73.58352 -56.46306 0 -73.58319 -41.99308 0 -66.6058 -56.46306 0 -73.58319 -40.625 0 -66.36457 -34.32729 0 -65.55632 -51.68506 0 -56.77999 -43.56186 0 -59.81944 -39.05015 0 -62.85763 -46.375 15 -80.32386 -46.3744 0 -80.32411 -41.99308 0 -74.12334 -46.3744 0 -80.32411 -43.19615 0 -67.30039 -44.0891 0 -68.36457 -44.56423 0 -69.66997 -44.56423 0 -71.05916 -44.0891 0 -72.36457 -43.19615 0 -73.42874 -35.49389 15 -85.68983 -35.49462 0 -85.68946 -4.185433 0 -80.73801 -1.453586 0 -76.00631 0 0 -75.75 -40.625 0 -74.36457 -2.731847 0 -76.74431 -3.680608 0 -77.875 -4.185433 0 -79.262 -24.00547 15 -89.58963 -24.00468 0 -89.5898 -1.453586 0 -83.99369 -3.680608 0 -82.125 -2.731847 0 -83.25569 -22.24928 17.56821 -86.65523 -24.00547 15 -89.58963 0 17.56821 -89.46598 -11.21306 17.56821 -88.7605 -32.93462 17.56821 -83.18335 -35.49389 15 -85.68983 -43.10056 17.56821 -78.39963 -46.375 15 -80.32386 -52.58678 17.56821 -72.3795 -56.46262 15 -73.58352 -61.24367 17.56821 -65.21788 -65.58415 15 -65.58415 -68.93473 17.56821 -57.02775 -73.58352 15 -56.46262 -75.53861 17.56821 -47.93826 -80.32386 15 -46.375 -80.95124 17.56821 -38.09275 -85.68983 15 -35.49389 -85.08719 17.56821 -27.6465 -89.58963 15 -24.00547 -87.88128 17.56821 -16.76425 -91.95652 15 -12.1063 -89.28943 17.56821 -5.617614 -92.75 15 0 -89.28943 17.56821 5.617614 -91.95652 15 12.1063 -87.88128 17.56821 16.76425 -89.58963 15 24.00547 -85.08719 17.56821 27.6465 -85.68983 15 35.49389 -80.95124 17.56821 38.09275 -80.32386 15 46.375 -75.53861 17.56821 47.93826 -73.58352 15 56.46262 -68.93473 17.56821 57.02775 -65.58415 15 65.58415 -61.24367 17.56821 65.21788 -56.46262 15 73.58352 -52.58678 17.56821 72.3795 -46.375 15 80.32386 -43.10056 17.56821 78.39963 -35.49389 15 85.68983 -32.93462 17.56821 83.18335 -24.00547 15 89.58963 -22.24928 17.56821 86.65523 56.53218 26.88902 62.14625 -60.42392 28 58 56.53218 26.88902 62.14625 60.42392 28 58 -60.42392 28 58 -46.56652 36.20468 58 -50.58826 32.82986 58 -48.87478 33.45357 58 -47.47806 34.62569 58 -36.44685 85 58 -36.44685 86.8284 58 -31.25827 85 58 -30.13828 85 58 -29.23825 85 58 -25.98325 85 58 -25.47593 85 58 -20 85 58 69.38591 24.39945 48.82408 65.31641 20.77186 57.13412 70.31708 22.85943 48.72317 70.17053 12 48.45344 70.31708 22.85943 48.72317 54.74356 24.46426 64.78382 57.38381 20.77186 65.09716 52.49607 25.8636 65.97315 45.97255 24.43957 71.28771 48.48851 20.77186 71.96808 45.97255 24.43957 71.28771 52.49607 25.8636 65.97315 44.07157 24.07225 72.65855 44.07157 24.07225 72.65855 38.77975 20.77186 77.63164 35.34436 22.63173 78.03467 35.34436 22.63173 78.03467 71.82141 21.06345 48.36018 71.482 12 48.21037 71.82141 21.06345 48.36018 72.1659 20.73472 48.23857 72.1659 20.73472 48.23857 73.29663 19.81758 47.72366 72.73931 12 47.76514 73.29663 19.81758 47.72366 28.4204 20.77186 81.99282 26.49618 21.53731 82.11911 17.5829 20.77094 84.97924 17.5829 20.77094 84.97924 26.49618 21.53731 82.11911 8.800604 20.32513 86.64302 8.800604 20.32513 86.64302 0 20.17705 87.19565 0 20.17705 87.19565 74.6546 18.99996 46.82167 73.91146 12 47.1287 74.6546 18.99996 46.82167 75.83428 18.53583 45.67951 74.96965 12 46.31673 75.83428 18.53583 45.67951 76.78805 18.38519 44.3336 75.88777 12 45.34922 76.78805 18.38519 44.3336 77.47677 18.53584 42.83462 76.64325 12 44.25 76.78805 18.38519 44.3336 77.47677 18.53584 42.83462 76.64325 12 44.25 77.87606 18.99997 41.24192 77.59629 12 41.76725 77.87606 18.99997 41.24192 77.21747 12 43.04613 77.97822 19.81758 39.6149 77.7704 12 40.44485 77.97822 19.81758 39.6149 77.85877 20.73472 38.37821 77.73548 12 39.11151 77.85877 20.73472 38.37821 82.17361 20.77186 27.89335 77.79184 21.06346 38.01905 77.79184 21.06346 38.01905 85.11135 20.77186 16.92922 76.97584 24.39945 35.6779 77.35404 22.85944 36.53479 86.59291 20.77186 5.67544 86.59291 20.77186 -5.67544 85.11135 20.77186 -16.92922 82.17361 20.77186 -27.89335 77.85877 20.73472 -38.37821 77.79184 21.06346 -38.01905 76.97584 24.39945 -35.6779 77.35404 22.85944 -36.53479 77.97822 19.81758 -39.6149 77.73548 12 -39.11151 77.85877 20.73472 -38.37821 77.97822 19.81758 -39.6149 77.4924 12 -37.80004 77.79184 21.06346 -38.01905 77.87606 18.99997 -41.24192 77.7704 12 -40.44485 77.87606 18.99997 -41.24192 77.47677 18.53584 -42.83462 77.59629 12 -41.76725 77.47677 18.53584 -42.83462 76.78805 18.38519 -44.3336 77.21747 12 -43.04613 76.78805 18.38519 -44.3336 75.83428 18.53583 -45.67951 76.64325 12 -44.25 76.78805 18.38519 -44.3336 75.83428 18.53583 -45.67951 76.64325 12 -44.25 74.6546 18.99996 -46.82167 74.96965 12 -46.31673 74.6546 18.99996 -46.82167 75.88777 12 -45.34922 73.29663 19.81757 -47.72366 73.91146 12 -47.1287 73.29663 19.81757 -47.72366 72.1659 20.73472 -48.23857 72.73931 12 -47.76514 72.1659 20.73472 -48.23857 65.24315 20.77186 -57.21776 71.82141 21.06345 -48.36018 71.82141 21.06345 -48.36018 57.2168 20.77186 -65.24398 69.38591 24.39945 -48.82408 70.3171 22.85943 -48.72317 48.21152 20.77186 -72.15393 38.38137 20.77186 -77.82937 27.89454 20.77186 -82.17321 16.93045 20.77186 -85.11111 5.692887 20.73473 -86.61679 5.97046 21.06346 -86.37924 7.589947 24.39945 -84.50199 7.036967 22.85944 -85.25796 4.681576 19.81756 -87.3386 4.996175 12 -86.87664 5.692887 20.73473 -86.61679 4.681576 19.81756 -87.3386 6.010408 12 -86.01041 5.97046 21.06346 -86.37924 3.221466 18.99996 -88.06362 3.858919 12 -87.57357 3.221466 18.99996 -88.06362 0 17.56821 -89.46598 1.642664 18.53587 -88.51413 2.626644 12 -88.08398 1.642664 18.53587 -88.51413 0 18.38519 -88.66722 1.329693 12 -88.39535 0 18.38519 -88.66722 0 18.38519 -88.66722 -1.642655 18.53586 -88.51414 0 12 -88.5 0 18.38519 -88.66722 -1.642655 18.53586 -88.51414 0 12 -88.5 -8.800391 20.32512 86.64303 0 17.56821 89.46598 0 20.17705 87.19565 -8.800391 20.32512 86.64303 76.97584 24.39945 -35.6779 77.04718 12 -36.54274 77.35404 22.85944 -36.53479 77.04718 12 36.54274 76.97584 24.39945 35.6779 77.35404 22.85944 36.53479 77.4924 12 37.80004 7.589947 24.39945 -84.50199 6.876644 12 -84.99618 7.036967 22.85944 -85.25796 70.17053 12 -48.45344 69.38591 24.39945 -48.82408 70.3171 22.85943 -48.72317 71.482 12 -48.21037 -17.58298 20.77095 84.9792 -28.42046 20.77186 81.99279 -38.77979 20.77186 77.63162 -48.48854 20.77186 71.96807 -57.38383 20.77186 65.09713 -65.31642 20.77186 57.13411 -73.29663 19.81757 47.72366 -72.1659 20.73472 48.23857 -77.47677 18.53584 42.83462 -76.78805 18.38519 44.3336 -75.83428 18.53583 45.67951 -74.6546 18.99996 46.82167 -82.17361 20.77186 27.89335 -77.85877 20.73472 38.37821 -77.97822 19.81758 39.6149 -77.87606 18.99997 41.24192 -85.11135 20.77186 16.92922 -86.59291 20.77186 5.67544 -86.59291 20.77186 -5.67544 -85.11135 20.77186 -16.92922 -82.17361 20.77186 -27.89335 -75.83428 18.53583 -45.67951 -76.78805 18.38519 -44.3336 -77.47677 18.53584 -42.83462 -77.87606 18.99997 -41.24192 -77.97822 19.81758 -39.6149 -77.85877 20.73472 -38.37821 -72.1659 20.73472 -48.23857 -73.29663 19.81758 -47.72366 -74.6546 18.99996 -46.82167 -65.24315 20.77186 -57.21776 -57.2168 20.77186 -65.24398 -48.21152 20.77186 -72.15393 -38.38137 20.77186 -77.82937 -27.89454 20.77186 -82.17321 -16.93045 20.77186 -85.11111 -3.22146 18.99996 -88.06362 -4.681574 19.81756 -87.3386 -5.692884 20.73473 -86.61679 -2.626644 12 -88.08398 -3.22146 18.99996 -88.06362 -1.329693 12 -88.39535 -3.858919 12 -87.57357 -4.681574 19.81756 -87.3386 -4.996175 12 -86.87664 -5.692884 20.73473 -86.61679 -5.970464 21.06347 -86.37924 -5.970464 21.06347 -86.37924 -7.589947 24.39945 -84.50199 -7.036967 22.85944 -85.25796 -71.82141 21.06345 -48.36018 -69.38591 24.39945 -48.82408 -70.31708 22.85943 -48.72317 -72.73931 12 -47.76514 -72.1659 20.73472 -48.23857 -73.29663 19.81758 -47.72366 -71.482 12 -48.21037 -71.82141 21.06345 -48.36018 -73.91146 12 -47.1287 -74.6546 18.99996 -46.82167 -74.96965 12 -46.31673 -75.83428 18.53583 -45.67951 -75.88777 12 -45.34922 -76.78805 18.38519 -44.3336 -76.64325 12 -44.25 -76.78805 18.38519 -44.3336 -77.47677 18.53584 -42.83462 -76.64325 12 -44.25 -77.59629 12 -41.76725 -77.87606 18.99997 -41.24192 -77.21747 12 -43.04613 -77.7704 12 -40.44485 -77.97822 19.81758 -39.6149 -77.73548 12 -39.11151 -77.85877 20.73472 -38.37821 -77.79184 21.06346 -38.01905 -77.79184 21.06346 -38.01905 -76.97584 24.39945 -35.6779 -77.35404 22.85944 -36.53479 -77.79184 21.06346 38.01905 -76.97584 24.39945 35.6779 -77.35404 22.85944 36.53479 -77.73548 12 39.11151 -77.85877 20.73472 38.37821 -77.97822 19.81758 39.6149 -77.4924 12 37.80004 -77.79184 21.06346 38.01905 -77.7704 12 40.44485 -77.87606 18.99997 41.24192 -77.59629 12 41.76725 -77.47677 18.53584 42.83462 -77.21747 12 43.04613 -76.78805 18.38519 44.3336 -76.64325 12 44.25 -76.78805 18.38519 44.3336 -75.83428 18.53583 45.67951 -76.64325 12 44.25 -74.96965 12 46.31673 -74.6546 18.99996 46.82167 -75.88777 12 45.34922 -73.91146 12 47.1287 -73.29663 19.81757 47.72366 -72.73931 12 47.76514 -72.1659 20.73472 48.23857 -71.82141 21.06345 48.36018 -71.82141 21.06345 48.36018 -70.3171 22.85943 48.72317 -69.38591 24.39945 48.82408 -54.74356 24.46426 64.78382 -45.97254 24.43957 71.28771 -35.34425 22.63171 78.03473 -44.0715 24.07224 72.65859 -26.49603 21.53729 82.11917 -17.58298 20.77095 84.9792 -26.49603 21.53729 82.11917 -35.34425 22.63171 78.03473 -71.482 12 48.21037 -70.3171 22.85943 48.72317 -70.17053 12 48.45344 -69.38591 24.39945 48.82408 -52.49603 25.86359 65.97319 -56.53216 26.88901 62.14626 -45.97254 24.43957 71.28771 -44.0715 24.07224 72.65859 -52.49603 25.86359 65.97319 -56.53216 26.88901 62.14626 -69.38591 24.39945 -48.82408 -70.17053 12 -48.45344 -70.31708 22.85943 -48.72317 -6.876644 12 -84.99618 -7.589947 24.39945 -84.50199 -7.036967 22.85944 -85.25796 -6.010408 12 -86.01041 -76.97584 24.39945 35.6779 -77.04718 12 36.54274 -77.35404 22.85944 36.53479 -77.04718 12 -36.54274 -76.97584 24.39945 -35.6779 -77.35404 22.85944 -36.53479 -77.4924 12 -37.80004 0 10 -71.5 0 12 -71.5 1.329693 12 -71.60466 -2.626644 10 -71.91603 -1.329693 12 -71.60466 0 12 -71.5 0 10 -71.5 2.626644 12 -71.91603 2.626644 10 -71.91603 3.858919 12 -72.42646 4.996175 12 -73.12336 4.996175 10 -73.12336 6.010408 12 -73.9896 6.876644 12 -75.00382 6.876644 10 -75.00382 7.573555 12 -76.14109 8.08398 12 -77.37336 8.08398 10 -77.37336 8.395353 12 -78.67031 8.5 12 -80 8.5 10 -80 8.395353 12 -81.3297 8.08398 12 -82.62664 8.08398 10 -82.62664 7.573555 12 -83.85892 6.876644 12 -84.99618 6.876644 10 -84.99618 6.010408 12 -86.01041 4.996175 12 -86.87664 4.996175 10 -86.87664 3.858919 12 -87.57357 2.626644 12 -88.08398 2.626644 10 -88.08398 1.329693 12 -88.39535 0 12 -88.5 0 10 -88.5 0 12 -88.5 -1.329693 12 -88.39535 0 10 -88.5 -2.626644 12 -88.08398 -2.626644 10 -88.08398 -3.858919 12 -87.57357 -4.996175 12 -86.87664 -4.996175 10 -86.87664 -6.010408 12 -86.01041 -6.876644 12 -84.99618 -6.876644 10 -84.99618 -7.573555 12 -83.85892 -8.08398 12 -82.62664 -8.08398 10 -82.62664 -8.395353 12 -81.3297 -8.5 12 -80 -8.5 10 -80 -8.395353 12 -78.67031 -8.08398 12 -77.37336 -8.08398 10 -77.37336 -7.573555 12 -76.14109 -6.876644 12 -75.00382 -6.876644 10 -75.00382 -6.010408 12 -73.9896 -4.996175 12 -73.12336 -4.996175 10 -73.12336 -3.858919 12 -72.42646 -2.626644 12 -71.91603 -61.92081 10 -35.75 -61.92081 12 -35.75 -61.3466 12 -36.95387 -63.59442 10 -33.68327 -62.67629 12 -34.65077 -61.92081 12 -35.75 -61.92081 10 -35.75 -60.96778 12 -38.23275 -60.96778 10 -38.23275 -60.79368 12 -39.55514 -60.82859 12 -40.88849 -60.82859 10 -40.88849 -61.07166 12 -42.19996 -61.51689 12 -43.45726 -61.51689 10 -43.45726 -62.15333 12 -44.62943 -62.9653 12 -45.68761 -62.9653 10 -45.68761 -63.93281 12 -46.60574 -65.03203 12 -47.36122 -65.03203 10 -47.36122 -66.23591 12 -47.93543 -67.5148 12 -48.31425 -67.5148 10 -48.31425 -68.83718 12 -48.48835 -70.17053 12 -48.45344 -70.17053 10 -48.45344 -71.482 12 -48.21037 -72.73931 12 -47.76514 -72.73931 10 -47.76514 -73.91146 12 -47.1287 -74.96965 12 -46.31673 -74.96965 10 -46.31673 -75.88777 12 -45.34922 -76.64325 12 -44.25 -76.64325 10 -44.25 -76.64325 12 -44.25 -77.21747 12 -43.04613 -76.64325 10 -44.25 -77.59629 12 -41.76725 -77.59629 10 -41.76725 -77.7704 12 -40.44485 -77.73548 12 -39.11151 -77.73548 10 -39.11151 -77.4924 12 -37.80004 -77.04718 12 -36.54274 -77.04718 10 -36.54274 -76.41073 12 -35.37057 -75.59877 12 -34.31239 -75.59877 10 -34.31239 -74.63127 12 -33.39426 -73.53203 12 -32.63878 -73.53203 10 -32.63878 -72.32817 12 -32.06457 -71.04928 12 -31.68575 -71.04928 10 -31.68575 -69.72689 12 -31.51165 -68.39354 12 -31.54656 -68.39354 10 -31.54656 -67.08207 12 -31.78963 -65.82477 12 -32.23486 -65.82477 10 -32.23486 -64.65261 12 -32.8713 -63.59442 12 -33.68327 -61.92081 10 35.75 -61.92081 12 35.75 -62.67629 12 34.65077 -60.96778 10 38.23275 -61.3466 12 36.95387 -61.92081 12 35.75 -61.92081 10 35.75 -63.59442 12 33.68327 -63.59442 10 33.68327 -64.65261 12 32.8713 -65.82477 12 32.23486 -65.82477 10 32.23486 -67.08207 12 31.78963 -68.39354 12 31.54656 -68.39354 10 31.54656 -69.72689 12 31.51165 -71.04928 12 31.68575 -71.04928 10 31.68575 -72.32817 12 32.06457 -73.53203 12 32.63878 -73.53203 10 32.63878 -74.63127 12 33.39426 -75.59877 12 34.31239 -75.59877 10 34.31239 -76.41073 12 35.37057 -77.04718 12 36.54274 -77.04718 10 36.54274 -77.4924 12 37.80004 -77.73548 12 39.11151 -77.73548 10 39.11151 -77.7704 12 40.44485 -77.59629 12 41.76725 -77.59629 10 41.76725 -77.21747 12 43.04613 -76.64325 12 44.25 -76.64325 10 44.25 -76.64325 12 44.25 -75.88777 12 45.34922 -76.64325 10 44.25 -74.96965 12 46.31673 -74.96965 10 46.31673 -73.91146 12 47.1287 -72.73931 12 47.76514 -72.73931 10 47.76514 -71.482 12 48.21037 -70.17053 12 48.45344 -70.17053 10 48.45344 -68.83718 12 48.48835 -67.5148 12 48.31425 -67.5148 10 48.31425 -66.23591 12 47.93543 -65.03203 12 47.36122 -65.03203 10 47.36122 -63.93281 12 46.60574 -62.9653 12 45.68761 -62.9653 10 45.68761 -62.15333 12 44.62943 -61.51689 12 43.45726 -61.51689 10 43.45726 -61.07166 12 42.19996 -60.82859 12 40.88849 -60.82859 10 40.88849 -60.79368 12 39.55514 -60.96778 12 38.23275 61.92081 10 35.75 61.92081 12 35.75 61.3466 12 36.95387 63.59442 10 33.68327 62.67629 12 34.65077 61.92081 12 35.75 61.92081 10 35.75 60.96778 12 38.23275 60.96778 10 38.23275 60.79368 12 39.55514 60.82859 12 40.88849 60.82859 10 40.88849 61.07166 12 42.19996 61.51689 12 43.45726 61.51689 10 43.45726 62.15333 12 44.62943 62.9653 12 45.68761 62.9653 10 45.68761 63.93281 12 46.60574 65.03203 12 47.36122 65.03203 10 47.36122 66.23591 12 47.93543 67.5148 12 48.31425 67.5148 10 48.31425 68.83718 12 48.48835 70.17053 12 48.45344 70.17053 10 48.45344 71.482 12 48.21037 72.73931 12 47.76514 72.73931 10 47.76514 73.91146 12 47.1287 74.96965 12 46.31673 74.96965 10 46.31673 75.88777 12 45.34922 76.64325 12 44.25 76.64325 10 44.25 76.64325 12 44.25 77.21747 12 43.04613 76.64325 10 44.25 77.59629 12 41.76725 77.59629 10 41.76725 77.7704 12 40.44485 77.73548 12 39.11151 77.73548 10 39.11151 77.4924 12 37.80004 77.04718 12 36.54274 77.04718 10 36.54274 76.41073 12 35.37057 75.59877 12 34.31239 75.59877 10 34.31239 74.63127 12 33.39426 73.53203 12 32.63878 73.53203 10 32.63878 72.32817 12 32.06457 71.04928 12 31.68575 71.04928 10 31.68575 69.72689 12 31.51165 68.39354 12 31.54656 68.39354 10 31.54656 67.08207 12 31.78963 65.82477 12 32.23486 65.82477 10 32.23486 64.65261 12 32.8713 63.59442 12 33.68327 61.92081 10 -35.75 61.92081 12 -35.75 62.67629 12 -34.65077 60.96778 10 -38.23275 61.3466 12 -36.95387 61.92081 12 -35.75 61.92081 10 -35.75 63.59442 12 -33.68327 63.59442 10 -33.68327 64.65261 12 -32.8713 65.82477 12 -32.23486 65.82477 10 -32.23486 67.08207 12 -31.78963 68.39354 12 -31.54656 68.39354 10 -31.54656 69.72689 12 -31.51165 71.04928 12 -31.68575 71.04928 10 -31.68575 72.32817 12 -32.06457 73.53203 12 -32.63878 73.53203 10 -32.63878 74.63127 12 -33.39426 75.59877 12 -34.31239 75.59877 10 -34.31239 76.41073 12 -35.37057 77.04718 12 -36.54274 77.04718 10 -36.54274 77.4924 12 -37.80004 77.73548 12 -39.11151 77.73548 10 -39.11151 77.7704 12 -40.44485 77.59629 12 -41.76725 77.59629 10 -41.76725 77.21747 12 -43.04613 76.64325 12 -44.25 76.64325 10 -44.25 76.64325 12 -44.25 75.88777 12 -45.34922 76.64325 10 -44.25 74.96965 12 -46.31673 74.96965 10 -46.31673 73.91146 12 -47.1287 72.73931 12 -47.76514 72.73931 10 -47.76514 71.482 12 -48.21037 70.17053 12 -48.45344 70.17053 10 -48.45344 68.83718 12 -48.48835 67.5148 12 -48.31425 67.5148 10 -48.31425 66.23591 12 -47.93543 65.03203 12 -47.36122 65.03203 10 -47.36122 63.93281 12 -46.60574 62.9653 12 -45.68761 62.9653 10 -45.68761 62.15333 12 -44.62943 61.51689 12 -43.45726 61.51689 10 -43.45726 61.07166 12 -42.19996 60.82859 12 -40.88849 60.82859 10 -40.88849 60.79368 12 -39.55514 60.96778 12 -38.23275 0 10 -84.25 0 0 -84.25 1.453586 0 -83.99369 -1.453902 10 -83.99356 -1.453586 0 -83.99369 0 0 -84.25 0 10 -84.25 1.453902 10 -83.99356 2.731847 0 -83.25569 2.732141 10 -83.25537 3.680608 0 -82.125 3.680695 10 -82.12467 4.185433 0 -80.73801 4.185343 10 -80.73786 4.185433 0 -79.262 4.185343 10 -79.26214 3.680608 0 -77.875 2.731847 0 -76.74431 3.680695 10 -77.87535 2.731847 0 -76.74431 1.453586 0 -76.00631 2.732141 10 -76.74463 1.453586 0 -76.00631 17.84374 0 -75.78388 1.453902 10 -76.00644 0 0 -75.75 0 10 -75.75 0 0 -75.75 -1.453586 0 -76.00631 16.37053 0 -75.01541 0 10 -75.75 -1.453902 10 -76.00644 -2.731847 0 -76.74431 -2.732141 10 -76.74463 -3.680608 0 -77.875 -3.680695 10 -77.87535 -4.185433 0 -79.262 -4.185343 10 -79.26214 -4.185433 0 -80.73801 -4.185343 10 -80.73786 -3.680608 0 -82.125 -3.680695 10 -82.12467 -2.731847 0 -83.25569 -2.732141 10 -83.25537 -72.96264 10 -42.125 -72.96264 0 -42.125 -72.01388 0 -43.25569 -73.46751 10 -40.73766 -73.46747 0 -40.73801 -72.96264 0 -42.125 -72.96264 10 -42.125 -72.01361 10 -43.2559 -70.73562 0 -43.99369 -70.73519 10 -43.99379 -69.28203 0 -44.25 -67.82846 0 -43.99369 -69.2817 10 -44.24991 -67.82846 0 -43.99369 -66.5502 0 -43.25569 -67.82837 10 -43.99354 -66.5502 0 -43.25569 -62.85785 0 -39.0498 -65.60144 0 -42.125 -66.55036 10 -43.25568 -65.60144 0 -42.125 -65.09661 0 -40.73801 -65.60167 10 -42.12524 -65.09661 0 -40.73801 -65.09661 0 -39.26199 -65.09674 10 -40.73842 -65.09661 0 -39.26199 -65.60144 0 -37.875 -65.09656 10 -39.26234 -65.60144 0 -37.875 -66.5502 0 -36.74431 -65.60144 10 -37.875 -65.60144 0 -37.875 -66.5502 0 -36.74431 -65.60144 10 -37.875 -67.82846 0 -36.0063 -66.55046 10 -36.7441 -67.82846 0 -36.0063 -67.82888 10 -36.00621 -69.28203 0 -35.75 -69.28237 10 -35.75009 -70.73562 0 -36.0063 -70.73571 10 -36.00645 -72.01388 0 -36.74431 -72.01371 10 -36.74432 -72.96264 0 -37.875 -72.9624 10 -37.87476 -73.46747 0 -39.26199 -73.46734 10 -39.26158 -72.96264 10 42.125 -72.96264 0 42.125 -73.46747 0 40.73801 -72.01361 10 43.2559 -72.01388 0 43.25569 -72.96264 0 42.125 -72.96264 10 42.125 -73.46751 10 40.73766 -73.46747 0 39.26199 -73.46734 10 39.26158 -72.96264 0 37.875 -72.9624 10 37.87476 -72.01388 0 36.74431 -72.01371 10 36.74432 -70.73562 0 36.0063 -70.73571 10 36.00645 -69.28203 0 35.75 -67.82846 0 36.0063 -69.28237 10 35.75009 -67.82846 0 36.0063 -66.5502 0 36.74431 -67.82888 10 36.00621 -66.5502 0 36.74431 -62.50617 0 39.61026 -65.60144 0 37.875 -66.55046 10 36.7441 -65.60144 0 37.875 -65.09661 0 39.26199 -65.60144 10 37.875 -65.60144 0 37.875 -65.09661 0 39.26199 -65.60144 10 37.875 -65.09661 0 40.73801 -65.09656 10 39.26234 -65.09661 0 40.73801 -59.42761 0 44.09479 -65.60144 0 42.125 -65.09674 10 40.73842 -65.60144 0 42.125 -66.5502 0 43.25569 -65.60167 10 42.12524 -66.5502 0 43.25569 -67.82846 0 43.99369 -66.55036 10 43.25568 -67.82846 0 43.99369 -67.82837 10 43.99354 -69.28203 0 44.25 -69.2817 10 44.24991 -70.73562 0 43.99369 -70.73519 10 43.99379 72.96264 10 42.125 72.96264 0 42.125 72.01388 0 43.25569 73.46751 10 40.73766 73.46747 0 40.73801 72.96264 0 42.125 72.96264 10 42.125 72.01361 10 43.2559 70.73562 0 43.99369 70.73519 10 43.99379 69.28203 0 44.25 67.82846 0 43.99369 69.2817 10 44.24991 67.82846 0 43.99369 66.5502 0 43.25569 67.82837 10 43.99354 66.5502 0 43.25569 62.85779 0 39.04988 65.60144 0 42.125 66.55036 10 43.25568 65.60144 0 42.125 65.09661 0 40.73801 65.60167 10 42.12524 65.09661 0 40.73801 65.09661 0 39.26199 65.09674 10 40.73842 65.09661 0 39.26199 65.60144 0 37.875 65.09656 10 39.26234 65.60144 0 37.875 66.5502 0 36.74431 65.60144 10 37.875 65.60144 0 37.875 66.5502 0 36.74431 65.60144 10 37.875 67.82846 0 36.0063 66.55046 10 36.7441 67.82846 0 36.0063 67.82888 10 36.00621 69.28203 0 35.75 69.28237 10 35.75009 70.73562 0 36.0063 70.73571 10 36.00645 72.01388 0 36.74431 72.01371 10 36.74432 72.96264 0 37.875 72.9624 10 37.87476 73.46747 0 39.26199 73.46734 10 39.26158 72.96264 10 -42.125 72.96264 0 -42.125 73.46747 0 -40.73801 72.01361 10 -43.2559 72.01388 0 -43.25569 72.96264 0 -42.125 72.96264 10 -42.125 73.46751 10 -40.73766 73.46747 0 -39.26199 73.46734 10 -39.26158 72.96264 0 -37.875 72.9624 10 -37.87476 72.01388 0 -36.74431 72.01371 10 -36.74432 70.73562 0 -36.0063 70.73571 10 -36.00645 69.28203 0 -35.75 67.82846 0 -36.0063 69.28237 10 -35.75009 67.82846 0 -36.0063 66.5502 0 -36.74431 67.82888 10 -36.00621 66.5502 0 -36.74431 62.50635 0 -39.60998 65.60144 0 -37.875 66.55046 10 -36.7441 65.60144 0 -37.875 65.09661 0 -39.26199 65.60144 10 -37.875 65.60144 0 -37.875 65.09661 0 -39.26199 65.60144 10 -37.875 65.09661 0 -40.73801 65.09656 10 -39.26234 65.09661 0 -40.73801 59.42784 0 -44.09448 65.60144 0 -42.125 65.09674 10 -40.73842 65.60144 0 -42.125 66.5502 0 -43.25569 65.60167 10 -42.12524 66.5502 0 -43.25569 67.82846 0 -43.99369 66.55036 10 -43.25568 67.82846 0 -43.99369 67.82837 10 -43.99354 69.28203 0 -44.25 69.2817 10 -44.24991 70.73562 0 -43.99369 70.73519 10 -43.99379 -40.625 10 -66.36457 -40.625 0 -66.36457 -41.99308 0 -66.6058 -39.25692 0 -66.6058 -39.25692 10 -66.6058 -39.25692 0 -66.6058 -40.625 0 -66.36457 -40.625 10 -66.36457 -41.99308 10 -66.6058 -43.19615 0 -67.30039 -43.19615 10 -67.30039 -44.0891 0 -68.36457 -44.0891 10 -68.36457 -44.56423 0 -69.66997 -44.56423 10 -69.66997 -44.56423 0 -71.05916 -44.56423 10 -71.05916 -44.0891 0 -72.36457 -44.0891 10 -72.36457 -43.19615 0 -73.42874 -43.19615 10 -73.42874 -41.99308 0 -74.12334 -41.99308 10 -74.12334 -40.625 0 -74.36457 2.389175 0 -73.96141 -39.25692 0 -74.12334 -40.625 10 -74.36457 -40.625 0 -74.36457 -39.25692 0 -74.12334 -40.625 10 -74.36457 -8.473461 0 -73.51322 -38.05385 0 -73.42874 -39.25692 10 -74.12334 -38.05385 0 -73.42874 -3.050451 0 -73.93706 -13.85064 0 -72.69216 -37.1609 0 -72.36457 -38.05385 10 -73.42874 -37.1609 0 -72.36457 -19.15298 0 -71.47834 -36.68577 0 -71.05916 -37.1609 10 -72.36457 -36.68577 0 -71.05916 -24.35181 0 -69.87832 -36.68577 0 -69.66997 -36.68577 10 -71.05916 -36.68577 0 -69.66997 -29.41902 0 -67.90076 -37.1609 0 -68.36457 -36.68577 10 -69.66997 -37.1609 0 -68.36457 -38.05385 0 -67.30039 -37.1609 10 -68.36457 -38.05385 0 -67.30039 -38.05385 10 -67.30039 73.96138 0 -2.389636 78.67885 0 -3.064178 77.7859 0 -2 77.7859 10 -2 77.7859 0 -2 78.67885 0 -3.064178 77.31077 0 -0.694593 77.31077 10 -0.694593 77.31077 0 -0.694593 77.7859 0 -2 77.7859 10 -2 79.88192 0 -3.75877 78.67885 10 -3.064178 79.88192 0 -3.75877 81.25 0 -4 79.88192 10 -3.75877 81.25 0 -4 81.25 10 -4 82.61808 0 -3.75877 82.61808 10 -3.75877 83.82115 0 -3.064178 83.82115 10 -3.064178 84.71411 0 -2 84.71411 10 -2 85.18923 0 -0.694593 85.18923 10 -0.694593 85.18923 0 0.694593 85.18923 10 0.694593 84.71411 0 2 84.71411 10 2 84.71411 0 2 83.82115 0 3.064178 84.71411 10 2 83.82115 10 3.064178 82.61808 0 3.75877 82.61808 10 3.75877 81.25 0 4 73.93708 0 3.049869 79.88192 0 3.75877 81.25 10 4 79.88192 0 3.75877 78.67885 0 3.064178 79.88192 10 3.75877 78.67885 0 3.064178 77.7859 0 2 78.67885 10 3.064178 77.7859 0 2 77.31077 0 0.694593 77.7859 10 2 77.31077 0 0.694593 77.31077 10 0.694593 -71.52102 0 23.65241 -71.52102 7 23.65241 -71.52102 0 23.65241 -73.15052 0 23.33041 -70.73329 7 23.82219 -70.73329 0 23.82219 -71.52102 0 23.65241 -71.52102 7 23.65241 -73.15052 7 23.33041 -74.55265 0 22.43881 -74.55265 7 22.43881 -75.53559 0 21.09942 -75.53559 7 21.09942 -75.96543 0 19.49533 -75.96543 7 19.49533 -75.78392 0 17.84387 -75.78392 7 17.84387 -75.01544 0 16.37059 -75.01544 7 16.37059 -73.76522 0 15.27692 -73.76522 7 15.27692 -73.76522 0 15.27692 -73.16793 0 14.73602 -73.76522 7 15.27692 -73.16793 7 14.73602 -72.83258 0 14.0033 -72.83258 7 14.0033 -72.81361 0 13.1977 -72.81361 7 13.1977 -72.81361 0 13.1977 -73.58609 0 7.81595 -72.81361 7 13.1977 -73.58609 7 7.81595 -73.96138 0 2.389604 -73.96138 7 2.389604 -73.93708 0 -3.049872 -73.93708 7 -3.049872 -73.51329 0 -8.472777 -73.51329 7 -8.472778 -72.6923 0 -13.8499 -72.6923 7 -13.8499 -71.47854 0 -19.15223 -71.47854 7 -19.15223 -69.87857 0 -24.3511 -69.87857 7 -24.3511 -67.90103 0 -29.41839 -67.90103 7 -29.41839 -65.55659 0 -34.32678 -65.55659 7 -34.32678 -62.85785 0 -39.0498 -62.85785 7 -39.0498 -59.81959 0 -43.56166 -59.81959 7 -43.56166 -56.45958 0 -47.83634 -56.45958 7 -47.83634 -56.45958 0 -47.83634 -56.0732 0 -48.54349 -56.45958 7 -47.83634 -56.0732 7 -48.54349 -55.99727 0 -49.34572 -55.99727 7 -49.34572 -56.24409 0 -50.11281 -56.24409 7 -50.11281 -56.24409 0 -50.11281 -56.77998 0 -51.685 -56.24409 7 -50.11281 -56.77998 7 -51.685 -56.7089 0 -53.34508 -56.7089 7 -53.34508 -56.04042 0 -54.86601 -56.04042 7 -54.86601 -54.86616 0 -56.04032 -54.86616 7 -56.04032 -53.3452 0 -56.70886 -53.3452 7 -56.70886 -51.68506 0 -56.77999 -47.83634 0 -56.45958 -50.11281 0 -56.24409 -51.68506 7 -56.77999 -50.11281 0 -56.24409 -48.54349 0 -56.0732 -49.34572 0 -55.99727 -50.11281 7 -56.24409 -50.11281 0 -56.24409 -49.34572 0 -55.99727 -50.11281 7 -56.24409 -49.34572 7 -55.99727 -48.54349 0 -56.0732 -48.54349 7 -56.0732 -47.83634 0 -56.45958 -47.83634 7 -56.45958 -47.83634 0 -56.45958 -43.56186 0 -59.81944 -47.83634 7 -56.45958 -43.56186 7 -59.81944 -39.05015 0 -62.85763 -39.05015 7 -62.85763 -34.32729 0 -65.55632 -34.32729 7 -65.55632 -29.41902 0 -67.90076 -29.41902 7 -67.90076 -24.35181 0 -69.87832 -24.35181 7 -69.87832 -19.15298 0 -71.47834 -19.15298 7 -71.47834 -13.85064 0 -72.69216 -13.85064 7 -72.69216 -8.473461 0 -73.51322 -8.473461 7 -73.51322 -3.050451 0 -73.93706 -3.050451 7 -73.93706 2.389175 0 -73.96141 15.27692 0 -73.76522 7.8157 0 -73.58612 2.389175 7 -73.96141 7.8157 0 -73.58612 14.0033 0 -72.83258 13.1977 0 -72.81361 7.8157 7 -73.58612 13.1977 0 -72.81361 14.73602 0 -73.16793 13.1977 7 -72.81361 13.1977 0 -72.81361 14.0033 0 -72.83258 13.1977 7 -72.81361 14.0033 7 -72.83258 14.73602 0 -73.16793 14.73602 7 -73.16793 15.27692 0 -73.76522 15.27692 7 -73.76522 15.27692 0 -73.76522 16.37053 0 -75.01541 15.27692 7 -73.76522 16.37053 7 -75.01541 17.84374 0 -75.78388 17.84374 7 -75.78388 19.49515 0 -75.96544 19.49515 7 -75.96544 21.09926 0 -75.53565 21.09926 7 -75.53565 22.43872 0 -74.55274 22.43872 7 -74.55274 23.33038 0 -73.15058 23.33038 7 -73.15058 23.65241 0 -71.52102 23.65241 7 -71.52102 23.65241 0 -71.52102 23.82219 0 -70.73329 23.65241 7 -71.52102 23.82219 7 -70.73329 24.28907 0 -70.0765 24.28907 7 -70.0765 24.97726 0 -69.65728 24.97726 7 -69.65728 24.97726 0 -69.65728 30.02434 0 -67.63536 24.97726 7 -69.65728 30.02442 7 -67.63533 34.91143 0 -65.24713 34.91155 7 -65.24707 39.61006 0 -62.50629 39.61022 7 -62.50619 44.09458 0 -59.42776 44.09475 7 -59.42764 48.34083 0 -56.02815 48.341 7 -56.02801 52.3259 0 -52.3258 52.32606 7 -52.32564 56.02824 0 -48.34072 56.02838 7 -48.34056 59.42784 0 -44.09448 59.42795 7 -44.09433 62.50635 0 -39.60998 62.50643 7 -39.60985 65.24717 0 -34.91135 65.24723 7 -34.91126 67.63537 0 -30.0243 67.63539 7 -30.02425 69.65728 0 -24.97726 69.65728 7 -24.97726 69.65728 0 -24.97726 70.0765 0 -24.28907 69.65728 7 -24.97726 70.0765 7 -24.28907 70.73329 0 -23.82219 71.52102 0 -23.65241 70.73329 7 -23.82219 71.52102 0 -23.65241 71.52102 7 -23.65241 71.52102 0 -23.65241 73.15052 0 -23.33041 71.52102 7 -23.65241 73.15052 7 -23.33041 74.55265 0 -22.43881 74.55265 7 -22.43881 75.53559 0 -21.09942 75.53559 7 -21.09942 75.96543 0 -19.49533 75.96543 7 -19.49533 75.78392 0 -17.84387 75.78392 7 -17.84387 75.01544 0 -16.37059 75.01544 7 -16.37059 73.76522 0 -15.27692 73.76522 7 -15.27692 73.76522 0 -15.27692 73.16793 0 -14.73602 73.76522 7 -15.27692 73.16793 7 -14.73602 72.83258 0 -14.0033 72.83258 7 -14.0033 72.81361 0 -13.1977 72.81361 7 -13.1977 72.81361 0 -13.1977 73.58609 0 -7.815966 72.81361 7 -13.1977 73.5861 7 -7.815814 73.96138 0 -2.389636 73.96139 7 -2.389348 73.93708 0 3.049869 73.93708 7 3.050184 73.51329 0 8.472822 73.51325 7 8.473104 72.69229 0 13.84998 72.69224 7 13.85023 71.47851 0 19.15234 71.47846 7 19.15255 69.87854 0 24.35123 69.87847 7 24.35139 67.90097 0 29.41852 67.90092 7 29.41865 65.55654 0 34.32689 65.55648 7 34.32698 62.85779 0 39.04988 62.85776 7 39.04994 59.81955 0 43.56171 59.81953 7 43.56174 56.45958 0 47.83634 56.45958 7 47.83634 56.45958 0 47.83634 56.0732 0 48.54349 56.45958 7 47.83634 56.0732 7 48.54349 55.99727 0 49.34572 55.99727 7 49.34572 56.24409 0 50.11281 56.24409 7 50.11281 56.24409 0 50.11281 56.77998 0 51.685 56.24409 7 50.11281 56.77998 7 51.685 56.7089 0 53.34508 56.7089 7 53.34508 56.04042 0 54.86601 56.04042 7 54.86601 54.86616 0 56.04032 54.86616 7 56.04032 53.3452 0 56.70886 53.3452 7 56.70886 51.68506 0 56.77999 47.83634 0 56.45958 50.11281 0 56.24409 51.68506 7 56.77999 50.11281 0 56.24409 48.54349 0 56.0732 49.34572 0 55.99727 50.11281 7 56.24409 50.11281 0 56.24409 49.34572 0 55.99727 50.11281 7 56.24409 49.34572 7 55.99727 48.54349 0 56.0732 48.54349 7 56.0732 47.83634 0 56.45958 47.83634 7 56.45958 47.83634 0 56.45958 43.56184 0 59.81946 47.83634 7 56.45958 43.56184 7 59.81946 39.05011 0 62.85765 39.05011 7 62.85765 34.32722 0 65.55636 34.32722 7 65.55636 29.41893 0 67.90081 29.41893 7 67.90081 24.3517 0 69.87836 24.3517 7 69.87836 19.15286 0 71.47837 19.15286 7 71.47837 13.85052 0 72.69219 13.85052 7 72.69219 8.473347 0 73.51322 8.473347 7 73.51322 3.050353 0 73.93708 3.050352 7 73.93708 -2.389251 0 73.96141 -15.27692 0 73.76522 -7.815748 0 73.58612 -2.389251 7 73.96141 -7.815748 0 73.58612 -14.0033 0 72.83258 -13.1977 0 72.81361 -7.815748 7 73.58612 -13.1977 0 72.81361 -14.73602 0 73.16793 -13.1977 7 72.81361 -13.1977 0 72.81361 -14.0033 0 72.83258 -13.1977 7 72.81361 -14.0033 7 72.83258 -14.73602 0 73.16793 -14.73602 7 73.16793 -15.27692 0 73.76522 -15.27692 7 73.76522 -15.27692 0 73.76522 -16.37053 0 75.01541 -15.27692 7 73.76522 -16.37053 7 75.01541 -17.84374 0 75.78388 -17.84374 7 75.78388 -19.49515 0 75.96544 -19.49515 7 75.96544 -21.09926 0 75.53565 -21.09926 7 75.53565 -22.43872 0 74.55274 -22.43872 7 74.55274 -23.33038 0 73.15058 -23.33038 7 73.15058 -23.65241 0 71.52102 -23.65241 7 71.52102 -23.65241 0 71.52102 -23.82219 0 70.73329 -23.65241 7 71.52102 -23.82219 7 70.73329 -24.28907 0 70.0765 -24.28907 7 70.0765 -24.97726 0 69.65728 -24.97726 7 69.65728 -24.97726 0 69.65728 -30.02424 0 67.63539 -24.97726 7 69.65728 -30.02424 7 67.63539 -34.91125 0 65.24723 -34.91125 7 65.24723 -39.60983 0 62.50645 -39.60983 7 62.50645 -44.09431 0 59.42797 -44.09431 7 59.42797 -48.34053 0 56.02841 -48.34053 7 56.02841 -52.32561 0 52.32609 -52.32561 7 52.32609 -56.02798 0 48.34104 -56.02798 7 48.34104 -59.42761 0 44.09479 -59.42761 7 44.09479 -62.50617 0 39.61026 -62.50617 7 39.61026 -65.24707 0 34.91158 -65.24707 7 34.91157 -67.6353 0 30.02444 -67.6353 7 30.02444 -69.65728 0 24.97726 -69.65728 7 24.97726 -69.65728 0 24.97726 -70.0765 0 24.28907 -69.65728 7 24.97726 -70.0765 7 24.28907 0 122.7 61.5 0 129.5 61.5 9.621398 129.5 60.74267 -9.621379 122.7 60.74265 -9.621398 129.5 60.74267 0 129.5 61.5 0 122.7 61.5 9.621379 122.7 60.74265 19.00452 129.5 58.48989 19.00415 122.7 58.49 27.91977 129.5 54.79717 27.91989 122.7 54.79715 36.14879 129.5 49.75454 36.14939 122.7 49.75405 43.48752 129.5 43.48654 43.48699 122.7 43.48699 49.75447 129.5 36.14874 49.75405 122.7 36.14939 54.79654 129.5 27.92101 54.79715 122.7 27.91989 58.48997 129.5 19.00455 58.49 122.7 19.00415 60.74289 129.5 9.620025 60.74265 122.7 9.621379 61.4999 129.5 0 61.5 122.7 0 60.74289 129.5 -9.620025 60.74265 122.7 -9.621379 58.48997 129.5 -19.00455 58.49 122.7 -19.00415 54.79654 129.5 -27.92101 54.79715 122.7 -27.91989 49.75447 129.5 -36.14874 49.75405 122.7 -36.14939 43.48752 129.5 -43.48654 43.48699 122.7 -43.48699 36.14879 129.5 -49.75454 36.14939 122.7 -49.75405 27.91977 129.5 -54.79717 27.91989 122.7 -54.79715 19.00452 129.5 -58.48989 19.00415 122.7 -58.49 9.621398 129.5 -60.74267 9.621379 122.7 -60.74265 0 129.5 -61.5 0 122.7 -61.5 0 129.5 -61.5 -9.621398 129.5 -60.74267 0 122.7 -61.5 -9.621379 122.7 -60.74265 -19.00452 129.5 -58.48989 -19.00415 122.7 -58.49 -27.91977 129.5 -54.79717 -27.91989 122.7 -54.79715 -36.14879 129.5 -49.75454 -36.14939 122.7 -49.75405 -43.48752 129.5 -43.48654 -43.48699 122.7 -43.48699 -49.75447 129.5 -36.14874 -49.75405 122.7 -36.14939 -54.79654 129.5 -27.92101 -54.79715 122.7 -27.91989 -58.48997 129.5 -19.00455 -58.49 122.7 -19.00415 -60.74289 129.5 -9.620025 -60.74265 122.7 -9.621379 -61.4999 129.5 0 -61.5 122.7 0 -60.74289 129.5 9.620025 -60.74265 122.7 9.621379 -58.48997 129.5 19.00455 -58.49 122.7 19.00415 -54.79654 129.5 27.92101 -54.79715 122.7 27.91989 -49.75447 129.5 36.14874 -49.75405 122.7 36.14939 -43.48752 129.5 43.48654 -43.48699 122.7 43.48699 -36.14879 129.5 49.75454 -36.14939 122.7 49.75405 -27.91977 129.5 54.79717 -27.91989 122.7 54.79715 -19.00452 129.5 58.48989 -19.00415 122.7 58.49 8.379154 129.5 -47.51683 4.576298 129.5 -52.30016 0 129.5 -52.5 0 122.7 -52.5 0 129.5 -52.5 4.576298 129.5 -52.30016 0 129.5 -48.25 -4.576298 129.5 -52.30016 -4.576581 122.7 -52.30014 -4.576298 129.5 -52.30016 0 129.5 -52.5 0 122.7 -52.5 9.117215 129.5 -51.70225 4.576581 122.7 -52.30014 9.117215 129.5 -51.70225 16.50293 129.5 -45.33992 13.58867 129.5 -50.71087 9.117303 122.7 -51.70221 13.58867 129.5 -50.71087 17.95656 129.5 -49.33359 13.58857 122.7 -50.71086 17.95656 129.5 -49.33359 24.12495 129.5 -41.78564 22.1877 129.5 -47.58094 17.95623 122.7 -49.33368 22.1877 129.5 -47.58094 26.24995 129.5 -45.46625 22.18721 122.7 -47.58115 26.24995 129.5 -45.46625 31.01406 129.5 -36.96192 30.11246 129.5 -43.00558 26.24942 122.7 -45.46656 30.11246 129.5 -43.00558 33.74587 129.5 -40.21763 30.11208 122.7 -43.00589 33.74587 129.5 -40.21763 36.96121 129.5 -31.01498 37.12257 129.5 -37.12356 33.74585 122.7 -40.21773 37.12257 129.5 -37.12356 41.78572 129.5 -24.125 40.21686 129.5 -33.74686 37.1231 122.7 -37.1231 40.21686 129.5 -33.74686 43.0052 129.5 -30.11315 40.21773 122.7 -33.74585 43.0052 129.5 -30.11315 45.34036 129.5 -16.50186 45.46633 129.5 -26.25 43.00589 122.7 -30.11208 45.46633 129.5 -26.25 47.51699 129.5 -8.378005 47.58135 129.5 -22.18702 45.46656 122.7 -26.24942 47.58135 129.5 -22.18702 49.33407 129.5 17.95539 49.33407 129.5 -17.95539 47.58115 122.7 -22.18721 49.33407 129.5 -17.95539 48.24991 129.5 0 50.71123 129.5 13.5873 50.71123 129.5 -13.5873 49.33368 122.7 -17.95623 50.71123 129.5 -13.5873 51.70243 129.5 9.115964 51.70243 129.5 -9.115964 50.71086 122.7 -13.58857 51.70243 129.5 -9.115964 52.30015 129.5 4.575363 52.30015 129.5 -4.575363 51.70221 122.7 -9.117303 52.30015 129.5 -4.575363 52.4999 129.5 0 52.30015 122.7 -4.576309 52.4999 129.5 0 52.5 122.7 0 52.30015 129.5 4.575363 52.30015 122.7 4.576309 51.70243 129.5 9.115964 51.70221 122.7 9.117303 50.71123 129.5 13.5873 50.71086 122.7 13.58857 49.33407 129.5 17.95539 47.58135 129.5 22.18702 49.33368 122.7 17.95623 47.58135 129.5 22.18702 47.51699 129.5 8.378005 45.46633 129.5 26.25 47.58115 122.7 22.18721 45.46633 129.5 26.25 45.34036 129.5 16.50186 43.0052 129.5 30.11315 45.46656 122.7 26.24942 43.0052 129.5 30.11315 41.78572 129.5 24.125 40.21686 129.5 33.74686 43.00589 122.7 30.11208 40.21686 129.5 33.74686 36.96121 129.5 31.01498 37.12257 129.5 37.12356 40.21773 122.7 33.74585 37.12257 129.5 37.12356 33.74587 129.5 40.21763 37.1231 122.7 37.1231 33.74587 129.5 40.21763 31.01406 129.5 36.96192 30.11246 129.5 43.00558 33.74585 122.7 40.21773 30.11246 129.5 43.00558 24.12495 129.5 41.78564 26.24995 129.5 45.46625 30.11208 122.7 43.00589 26.24995 129.5 45.46625 22.1877 129.5 47.58094 26.24942 122.7 45.46656 22.1877 129.5 47.58094 16.50293 129.5 45.33992 17.95656 129.5 49.33359 22.18721 122.7 47.58115 17.95656 129.5 49.33359 13.58867 129.5 50.71087 17.95623 122.7 49.33368 13.58867 129.5 50.71087 8.379154 129.5 47.51683 9.117215 129.5 51.70225 13.58857 122.7 50.71086 9.117215 129.5 51.70225 4.576298 129.5 52.30016 9.117303 122.7 51.70221 4.576298 129.5 52.30016 0 129.5 48.25 0 129.5 52.5 4.576581 122.7 52.30014 0 129.5 52.5 -8.379154 129.5 47.51683 -4.576298 129.5 52.30016 0 122.7 52.5 0 129.5 52.5 -4.576298 129.5 52.30016 0 122.7 52.5 -9.117215 129.5 51.70225 -4.576581 122.7 52.30014 -9.117215 129.5 51.70225 -16.50293 129.5 45.33992 -13.58867 129.5 50.71087 -9.117303 122.7 51.70221 -13.58867 129.5 50.71087 -17.95656 129.5 49.33359 -13.58857 122.7 50.71086 -17.95656 129.5 49.33359 -24.12495 129.5 41.78564 -22.1877 129.5 47.58094 -17.95623 122.7 49.33368 -22.1877 129.5 47.58094 -26.24995 129.5 45.46625 -22.18721 122.7 47.58115 -26.24995 129.5 45.46625 -31.01406 129.5 36.96192 -30.11246 129.5 43.00558 -26.24942 122.7 45.46656 -30.11246 129.5 43.00558 -33.74587 129.5 40.21763 -30.11208 122.7 43.00589 -33.74587 129.5 40.21763 -36.96121 129.5 31.01498 -37.12257 129.5 37.12356 -33.74585 122.7 40.21773 -37.12257 129.5 37.12356 -41.78572 129.5 24.125 -40.21686 129.5 33.74686 -37.1231 122.7 37.1231 -40.21686 129.5 33.74686 -43.0052 129.5 30.11315 -40.21773 122.7 33.74585 -43.0052 129.5 30.11315 -45.34036 129.5 16.50186 -45.46633 129.5 26.25 -43.00589 122.7 30.11208 -45.46633 129.5 26.25 -47.51699 129.5 8.378005 -47.58135 129.5 22.18702 -45.46656 122.7 26.24942 -47.58135 129.5 22.18702 -49.33407 129.5 -17.95539 -49.33407 129.5 17.95539 -47.58115 122.7 22.18721 -49.33407 129.5 17.95539 -48.24991 129.5 0 -50.71123 129.5 -13.5873 -50.71123 129.5 13.5873 -49.33368 122.7 17.95623 -50.71123 129.5 13.5873 -51.70243 129.5 -9.115964 -51.70243 129.5 9.115964 -50.71086 122.7 13.58857 -51.70243 129.5 9.115964 -52.30015 129.5 -4.575363 -52.30015 129.5 4.575363 -51.70221 122.7 9.117303 -52.30015 129.5 4.575363 -52.4999 129.5 0 -52.30015 122.7 4.576309 -52.4999 129.5 0 -52.5 122.7 0 -52.30015 129.5 -4.575363 -52.30015 122.7 -4.576309 -51.70243 129.5 -9.115964 -51.70221 122.7 -9.117303 -50.71123 129.5 -13.5873 -50.71086 122.7 -13.58857 -49.33407 129.5 -17.95539 -47.58135 129.5 -22.18702 -49.33368 122.7 -17.95623 -47.58135 129.5 -22.18702 -47.51699 129.5 -8.378005 -45.46633 129.5 -26.25 -47.58115 122.7 -22.18721 -45.46633 129.5 -26.25 -45.34036 129.5 -16.50186 -43.0052 129.5 -30.11315 -45.46656 122.7 -26.24942 -43.0052 129.5 -30.11315 -41.78572 129.5 -24.125 -40.21686 129.5 -33.74686 -43.00589 122.7 -30.11208 -40.21686 129.5 -33.74686 -36.96121 129.5 -31.01498 -37.12257 129.5 -37.12356 -40.21773 122.7 -33.74585 -37.12257 129.5 -37.12356 -33.74587 129.5 -40.21763 -37.1231 122.7 -37.1231 -33.74587 129.5 -40.21763 -31.01406 129.5 -36.96192 -30.11246 129.5 -43.00558 -33.74585 122.7 -40.21773 -30.11246 129.5 -43.00558 -24.12495 129.5 -41.78564 -26.24995 129.5 -45.46625 -30.11208 122.7 -43.00589 -26.24995 129.5 -45.46625 -22.1877 129.5 -47.58094 -26.24942 122.7 -45.46656 -22.1877 129.5 -47.58094 -16.50293 129.5 -45.33992 -17.95656 129.5 -49.33359 -22.18721 122.7 -47.58115 -17.95656 129.5 -49.33359 -13.58867 129.5 -50.71087 -17.95623 122.7 -49.33368 -13.58867 129.5 -50.71087 -8.379154 129.5 -47.51683 -9.117215 129.5 -51.70225 -13.58857 122.7 -50.71086 -9.117215 129.5 -51.70225 -9.117303 122.7 -51.70221 0 110.4 48.25 0 129.5 48.25 8.379154 129.5 47.51683 -8.379238 110.4 47.51679 -8.379154 129.5 47.51683 0 129.5 48.25 0 110.4 48.25 8.379238 110.4 47.51679 16.50293 129.5 45.33992 16.50263 110.4 45.34 24.12495 129.5 41.78564 24.12447 110.4 41.78593 31.01406 129.5 36.96192 31.01404 110.4 36.96201 36.96121 129.5 31.01498 36.96201 110.4 31.01404 41.78572 129.5 24.125 41.78593 110.4 24.12447 45.34036 129.5 16.50186 45.34 110.4 16.50263 47.51699 129.5 8.378005 47.51679 110.4 8.379238 48.24991 129.5 0 48.25 110.4 0 47.51699 129.5 -8.378005 47.51679 110.4 -8.379238 45.34036 129.5 -16.50186 45.34 110.4 -16.50263 41.78572 129.5 -24.125 41.78593 110.4 -24.12447 36.96121 129.5 -31.01498 36.96201 110.4 -31.01404 31.01406 129.5 -36.96192 31.01404 110.4 -36.96201 24.12495 129.5 -41.78564 24.12447 110.4 -41.78593 16.50293 129.5 -45.33992 16.50263 110.4 -45.34 8.379154 129.5 -47.51683 8.379238 110.4 -47.51679 0 129.5 -48.25 0 110.4 -48.25 0 129.5 -48.25 -8.379154 129.5 -47.51683 0 110.4 -48.25 -8.379238 110.4 -47.51679 -16.50293 129.5 -45.33992 -16.50263 110.4 -45.34 -24.12495 129.5 -41.78564 -24.12447 110.4 -41.78593 -31.01406 129.5 -36.96192 -31.01404 110.4 -36.96201 -36.96121 129.5 -31.01498 -36.96201 110.4 -31.01404 -41.78572 129.5 -24.125 -41.78593 110.4 -24.12447 -45.34036 129.5 -16.50186 -45.34 110.4 -16.50263 -47.51699 129.5 -8.378005 -47.51679 110.4 -8.379238 -48.24991 129.5 0 -48.25 110.4 0 -47.51699 129.5 8.378005 -47.51679 110.4 8.379238 -45.34036 129.5 16.50186 -45.34 110.4 16.50263 -41.78572 129.5 24.125 -41.78593 110.4 24.12447 -36.96121 129.5 31.01498 -36.96201 110.4 31.01404 -31.01406 129.5 36.96192 -31.01404 110.4 36.96201 -24.12495 129.5 41.78564 -24.12447 110.4 41.78593 -16.50293 129.5 45.33992 -16.50263 110.4 45.34 -46.25 38 57.9 -46.25 38 58 -46.56652 39.79531 58 -46.56661 36.20439 57.9 -46.56652 36.20468 58 -46.25 38 58 -46.25 38 57.9 -46.56661 39.7956 57.9 -47.47806 41.37431 58 -47.47827 41.37463 57.9 -48.87478 42.54642 58 -48.875 42.54663 57.9 -50.58826 43.17013 58 -50.58835 43.17024 57.9 -52.41174 43.17013 58 -52.41165 43.17024 57.9 -54.12522 42.54642 58 -54.125 42.54663 57.9 -55.52194 41.37431 58 -55.52173 41.37463 57.9 -56.43347 39.79531 58 -56.43339 39.7956 57.9 -56.75 38 58 -56.75 38 57.9 -56.75 38 58 -56.43347 36.20468 58 -56.75 38 57.9 -56.43339 36.20439 57.9 -55.52194 34.62569 58 -55.52173 34.62537 57.9 -54.12522 33.45357 58 -54.125 33.45336 57.9 -52.41174 32.82986 58 -52.41165 32.82976 57.9 -50.58826 32.82986 58 -50.58835 32.82976 57.9 -48.87478 33.45357 58 -48.875 33.45336 57.9 -47.47806 34.62569 58 -47.47827 34.62537 57.9 -36.44685 89.08293 58.5 -36.44685 89.08293 58 -33.44577 89.08293 58 -36.44685 89.08293 58.5 -36.44685 87.80018 58.5 -36.44685 89.08293 58 -32.8903 88.12107 58 -32.8903 88.76204 58 -33.1249 88.99686 58 -20 85 58.5 -20 85.97177 58 -20 85.97177 58.5 -23.94784 85.97177 58.5 -23.94784 85.97177 58 -20.17238 89.08293 58 -20 85.97177 58.5 -23.94784 85.97177 58 -23.94784 85.97177 58.5 -20.17238 89.08293 58.5 -20.17238 89.08293 58 -20.17238 90.05471 58 -20.17238 89.08293 58.5 -20.17238 90.05471 58.5 -36.44685 89.08293 58.5 -33.44577 89.08293 58 -33.44577 89.08293 58.5 -32.18442 89.44702 58.5 -32.18456 89.44734 58 -32.74585 89.89495 58 -31.87316 88.80036 58.5 -32.74557 89.89479 58.5 -33.44577 90.05471 58 -33.44577 90.05471 58.5 -33.44577 90.05471 58 -37.5 90.05471 58 -33.44577 90.05471 58.5 -37.5 90.05471 58.5 15.68508 44.53391 58 15.50007 46.4 58 15.68508 48.26609 58 15.68508 48.26609 62.5 15.68508 48.26609 58 15.50007 46.4 58 18.72646 53.53391 58 18.72646 53.53391 62.5 18.72646 53.53391 58 15.68508 48.26609 58 17.20601 50.90041 63 15.68508 48.26609 62.5 15.5 46.4 62.5 15.68508 44.53391 58 15.54638 47.3376 62.5 18.72646 39.26609 58 15.68508 44.53391 62.5 15.68508 44.53391 58 18.72646 39.26609 58 15.54638 45.46239 62.5 15.68508 44.53391 62.5 20.25304 54.629 58 20.25304 38.171 58 18.72646 39.26609 62.5 18.72646 39.26609 58 20.25304 38.171 58 17.20553 41.90041 63 18.72646 39.26609 62.5 21.95862 55.4 58 21.95862 37.4 58 20.25001 38.17276 62.5 21.95862 37.4 58 28.04138 55.4 58 28.04138 37.4 58 21.95862 37.4 62.5 21.95862 37.4 58 28.04138 37.4 58 21.95862 37.4 62.5 29.74696 54.629 58 29.74696 38.171 58 28.04138 37.4 62.5 28.04138 37.4 58 29.74696 38.171 58 24.99953 37.4 63 28.04138 37.4 62.5 31.27354 53.53391 58 31.27354 39.26609 58 29.75 38.17276 62.5 31.27354 39.26609 58 34.31492 48.26609 58 34.31492 44.53391 58 31.27354 39.26609 62.5 31.27354 39.26609 58 34.31492 44.53391 58 31.27354 39.26609 62.5 34.49993 46.4 58 34.31492 44.53391 62.5 34.31492 44.53391 58 34.49993 46.4 58 32.79399 41.89959 63 34.31492 44.53391 62.5 34.5 46.4 62.5 34.31492 48.26609 58 34.45362 45.46239 62.5 34.31492 48.26609 62.5 34.31492 48.26609 58 31.27354 53.53391 58 34.45362 47.3376 62.5 34.31492 48.26609 62.5 31.27354 53.53391 62.5 31.27354 53.53391 58 29.74696 54.629 58 32.79446 50.89959 63 31.27354 53.53391 62.5 29.75 54.62724 62.5 28.04138 55.4 58 28.04138 55.4 62.5 28.04138 55.4 58 21.95862 55.4 58 28.04138 55.4 62.5 21.95862 55.4 62.5 21.95862 55.4 58 20.25304 54.629 58 25.00048 55.4 63 21.95862 55.4 62.5 20.25001 54.62724 62.5 18.72646 53.53391 58 18.72646 53.53391 62.5 32.31127 48.07153 64.5 30.40465 49.00365 64.5 31 46.4 64.5 31 46.4 76.5 31 46.4 64.5 30.40465 49.00365 64.5 32.5 46.4 64.5 30.40465 43.79634 64.5 30.40511 43.79825 76.5 30.40465 43.79634 64.5 31 46.4 64.5 31 46.4 76.5 30.86299 51.07585 64.5 28.7424 51.08954 64.5 30.40511 49.00175 76.5 28.7424 51.08954 64.5 31.75617 49.65515 64.5 29.67668 52.26232 64.5 26.33299 52.24942 64.5 28.73861 51.09243 76.5 26.33299 52.24942 64.5 23.66701 52.24942 64.5 26.33759 52.24808 76.5 23.66701 52.24942 64.5 19.13702 51.07585 64.5 21.25761 51.08954 64.5 23.66241 52.24808 76.5 21.25761 51.08954 64.5 20.32333 52.26232 64.5 18.24383 49.65515 64.5 19.59535 49.00365 64.5 21.26139 51.09243 76.5 19.59535 49.00365 64.5 17.5 46.4 64.5 19 46.4 64.5 19.59489 49.00175 76.5 19 46.4 64.5 17.68872 48.07153 64.5 17.68872 44.72847 64.5 19.59535 43.79634 64.5 19 46.4 76.5 19 46.4 64.5 19.59535 43.79634 64.5 19 46.4 76.5 19.13702 41.72415 64.5 21.25761 41.71046 64.5 19.59489 43.79825 76.5 21.25761 41.71046 64.5 18.24383 43.14485 64.5 20.32332 40.53768 64.5 23.66701 40.55058 64.5 21.26139 41.70757 76.5 23.66701 40.55058 64.5 26.33299 40.55058 64.5 23.66241 40.55192 76.5 26.33299 40.55058 64.5 30.86298 41.72415 64.5 28.7424 41.71046 64.5 26.33759 40.55192 76.5 28.7424 41.71046 64.5 29.67667 40.53767 64.5 31.75617 43.14485 64.5 28.73861 41.70757 76.5 32.31127 44.72847 64.5 15.5 46.4 62.5 17.5 46.4 64.5 17.68872 48.07153 64.5 15.68508 44.53391 62.5 17.68872 44.72847 64.5 17.5 46.4 64.5 15.54638 45.46239 62.5 15.5 46.4 62.5 15.68508 48.26609 62.5 18.24383 49.65515 64.5 15.54638 47.3376 62.5 17.20601 50.90041 63 19.13702 51.07585 64.5 18.72646 53.53391 62.5 20.32333 52.26232 64.5 28.25598 53.15576 64.5 21.74402 53.15577 64.5 20.25001 54.62724 62.5 21.74402 53.15577 64.5 26.67096 53.71129 64.5 23.32905 53.71129 64.5 21.95862 55.4 62.5 23.32905 53.71129 64.5 25 53.9 64.5 25 53.9 64.5 25.00048 55.4 63 26.67096 53.71129 64.5 28.04138 55.4 62.5 28.25598 53.15576 64.5 29.75 54.62724 62.5 29.67668 52.26232 64.5 31.27354 53.53391 62.5 30.86299 51.07585 64.5 32.79446 50.89959 63 31.75617 49.65515 64.5 32.31127 48.07153 64.5 34.31492 48.26609 62.5 32.5 46.4 64.5 34.5 46.4 62.5 32.5 46.4 64.5 32.31127 44.72847 64.5 34.45362 47.3376 62.5 34.5 46.4 62.5 34.31492 44.53391 62.5 31.75617 43.14485 64.5 34.45362 45.46239 62.5 32.79399 41.89959 63 30.86298 41.72415 64.5 31.27354 39.26609 62.5 29.67667 40.53767 64.5 21.74402 39.64423 64.5 28.25598 39.64423 64.5 29.75 38.17276 62.5 28.25598 39.64423 64.5 23.32904 39.08871 64.5 26.67095 39.08871 64.5 28.04138 37.4 62.5 26.67095 39.08871 64.5 25 38.9 64.5 25 38.9 64.5 24.99953 37.4 63 23.32904 39.08871 64.5 21.95862 37.4 62.5 21.74402 39.64423 64.5 20.25001 38.17276 62.5 20.32332 40.53768 64.5 18.72646 39.26609 62.5 19.13702 41.72415 64.5 17.20553 41.90041 63 18.24383 43.14485 64.5 19.59489 43.79825 76.5 30.40511 43.79825 76.5 31 46.4 76.5 19 46.4 76.5 30.40511 49.00175 76.5 21.26139 41.70757 76.5 28.73861 41.70757 76.5 23.66241 40.55192 76.5 26.33759 40.55192 76.5 19.59489 49.00175 76.5 28.73861 51.09243 76.5 21.26139 51.09243 76.5 26.33759 52.24808 76.5 23.66241 52.24808 76.5 -20.17238 90.05471 58 -20.17238 89.08293 58 -20 85.97177 58 -31.25827 85 58 -31.87307 88.08259 58 -32.18456 87.43577 58 -33.44577 87.80018 58 -33.1249 87.88626 58 -33.44577 89.08293 58 -33.44577 86.8284 58.5 -33.44577 86.8284 58 -32.74585 86.98815 58 -36.44685 86.8284 58.5 -33.44577 86.8284 58 -33.44577 86.8284 58.5 -33.1249 87.88626 58 -33.1249 88.99686 58 -33.44577 89.08293 58 -33.44577 89.08293 58.5 -33.1249 88.99686 58 -33.12493 88.99678 58.5 -33.44577 89.08293 58.5 -33.44577 89.08293 58 -33.1249 88.99686 58 -31.87316 88.08275 58.5 -31.87307 88.08259 58 -31.87307 88.80051 58 -32.18442 87.43608 58.5 -9.117303 122.7 51.70221 -9.621379 122.7 60.74265 0 122.7 61.5 0 122.7 52.5 9.621379 122.7 60.74265 -4.576581 122.7 52.30014 -17.95623 122.7 49.33368 -19.00415 122.7 58.49 -13.58857 122.7 50.71086 -26.24942 122.7 45.46656 -27.91989 122.7 54.79715 -22.18721 122.7 47.58115 -33.74585 122.7 40.21773 -36.14939 122.7 49.75405 -30.11208 122.7 43.00589 -43.00589 122.7 30.11208 -43.48699 122.7 43.48699 -40.21773 122.7 33.74585 -37.1231 122.7 37.1231 -49.33368 122.7 17.95623 -49.75405 122.7 36.14939 -47.58115 122.7 22.18721 -45.46656 122.7 26.24942 -52.30015 122.7 4.576309 -54.79715 122.7 27.91989 -51.70221 122.7 9.117303 -50.71086 122.7 13.58857 -58.49 122.7 -19.00415 -58.49 122.7 19.00415 -54.79715 122.7 -27.91989 -60.74265 122.7 -9.621379 -60.74265 122.7 9.621379 -61.5 122.7 0 -50.71086 122.7 -13.58857 -49.75405 122.7 -36.14939 -51.70221 122.7 -9.117303 -52.30015 122.7 -4.576309 -52.5 122.7 0 -45.46656 122.7 -26.24942 -43.48699 122.7 -43.48699 -47.58115 122.7 -22.18721 -49.33368 122.7 -17.95623 -37.1231 122.7 -37.1231 -36.14939 122.7 -49.75405 -40.21773 122.7 -33.74585 -43.00589 122.7 -30.11208 -30.11208 122.7 -43.00589 -27.91989 122.7 -54.79715 -33.74585 122.7 -40.21773 -22.18721 122.7 -47.58115 -19.00415 122.7 -58.49 -26.24942 122.7 -45.46656 -13.58857 122.7 -50.71086 -9.621379 122.7 -60.74265 -17.95623 122.7 -49.33368 0 122.7 -52.5 0 122.7 -61.5 -4.576581 122.7 -52.30014 -9.117303 122.7 -51.70221 9.117303 122.7 -51.70221 9.621379 122.7 -60.74265 4.576581 122.7 -52.30014 17.95623 122.7 -49.33368 19.00415 122.7 -58.49 13.58857 122.7 -50.71086 26.24942 122.7 -45.46656 27.91989 122.7 -54.79715 22.18721 122.7 -47.58115 33.74585 122.7 -40.21773 36.14939 122.7 -49.75405 30.11208 122.7 -43.00589 43.00589 122.7 -30.11208 43.48699 122.7 -43.48699 40.21773 122.7 -33.74585 37.1231 122.7 -37.1231 49.33368 122.7 -17.95623 49.75405 122.7 -36.14939 47.58115 122.7 -22.18721 45.46656 122.7 -26.24942 52.30015 122.7 -4.576309 54.79715 122.7 -27.91989 51.70221 122.7 -9.117303 50.71086 122.7 -13.58857 58.49 122.7 19.00415 58.49 122.7 -19.00415 54.79715 122.7 27.91989 60.74265 122.7 9.621379 60.74265 122.7 -9.621379 61.5 122.7 0 50.71086 122.7 13.58857 49.75405 122.7 36.14939 51.70221 122.7 9.117303 52.30015 122.7 4.576309 52.5 122.7 0 45.46656 122.7 26.24942 43.48699 122.7 43.48699 47.58115 122.7 22.18721 49.33368 122.7 17.95623 37.1231 122.7 37.1231 36.14939 122.7 49.75405 40.21773 122.7 33.74585 43.00589 122.7 30.11208 30.11208 122.7 43.00589 27.91989 122.7 54.79715 33.74585 122.7 40.21773 22.18721 122.7 47.58115 19.00415 122.7 58.49 26.24942 122.7 45.46656 13.58857 122.7 50.71086 17.95623 122.7 49.33368 4.576581 122.7 52.30014 9.117303 122.7 51.70221 -8.379238 110.4 -47.51679 -8.379238 110.4 47.51679 0 110.4 48.25 0 110.4 -48.25 8.379238 110.4 47.51679 -16.50263 110.4 -45.34 -16.50263 110.4 45.34 -24.12447 110.4 -41.78593 -24.12447 110.4 41.78593 -31.01404 110.4 -36.96201 -31.01404 110.4 36.96201 -36.96201 110.4 -31.01404 -36.96201 110.4 31.01404 -41.78593 110.4 -24.12447 -41.78593 110.4 24.12447 -45.34 110.4 -16.50263 -45.34 110.4 16.50263 -47.51679 110.4 -8.379238 -47.51679 110.4 8.379238 -48.25 110.4 0 8.379238 110.4 -47.51679 16.50263 110.4 45.34 16.50263 110.4 -45.34 24.12447 110.4 41.78593 24.12447 110.4 -41.78593 31.01404 110.4 36.96201 31.01404 110.4 -36.96201 36.96201 110.4 31.01404 36.96201 110.4 -31.01404 41.78593 110.4 24.12447 41.78593 110.4 -24.12447 45.34 110.4 16.50263 45.34 110.4 -16.50263 47.51679 110.4 8.379238 47.51679 110.4 -8.379238 48.25 110.4 0 0 10 -71.5 0 10 -75.75 -1.453902 10 -76.00644 2.626644 10 -71.91603 1.453902 10 -76.00644 -2.626644 10 -71.91603 -2.732141 10 -76.74463 -3.680695 10 -77.87535 -4.185343 10 -79.26214 -4.996175 10 -86.87664 -4.185343 10 -80.73786 -4.996175 10 -73.12336 -3.680695 10 -82.12467 -2.732141 10 -83.25537 -2.626644 10 -88.08398 -1.453902 10 -83.99356 0 10 -84.25 0 10 -88.5 1.453902 10 -83.99356 2.626644 10 -88.08398 2.732141 10 -83.25537 3.680695 10 -82.12467 4.185343 10 -80.73786 4.996175 10 -73.12336 4.185343 10 -79.26214 4.996175 10 -86.87664 3.680695 10 -77.87535 2.732141 10 -76.74463 -61.92081 10 -35.75 -65.60144 10 -37.875 -66.55046 10 -36.7441 -60.96778 10 -38.23275 -65.09656 10 -39.26234 -63.59442 10 -33.68327 -67.82888 10 -36.00621 -69.28237 10 -35.75009 -70.73571 10 -36.00645 -77.73548 10 -39.11151 -72.01371 10 -36.74432 -65.82477 10 -32.23486 -72.9624 10 -37.87476 -73.46734 10 -39.26158 -77.59629 10 -41.76725 -73.46751 10 -40.73766 -72.96264 10 -42.125 -76.64325 10 -44.25 -72.01361 10 -43.2559 -74.96965 10 -46.31673 -70.73519 10 -43.99379 -69.2817 10 -44.24991 -67.82837 10 -43.99354 -60.82859 10 -40.88849 -66.55036 10 -43.25568 -72.73931 10 -47.76514 -65.60167 10 -42.12524 -65.09674 10 -40.73842 -61.92081 10 35.75 -65.60144 10 37.875 -65.09656 10 39.26234 -63.59442 10 33.68327 -66.55046 10 36.7441 -60.96778 10 38.23275 -65.09674 10 40.73842 -65.60167 10 42.12524 -66.55036 10 43.25568 -72.73931 10 47.76514 -67.82837 10 43.99354 -60.82859 10 40.88849 -69.2817 10 44.24991 -70.73519 10 43.99379 -74.96965 10 46.31673 -72.01361 10 43.2559 -72.96264 10 42.125 -76.64325 10 44.25 -73.46751 10 40.73766 -77.59629 10 41.76725 -73.46734 10 39.26158 -72.9624 10 37.87476 -72.01371 10 36.74432 -65.82477 10 32.23486 -70.73571 10 36.00645 -77.73548 10 39.11151 -69.28237 10 35.75009 -67.82888 10 36.00621 61.92081 10 35.75 65.60144 10 37.875 66.55046 10 36.7441 60.96778 10 38.23275 65.09656 10 39.26234 63.59442 10 33.68327 67.82888 10 36.00621 69.28237 10 35.75009 70.73571 10 36.00645 77.73548 10 39.11151 72.01371 10 36.74432 65.82477 10 32.23486 72.9624 10 37.87476 73.46734 10 39.26158 77.59629 10 41.76725 73.46751 10 40.73766 72.96264 10 42.125 76.64325 10 44.25 72.01361 10 43.2559 74.96965 10 46.31673 70.73519 10 43.99379 69.2817 10 44.24991 67.82837 10 43.99354 60.82859 10 40.88849 66.55036 10 43.25568 72.73931 10 47.76514 65.60167 10 42.12524 65.09674 10 40.73842 61.92081 10 -35.75 65.60144 10 -37.875 65.09656 10 -39.26234 63.59442 10 -33.68327 66.55046 10 -36.7441 60.96778 10 -38.23275 65.09674 10 -40.73842 65.60167 10 -42.12524 66.55036 10 -43.25568 72.73931 10 -47.76514 67.82837 10 -43.99354 60.82859 10 -40.88849 69.2817 10 -44.24991 70.73519 10 -43.99379 74.96965 10 -46.31673 72.01361 10 -43.2559 72.96264 10 -42.125 76.64325 10 -44.25 73.46751 10 -40.73766 77.59629 10 -41.76725 73.46734 10 -39.26158 72.9624 10 -37.87476 72.01371 10 -36.74432 65.82477 10 -32.23486 70.73571 10 -36.00645 77.73548 10 -39.11151 69.28237 10 -35.75009 67.82888 10 -36.00621 6.876644 10 -75.00382 6.876644 10 -84.99618 8.08398 10 -77.37336 8.08398 10 -82.62664 8.5 10 -80 -6.876644 10 -84.99618 -6.876644 10 -75.00382 -8.08398 10 -82.62664 -8.08398 10 -77.37336 -8.5 10 -80 -61.51689 10 -43.45726 -70.17053 10 -48.45344 -62.9653 10 -45.68761 -67.5148 10 -48.31425 -65.03203 10 -47.36122 -77.04718 10 -36.54274 -68.39354 10 -31.54656 -75.59877 10 -34.31239 -71.04928 10 -31.68575 -73.53203 10 -32.63878 -68.39354 10 31.54656 -77.04718 10 36.54274 -71.04928 10 31.68575 -75.59877 10 34.31239 -73.53203 10 32.63878 -70.17053 10 48.45344 -61.51689 10 43.45726 -67.5148 10 48.31425 -62.9653 10 45.68761 -65.03203 10 47.36122 61.51689 10 43.45726 70.17053 10 48.45344 62.9653 10 45.68761 67.5148 10 48.31425 65.03203 10 47.36122 77.04718 10 36.54274 68.39354 10 31.54656 75.59877 10 34.31239 71.04928 10 31.68575 73.53203 10 32.63878 68.39354 10 -31.54656 77.04718 10 -36.54274 71.04928 10 -31.68575 75.59877 10 -34.31239 73.53203 10 -32.63878 70.17053 10 -48.45344 61.51689 10 -43.45726 67.5148 10 -48.31425 62.9653 10 -45.68761 65.03203 10 -47.36122 -41.99308 10 -74.12334 -40.625 10 -74.36457 -40.625 12.40344 -70.36457 -39.25692 10 -74.12334 -40.625 12.40344 -70.36457 -40.625 10 -74.36457 -43.19615 10 -73.42874 -44.0891 10 -72.36457 -44.56423 10 -71.05916 -44.56423 10 -69.66997 -44.0891 10 -68.36457 -43.19615 10 -67.30039 -41.99308 10 -66.6058 -40.625 10 -66.36457 -39.25692 10 -66.6058 -40.625 10 -66.36457 -38.05385 10 -67.30039 -37.1609 10 -68.36457 -36.68577 10 -69.66997 -36.68577 10 -71.05916 -37.1609 10 -72.36457 -38.05385 10 -73.42874 85.18923 10 0.694593 84.71411 10 2 81.25 12.40344 0 83.82115 10 3.064178 81.25 12.40344 0 84.71411 10 2 85.18923 10 -0.694593 84.71411 10 -2 83.82115 10 -3.064178 82.61808 10 -3.75877 81.25 10 -4 79.88192 10 -3.75877 78.67885 10 -3.064178 77.7859 10 -2 77.31077 10 -0.694593 77.7859 10 -2 77.31077 10 0.694593 77.7859 10 2 78.67885 10 3.064178 79.88192 10 3.75877 81.25 10 4 82.61808 10 3.75877 24.3517 7 69.87836 -24.28907 7 70.0765 -24.97726 7 69.65728 29.41893 7 67.90081 -30.02424 7 67.63539 19.15286 7 71.47837 -23.82219 7 70.73329 -23.65241 7 71.52102 -14.0033 7 72.83258 -23.33038 7 73.15058 -13.1977 7 72.81361 13.85052 7 72.69219 -15.27692 7 73.76522 -22.43872 7 74.55274 -14.73602 7 73.16793 -16.37053 7 75.01541 -21.09926 7 75.53565 -17.84374 7 75.78388 -19.49515 7 75.96544 8.473347 7 73.51322 -7.815748 7 73.58612 3.050352 7 73.93708 -2.389251 7 73.96141 34.32722 7 65.55636 -34.91125 7 65.24723 39.05011 7 62.85765 -39.60983 7 62.50645 43.56184 7 59.81946 -44.09431 7 59.42797 47.83634 7 56.45958 -48.34053 7 56.02841 48.54349 7 56.0732 49.34572 7 55.99727 54.86616 7 56.04032 50.11281 7 56.24409 56.04042 7 54.86601 -52.32561 7 52.32609 53.3452 7 56.70886 51.68506 7 56.77999 56.7089 7 53.34508 56.77998 7 51.685 -56.02798 7 48.34104 56.24409 7 50.11281 55.99727 7 49.34572 56.0732 7 48.54349 56.45958 7 47.83634 -59.42761 7 44.09479 59.81953 7 43.56174 -62.50617 7 39.61026 62.85776 7 39.04994 -65.24707 7 34.91157 65.55648 7 34.32698 -67.6353 7 30.02444 67.90092 7 29.41865 -69.65728 7 24.97726 69.87847 7 24.35139 -75.96543 7 19.49533 71.47846 7 19.15255 -75.53559 7 21.09942 -74.55265 7 22.43881 -73.15052 7 23.33041 -71.52102 7 23.65241 -70.73329 7 23.82219 -70.0765 7 24.28907 -72.83258 7 14.0033 72.69224 7 13.85023 -73.16793 7 14.73602 -73.76522 7 15.27692 -75.01544 7 16.37059 -75.78392 7 17.84387 -72.81361 7 13.1977 73.51325 7 8.473104 -73.58609 7 7.81595 73.93708 7 3.050184 -73.96138 7 2.389604 73.96139 7 -2.389348 -73.93708 7 -3.049872 73.5861 7 -7.815814 -73.51329 7 -8.472778 72.81361 7 -13.1977 -72.6923 7 -13.8499 72.83258 7 -14.0033 -71.47854 7 -19.15223 73.16793 7 -14.73602 73.76522 7 -15.27692 75.01544 7 -16.37059 75.78392 7 -17.84387 75.96543 7 -19.49533 -69.87857 7 -24.3511 75.53559 7 -21.09942 74.55265 7 -22.43881 73.15052 7 -23.33041 71.52102 7 -23.65241 70.73329 7 -23.82219 70.0765 7 -24.28907 69.65728 7 -24.97726 -67.90103 7 -29.41839 67.63539 7 -30.02425 -65.55659 7 -34.32678 65.24723 7 -34.91126 -62.85785 7 -39.0498 62.50643 7 -39.60985 -59.81959 7 -43.56166 59.42795 7 -44.09433 -56.45958 7 -47.83634 56.02838 7 -48.34056 -56.77998 7 -51.685 52.32606 7 -52.32564 -56.24409 7 -50.11281 -55.99727 7 -49.34572 -56.0732 7 -48.54349 -49.34572 7 -55.99727 48.341 7 -56.02801 -56.04042 7 -54.86601 -56.7089 7 -53.34508 -47.83634 7 -56.45958 44.09475 7 -59.42764 -48.54349 7 -56.0732 -43.56186 7 -59.81944 39.61022 7 -62.50619 -39.05015 7 -62.85763 34.91155 7 -65.24707 -34.32729 7 -65.55632 30.02442 7 -67.63533 -29.41902 7 -67.90076 24.97726 7 -69.65728 -24.35181 7 -69.87832 24.28907 7 -70.0765 -19.15298 7 -71.47834 23.82219 7 -70.73329 23.65241 7 -71.52102 14.0033 7 -72.83258 23.33038 7 -73.15058 13.1977 7 -72.81361 -13.85064 7 -72.69216 15.27692 7 -73.76522 22.43872 7 -74.55274 14.73602 7 -73.16793 16.37053 7 -75.01541 21.09926 7 -75.53565 17.84374 7 -75.78388 19.49515 7 -75.96544 -8.473461 7 -73.51322 7.8157 7 -73.58612 -3.050451 7 -73.93706 2.389175 7 -73.96141 -54.86616 7 -56.04032 -50.11281 7 -56.24409 -53.3452 7 -56.70886 -51.68506 7 -56.77999 -52.21591 39.4866 49 -51.5 38 48.00858 -51.5 39.65 49 -50.78409 39.4866 49 -51.5 39.65 49 -51.5 38 48.00858 -52.21591 39.4866 57.9 -52.21591 39.4866 49 -51.5 39.65 49 -51.5 39.65 57.9 -50.78409 39.4866 49 -51.5 39.65 57.9 -51.5 39.65 49 -52.21591 36.5134 49 -51.5 36.35 49 -50.78409 36.5134 49 -51.5 36.35 49 -52.79002 36.97124 49 -53.10863 37.63284 49 -53.10863 38.36716 49 -52.79002 39.02876 49 -50.20998 39.02876 49 -49.89137 38.36716 49 -49.89137 37.63284 49 -50.20998 36.97124 49 -51.5 36.35 57.9 -51.5 36.35 49 -52.21591 36.5134 49 -50.78409 36.5134 57.9 -51.5 36.35 49 -51.5 36.35 57.9 -50.78409 36.5134 49 -52.21591 36.5134 57.9 -52.79002 36.97124 49 -52.79002 36.97124 57.9 -53.10863 37.63284 49 -53.10863 37.63284 57.9 -53.10863 38.36716 49 -53.10863 38.36716 57.9 -52.79002 39.02876 49 -52.79002 39.02876 57.9 -56.43339 39.7956 57.9 -52.21591 39.4866 57.9 -51.5 39.65 57.9 -50.78409 39.4866 57.9 -46.56661 39.7956 57.9 -50.78409 39.4866 57.9 -56.43339 36.20439 57.9 -51.5 36.35 57.9 -52.21591 36.5134 57.9 -46.56661 36.20439 57.9 -50.78409 36.5134 57.9 -52.79002 36.97124 57.9 -53.10863 37.63284 57.9 -56.75 38 57.9 -53.10863 38.36716 57.9 -52.79002 39.02876 57.9 -50.20998 39.02876 49 -50.20998 39.02876 57.9 -49.89137 38.36716 49 -49.89137 38.36716 57.9 -49.89137 37.63284 49 -49.89137 37.63284 57.9 -50.20998 36.97124 49 -50.20998 36.97124 57.9 -50.20998 39.02876 57.9 -49.89137 38.36716 57.9 -46.25 38 57.9 -49.89137 37.63284 57.9 -50.20998 36.97124 57.9 -55.52173 34.62537 57.9 -47.47827 34.62537 57.9 -54.125 33.45336 57.9 -48.875 33.45336 57.9 -52.41165 32.82976 57.9 -50.58835 32.82976 57.9 -47.47827 41.37463 57.9 -55.52173 41.37463 57.9 -48.875 42.54663 57.9 -54.125 42.54663 57.9 -50.58835 43.17024 57.9 -52.41165 43.17024 57.9 -20 85.97177 58.5 -20 85.97177 58 -23.94784 85.97177 58 -31.25827 85 58 -33.44577 86.8284 58 -36.44685 86.8284 58 -31.87316 88.08275 58.5 -31.87307 88.80051 58 -31.87316 88.80036 58.5 -36.44685 85 58.5 -37.5 90.05471 58.5 -37.5 85 58.5 -33.44577 89.08293 58.5 -33.44577 90.05471 58.5 -36.44685 86.8284 58.5 -36.44685 87.80018 58.5 -36.44685 89.08293 58.5 -32.89055 88.7624 58.5 -32.74557 89.89479 58.5 -33.12493 88.99678 58.5 -32.18442 87.43608 58.5 -32.18442 89.44702 58.5 -32.74557 86.98833 58.5 -32.8044 88.44155 58.5 -31.87316 88.08275 58.5 -31.87316 88.80036 58.5 -33.44577 87.80018 58.5 -33.44577 86.8284 58.5 -33.12493 87.88633 58.5 -32.89055 88.12071 58.5 -30.13828 85 58.5 -30.13828 90.05471 58.5 -31.25827 90.05471 58.5 -31.25827 85 58.5 -28.17565 85.97177 58.5 -28.17565 90.05471 58.5 -29.23825 90.05471 58.5 -29.23825 85 58.5 -25.98325 85 58.5 -25.98325 85.97177 58.5 -20.17238 89.08293 58.5 -20.17238 90.05471 58.5 -25.41853 90.05471 58.5 -21.70046 89.08293 58.5 -25.41853 89.08293 58.5 -23.94784 85.97177 58.5 -20 85 58.5 -20 85.97177 58.5 -25.47593 85.97177 58.5 -25.47593 85 58.5 -32.8903 88.12107 58 -32.8045 88.44155 58 -32.8903 88.76204 58 -25.47593 85 58 -25.98325 85.97177 58 -25.98325 85 58 -31.25827 90.05471 58 -32.18456 89.44734 58 -31.87307 88.80051 58 -33.12493 88.99678 58.5 -33.1249 88.99686 58 -32.8903 88.76204 58 -20.17238 89.08293 58 -23.94784 85.97177 58 -20 85.97177 58 -25.47593 85.97177 58 -21.70046 89.08293 58 -25.41853 89.08293 58 -31.25827 85 58 -31.25827 90.05471 58 -31.87307 88.80051 58 -36.44685 86.8284 58.5 -36.44685 86.8284 58 -33.44577 86.8284 58 -36.44685 85 58.5 -36.44685 86.8284 58 -36.44685 86.8284 58.5 -37.5 85 58.5 -37.5 85 58 -36.44685 85 58 -37.5 90.05471 58.5 -37.5 90.05471 58 -37.5 85 58 -37.5 85 58.5 -36.44685 85 58.5 -36.44685 85 58 -36.44685 86.8284 58 -36.44685 85 58.5 -31.25827 85 58 -32.18456 87.43577 58 -32.74585 86.98815 58 -31.25827 85 58 -32.74585 86.98815 58 -33.44577 86.8284 58 -25.41853 89.08293 58 -25.41853 90.05471 58 -28.17565 90.05471 58 -25.47593 85.97177 58 -33.44577 87.80018 58 -36.44685 89.08293 58 -36.44685 87.80018 58 -36.44685 87.80018 58.5 -36.44685 87.80018 58 -36.44685 89.08293 58 -33.44577 87.80018 58.5 -33.44577 87.80018 58 -36.44685 87.80018 58 -36.44685 87.80018 58.5 -31.87316 88.80036 58.5 -31.87307 88.80051 58 -32.18456 89.44734 58 -34.31492 44.53391 58 -34.49993 46.4 58 -34.31492 48.26609 58 -34.31492 48.26609 62.5 -34.31492 48.26609 58 -34.49993 46.4 58 -31.27354 53.53391 58 -31.27354 53.53391 62.5 -31.27354 53.53391 58 -34.31492 48.26609 58 -32.79399 50.90041 63 -34.31492 48.26609 62.5 -34.5 46.4 62.5 -34.31492 44.53391 58 -34.45362 47.3376 62.5 -31.27354 39.26609 58 -34.31492 44.53391 62.5 -34.31492 44.53391 58 -31.27354 39.26609 58 -34.45362 45.46239 62.5 -34.31492 44.53391 62.5 -29.74696 54.629 58 -29.74696 38.171 58 -31.27354 39.26609 62.5 -31.27354 39.26609 58 -29.74696 38.171 58 -32.79446 41.90041 63 -31.27354 39.26609 62.5 -28.04138 55.4 58 -28.04138 37.4 58 -29.75 38.17276 62.5 -28.04138 37.4 58 -21.95862 55.4 58 -21.95862 37.4 58 -28.04138 37.4 62.5 -28.04138 37.4 58 -21.95862 37.4 58 -28.04138 37.4 62.5 -20.25304 54.629 58 -20.25304 38.171 58 -21.95862 37.4 62.5 -21.95862 37.4 58 -20.25304 38.171 58 -25.00048 37.4 63 -21.95862 37.4 62.5 -18.72646 53.53391 58 -18.72646 39.26609 58 -20.25001 38.17276 62.5 -18.72646 39.26609 58 -15.68508 48.26609 58 -15.68508 44.53391 58 -18.72646 39.26609 62.5 -18.72646 39.26609 58 -15.68508 44.53391 58 -18.72646 39.26609 62.5 -15.50007 46.4 58 -15.68508 44.53391 62.5 -15.68508 44.53391 58 -15.50007 46.4 58 -17.20601 41.89959 63 -15.68508 44.53391 62.5 -15.5 46.4 62.5 -15.68508 48.26609 58 -15.54638 45.46239 62.5 -15.68508 48.26609 62.5 -15.68508 48.26609 58 -18.72646 53.53391 58 -15.54638 47.3376 62.5 -15.68508 48.26609 62.5 -18.72646 53.53391 62.5 -18.72646 53.53391 58 -20.25304 54.629 58 -17.20553 50.89959 63 -18.72646 53.53391 62.5 -20.25001 54.62724 62.5 -21.95862 55.4 58 -21.95862 55.4 62.5 -21.95862 55.4 58 -28.04138 55.4 58 -21.95862 55.4 62.5 -28.04138 55.4 62.5 -28.04138 55.4 58 -29.74696 54.629 58 -24.99953 55.4 63 -28.04138 55.4 62.5 -29.75 54.62724 62.5 -31.27354 53.53391 58 -31.27354 53.53391 62.5 -17.68872 48.07153 64.5 -19.59535 49.00365 64.5 -19 46.4 64.5 -19 46.4 76.5 -19 46.4 64.5 -19.59535 49.00365 64.5 -17.5 46.4 64.5 -19.59535 43.79634 64.5 -19.59489 43.79825 76.5 -19.59535 43.79634 64.5 -19 46.4 64.5 -19 46.4 76.5 -19.13702 51.07585 64.5 -21.25761 51.08954 64.5 -19.59489 49.00175 76.5 -21.25761 51.08954 64.5 -18.24383 49.65515 64.5 -20.32332 52.26232 64.5 -23.66701 52.24942 64.5 -21.26139 51.09243 76.5 -23.66701 52.24942 64.5 -26.33299 52.24942 64.5 -23.66241 52.24808 76.5 -26.33299 52.24942 64.5 -30.86298 51.07585 64.5 -28.7424 51.08954 64.5 -26.33759 52.24808 76.5 -28.7424 51.08954 64.5 -29.67667 52.26232 64.5 -31.75617 49.65515 64.5 -30.40465 49.00365 64.5 -28.73861 51.09243 76.5 -30.40465 49.00365 64.5 -32.5 46.4 64.5 -31 46.4 64.5 -30.40511 49.00175 76.5 -31 46.4 64.5 -32.31127 48.07153 64.5 -32.31127 44.72847 64.5 -30.40465 43.79634 64.5 -31 46.4 76.5 -31 46.4 64.5 -30.40465 43.79634 64.5 -31 46.4 76.5 -30.86299 41.72415 64.5 -28.7424 41.71046 64.5 -30.40511 43.79825 76.5 -28.7424 41.71046 64.5 -31.75617 43.14485 64.5 -29.67668 40.53768 64.5 -26.33299 40.55058 64.5 -28.73861 41.70757 76.5 -26.33299 40.55058 64.5 -23.66701 40.55058 64.5 -26.33759 40.55192 76.5 -23.66701 40.55058 64.5 -19.13702 41.72415 64.5 -21.25761 41.71046 64.5 -23.66241 40.55192 76.5 -21.25761 41.71046 64.5 -20.32333 40.53767 64.5 -18.24383 43.14485 64.5 -21.26139 41.70757 76.5 -17.68872 44.72847 64.5 -34.5 46.4 62.5 -32.5 46.4 64.5 -32.31127 48.07153 64.5 -34.31492 44.53391 62.5 -32.31127 44.72847 64.5 -32.5 46.4 64.5 -34.45362 45.46239 62.5 -34.5 46.4 62.5 -34.31492 48.26609 62.5 -31.75617 49.65515 64.5 -34.45362 47.3376 62.5 -32.79399 50.90041 63 -30.86298 51.07585 64.5 -31.27354 53.53391 62.5 -29.67667 52.26232 64.5 -21.74402 53.15576 64.5 -28.25598 53.15577 64.5 -29.75 54.62724 62.5 -28.25598 53.15577 64.5 -23.32904 53.71129 64.5 -26.67095 53.71129 64.5 -28.04138 55.4 62.5 -26.67095 53.71129 64.5 -25 53.9 64.5 -25 53.9 64.5 -24.99953 55.4 63 -23.32904 53.71129 64.5 -21.95862 55.4 62.5 -21.74402 53.15576 64.5 -20.25001 54.62724 62.5 -20.32332 52.26232 64.5 -18.72646 53.53391 62.5 -19.13702 51.07585 64.5 -17.20553 50.89959 63 -18.24383 49.65515 64.5 -17.68872 48.07153 64.5 -15.68508 48.26609 62.5 -17.5 46.4 64.5 -15.5 46.4 62.5 -17.5 46.4 64.5 -17.68872 44.72847 64.5 -15.54638 47.3376 62.5 -15.5 46.4 62.5 -15.68508 44.53391 62.5 -18.24383 43.14485 64.5 -15.54638 45.46239 62.5 -17.20601 41.89959 63 -19.13702 41.72415 64.5 -18.72646 39.26609 62.5 -20.32333 40.53767 64.5 -28.25598 39.64423 64.5 -21.74402 39.64423 64.5 -20.25001 38.17276 62.5 -21.74402 39.64423 64.5 -26.67096 39.08871 64.5 -23.32905 39.08871 64.5 -21.95862 37.4 62.5 -23.32905 39.08871 64.5 -25 38.9 64.5 -25 38.9 64.5 -25.00048 37.4 63 -26.67096 39.08871 64.5 -28.04138 37.4 62.5 -28.25598 39.64423 64.5 -29.75 38.17276 62.5 -29.67668 40.53768 64.5 -31.27354 39.26609 62.5 -30.86299 41.72415 64.5 -32.79446 41.90041 63 -31.75617 43.14485 64.5 -30.40511 43.79825 76.5 -19.59489 43.79825 76.5 -19 46.4 76.5 -31 46.4 76.5 -19.59489 49.00175 76.5 -28.73861 41.70757 76.5 -21.26139 41.70757 76.5 -26.33759 40.55192 76.5 -23.66241 40.55192 76.5 -30.40511 49.00175 76.5 -21.26139 51.09243 76.5 -28.73861 51.09243 76.5 -23.66241 52.24808 76.5 -26.33759 52.24808 76.5 -32.18442 87.43608 58.5 -32.18456 87.43577 58 -31.87307 88.08259 58 -32.74557 86.98833 58.5 -32.89055 88.7624 58.5 -32.8903 88.76204 58 -32.8045 88.44155 58 -33.12493 88.99678 58.5 -32.8044 88.44155 58.5 -32.8903 88.12107 58 -32.89055 88.12071 58.5 -33.1249 87.88626 58 -33.12493 87.88633 58.5 -33.44577 87.80018 58 -33.44577 87.80018 58.5 -31.25827 90.05471 58.5 -31.25827 90.05471 58 -31.25827 85 58 -30.13828 90.05471 58.5 -30.13828 90.05471 58 -31.25827 90.05471 58 -31.25827 90.05471 58.5 -31.25827 85 58.5 -31.25827 85 58 -30.13828 85 58 -31.25827 85 58.5 -30.13828 85 58.5 -30.13828 85 58 -30.13828 90.05471 58 -31.25827 85 58.5 -30.13828 85 58 -30.13828 85 58.5 -28.17565 90.05471 58 -28.17565 85.97177 58 -25.98325 85.97177 58 -25.41853 89.08293 58.5 -25.41853 89.08293 58 -21.70046 89.08293 58 -25.41853 89.08293 58.5 -25.41853 90.05471 58.5 -25.41853 89.08293 58 -21.70046 89.08293 58.5 -21.70046 89.08293 58 -25.47593 85.97177 58 -21.70046 89.08293 58.5 -25.47593 85.97177 58.5 -25.47593 85.97177 58 -25.47593 85 58 -25.47593 85.97177 58.5 -25.47593 85 58.5 -25.47593 85 58 -20 85 58 -25.47593 85 58.5 -20 85 58.5 -20 85 58 -20 85.97177 58 -20 85 58.5 -29.23825 85 58 -30.13828 90.05471 58 -30.13828 85 58 -25.47593 85.97177 58 -28.17565 90.05471 58 -25.98325 85.97177 58 -25.47593 85 58 -31.25827 90.05471 58 -32.74585 89.89495 58 -32.18456 89.44734 58 -29.23825 85 58 -29.23825 90.05471 58 -30.13828 90.05471 58 -25.98325 85.97177 58.5 -25.98325 85.97177 58 -28.17565 85.97177 58 -25.98325 85 58.5 -25.98325 85 58 -25.98325 85.97177 58 -29.23825 85 58.5 -25.98325 85 58 -25.98325 85 58.5 -33.1249 87.88626 58 -32.8903 88.12107 58 -33.1249 88.99686 58 -30.13828 85 58.5 -30.13828 90.05471 58 -30.13828 90.05471 58.5 -29.23825 90.05471 58.5 -29.23825 90.05471 58 -29.23825 85 58 -28.17565 90.05471 58.5 -28.17565 90.05471 58 -29.23825 90.05471 58 -29.23825 90.05471 58.5 -29.23825 85 58.5 -29.23825 85 58 -25.98325 85 58 -29.23825 85 58.5 -31.25827 85 58 -31.87307 88.80051 58 -31.87307 88.08259 58 -28.17565 85.97177 58.5 -28.17565 90.05471 58 -28.17565 90.05471 58.5 -25.41853 90.05471 58.5 -25.41853 90.05471 58 -25.41853 89.08293 58 -20.17238 90.05471 58.5 -20.17238 90.05471 58 -25.41853 90.05471 58 -25.41853 90.05471 58.5 -25.98325 85 58.5 -25.98325 85.97177 58 -25.98325 85.97177 58.5 -28.17565 85.97177 58.5 -28.17565 85.97177 58 -28.17565 90.05471 58 -25.98325 85.97177 58.5 -28.17565 85.97177 58 -28.17565 85.97177 58.5 15.68508 75.53392 58 15.50007 77.4 58 15.68508 79.26609 58 15.68508 79.26609 62.5 15.68508 79.26609 58 15.50007 77.4 58 18.72646 84.53392 58 18.72646 84.53392 62.5 18.72646 84.53392 58 15.68508 79.26609 58 17.20601 81.90042 63 15.68508 79.26609 62.5 15.5 77.4 62.5 15.68508 75.53392 58 15.54638 78.33761 62.5 18.72646 70.26609 58 15.68508 75.53392 62.5 15.68508 75.53392 58 18.72646 70.26609 58 15.54638 76.4624 62.5 15.68508 75.53392 62.5 20.25304 85.629 58 20.25304 69.17102 58 18.72646 70.26609 62.5 18.72646 70.26609 58 20.25304 69.17102 58 17.20553 72.90042 63 18.72646 70.26609 62.5 21.95862 86.4 58 21.95862 68.4 58 20.25001 69.17276 62.5 21.95862 68.4 58 28.04138 86.4 58 28.04138 68.4 58 21.95862 68.4 62.5 21.95862 68.4 58 28.04138 68.4 58 21.95862 68.4 62.5 29.74696 85.629 58 29.74696 69.17102 58 28.04138 68.4 62.5 28.04138 68.4 58 29.74696 69.17102 58 24.99953 68.4 63 28.04138 68.4 62.5 31.27354 84.53392 58 31.27354 70.26609 58 29.75 69.17276 62.5 31.27354 70.26609 58 34.31492 79.26609 58 34.31492 75.53392 58 31.27354 70.26609 62.5 31.27354 70.26609 58 34.31492 75.53392 58 31.27354 70.26609 62.5 34.49993 77.4 58 34.31492 75.53392 62.5 34.31492 75.53392 58 34.49993 77.4 58 32.79399 72.89959 63 34.31492 75.53392 62.5 34.5 77.4 62.5 34.31492 79.26609 58 34.45362 76.4624 62.5 34.31492 79.26609 62.5 34.31492 79.26609 58 31.27354 84.53392 58 34.45362 78.33761 62.5 34.31492 79.26609 62.5 31.27354 84.53392 62.5 31.27354 84.53392 58 29.74696 85.629 58 32.79446 81.89959 63 31.27354 84.53392 62.5 29.75 85.62725 62.5 28.04138 86.4 58 28.04138 86.4 62.5 28.04138 86.4 58 21.95862 86.4 58 28.04138 86.4 62.5 21.95862 86.4 62.5 21.95862 86.4 58 20.25304 85.629 58 25.00048 86.4 63 21.95862 86.4 62.5 20.25001 85.62725 62.5 18.72646 84.53392 58 18.72646 84.53392 62.5 32.31127 79.07154 64.5 30.40465 80.00366 64.5 31 77.4 64.5 31 77.4 76.5 31 77.4 64.5 30.40465 80.00366 64.5 32.5 77.4 64.5 30.40465 74.79634 64.5 30.40511 74.79825 76.5 30.40465 74.79634 64.5 31 77.4 64.5 31 77.4 76.5 30.86299 82.07585 64.5 28.7424 82.08954 64.5 30.40511 80.00175 76.5 28.7424 82.08954 64.5 31.75617 80.65515 64.5 29.67668 83.26232 64.5 26.33299 83.24942 64.5 28.73861 82.09243 76.5 26.33299 83.24942 64.5 23.66701 83.24942 64.5 26.33759 83.24808 76.5 23.66701 83.24942 64.5 19.13702 82.07585 64.5 21.25761 82.08954 64.5 23.66241 83.24808 76.5 21.25761 82.08954 64.5 20.32333 83.26233 64.5 18.24383 80.65515 64.5 19.59535 80.00366 64.5 21.26139 82.09243 76.5 19.59535 80.00366 64.5 17.5 77.4 64.5 19 77.4 64.5 19.59489 80.00175 76.5 19 77.4 64.5 17.68872 79.07154 64.5 17.68872 75.72847 64.5 19.59535 74.79634 64.5 19 77.4 76.5 19 77.4 64.5 19.59535 74.79634 64.5 19 77.4 76.5 19.13702 72.72415 64.5 21.25761 72.71046 64.5 19.59489 74.79825 76.5 21.25761 72.71046 64.5 18.24383 74.14485 64.5 20.32332 71.53768 64.5 23.66701 71.55059 64.5 21.26139 72.70758 76.5 23.66701 71.55059 64.5 26.33299 71.55059 64.5 23.66241 71.55194 76.5 26.33299 71.55059 64.5 30.86298 72.72415 64.5 28.7424 72.71046 64.5 26.33759 71.55194 76.5 28.7424 72.71046 64.5 29.67667 71.53768 64.5 31.75617 74.14485 64.5 28.73861 72.70758 76.5 32.31127 75.72847 64.5 15.5 77.4 62.5 17.5 77.4 64.5 17.68872 79.07154 64.5 15.68508 75.53392 62.5 17.68872 75.72847 64.5 17.5 77.4 64.5 15.54638 76.4624 62.5 15.5 77.4 62.5 15.68508 79.26609 62.5 18.24383 80.65515 64.5 15.54638 78.33761 62.5 17.20601 81.90042 63 19.13702 82.07585 64.5 18.72646 84.53392 62.5 20.32333 83.26233 64.5 28.25598 84.15577 64.5 21.74402 84.15577 64.5 20.25001 85.62725 62.5 21.74402 84.15577 64.5 26.67096 84.71129 64.5 23.32905 84.71129 64.5 21.95862 86.4 62.5 23.32905 84.71129 64.5 25 84.9 64.5 25 84.9 64.5 25.00048 86.4 63 26.67096 84.71129 64.5 28.04138 86.4 62.5 28.25598 84.15577 64.5 29.75 85.62725 62.5 29.67668 83.26232 64.5 31.27354 84.53392 62.5 30.86299 82.07585 64.5 32.79446 81.89959 63 31.75617 80.65515 64.5 32.31127 79.07154 64.5 34.31492 79.26609 62.5 32.5 77.4 64.5 34.5 77.4 62.5 32.5 77.4 64.5 32.31127 75.72847 64.5 34.45362 78.33761 62.5 34.5 77.4 62.5 34.31492 75.53392 62.5 31.75617 74.14485 64.5 34.45362 76.4624 62.5 32.79399 72.89959 63 30.86298 72.72415 64.5 31.27354 70.26609 62.5 29.67667 71.53768 64.5 21.74402 70.64424 64.5 28.25598 70.64424 64.5 29.75 69.17276 62.5 28.25598 70.64424 64.5 23.32904 70.08872 64.5 26.67095 70.08871 64.5 28.04138 68.4 62.5 26.67095 70.08871 64.5 25 69.9 64.5 25 69.9 64.5 24.99953 68.4 63 23.32904 70.08872 64.5 21.95862 68.4 62.5 21.74402 70.64424 64.5 20.25001 69.17276 62.5 20.32332 71.53768 64.5 18.72646 70.26609 62.5 19.13702 72.72415 64.5 17.20553 72.90042 63 18.24383 74.14485 64.5 19.59489 74.79825 76.5 30.40511 74.79825 76.5 31 77.4 76.5 19 77.4 76.5 30.40511 80.00175 76.5 21.26139 72.70758 76.5 28.73861 72.70758 76.5 23.66241 71.55194 76.5 26.33759 71.55194 76.5 19.59489 80.00175 76.5 28.73861 82.09243 76.5 21.26139 82.09243 76.5 26.33759 83.24808 76.5 23.66241 83.24808 76.5 -33.44577 87.80018 58 -33.44577 89.08293 58 -36.44685 89.08293 58 -32.74557 86.98833 58.5 -32.74585 86.98815 58 -32.18456 87.43577 58 -33.44577 86.8284 58.5 - - - - - - - - - - 0 -0.8660238 0.5000029 0.4938971 0.1724047 0.8522572 0.4846759 0.1709077 0.8578345 0.5879557 0.1721597 0.7903602 -5.5399e-6 -0.8660327 0.4999873 2.86058e-6 -0.8660214 0.500007 2.93474e-6 -0.8660196 0.50001 -1.99472e-6 -0.8660287 0.4999946 0.553528 0.1723423 0.8148036 0.6140754 0.1745999 0.7696924 0.6738069 0.1728923 0.7183958 0 0 1 0 -0.8660258 0.4999995 4.35738e-7 -0.8660227 0.5000047 -1.69633e-7 -0.8660241 0.5000024 0 -0.866027 0.4999973 0.4269962 0.1738687 0.8873805 0.3687059 0.169963 0.9138756 0.2907833 0.1738352 0.9408647 0.2480635 0.1703605 0.9536467 0.3596646 0.1736217 0.9167862 0.1482912 0.1727674 0.9737357 0.1242424 0.171913 0.977246 0.2177251 0.1727701 0.9605969 0.0416277 0.1673043 0.9850262 0.06137341 0.1733167 0.982952 0.0706824 0.1702055 0.9828704 -0.07309389 0.1738688 0.9820525 -0.05856639 0.1695039 0.9837878 -0.03683614 0.1735298 0.9841396 -0.1254957 0.1703897 0.9773527 0 1 0 0 1 5.22092e-6 0 1 2.78484e-6 0.6698419 0.1741747 0.7217861 0 1 2.80769e-6 0.7285062 0.1732605 0.6627666 0.7218454 0.1740522 0.6698098 0 1 -2.87797e-6 0.7563231 0.1724021 0.6310729 0.7699418 0.1740212 0.613927 0 1 2.74477e-6 0 1 2.8196e-6 0.8021505 0.1761904 0.5705361 0.8136528 0.1740227 0.5546939 0.7999897 0.176063 0.5736011 0.7979041 0.1756097 0.5766372 0.7958396 0.1751781 0.5796137 0.7938042 0.174875 0.5824893 0.7918056 0.174597 0.5852862 0.7898617 0.1743549 0.5879787 0.7880064 0.1741732 0.5905165 0.7862008 0.17405 0.5929543 0.7845349 0.1739307 0.5951918 0.7827257 0.1738373 0.5975962 0.7801617 0.1736846 0.6009837 0.7692586 0.1731945 0.6150162 0.7734584 0.1733208 0.6096901 0.8506338 0.1774696 0.4949008 0.8527851 0.1739262 0.4924504 0 1 2.7216e-6 0.84765 0.1817744 0.4984453 0.8439691 0.1798782 0.5053316 0.8406013 0.1783565 0.5114474 0.8375985 0.1771942 0.5167505 0.8348184 0.1762781 0.5215403 0.832179 0.1755794 0.5259754 0.8296312 0.1749965 0.5301778 0.8271318 0.1745699 0.5342084 0.8246688 0.1742056 0.5381208 0.8221471 0.1739574 0.5420452 0.8195453 0.1737791 0.5460278 0.8168981 0.1736828 0.5500108 0.8140976 0.1736233 0.5541662 0.8868893 0.1740512 0.4279409 0.8870807 0.1742665 0.4274566 0.9149008 0.192911 0.3546011 0.9018666 0.1871119 0.3893917 0.8929532 0.1834797 0.4110594 0.886304 0.1809475 0.4262902 0.8809827 0.1790593 0.4379582 0.8764619 0.1776241 0.4475089 0.8725364 0.176491 0.4555561 0.8689829 0.1755789 0.4626457 0.8655861 0.1748751 0.469233 0.8623455 0.1743246 0.4753643 0.8591163 0.173929 0.4813188 0.855926 0.1737121 0.4870471 0.9066131 0.1740528 0.3843935 0.916759 0.1741411 0.3594828 0.9185135 0.176494 0.353812 0.9087631 0.1753619 0.3786793 0.9035781 0.1747522 0.3911629 0.8998599 0.1743869 0.399802 0.89682 0.1740841 0.4067049 0.8941106 0.1738963 0.4127063 0.8915941 0.173747 0.418177 0.8892645 0.1736535 0.4231469 0 1 -5.18145e-7 0.9407093 0.1718509 0.2924609 0.9414033 0.1727401 0.2896907 0 1 -7.98783e-7 0.9231631 0.1726448 0.3434585 0.9105904 0.1736826 0.375046 0.9089162 0.1738361 0.3790152 0.9077498 0.1739264 0.3817591 0 1 -9.36554e-7 0.9686481 0.1731047 0.1782014 0.960068 0.1728903 0.2199507 0 1 1.00213e-6 0.9738693 0.173624 0.1464008 0.9831733 0.1726467 0.05969536 0.9820494 0.1735631 0.07385665 0.9847584 0.1739281 0 0.9831287 0.1728578 -0.05981659 0.9821044 0.1731348 -0.07413083 0.9687598 0.1728892 -0.1778028 0.9739775 0.1732248 -0.1461546 0.9600419 0.1738067 -0.2193413 0.9406956 0.1713962 -0.2927714 0.9410827 0.1736223 -0.2902048 0.9167074 0.1738377 -0.3597612 0.8951727 0.1762146 -0.4094075 0.8872203 0.1740198 -0.4272672 0.8967523 0.1760665 -0.4059999 0.8983404 0.1756089 -0.4026738 0.8998835 0.1751791 -0.3994023 0.9013611 0.1748458 -0.3962034 0.9027858 0.1745998 -0.3930556 0.9041398 0.1743578 -0.390039 0.9054206 0.1741745 -0.3871392 0.9066131 0.1740528 -0.3843935 0.9077339 0.1739292 -0.3817957 0.9089052 0.1738093 -0.3790538 0.9105852 0.1736875 -0.3750563 0.9172185 0.1731649 -0.3587815 0.9232351 0.1725553 -0.34331 0 1 7.02416e-7 0.8539162 0.1774668 -0.4892165 0.852887 0.1739283 -0.4922732 0.8554918 0.181774 -0.4848631 0.8596103 0.1798815 -0.4782395 0.8632314 0.1783533 -0.4722518 0.8663312 0.1771971 -0.4669814 0.8691016 0.1762802 -0.4621556 0.8716118 0.1755797 -0.4576733 0.8739592 0.1749994 -0.4533991 0.8762047 0.1745695 -0.4492113 0.8783762 0.1742042 -0.4450936 0.8805029 0.1739581 -0.4409686 0.8826599 0.1737791 -0.4367062 0.8847945 0.1736872 -0.4324021 0.8869748 0.1736228 -0.4279379 0.8140681 0.1740508 -0.5540754 0.8137455 0.1742672 -0.554481 0 1 -2.7216e-6 0.76442 0.1929132 -0.6151801 0.7881519 0.1871727 -0.5863301 0.802472 0.1834814 -0.5677793 0.812332 0.1809489 -0.5544134 0.8197336 0.179084 -0.5440273 0.8257898 0.177622 -0.5352771 0.8308054 0.176495 -0.527837 0.8351516 0.1756061 -0.5212334 0.8391557 0.1748749 -0.5150114 0.8428539 0.1743267 -0.5091243 0.8463932 0.1739298 -0.5033558 0.8497512 0.1737163 -0.4977406 0.7861892 0.1740542 -0.5929686 0.7696962 0.174143 -0.6142004 0.7656748 0.1764946 -0.6185401 0.7823912 0.175333 -0.5975972 0.7905665 0.1747522 -0.5869126 0.7961604 0.174388 -0.5794114 0.8006381 0.1740809 -0.5733014 0.804503 0.1738954 -0.5679221 0.8079714 0.1737471 -0.5630224 0.8111044 0.1736533 -0.5585289 0.7236443 0.1718544 -0.6684348 0.721568 0.1727393 -0.6704482 0 1 -2.74477e-6 0.7590215 0.1726492 -0.6277568 0.7801093 0.1736865 -0.6010513 0.7827298 0.1738077 -0.5975994 0.7845089 0.1739317 -0.5952257 0 1 -1.56504e-6 0.6386691 0.1731032 -0.749758 0.6705085 0.1728916 -0.7214756 0.6137398 0.1736233 -0.7701809 0.5432964 0.172645 -0.8215978 0.5549906 0.1735624 -0.8135488 0.4923912 0.173927 -0.852819 0.4397488 0.1728598 -0.8813288 0.4268197 0.1731389 -0.887608 0.3303723 0.1728923 -0.9278807 0.3603708 0.173227 -0.9165835 0.2900558 0.1738076 -0.9410943 0 1 5.09709e-6 0.2167794 0.171397 -0.9610566 0.2191902 0.1736248 -0.9601094 0 1 -5.94659e-6 0.1468273 0.1738062 -0.9737727 0.09302294 0.1762187 -0.9799458 0.07358199 0.174021 -0.981989 0.09677678 0.1760661 -0.9796097 0.1004379 0.1756062 -0.9793236 0.10407 0.1751794 -0.9790208 0.1075173 0.1748719 -0.9787032 0.1109993 0.1746019 -0.9783627 0.1142652 0.1743583 -0.97803 0.1174083 0.1741744 -0.9776905 0.1203985 0.1740513 -0.9773488 0.1232672 0.1739292 -0.9770128 0.1261343 0.1738352 -0.9766635 0.1305589 0.1736817 -0.9761092 0.1478974 0.1731676 -0.9737246 0.1642536 0.1725548 -0.9712083 0.009338796 0.1812835 -0.9833866 0.03683614 0.1735298 -0.9841396 0 1 -5.22092e-6 0.007812917 0.1818039 -0.9833039 0.01562565 0.1798787 -0.9835647 0.02264547 0.1783561 -0.9837055 0.02874904 0.1771944 -0.983756 0.03424215 0.1762769 -0.9837449 0.03943002 0.1755737 -0.9836764 0.04428333 0.174997 -0.9835726 0.04904443 0.1745702 -0.9834225 0.05365324 0.1742053 -0.9832467 0.05838304 0.1739589 -0.9830207 0.06305176 0.1737738 -0.9827651 0.06787371 0.1736823 -0.9824601 0.07288008 0.1736243 -0.9821116 -0.006164729 0.1737124 -0.9847771 -0.0366224 0.1741092 -0.9840452 -0.002807676 0.173621 -0.9848086 -0.1504919 0.1929141 -0.9696063 -0.07281833 0.1740499 -0.9820409 -0.0733686 0.1742658 -0.9819616 -0.1136549 0.1871154 -0.975741 -0.0904268 0.1834782 -0.9788559 -0.07385504 0.1809449 -0.9807163 -0.06122195 0.1790574 -0.9819319 -0.05066108 0.1776189 -0.9827945 -0.04175007 0.1764918 -0.9834163 -0.03375452 0.1755785 -0.9838866 -0.02642941 0.1748735 -0.9842361 -0.01950186 0.1743268 -0.9844947 -0.01272654 0.1739296 -0.9846758 -0.07837384 0.02615511 -0.9965808 -0.01748752 0.02615493 -0.9995049 -0.03222823 0.02621597 -0.9991367 0.1563193 0.026277 -0.987357 0.03201431 0.02682608 -0.9991274 0.01800632 0.02694845 -0.9994747 0.0784043 0.02609407 -0.9965801 -0.06582945 0.02633786 -0.9974833 -0.100804 0.026582 -0.9945512 -0.1356561 0.02667343 -0.9903969 -0.1563491 0.02627688 -0.9873523 -0.1713019 0.02615457 -0.9848714 -0.2057932 0.0262773 -0.9782427 -0.2398503 0.02646011 -0.9704493 -0.2735754 0.02664333 -0.9614815 -0.3088847 0.02636855 -0.9507339 -0.3091253 0.02615463 -0.9506617 -0.3437713 0.0262162 -0.9386875 -0.3783749 0.02639895 -0.925276 -0.4131435 0.02661305 -0.910277 -0.4538455 0.02630722 -0.8906921 -0.4508654 0.02615523 -0.8922086 -0.4876667 0.02621597 -0.8726363 -0.5245609 0.02645999 -0.8509618 -0.5614259 0.02679556 -0.8270931 -0.5875898 0.02624666 -0.8087332 -0.60293 0.02615463 -0.7973654 -0.641938 0.02636843 -0.7663031 -0.6806094 0.02679586 -0.7321563 -0.7067993 0.02639925 -0.7069214 -0.7240318 0.02615469 -0.6892707 -0.7641137 0.02646028 -0.6445388 -0.8087267 0.0265516 -0.587585 -0.8066502 0.02609378 -0.5904529 -0.8466798 0.0263071 -0.5314523 -0.8906979 0.02658206 -0.453818 -0.8867861 0.02606308 -0.4614449 -0.9229345 0.02633816 -0.384055 -0.9507054 0.02667379 -0.3089464 -0.9567142 0.02594125 -0.2898709 -0.9873521 0.02664309 -0.156288 -0.9828739 0.02594137 -0.1824443 0.1617811 0.1716387 -0.9717855 -0.9996516 0.02639895 6.10381e-5 -0.9980518 0.02609342 -0.0566731 0.1588803 0.1698976 -0.9725698 -0.9873594 0.02636861 0.1562891 -0.9949853 0.02584969 0.09662359 0.1572033 0.1682512 -0.9731284 -0.9508332 0.02704018 0.308521 -0.9566618 0.02438497 0.2901787 0.1978272 0.3747181 -0.9057874 0.1413325 0.2542214 -0.9567638 0.2135387 0.2763156 -0.9370437 0.1403268 0.2964321 -0.9446886 -0.8907449 0.02795594 0.4536432 -0.9040143 0.02581936 0.4267219 0.3086124 0.3752363 -0.8740459 0.3243299 0.2760176 -0.9047787 0.4138982 0.3753833 -0.8293225 0.4303833 0.2754977 -0.8595762 0.5291994 0.275495 -0.8025276 0.5112572 0.3753858 -0.7731117 0.6214057 0.2760176 -0.7332594 0.6026345 0.375235 -0.7042943 0.704728 0.2763244 -0.653455 0.7628313 0.1699012 -0.6238766 0.7641472 0.1682235 -0.6227199 0.6854968 0.3747175 -0.6242444 0.7579042 0.2542217 -0.6007934 0.7606914 0.17164 -0.6260101 0.758585 0.172708 -0.6282681 0.2082017 0.02703994 0.9777121 0.2268205 0.02438503 0.9736313 0.4132277 0.02584958 0.9102608 0.7479479 0.2964385 -0.5938841 0.05200433 0.02722293 0.9982758 0.0823397 0.0263682 0.9962555 0.3582915 0.02639877 0.9332365 0.5474272 0.02609407 0.8364464 0.4997505 0.02642953 0.8657662 0.6488597 0.02591043 0.7604668 0.6290288 0.02667367 0.7769243 0.7289595 0.02594161 0.6840652 0.742949 0.02661234 0.6688188 0.7942627 0.02649068 0.6069968 0.8427007 0.0260635 0.5377512 0.8383892 0.02645999 0.5444296 0.8841629 0.02661246 0.4664202 0.9144361 0.02612411 0.4038864 0.9132088 0.02649015 0.4066301 0.9399843 0.02639889 0.340195 0.9588081 0.02615457 0.282848 0.9655918 0.0264905 0.2587099 0.9735786 0.02618503 0.2268459 0.9846912 0.02652084 0.172279 0.9919531 0.02615457 0.1238759 0.9941853 0.02636831 0.1044053 0.9967762 0.02618515 0.07583934 0.9992257 0.02642953 0.02914571 0.9995122 0.02682656 -0.01599216 0.9981272 0.02621591 -0.05527007 0.9982852 0.02627706 -0.05230998 0.9950664 0.02624619 -0.09567654 0.9905024 0.02646017 -0.1349256 0.98456 0.0267961 -0.1729847 0.9779227 0.02621585 -0.2073161 0.9778172 0.02630704 -0.2078014 0.9697804 0.02621603 -0.2425672 0.9604399 0.02636855 -0.2772366 0.9499006 0.02664297 -0.3114148 0.9386203 0.02624654 -0.3439522 0.9332395 0.02627682 -0.3582927 0.9258657 0.02618557 -0.3769446 0.9117801 0.02627664 -0.4098372 0.8966796 0.02652102 -0.441885 0.881268 0.0268262 -0.471855 0.8745716 0.02694791 -0.4841471 0.8238749 0.02615523 -0.5661679 0.8568359 0.02615523 -0.5149255 0.8491355 0.02621597 -0.5275242 0.9022816 0.02609425 -0.4303569 0.8309249 0.02633833 -0.5557609 0.8109059 0.02658253 -0.5845725 0.7898645 0.02667367 -0.6127012 0.7768905 0.02627676 -0.6290872 0.7672801 0.02615481 -0.6407786 0.74427 0.02627694 -0.6673618 0.7204892 0.02645981 -0.6929612 0.6959074 0.02664357 -0.7176373 0.6688873 0.02636849 -0.7428961 0.668682 0.02615517 -0.7430885 0.6410594 0.02621608 -0.7670434 0.612054 0.02639871 -0.7903752 0.5817856 0.02661263 -0.8129067 0.5444103 0.02630794 -0.8384065 0.5472423 0.02615505 -0.8365656 0.5118933 0.02621567 -0.858649 0.4746617 0.02645993 -0.8797706 0.435541 0.02679592 -0.8997701 0.4065818 0.02624678 -0.9132373 0.3890905 0.02615499 -0.9208282 0.3426361 0.02636831 -0.9390982 0.2937422 0.02679538 -0.9555091 0.2588036 0.02639913 -0.9655692 0.2349053 0.02615481 -0.9716663 0.1760935 0.02645975 -0.9840178 0.1044985 0.0265519 -0.9941706 0.1080053 0.02609336 -0.9938079 0.03689724 0.02630722 -0.9989728 -0.05230957 0.02658206 -0.9982771 -0.04373365 0.0260632 -0.9987033 -0.1288807 0.02633768 -0.9913103 -0.2077764 0.02667397 -0.9778127 -0.2272728 0.02594089 -0.9734857 -0.3582994 0.02664351 -0.9332265 -0.3334184 0.02594101 -0.9424221 0.9224858 0.1716366 -0.3457758 -0.4999049 0.02639913 -0.8656778 -0.44994 0.0260936 -0.8926776 0.9217126 0.1699008 -0.3486827 -0.6290339 0.02636867 -0.7769306 -0.5811768 0.02584969 -0.8133667 0.9213584 0.1682494 -0.3504153 -0.7426232 0.02703994 -0.6691635 -0.729622 0.02438479 -0.6834159 0.8833571 0.3747187 -0.2815426 0.8992596 0.2542281 -0.3559499 0.9182767 0.2763162 -0.2835796 0.8883057 0.2964071 -0.3507931 -0.83824 0.02795553 -0.5445845 -0.8215499 0.0258193 -0.5695518 0.9112628 0.3752294 -0.1697154 0.945731 0.2760162 -0.1714877 0.9251617 0.3753872 -0.05621647 0.9596168 0.2754667 -0.05704045 0.9596168 0.2754667 0.05704045 0.9251617 0.3753872 0.05621647 0.945731 0.2760162 0.1714877 0.9112628 0.3752294 0.1697154 0.9182767 0.2763162 0.2835796 0.9217126 0.1699008 0.3486827 0.9213584 0.1682494 0.3504153 0.8833571 0.3747187 0.2815426 0.8992596 0.2542281 0.3559499 0.9224812 0.1716414 0.3457855 0.9233977 0.1727098 0.3427949 -0.7426232 0.02703994 0.6691635 -0.7297694 0.02438461 0.6832584 -0.5816934 0.02584964 0.8129974 0.8883057 0.2964071 0.3507931 -0.8385196 0.02722322 0.5441909 -0.8216007 0.02636837 0.5694532 -0.6290519 0.02639865 0.7769151 -0.4506468 0.0260939 0.8923209 -0.4999046 0.02642959 0.8656772 -0.3341559 0.02591085 0.9421616 -0.3582991 0.02667403 0.9332258 -0.2279432 0.02594077 0.9733289 -0.2077413 0.02661234 0.9778218 -0.1285461 0.0264905 0.9913497 -0.04434424 0.02606326 0.9986764 -0.05230975 0.02646005 0.9982803 0.03811824 0.02661257 0.9989188 0.1074557 0.02612382 0.9938666 0.1044352 0.02649027 0.9941789 0.1753628 0.02639901 0.98415 0.2344161 0.02615469 0.9717845 0.2587383 0.02649027 0.9655842 0.2902662 0.02618527 0.9565877 0.3431245 0.02652096 0.9389155 0.3886882 0.02615463 0.9209982 0.4066427 0.02636891 0.9132066 0.4326958 0.02618509 0.9011597 0.4743255 0.02642935 0.8799528 0.5136373 0.02682632 0.857588 0.5469083 0.02621614 0.8367819 0.5444537 0.02627658 0.8383793 0.5803854 0.02624654 0.813919 0.6120869 0.02645987 0.7903478 0.6421284 0.02679604 0.7661287 0.6684887 0.02621579 0.7432603 0.6688883 0.02630746 0.7428973 0.6949542 0.02621603 0.718576 0.7203414 0.02636843 0.6931183 0.7446382 0.02664327 0.6669363 0.7671806 0.02624613 0.6408939 0.7769175 0.02627664 0.6290538 0.7893806 0.02618551 0.6133456 0.8108338 0.026277 0.5846865 0.8310292 0.0265209 0.5555962 0.8492651 0.02682656 0.5272848 0.8565778 0.02694827 0.5153139 0.9022564 0.02615451 0.430406 0.8743588 0.02615445 0.4845748 0.8814179 0.02621573 0.4716094 0.823862 0.02609378 0.5661896 0.8967745 0.02633798 0.4417035 0.9117118 0.02658253 0.4099696 0.9255436 0.02667337 0.3777006 0.9332497 0.02627706 0.3582661 0.9385795 0.02615469 0.3440705 0.9500901 0.02627694 0.3108675 0.9603677 0.02645981 0.2774775 0.969447 0.02664333 0.2438495 0.9778082 0.02636867 0.2078365 0.9778721 0.02615511 0.2075624 0.9848164 0.02621579 0.1716081 0.9905081 0.02639925 0.1348959 0.9948937 0.02661269 0.09735608 0.9982859 0.02630758 0.05227953 0.9981104 0.02615439 0.05560481 0.9995586 0.02621579 0.0139777 0.9992347 0.02646028 -0.02881026 0.9969964 0.02679568 -0.07266587 0.9941821 0.02624619 -0.104466 0.9920102 0.02615451 -0.1234176 0.9846042 0.02636837 -0.1727986 0.9743731 0.02679544 -0.2233364 0.9656115 0.02639865 -0.258646 0.9589504 0.02615511 -0.2823656 0.9402355 0.02646011 -0.3394956 0.9132413 0.02655214 -0.406553 0.9146633 0.02609395 -0.4033735 0.8836023 0.02630782 -0.4674986 0.8383634 0.02658224 -0.5444632 0.8430191 0.02606296 -0.5372519 0.7940546 0.02633821 -0.6072756 0.742919 0.02667337 -0.6688498 0.7294173 0.02594161 -0.683577 0.6290293 0.02664315 -0.7769249 0.6494507 0.02594137 -0.7599611 0.7755948 0.1727715 0.6071266 0.4997509 0.02639901 -0.8657668 0.548093 0.02609384 -0.8360104 0.7775636 0.1718831 0.6048564 0.3582918 0.02636831 -0.9332372 0.4138118 0.02584987 -0.9099954 0.7790641 0.170755 0.6032429 0.2082017 0.02703994 -0.9777121 0.2270299 0.02438455 -0.9735826 0.7718538 0.3263082 0.5456781 0.7662438 0.2466556 0.5933225 0.7476075 0.2569138 0.6124364 0.05249339 0.02795577 -0.99823 0.08243179 0.02581906 -0.9962623 0.6817993 0.3701981 0.6309543 0.6744493 0.254929 0.6929137 0.7426903 0.3812487 0.5505095 0.5804173 0.1863512 0.79271 0.1305003 0 -0.9914484 0.1305303 0 -0.9914444 0.06540286 0 -0.997859 0 -1 0 -0.1305003 0 -0.9914484 -0.06540286 0 -0.997859 0.2588022 0 -0.9659304 0.3826816 0 -0.9238803 0.4999893 0 -0.8660317 0.6087679 0 -0.7933484 0.7071068 0 -0.7071068 0.7933484 0 -0.6087679 0.8660317 0 -0.4999893 0.9238803 0 -0.3826816 0.9659304 0 -0.2588022 0.9914484 0 -0.1305003 1 0 0 0.9914484 0 0.1305003 0.9914444 0 0.1305303 0.9659304 0 0.2588022 0.9238803 0 0.3826816 0.8660317 0 0.4999893 0.7933484 0 0.6087679 0.7071068 0 0.7071068 0.6087679 0 0.7933484 0.4999893 0 0.8660317 0.3826816 0 0.9238803 0.2588022 0 0.9659304 0.1305003 0 0.9914484 0.06540286 0 0.997859 -0.1305003 0 0.9914484 -0.06540286 0 0.997859 -0.1305303 0 0.9914444 0.02383524 0.7544878 0.6558813 0.03985822 0.7925565 0.6084945 0.08044922 0.7872487 0.6113652 -0.08484214 0.722898 0.6857261 -0.0813328 0.7869294 0.6116594 -0.03622668 0.7908234 0.6109715 -0.03894275 0.7614592 0.647042 0.1716687 0.7229924 0.6691876 0.1616282 0.7867778 0.5956988 0.08343875 0.7231156 0.6856689 0.03222811 0.6992228 0.7141771 0.2541956 0.7225762 0.6428596 0.2387837 0.7868816 0.5690342 0.3329637 0.722052 0.6064455 0.3112981 0.7871876 0.5323809 0.4067925 0.7214165 0.5604269 0.3780112 0.7876099 0.4865987 0.4744238 0.7207151 0.505462 0.43786 0.7880992 0.4326412 0.5347046 0.7201421 0.4421384 0.4899293 0.788593 0.3716052 0.582585 0.7258737 0.365653 0.5335311 0.7890353 0.3045784 0.627996 0.7197982 0.2958238 0.5680521 0.7894072 0.2327082 0.6617485 0.7184532 0.2142755 0.5930258 0.7896938 0.1571757 0.6835972 0.7182363 0.1297366 0.6081511 0.7898609 0.07919663 0.6943979 0.7182943 0.04318428 0.6131945 0.789932 0 0.6943979 0.7182943 -0.04318428 0.6081318 0.7898755 -0.07919812 0.6835972 0.7182363 -0.1297366 0.5930258 0.7896938 -0.1571757 0.6617485 0.7184532 -0.2142755 0.5680521 0.7894072 -0.2327082 0.6280638 0.7197753 -0.2957354 0.5335311 0.7890353 -0.3045784 0.5774522 0.7285523 -0.3684573 0.4899293 0.788593 -0.3716052 0.5349081 0.7204641 -0.441367 0.43786 0.7880992 -0.4326412 0.4742434 0.7210245 -0.5051902 0.3780112 0.7876099 -0.4865987 0.4064928 0.7217926 -0.5601599 0.3112981 0.7871876 -0.5323809 0.3325426 0.7224928 -0.6061517 0.2387837 0.7868816 -0.5690342 0.2536134 0.7230575 -0.6425483 0.1616282 0.7867778 -0.5956988 0.1709656 0.7234453 -0.6688779 0.0813328 0.7869294 -0.6116594 0.08438587 0.7240095 -0.6846089 0.02682685 0.8045313 -0.5933041 -0.02868813 0.7750388 -0.6312621 -0.03833186 0.8099144 -0.5852943 -0.07983696 0.7873221 -0.6113511 0.03125166 0.7822381 -0.6221954 -0.7218454 0.1740522 0.6698098 -0.7563231 0.1724021 0.6310729 -0.7285062 0.1732605 0.6627666 -0.731114 0.1910186 0.654969 -0.7320635 0.185404 0.6555215 -0.7554335 0.2390238 0.6100721 -0.6698419 0.1741747 0.7217861 -0.6738069 0.1728923 0.7183958 0 0 1 -0.7775636 0.1718831 0.6048564 -0.7790681 0.1707254 0.603246 -0.6821351 0.3729448 0.6289706 -0.7630749 0.240065 0.6000711 -0.7755948 0.1727715 0.6071266 -0.7737474 0.1732562 0.6093418 -0.7733332 0.1733506 0.6098403 -0.7697542 0.1743254 0.614076 -0.7005703 0.2470842 0.6694406 -0.2082017 0.02703994 -0.9777121 -0.2268205 0.02438503 -0.9736313 -0.4132277 0.02584958 -0.9102608 -0.746737 0.2960336 0.5956073 -0.05200433 0.02722293 -0.9982758 -0.0823397 0.0263682 -0.9962555 -0.3582915 0.02639877 -0.9332365 -0.5474272 0.02609407 -0.8364464 -0.4997505 0.02642953 -0.8657662 -0.6488597 0.02591043 -0.7604668 -0.6290288 0.02667367 -0.7769243 -0.7289595 0.02594161 -0.6840652 -0.7801093 0.1736865 0.6010513 -0.742949 0.02661234 -0.6688188 -0.7942627 0.02649068 -0.6069968 -0.7827298 0.1738077 0.5975994 -0.8427007 0.0260635 -0.5377512 -0.7845089 0.1739317 0.5952257 -0.8383892 0.02645999 -0.5444296 -0.8841629 0.02661246 -0.4664202 -0.7862008 0.17405 0.5929543 -0.9144361 0.02612411 -0.4038864 -0.8137455 0.1742672 0.554481 -0.7656748 0.1764946 0.6185401 -0.9132088 0.02649015 -0.4066301 -0.9399843 0.02639889 -0.340195 -0.7823912 0.175333 0.5975972 -0.9588081 0.02615457 -0.282848 -0.7905551 0.1747565 0.5869268 -0.9655918 0.0264905 -0.2587099 -0.9735786 0.02618503 -0.2268459 -0.7961604 0.174388 0.5794114 -0.9846912 0.02652084 -0.172279 -0.8006381 0.1740809 0.5733014 -0.9919531 0.02615457 -0.1238759 -0.804503 0.1738954 0.5679221 -0.9941853 0.02636831 -0.1044053 -0.9967762 0.02618515 -0.07583934 -0.8079714 0.1737471 0.5630224 -0.9992257 0.02642953 -0.02914571 -0.8111044 0.1736533 0.5585289 -0.9995122 0.02682656 0.01599216 -0.8138731 0.1736413 0.55449 -0.9981272 0.02621591 0.05527007 -0.852887 0.1739283 0.4922732 -0.76442 0.1929132 0.6151801 -0.8140681 0.1740508 0.5540754 -0.9982852 0.02627706 0.05230998 -0.9950664 0.02624619 0.09567654 -0.7881564 0.1871432 0.5863334 -0.9905024 0.02646017 0.1349256 -0.802472 0.1834814 0.5677793 -0.98456 0.0267961 0.1729847 -0.8123561 0.1809474 0.5543786 -0.9779227 0.02621585 0.2073161 -0.8197236 0.1790885 0.5440409 -0.9778172 0.02630704 0.2078014 -0.9697804 0.02621603 0.2425672 -0.8257898 0.177622 0.5352771 -0.9604399 0.02636855 0.2772366 -0.8308149 0.1764906 0.5278236 -0.9499006 0.02664297 0.3114148 -0.8351516 0.1756061 0.5212334 -0.9386203 0.02624654 0.3439522 -0.8391557 0.1748749 0.5150114 -0.9332395 0.02627682 0.3582927 -0.9258657 0.02618557 0.3769446 -0.8428539 0.1743267 0.5091243 -0.9117801 0.02627664 0.4098372 -0.8463932 0.1739298 0.5033558 -0.8966796 0.02652102 0.441885 -0.8497512 0.1737163 0.4977406 -0.881268 0.0268262 0.471855 -0.8539162 0.1774668 0.4892165 -0.8745716 0.02694791 0.4841471 -0.8872203 0.1740198 0.4272672 -0.855487 0.1818035 0.4848604 -0.8238749 0.02615523 0.5661679 -0.8568359 0.02615523 0.5149255 -0.8491355 0.02621597 0.5275242 -0.9022816 0.02609425 0.4303569 -0.8596103 0.1798815 0.4782395 -0.8309249 0.02633833 0.5557609 -0.8632314 0.1783533 0.4722518 -0.8109059 0.02658253 0.5845725 -0.8663312 0.1771971 0.4669814 -0.7898645 0.02667367 0.6127012 -0.8691016 0.1762802 0.4621556 -0.7768905 0.02627676 0.6290872 -0.7672801 0.02615481 0.6407786 -0.8716118 0.1755797 0.4576733 -0.74427 0.02627694 0.6673618 -0.8739592 0.1749994 0.4533991 -0.7204892 0.02645981 0.6929612 -0.8762047 0.1745695 0.4492113 -0.6959074 0.02664357 0.7176373 -0.8783762 0.1742042 0.4450936 -0.6688873 0.02636849 0.7428961 -0.668682 0.02615517 0.7430885 -0.8805029 0.1739581 0.4409686 -0.6410594 0.02621608 0.7670434 -0.8826599 0.1737791 0.4367062 -0.612054 0.02639871 0.7903752 -0.8847945 0.1736872 0.4324021 -0.5817856 0.02661263 0.8129067 -0.8869748 0.1736228 0.4279379 -0.5444103 0.02630794 0.8384065 -0.5472423 0.02615505 0.8365656 -0.8871297 0.1736432 0.4276086 -0.5118933 0.02621567 0.858649 -0.9167074 0.1738377 0.3597612 -0.8967523 0.1760665 0.4059999 -0.8951727 0.1762146 0.4094075 -0.4746617 0.02645993 0.8797706 -0.8983404 0.1756089 0.4026738 -0.435541 0.02679592 0.8997701 -0.8998835 0.1751791 0.3994023 -0.4065818 0.02624678 0.9132373 -0.3890905 0.02615499 0.9208282 -0.9013611 0.1748458 0.3962034 -0.3426361 0.02636831 0.9390982 -0.9027858 0.1745998 0.3930556 -0.2937422 0.02679538 0.9555091 -0.9041398 0.1743578 0.390039 -0.2588036 0.02639913 0.9655692 -0.2349053 0.02615481 0.9716663 -0.9054206 0.1741745 0.3871392 -0.1760935 0.02645975 0.9840178 -0.9066185 0.174048 0.3843829 -0.1044985 0.0265519 0.9941706 -0.1080053 0.02609336 0.9938079 -0.9077339 0.1739292 0.3817957 -0.03689724 0.02630722 0.9989728 -0.9089052 0.1738093 0.3790538 0.05230957 0.02658206 0.9982771 0.04373365 0.0260632 0.9987033 -0.9105748 0.1736855 0.3750826 0.1288807 0.02633768 0.9913103 -0.9172185 0.1731649 0.3587815 0.2077764 0.02667397 0.9778127 0.2272728 0.02594089 0.9734857 -0.9232351 0.1725553 0.34331 0.3582994 0.02664351 0.9332265 0.3334184 0.02594101 0.9424221 -0.9406956 0.1713962 0.2927714 -0.9224858 0.1716366 0.3457758 0.4999049 0.02639913 0.8656778 0.44994 0.0260936 0.8926776 -0.9217126 0.1699008 0.3486827 0.6290339 0.02636867 0.7769306 0.5811768 0.02584969 0.8133667 -0.9213584 0.1682494 0.3504153 0.7426232 0.02703994 0.6691635 0.729622 0.02438479 0.6834159 -0.8833571 0.3747187 0.2815426 -0.8992596 0.2542281 0.3559499 -0.9182767 0.2763162 0.2835796 -0.8883057 0.2964071 0.3507931 0.83824 0.02795553 0.5445845 0.8215499 0.0258193 0.5695518 -0.9600419 0.1738067 0.2193413 -0.9687598 0.1728892 0.1778028 -0.9112628 0.3752294 0.1697154 -0.945731 0.2760162 0.1714877 -0.9410827 0.1736223 0.2902048 -0.9821044 0.1731348 0.07413083 -0.9831287 0.1728578 0.05981659 -0.9251617 0.3753872 0.05621647 -0.9596168 0.2754667 0.05704045 -0.9739775 0.1732248 0.1461546 -0.9847584 0.1739281 0 -0.9831733 0.1726467 -0.05969536 -0.9596168 0.2754667 -0.05704045 -0.9738693 0.173624 -0.1464008 -0.9686481 0.1731047 -0.1782014 -0.9251617 0.3753872 -0.05621647 -0.945731 0.2760162 -0.1714877 -0.9820494 0.1735631 -0.07385665 -0.9414033 0.1727401 -0.2896907 -0.9407093 0.1718509 -0.2924609 -0.9112628 0.3752294 -0.1697154 -0.9182767 0.2763162 -0.2835796 -0.960068 0.1728903 -0.2199507 -0.9217126 0.1699008 -0.3486827 -0.9213584 0.1682494 -0.3504153 -0.8833571 0.3747187 -0.2815426 -0.8992596 0.2542281 -0.3559499 -0.9224812 0.1716414 -0.3457855 -0.9233977 0.1727098 -0.3427949 -0.9231631 0.1726448 -0.3434585 -0.916759 0.1741411 -0.3594828 0.7426232 0.02703994 -0.6691635 0.7297694 0.02438461 -0.6832584 0.5816934 0.02584964 -0.8129974 -0.8883057 0.2964071 -0.3507931 0.8385196 0.02722322 -0.5441909 0.8216007 0.02636837 -0.5694532 0.6290519 0.02639865 -0.7769151 0.4506468 0.0260939 -0.8923209 0.4999046 0.02642959 -0.8656772 0.3341559 0.02591085 -0.9421616 0.3582991 0.02667403 -0.9332258 0.2279432 0.02594077 -0.9733289 -0.9105904 0.1736826 -0.375046 0.2077413 0.02661234 -0.9778218 0.1285461 0.0264905 -0.9913497 -0.9089162 0.1738361 -0.3790152 0.04434424 0.02606326 -0.9986764 -0.9077605 0.1739284 -0.381733 0.05230975 0.02646005 -0.9982803 -0.03811824 0.02661257 -0.9989188 -0.9066131 0.1740528 -0.3843935 -0.1074557 0.02612382 -0.9938666 -0.8870807 0.1742665 -0.4274566 -0.9185281 0.1764909 -0.3537754 -0.1044352 0.02649027 -0.9941789 -0.1753628 0.02639901 -0.98415 -0.9087631 0.1753619 -0.3786793 -0.2344161 0.02615469 -0.9717845 -0.9035781 0.1747522 -0.3911629 -0.2587383 0.02649027 -0.9655842 -0.2902662 0.02618527 -0.9565877 -0.8998599 0.1743869 -0.399802 -0.3431245 0.02652096 -0.9389155 -0.89682 0.1740841 -0.4067049 -0.3886882 0.02615463 -0.9209982 -0.8941106 0.1738963 -0.4127063 -0.4066427 0.02636891 -0.9132066 -0.4326958 0.02618509 -0.9011597 -0.8915941 0.173747 -0.418177 -0.4743255 0.02642935 -0.8799528 -0.8892645 0.1736535 -0.4231469 -0.5136373 0.02682632 -0.857588 -0.8871486 0.1736443 -0.4275687 -0.5469083 0.02621614 -0.8367819 -0.8527851 0.1739262 -0.4924504 -0.9149008 0.192911 -0.3546011 -0.8868893 0.1740512 -0.4279409 -0.5444537 0.02627658 -0.8383793 -0.5803854 0.02624654 -0.813919 -0.9018666 0.1871119 -0.3893917 -0.6120869 0.02645987 -0.7903478 -0.8929532 0.1834797 -0.4110594 -0.6421284 0.02679604 -0.7661287 -0.886304 0.1809475 -0.4262902 -0.6684887 0.02621579 -0.7432603 -0.8809827 0.1790593 -0.4379582 -0.6688883 0.02630746 -0.7428973 -0.6949542 0.02621603 -0.718576 -0.8764619 0.1776241 -0.4475089 -0.7203414 0.02636843 -0.6931183 -0.8725364 0.176491 -0.4555561 -0.7446382 0.02664327 -0.6669363 -0.8689829 0.1755789 -0.4626457 -0.7671806 0.02624613 -0.6408939 -0.8655984 0.1748776 -0.4692091 -0.7769175 0.02627664 -0.6290538 -0.7893806 0.02618551 -0.6133456 -0.8623455 0.1743246 -0.4753643 -0.8108338 0.026277 -0.5846865 -0.8591163 0.173929 -0.4813188 -0.8310292 0.0265209 -0.5555962 -0.855926 0.1737121 -0.4870471 -0.8492651 0.02682656 -0.5272848 -0.8506338 0.1774696 -0.4949008 -0.8565778 0.02694827 -0.5153139 -0.8136528 0.1740227 -0.5546939 -0.8476586 0.1817697 -0.4984324 -0.9022564 0.02615451 -0.430406 -0.8743588 0.02615445 -0.4845748 -0.8814179 0.02621573 -0.4716094 -0.823862 0.02609378 -0.5661896 -0.8439691 0.1798782 -0.5053316 -0.8967745 0.02633798 -0.4417035 -0.8406013 0.1783565 -0.5114474 -0.9117118 0.02658253 -0.4099696 -0.8375985 0.1771942 -0.5167505 -0.9255436 0.02667337 -0.3777006 -0.8348184 0.1762781 -0.5215403 -0.9332497 0.02627706 -0.3582661 -0.9385795 0.02615469 -0.3440705 -0.832179 0.1755794 -0.5259754 -0.9500901 0.02627694 -0.3108675 -0.8296312 0.1749965 -0.5301778 -0.9603677 0.02645981 -0.2774775 -0.8271318 0.1745699 -0.5342084 -0.969447 0.02664333 -0.2438495 -0.8246785 0.1742012 -0.5381072 -0.9778082 0.02636867 -0.2078365 -0.9778721 0.02615511 -0.2075624 -0.8221471 0.1739574 -0.5420452 -0.9848164 0.02621579 -0.1716081 -0.8195453 0.1737791 -0.5460278 -0.9905081 0.02639925 -0.1348959 -0.8168981 0.1736828 -0.5500108 -0.9948937 0.02661269 -0.09735608 -0.8140976 0.1736233 -0.5541662 -0.9982859 0.02630758 -0.05227953 -0.9981104 0.02615439 -0.05560481 -0.8138757 0.1736436 -0.5544857 -0.9995586 0.02621579 -0.0139777 -0.7699106 0.173838 -0.614018 -0.7999897 0.176063 -0.5736011 -0.8021505 0.1761904 -0.5705361 -0.9992347 0.02646028 0.02881026 -0.7979084 0.1755801 -0.5766402 -0.9969964 0.02679568 0.07266587 -0.7958396 0.1751781 -0.5796137 -0.9941821 0.02624619 0.104466 -0.9920102 0.02615451 0.1234176 -0.7938042 0.174875 -0.5824893 -0.9846042 0.02636837 0.1727986 -0.7918056 0.174597 -0.5852862 -0.9743731 0.02679544 0.2233364 -0.7898617 0.1743549 -0.5879787 -0.9656115 0.02639865 0.258646 -0.9589504 0.02615511 0.2823656 -0.7880064 0.1741732 -0.5905165 -0.9402355 0.02646011 0.3394956 -0.7862008 0.17405 -0.5929543 -0.9132413 0.02655214 0.406553 -0.9146633 0.02609395 0.4033735 -0.7845349 0.1739307 -0.5951918 -0.8836023 0.02630782 0.4674986 -0.7827257 0.1738373 -0.5975962 -0.8383634 0.02658224 0.5444632 -0.8430191 0.02606296 0.5372519 -0.7801617 0.1736846 -0.6009837 -0.7940546 0.02633821 0.6072756 -0.7692586 0.1731945 -0.6150162 -0.742919 0.02667337 0.6688498 -0.7294173 0.02594161 0.683577 -0.7589495 0.1725551 -0.6278699 -0.6290293 0.02664315 0.7769249 -0.6494507 0.02594137 0.7599611 -0.7238913 0.1713973 -0.6682848 -0.7606914 0.17164 -0.6260101 -0.4997509 0.02639901 0.8657668 -0.548093 0.02609384 0.8360104 -0.7628313 0.1699012 -0.6238766 -0.3582918 0.02636831 0.9332372 -0.4138118 0.02584987 0.9099954 -0.7641433 0.1682531 -0.6227167 -0.2082017 0.02703994 0.9777121 -0.2270299 0.02438455 0.9735826 -0.6854968 0.3747175 -0.6242444 -0.7579042 0.2542217 -0.6007934 -0.704728 0.2763244 -0.653455 -0.7479479 0.2964385 -0.5938841 -0.05249339 0.02795577 0.99823 -0.08243179 0.02581906 0.9962623 -0.6699666 0.1738092 -0.7217584 -0.6383659 0.1728901 -0.7500654 -0.6026345 0.375235 -0.7042943 -0.6214057 0.2760176 -0.7332594 -0.7218693 0.1736234 -0.6698952 -0.5552769 0.1731387 -0.8134437 -0.5433954 0.172861 -0.8214868 -0.5112572 0.3753858 -0.7731117 -0.5291994 0.275495 -0.8025276 -0.6135859 0.1732262 -0.7703928 -0.4923912 0.173927 -0.852819 -0.4398754 0.172648 -0.8813073 -0.4303833 0.2754977 -0.8595762 -0.3600969 0.1736242 -0.916616 -0.3299692 0.1731026 -0.9279848 -0.4138982 0.3753833 -0.8293225 -0.3243299 0.2760176 -0.9047787 -0.4270571 0.1735634 -0.8874108 -0.2198274 0.1727368 -0.9601239 -0.2170495 0.1718512 -0.9609145 -0.3086124 0.3752363 -0.8740459 -0.2135387 0.2763156 -0.9370437 -0.289507 0.1728923 -0.9414318 -0.1588803 0.1698976 -0.9725698 -0.1572033 0.1682512 -0.9731284 -0.1978272 0.3747181 -0.9057874 -0.1413325 0.2542214 -0.9567638 -0.1617811 0.1716387 -0.9717855 -0.1648033 0.1727077 -0.971088 -0.1641322 0.1726471 -0.9712125 -0.1470707 0.174141 -0.9736761 0.9508332 0.02704018 0.308521 0.9566084 0.02438443 0.2903548 0.9949228 0.02584964 0.09726434 -0.1403268 0.2964321 -0.9446886 0.8905523 0.02722316 0.4540657 0.9039723 0.02636837 0.4267774 0.9873585 0.02639913 0.156289 0.9980981 0.02609384 -0.05585002 0.9996507 0.02642947 6.1038e-5 0.9830164 0.02591061 -0.1816795 0.9873513 0.02667361 -0.1562879 0.9568988 0.02594131 -0.2892609 -0.1303489 0.1736866 -0.9761364 0.950689 0.02661228 -0.3090021 0.9228153 0.0264908 -0.3843309 -0.1262288 0.1738088 -0.976656 0.8870693 0.02606332 -0.4609 -0.1232672 0.1739292 -0.9770128 0.8907008 0.02646005 -0.4538195 0.8460376 0.02661222 -0.5324587 -0.1204285 0.1740506 -0.9773451 0.8069847 0.02612429 -0.5899943 -0.1526852 0.1764898 -0.9723881 0.8087531 0.02649044 -0.5875515 0.7646162 0.02639865 -0.6439452 -0.1262591 0.1753344 -0.9763793 0.7243742 0.02615493 -0.6889109 -0.1129518 0.1747533 -0.9781121 0.7068434 0.02649021 -0.706874 0.6832578 0.02618521 -0.7297076 -0.1036436 0.1743569 -0.9792129 0.6415364 0.02655136 -0.766633 -0.09613496 0.1740806 -0.9800276 0.6032755 0.02615505 -0.7971038 -0.08957499 0.1738702 -0.9806863 0.5875189 0.02636826 -0.8087807 0.5640657 0.02618592 -0.8253147 -0.08359068 0.1737429 -0.9812371 0.5248641 0.02642935 -0.8507755 -0.07809817 0.1736532 -0.9817053 0.4858931 0.0268262 -0.8736065 -0.07328784 0.1736401 -0.9820784 0.4511935 0.02621585 -0.892041 0.4538217 0.02627706 -0.8907051 0.414665 0.02624654 -0.9095956 0.3783743 0.02645993 -0.9252746 0.3424608 0.02679622 -0.93915 0.3094642 0.02621591 -0.9505497 0.3089128 0.02630728 -0.9507265 0.2748242 0.02621585 -0.9611371 0.2400952 0.02636861 -0.9703912 0.2052113 0.02664327 -0.9783551 0.1713955 0.02624642 -0.9848527 0.1365131 0.02618557 -0.9902922 0.1009257 0.02627664 -0.9945469 0.06561642 0.02652126 -0.9974924 0 1 -2.78484e-6 0 1 -2.80769e-6 0 1 2.87797e-6 0 1 -2.8196e-6 0 1 5.18145e-7 0 1 7.98783e-7 0 1 9.36554e-7 0 1 -1.00213e-6 0 1 -7.02416e-7 0 1 1.56504e-6 -0.6140754 0.1745999 0.7696924 -0.5880744 0.1719146 0.7903252 -0.5538989 0.1731373 0.814383 -0.4843426 0.1704508 0.8581136 -0.4933395 0.1731647 0.852426 -0.4269962 0.1738687 0.8873805 -0.3677549 0.1714257 0.9139856 -0.3577447 0.1707543 0.9180751 -0.2494636 0.1719754 0.9529913 -0.2931383 0.17042 0.9407588 0 1 -5.09709e-6 -0.2177251 0.1727701 0.9605969 0 1 5.94659e-6 -0.1482606 0.1727978 0.973735 -6.46178e-6 0 1 6.59248e-6 0 1 -0.2588022 0 0.9659304 -0.3826816 0 0.9238803 -0.4999893 0 0.8660317 -0.6087679 0 0.7933484 -0.7071068 0 0.7071068 -0.7933484 0 0.6087679 -0.8660317 0 0.4999893 -0.9238803 0 0.3826816 -0.9659304 0 0.2588022 -0.9914484 0 0.1305003 -1 0 0 -0.9914484 0 -0.1305003 -0.9914444 0 -0.1305303 -0.9659304 0 -0.2588022 -0.9238803 0 -0.3826816 -0.8660317 0 -0.4999893 -0.7933484 0 -0.6087679 -0.7071068 0 -0.7071068 -0.6087679 0 -0.7933484 -0.4999893 0 -0.8660317 -0.3826816 0 -0.9238803 -0.2588022 0 -0.9659304 -0.1709656 0.7234453 -0.6688779 -0.1616282 0.7867778 -0.5956988 -0.03448724 0.7272236 -0.6855337 -0.08429366 0.7238516 -0.6847872 -0.2536134 0.7230575 -0.6425483 -0.2387837 0.7868816 -0.5690342 -0.3325426 0.7224928 -0.6061517 -0.3112981 0.7871876 -0.5323809 -0.4064928 0.7217926 -0.5601599 -0.3780112 0.7876099 -0.4865987 -0.4742434 0.7210245 -0.5051902 -0.43786 0.7880992 -0.4326412 -0.5346075 0.7203482 -0.4419202 -0.4899293 0.788593 -0.3716052 -0.582585 0.7258737 -0.365653 -0.5335311 0.7890353 -0.3045784 -0.627996 0.7197982 -0.2958238 -0.5680521 0.7894072 -0.2327082 -0.6617485 0.7184532 -0.2142755 -0.5930258 0.7896938 -0.1571757 -0.6835972 0.7182363 -0.1297366 -0.6081511 0.7898609 -0.07919663 -0.6943979 0.7182943 -0.04318428 -0.6131945 0.789932 0 -0.6943979 0.7182943 0.04318428 -0.6081318 0.7898755 0.07919812 -0.6835972 0.7182363 0.1297366 -0.5930258 0.7896938 0.1571757 -0.6617485 0.7184532 0.2142755 -0.5680521 0.7894072 0.2327082 -0.6280638 0.7197753 0.2957354 -0.5335311 0.7890353 0.3045784 -0.5774522 0.7285523 0.3684573 -0.4899293 0.788593 0.3716052 -0.5350053 0.7202581 0.4415854 -0.43786 0.7880992 0.4326412 -0.4744238 0.7207151 0.505462 -0.3780112 0.7876099 0.4865987 -0.4067925 0.7214165 0.5604269 -0.3112981 0.7871876 0.5323809 -0.3329637 0.722052 0.6064455 -0.2387837 0.7868816 0.5690342 -0.2541956 0.7225762 0.6428596 -0.1616282 0.7867778 0.5956988 -0.1716687 0.7229924 0.6691876 2.20938e-5 0 1 0.6578044 0.276135 0.7007445 0 0.9659263 0.2588176 7.87392e-7 0 1 8.54534e-4 0.02636843 -0.999652 0.6237149 0.5607849 0.5445184 0.7152436 0.4479581 0.5364328 -0.1048944 0.0275588 -0.9941015 -0.095739 0.02542257 -0.9950819 0.5895965 0.3942749 0.7049278 0.5477608 0.5600907 0.6214955 0.5801628 0.2824822 0.7639471 0.4899893 0.4587984 0.7412251 0.4639568 0.5594216 0.6868709 0 0.9659258 0.2588194 0.4465568 0.4569638 0.7692667 -7.10621e-7 0.9659256 0.2588202 -1.26973e-7 0.9659255 0.2588203 0.3622952 0.5770599 0.7319456 0.3500568 0.4829074 0.8026585 1.92327e-7 0.9659261 0.2588184 0.6851633 0.5051592 0.5247527 -0.2580069 0.02789425 -0.9657403 -0.2347839 0.02484256 -0.9717301 0.6457004 0.6108471 0.4581887 -0.3343431 0.02639949 -0.9420816 0.6702863 0.6933281 0.2645987 -0.4065106 0.02905386 -0.913184 -0.4478018 0.02313321 -0.8938336 0.2644449 0.5986862 0.7560713 0.2455865 0.4782635 0.8431794 0.1566555 0.6333363 0.7578551 -1.27173e-7 0.9659261 0.2588181 0.0618931 0.6414542 0.7646605 -2.81333e-7 0.9659258 0.2588196 1.55574e-7 0.9659259 0.2588192 0.04559636 0.6507101 0.7579562 0 0.9659258 0.2588197 0.6382579 0.6781777 0.3642828 -0.544283 0.02905446 -0.8383985 -0.6039251 0.02157747 -0.796749 0.6597001 0.65323 0.3716001 -0.6690979 0.02874886 -0.742618 -0.7496407 0.02224838 -0.6614711 0.4454559 -0.8000566 0.4018442 -0.7774193 0.02722322 -0.6283934 -0.8156729 0.0230416 -0.5780544 0.6856533 0.6238511 0.3750858 -0.9034844 0.02252298 -0.4280289 -0.9093627 0.02603322 -0.4151889 -0.9473754 0.02349972 -0.3192608 -0.823838 0.02609395 -0.5662246 0.6706067 0.6486326 0.3599479 -0.9776766 0.02874886 -0.2081396 -0.9919674 0.02157711 -0.1246406 -0.9324881 0.02533102 -0.3603114 0.6739518 0.6330257 0.3808775 -0.9982162 0.0290541 -0.05215698 -0.9979849 0.02313369 0.05908554 0.7176609 0.6087986 0.3381231 -0.9940761 0.02856606 0.1048644 -0.9822278 0.02942043 0.1853732 0.7824793 0.5610632 0.2700635 0.7974274 0.5048431 0.3305193 -0.9590057 0.02578872 0.2822113 0.8116623 0.5607627 0.1635532 0.8503603 0.3918073 0.3512471 0.8225766 0.4477126 0.3506014 0.8261312 0.5608561 0.0542941 0.8261312 0.5608561 -0.0542941 0.8116623 0.5607627 -0.1635532 0.7824793 0.5610632 -0.2700635 0.7176609 0.6087986 -0.3381231 0.7974274 0.5048431 -0.3305193 0.8503603 0.3918073 -0.3512471 0.8225766 0.4477126 -0.3506014 0.6739518 0.6330257 -0.3808775 -0.9940975 0.0290541 -0.1045278 -0.9830431 0.02639877 -0.1814652 -0.9979849 0.02313369 -0.05908554 -0.9653629 0.02789479 -0.2594159 -0.9589411 0.02484256 -0.2825154 0.6706067 0.6486326 -0.3599479 -0.9982162 0.0290541 0.05215698 -0.9919674 0.02157711 0.1246406 0.6857993 0.623601 -0.3752349 -0.9776766 0.02874886 0.2081396 -0.9476828 0.0222485 0.3184375 0.6831843 0.6245864 -0.3783531 -0.9329171 0.02722328 0.3590608 -0.9084556 0.02304172 0.4173457 0.6326637 0.6784425 -0.3734333 -0.8224306 0.0225231 0.5684195 -0.814253 0.02603286 0.5799263 -0.7501641 0.02349984 0.6608341 0.6382447 0.6781941 -0.3642753 -0.6690979 0.02874886 0.742618 -0.6039251 0.02157747 0.796749 -0.7782995 0.0253309 0.6273822 0.6402654 0.6343752 -0.4331611 -0.544283 0.02905446 0.8383985 -0.4478018 0.02313321 0.8938336 0.6672426 0.5735484 -0.4752154 -0.4062049 0.02856552 0.9133354 -0.3305839 0.02942049 0.943318 0.6228965 0.560027 -0.5462324 0.684947 0.5048519 -0.5253305 -0.2350873 0.025819 0.9716313 0.5455363 0.5592702 -0.6241852 0.729382 0.3918074 -0.5607931 0.7149235 0.4477237 -0.5370548 0.4588041 0.5591531 -0.6905409 0.365072 0.5587781 -0.7446407 0.2643621 0.5581147 -0.7865245 0.1584857 0.5581946 -0.814433 0.06720381 0.5920162 -0.8031193 0.1124331 0.5048505 -0.8558532 0.1209774 0.3918031 -0.9120608 0.1076404 0.4477133 -0.8876748 0.03827089 0.6110222 -0.7906879 -0.5875877 0.02905434 0.8086388 -0.6486852 0.02639907 0.760599 -0.5501705 0.02313357 0.8347319 -0.7073503 0.02789479 0.7063126 -0.72413 0.02484261 0.689216 0.04416179 0.6394457 -0.7675669 -0.4539088 0.02905404 0.8905745 -0.3880185 0.02157688 0.9213991 0.02993929 0.7143936 -0.6991034 -0.004059016 0.7047472 -0.709447 -0.3085519 0.02874934 0.9507731 -0.1980685 0.02224832 0.9799357 0.00250256 0.6990787 -0.7150404 -0.1554926 0.02722263 0.9874619 -0.09277892 0.02304208 0.9954201 -0.04348927 0.6804474 -0.7315054 -0.03274691 0.5383558 -0.8420812 0.08105921 0.02252322 0.9964548 0.0950967 0.02603256 0.9951277 0.1972121 0.02349942 0.9800791 -0.07843464 0.02609401 0.9965777 -0.06729525 0.647225 0.7593228 -0.04138404 0.6897035 0.7229084 -0.03628724 0.6560397 0.7538536 -3.54392e-7 0.9659255 0.2588201 -0.8653092 0.02636849 -0.5005444 -0.9133777 0.0275588 -0.4061796 -0.9096317 0.02542269 -0.414637 -0.9132053 0.02688765 0.4066116 -0.8600273 0.03054958 0.5093327 -0.9096317 0.02542269 0.414637 -0.965469 0.02737551 0.2590759 -0.8661572 0.02636831 0.4990757 -0.8084645 0.02755916 0.5878993 -0.8138971 0.02542281 0.5804526 -0.1044372 0.02688753 0.9941681 0.01110893 0.03054964 0.9994716 -0.09570878 0.02542263 0.9950847 -0.2583467 0.02737587 0.9656643 -0.1566555 0.6333363 0.7578551 -0.2644449 0.5986862 0.7560713 -0.3625102 0.5771535 0.7317652 -0.4629156 0.5600278 0.6870794 -0.5477608 0.5600907 0.6214955 -0.6237149 0.5607849 0.5445184 -0.6402654 0.6343752 0.4331611 -0.6673969 0.5735195 0.4750335 -0.6857993 0.623601 0.3752349 -0.6831713 0.624605 0.3783459 -0.6326637 0.6784425 0.3734333 -0.6382447 0.6781941 0.3642753 -0.7824793 0.5610632 0.2700635 -0.7176609 0.6087986 0.3381231 -0.6739518 0.6330257 0.3808775 -0.6706067 0.6486326 0.3599479 -0.8116623 0.5607627 0.1635532 -0.8261312 0.5608561 0.0542941 -0.8261312 0.5608561 -0.0542941 -0.8116623 0.5607627 -0.1635532 -0.7824793 0.5610632 -0.2700635 -0.6597001 0.65323 -0.3716001 -0.4454667 -0.8000455 -0.4018539 -0.6856533 0.6238511 -0.3750858 -0.6706067 0.6486326 -0.3599479 -0.6739518 0.6330257 -0.3808775 -0.7176609 0.6087986 -0.3381231 -0.6455421 0.6109029 -0.4583373 -0.6702863 0.6933281 -0.2645987 -0.6382579 0.6781777 -0.3642828 -0.6228965 0.560027 -0.5462324 -0.5455363 0.5592702 -0.6241852 -0.4588041 0.5591531 -0.6905409 -0.365072 0.5587781 -0.7446407 -0.2643621 0.5581147 -0.7865245 -0.1584857 0.5581946 -0.814433 -0.04233002 0.6183792 -0.7847391 -0.03827089 0.6110222 -0.7906879 -0.06720215 0.5920017 -0.8031301 0.3085516 0.0287798 0.9507722 0.3880185 0.02157688 0.9213991 0.1541821 0.02533078 0.9877178 0.4539088 0.02905404 0.8905745 0.5501705 0.02313357 0.8347319 0.5878627 0.02856606 0.8084563 0.65165 0.02942067 0.7579491 -0.112465 0.5048261 -0.8558635 0.7239191 0.02581936 0.6894017 -0.1209774 0.3918031 -0.9120608 -0.1076404 0.4477133 -0.8876748 -0.684947 0.5048519 -0.5253305 -0.729382 0.3918074 -0.5607931 -0.7149235 0.4477237 -0.5370548 0.4065106 0.02905386 0.913184 0.3343431 0.02639949 0.9420816 0.4478018 0.02313321 0.8938336 0.2580069 0.02789425 0.9657403 0.2347839 0.02484256 0.9717301 0.544283 0.02905446 0.8383985 0.6039251 0.02157747 0.796749 0.6690979 0.02874886 0.742618 0.7496407 0.02224838 0.6614711 0.7774193 0.02722322 0.6283934 0.8156729 0.0230416 0.5780544 0.9034844 0.02252298 0.4280289 0.9093627 0.02603322 0.4151889 0.9473754 0.02349972 0.3192608 0.823838 0.02609395 0.5662246 0.9776766 0.02874886 0.2081396 0.9919674 0.02157711 0.1246406 0.9324881 0.02533102 0.3603114 0.9982162 0.0290541 0.05215698 0.9979849 0.02313369 -0.05908554 0.9940761 0.02856606 -0.1048644 0.9822278 0.02942043 -0.1853732 -0.7974274 0.5048431 -0.3305193 0.9590057 0.02578872 -0.2822113 -0.8503603 0.3918073 -0.3512471 -0.8225766 0.4477126 -0.3506014 -0.7974274 0.5048431 0.3305193 -0.8503603 0.3918073 0.3512471 -0.8225766 0.4477126 0.3506014 0.9940975 0.0290541 0.1045278 0.9830431 0.02639877 0.1814652 0.9979849 0.02313369 0.05908554 0.9653629 0.02789479 0.2594159 0.9589411 0.02484256 0.2825154 0.9982162 0.0290541 -0.05215698 0.9919674 0.02157711 -0.1246406 0.9776766 0.02874886 -0.2081396 0.9476828 0.0222485 -0.3184375 0.9329171 0.02722328 -0.3590608 0.9084556 0.02304172 -0.4173457 0.8224306 0.0225231 -0.5684195 0.814253 0.02603286 -0.5799263 0.7501641 0.02349984 -0.6608341 0.6690979 0.02874886 -0.742618 0.6039251 0.02157747 -0.796749 0.7782995 0.0253309 -0.6273822 0.544283 0.02905446 -0.8383985 0.4478018 0.02313321 -0.8938336 0.4062049 0.02856552 -0.9133354 0.3305839 0.02942049 -0.943318 -0.6851366 0.5051925 0.5247556 0.2350873 0.025819 -0.9716313 -0.7152436 0.4479581 0.5364328 -0.7287313 0.3925041 0.5611518 -0.589513 0.3942192 0.705029 -0.48663 0.451777 0.7477225 -0.3500568 0.4829074 0.8026585 -0.4745821 0.4114978 0.7781011 -0.24559 0.4782399 0.8431916 1.11208e-6 0.965927 0.2588151 -4.99875e-7 0.9659252 0.2588216 -1.1817e-6 0.9659257 0.2588199 0.2583467 0.02737587 -0.9656643 0.09570878 0.02542263 -0.9950847 0.1044372 0.02688753 -0.9941681 -0.01110893 0.03054964 -0.9994716 -0.5801425 0.2824872 0.7639607 -0.6557418 0.2792839 0.7014295 8.79029e-6 0.9659267 0.2588158 -2.98354e-6 0.9659267 0.258816 3.68322e-7 0.9659256 0.25882 -3.20171e-5 0.965924 0.2588263 -8.54534e-4 0.02636843 0.999652 0.1048944 0.0275588 0.9941015 0.095739 0.02542257 0.9950819 0.808759 0.02688741 0.5875253 0.8711223 0.03055012 0.4901151 0.8138971 0.02542281 0.5804526 0.7071164 0.02737516 0.7065671 0.8653092 0.02636849 0.5005444 0.9133777 0.0275588 0.4061796 0.9096317 0.02542269 0.414637 0.9132053 0.02688765 -0.4066116 0.8600273 0.03054958 -0.5093327 0.9096317 0.02542269 -0.414637 0.965469 0.02737551 -0.2590759 -0.1441406 0.02258396 -0.9892995 -0.0784654 0 -0.9969169 -0.1846684 0.07147467 -0.9801984 0.3148976 0.01141417 -0.9490571 0.1272324 0.07147479 -0.9892944 0.1243641 0.04281789 -0.9913125 0.1564405 0 -0.9876874 -0.286881 0.02151602 -0.9577246 -0.3030567 0.01141417 -0.9529042 -0.4785338 0.07147485 -0.8751553 -0.5687798 0.02151578 -0.8222084 -0.5827034 0.01141417 -0.8126047 -0.7255532 0.0714749 -0.6844444 -0.7950213 0.0215159 -0.6061999 -0.8052957 0.01141393 -0.5927637 -0.9015519 0.07147711 -0.4267264 -0.9434451 0.02151614 -0.3308299 -0.9490571 0.01141417 -0.3148976 -0.9892944 0.07147479 -0.1272324 -0.9995016 0.02151596 -0.02310293 -0.9999157 0.01141399 -0.006195247 -0.9801984 0.07147467 0.1846684 -0.9577246 0.02151602 0.286881 -0.9529042 0.01141417 0.3030567 -0.8751553 0.07147485 0.4785338 -0.8222084 0.02151578 0.5687798 -0.8126047 0.01141417 0.5827034 -0.6844444 0.0714749 0.7255532 -0.6061999 0.0215159 0.7950213 -0.5927637 0.01141393 0.8052957 -0.4267264 0.07147711 0.9015519 -0.3308299 0.02151614 0.9434451 -0.3148976 0.01141417 0.9490571 -0.1272324 0.07147479 0.9892944 -0.1243641 0.04281789 0.9913125 0.1441406 0.02258396 0.9892995 0.07843506 0 0.9969193 0.1846684 0.07147467 0.9801984 -0.1564108 0 0.9876922 0.286881 0.02151602 0.9577246 0.3030567 0.01141417 0.9529042 0.4785338 0.07147485 0.8751553 0.5687798 0.02151578 0.8222084 0.5827034 0.01141417 0.8126047 0.7255532 0.0714749 0.6844444 0.7950213 0.0215159 0.6061999 0.8052849 0.01141422 0.5927783 0.9015519 0.07147711 0.4267264 0.9434451 0.02151614 0.3308299 0.9490571 0.01141417 0.3148976 0.9892944 0.07147479 0.1272324 0.9995016 0.02151596 0.02310293 0.9999157 0.01141399 0.006195247 0.9801984 0.07147467 -0.1846684 0.9577246 0.02151602 -0.286881 0.9529042 0.01141417 -0.3030567 0.8751553 0.07147485 -0.4785338 0.8222084 0.02151578 -0.5687798 0.8126047 0.01141417 -0.5827034 0.6844444 0.0714749 -0.7255532 0.6061999 0.0215159 -0.7950213 0.5927637 0.01141393 -0.8052957 0.4267146 0.07147514 -0.9015575 0.3308299 0.02151614 -0.9434451 -0.9288343 0.02258449 -0.3698063 -0.9025918 0 -0.4304974 -0.9412156 0.07147622 -0.3301579 -0.6644645 0.01141417 -0.7472327 -0.7931234 0.07147508 -0.6048527 -0.7963122 0.04281866 -0.6033685 -0.7771361 0 -0.6293326 -0.9728538 0.02151584 -0.2304183 -0.9767733 0.01141422 -0.2139714 -0.9971742 0.0714752 -0.02313327 -0.9964423 0.02151578 0.08148545 -0.9950884 0.01141393 0.09833079 -0.9555251 0.07147592 0.2861173 -0.9225008 0.02151596 0.3853952 -0.9159982 0.01141411 0.4010201 -0.8203397 0.07147717 0.5673922 -0.7582466 0.0215159 0.6516129 -0.7472327 0.01141417 0.6644645 -0.6048527 0.07147508 0.7931234 -0.5197656 0.02151572 0.854038 -0.5053403 0.01141422 0.8628447 -0.3301579 0.07147622 0.9412158 -0.2304183 0.02151584 0.9728538 -0.2139714 0.01141422 0.9767733 -0.02313327 0.0714752 0.9971742 0.08148545 0.02151578 0.9964423 0.09833079 0.01141393 0.9950884 0.2861173 0.07147592 0.9555251 0.3853952 0.02151596 0.9225008 0.4010201 0.01141411 0.9159982 0.5673922 0.07147717 0.8203397 0.6516129 0.0215159 0.7582466 0.6644645 0.01141417 0.7472327 0.7931234 0.07147508 0.6048527 0.7963122 0.04281866 0.6033685 0.9288343 0.02258449 0.3698063 0.9025918 0 0.4304974 0.9412156 0.07147622 0.3301579 0.7771511 0 0.6293141 0.9728538 0.02151584 0.2304183 0.9767733 0.01141422 0.2139714 0.9971742 0.0714752 0.02313327 0.9964423 0.02151578 -0.08148545 0.9950884 0.01141393 -0.09833079 0.9555251 0.07147592 -0.2861173 0.92249 0.02151566 -0.3854212 0.9159982 0.01141411 -0.4010201 0.8203496 0.07147538 -0.567378 0.7582466 0.0215159 -0.6516129 0.7472327 0.01141417 -0.6644645 0.6048527 0.07147508 -0.7931234 0.5197656 0.02151572 -0.854038 0.5053403 0.01141422 -0.8628447 0.3301579 0.07147622 -0.9412158 0.2304183 0.02151584 -0.9728538 0.2139714 0.01141422 -0.9767733 0.02313327 0.0714752 -0.9971742 -0.08148545 0.02151578 -0.9964423 -0.09833079 0.01141393 -0.9950884 -0.2861173 0.07147592 -0.9555251 -0.3853952 0.02151596 -0.9225008 -0.4010201 0.01141411 -0.9159982 -0.5673922 0.07147717 -0.8203397 -0.6516129 0.0215159 -0.7582466 -0.784685 0.02258437 0.6194833 -0.824131 0 0.5663993 -0.7565407 0.07147598 0.6500287 -0.9793617 0.01141417 0.201793 -0.9203888 0.0714752 0.384416 -0.9206953 0.04281806 0.3879262 -0.9335846 0 0.3583573 -0.6859797 0.02151602 0.7273026 -0.6736993 0.01141393 0.7389176 -0.5186403 0.07147556 0.8519997 -0.4276317 0.02151584 0.903697 -0.4123775 0.01141422 0.9109417 -0.2299621 0.07147592 0.9705713 -0.1274459 0.0215156 0.9916121 -0.1106923 0.01141405 0.9937893 0.08121144 0.0714758 0.9941308 0.1851892 0.02151584 0.9824673 0.201793 0.01141417 0.9793617 0.384416 0.0714752 0.9203888 0.479731 0.02151602 0.8771519 0.4945644 0.01141417 0.8690661 0.6500287 0.07147598 0.7565407 0.7273026 0.02151602 0.6859797 0.7389176 0.01141393 0.6736993 0.8519997 0.07147556 0.5186403 0.903697 0.02151584 0.4276317 0.9109417 0.01141422 0.4123775 0.9705713 0.07147592 0.2299621 0.9916121 0.0215156 0.1274459 0.9937893 0.01141405 0.1106923 0.9941308 0.0714758 -0.08121144 0.9824674 0.02151584 -0.1851892 0.9793617 0.01141417 -0.201793 0.9203888 0.0714752 -0.384416 0.9206953 0.04281806 -0.3879262 0.784685 0.02258437 -0.6194833 0.824131 0 -0.5663993 0.7565407 0.07147598 -0.6500287 0.9335846 0 -0.3583573 0.6859797 0.02151602 -0.7273026 0.6736993 0.01141393 -0.7389176 0.5186403 0.07147556 -0.8519997 0.4276317 0.02151584 -0.903697 0.4123775 0.01141422 -0.9109417 0.2299621 0.07147592 -0.9705713 0.1274459 0.0215156 -0.9916121 0.1106923 0.01141405 -0.9937893 -0.08121144 0.0714758 -0.9941308 -0.1851892 0.02151584 -0.9824673 -0.201793 0.01141417 -0.9793617 -0.384416 0.0714752 -0.9203888 -0.479731 0.02151602 -0.8771519 -0.4945644 0.01141417 -0.8690661 -0.6500287 0.07147598 -0.7565407 -0.7273026 0.02151602 -0.6859797 -0.7389176 0.01141393 -0.6736993 -0.8519997 0.07147556 -0.5186403 -0.903697 0.02151584 -0.4276317 -0.9109417 0.01141422 -0.4123775 -0.9705713 0.07147592 -0.2299621 -0.9916121 0.0215156 -0.1274459 -0.9937893 0.01141405 -0.1106923 -0.9941308 0.0714758 0.08121144 -0.9824674 0.02151584 0.1851892 0.7771361 0 0.6293326 0.9225008 0.02151596 -0.3853952 0.8203397 0.07147717 -0.5673922 -0.7771511 0 -0.6293141 -0.92249 0.02151566 0.3854212 -0.8203496 0.07147538 0.567378 -0.1736861 0 0.9848011 -0.1736513 0 0.9848073 -0.3420028 0 0.9396989 0.3420935 0 0.939666 0.3420028 0 0.9396989 0.1736513 0 0.9848073 0.1736861 0 0.9848011 -0.3420935 0 0.939666 -0.6427834 0 0.7660481 -0.6428821 0 0.7659652 -0.8660789 0 0.4999074 -0.9848124 0 0.1736217 -0.9848178 0 0.1735921 -0.9848124 0 -0.1736217 -0.9848178 0 -0.1735921 -0.8660789 0 -0.4999074 -0.6427834 0 -0.7660481 -0.6428821 0 -0.7659652 -0.3420028 0 -0.9396989 -0.3420935 0 -0.939666 -0.1736513 0 -0.9848073 0.1736861 0 -0.9848011 0.1736513 0 -0.9848073 0.3420028 0 -0.9396989 -0.1736861 0 -0.9848011 0.3420935 0 -0.939666 0.6427834 0 -0.7660481 0.6428821 0 -0.7659652 0.8660789 0 -0.4999074 0.9848124 0 -0.1736217 0.9848178 0 -0.1735921 0.9848124 0 0.1736217 0.9848178 0 0.1735921 0.8660657 0 0.4999303 0.6427984 0 0.7660355 0.6428821 0 0.7659652 0.7660204 0 0.6428163 0.7660355 0 0.6427984 0.6427834 0 0.7660481 0.9848229 0 0.1735625 0.9396989 0 0.3420028 0.9397124 0 0.341966 0.6427325 0 0.7660908 0.3419024 0 0.9397356 -6.1037e-5 0 1 -0.3420298 0 0.9396891 -0.3420567 0 0.9396793 -0.6427984 0 0.7660355 -0.6427654 0 0.7660631 -0.8659768 0 0.5000844 -0.9847906 0 0.1737453 -0.9848229 0 -0.1735625 -0.9396989 0 -0.3420028 -0.7660204 0 -0.6428163 -0.7660355 0 -0.6427984 -0.6427984 0 -0.7660355 -0.9397124 0 -0.341966 -0.6427325 0 -0.7660908 -0.3419024 0 -0.9397356 0 0 -1 6.1037e-5 0 -1 0.3420298 0 -0.9396891 0.3420567 0 -0.9396793 0.6427984 0 -0.7660355 0.6427654 0 -0.7660631 0.8659768 0 -0.5000844 0.9847906 0 -0.1737453 0.9397124 0 -0.341966 0.9396891 0 -0.3420298 0.9848073 0 -0.1736513 0.6427325 0 -0.7660908 0.7660355 0 -0.6427984 0.7660204 0 -0.6428163 0.9848229 0 -0.1735625 0.9848073 0 0.1736513 0.9847906 0 0.1737453 0.866024 0 0.5000025 0.8659768 0 0.5000844 0.6427654 0 0.7660631 0.3420567 0 0.9396793 6.1037e-5 0 1 -0.3419024 0 0.9397356 -0.6427325 0 0.7660908 -0.7660355 0 0.6427984 -0.9397124 0 0.341966 -0.9396891 0 0.3420298 -0.9848073 0 0.1736513 -0.7660204 0 0.6428163 -0.9848229 0 0.1735625 -0.9848073 0 -0.1736513 -0.9847906 0 -0.1737453 -0.866024 0 -0.5000025 -0.8659768 0 -0.5000844 -0.6427654 0 -0.7660631 -0.3420298 0 -0.9396891 -6.1037e-5 0 -1 0.3419024 0 -0.9397356 -0.3420567 0 -0.9396793 0.3420298 0 0.9396891 0.1736217 0 -0.9848124 -0.1736217 0 -0.9848124 -0.1736217 0 0.9848124 0.1736217 0 0.9848124 0.193856 0 -0.98103 0.3716012 0 -0.9283925 0.4033133 0 -0.915062 0.2106732 0 -0.9775565 0.6831377 0 -0.7302896 0.9015551 0 -0.4326646 0.9971013 0 -0.07608503 0.95677 0 0.2908459 0.7860229 0 0.6181976 0.6584138 0 0.7526561 0.6712498 0 0.7412313 0.8068037 0 0.5908198 0.9744879 0 0.2244404 0.9997232 0 0.02353042 0.9898572 0 -0.1420665 0.9944092 0 -0.1055966 0.9994797 0 -0.03225898 0.999151 0 0.04120022 0.9934259 0 0.114477 0.9823322 0 0.1871457 0.9443114 0 0.3290533 0.9175846 0 0.3975406 0.8859087 0 0.4638599 0.849444 0 0.5276789 0.8083876 0 0.5886507 0.7861965 0 0.6179765 0.877549 0 0.4794871 0.9561558 0 0.2928589 0.9941237 0 -0.1082506 0.9519397 0 -0.3062858 0.9465285 0 -0.3226205 0.9898136 0 -0.1423698 0.9740222 0 0.2264529 0.8254854 0 0.5644235 0.5644586 0 0.8254615 0.2264818 0 0.9740154 -0.1423399 0 0.9898179 -0.3226205 0 0.9465285 -0.3062858 0 0.9519397 -0.1082506 0 0.9941237 0.2928589 0 0.9561558 0.4794871 0 0.877549 0.6179765 0 0.7861965 0.5886507 0 0.8083876 0.5277009 0 0.8494303 0.4638599 0 0.8859087 0.3975406 0 0.9175846 0.3290627 0 0.9443081 0.1871752 0 0.9823266 0.1145071 0 0.9934225 0.04120022 0 0.999151 -0.03225898 0 0.9994797 -0.1055966 0 0.9944092 -0.1420665 0 0.9898572 0.02353042 0 0.9997232 0.2244404 0 0.9744879 0.5908198 0 0.8068037 0.7412313 0 0.6712498 0.7526713 0 0.6583966 0.6181976 0 0.7860229 0.2908738 0 0.9567614 -0.07605236 0 0.9971039 -0.4326398 0 0.9015669 -0.7302754 0 0.683153 -0.9283925 0 0.3716012 -0.928382 0 0.3716275 -0.98103 0 0.193856 -0.9775565 0 0.2106732 -0.9150782 0 0.4032765 -0.915062 0 0.4033133 -0.681622 0 0.7317045 -0.5202335 0 0.8540241 -0.37188 0 0.9282808 -0.4057505 0 0.9139839 -0.4717632 0 0.8817254 -0.535275 0 0.8446779 -0.5958806 0 0.8030731 -0.6532535 0 0.7571393 -0.7571393 0 0.6532535 -0.8030731 0 0.5958806 -0.8030877 0 0.5958609 -0.8446779 0 0.535275 -0.8817254 0 0.4717632 -0.9139953 0 0.405725 -0.9282808 0 0.37188 -0.8540241 0 0.5202335 -0.7317045 0 0.681622 -0.4033133 0 0.915062 -0.2106732 0 0.9775565 -0.193856 0 0.98103 -0.3716012 0 0.9283925 -0.6831377 0 0.7302896 -0.9015551 0 0.4326646 -0.9971013 0 0.07608503 -0.95677 0 -0.2908459 -0.7860229 0 -0.6181976 -0.6584138 0 -0.7526561 -0.6712498 0 -0.7412313 -0.8068037 0 -0.5908198 -0.9744879 0 -0.2244404 -0.9997232 0 -0.02353042 -0.9898572 0 0.1420665 -0.9944092 0 0.1055966 -0.9994797 0 0.03225898 -0.999151 0 -0.04120022 -0.9934259 0 -0.114477 -0.9823322 0 -0.1871457 -0.9443114 0 -0.3290533 -0.9175846 0 -0.3975406 -0.8859087 0 -0.4638599 -0.8494303 0 -0.5277009 -0.8083876 0 -0.5886507 -0.7861965 0 -0.6179765 -0.877549 0 -0.4794871 -0.9561558 0 -0.2928589 -0.9941237 0 0.1082506 -0.9519397 0 0.3062858 -0.9465285 0 0.3226205 -0.9898136 0 0.1423698 -0.9740222 0 -0.2264529 -0.8254854 0 -0.5644235 -0.5644586 0 -0.8254615 -0.2264818 0 -0.9740154 0.1423399 0 -0.9898179 0.3226205 0 -0.9465285 0.3062858 0 -0.9519397 0.1082506 0 -0.9941237 -0.2928589 0 -0.9561558 -0.4794871 0 -0.877549 -0.6179765 0 -0.7861965 -0.5886507 0 -0.8083876 -0.5277009 0 -0.8494303 -0.4638599 0 -0.8859087 -0.3975406 0 -0.9175846 -0.3290533 0 -0.9443114 -0.3290627 0 -0.9443081 -0.1871752 0 -0.9823266 -0.1871457 0 -0.9823322 -0.1145071 0 -0.9934225 -0.04120022 0 -0.999151 0.03225898 0 -0.9994797 0.1055966 0 -0.9944092 0.1420665 0 -0.9898572 -0.02353042 0 -0.9997232 -0.2244404 0 -0.9744879 -0.5908198 0 -0.8068037 -0.7412313 0 -0.6712498 -0.7526713 0 -0.6583966 -0.6181976 0 -0.7860229 -0.2908738 0 -0.9567614 0.07605236 0 -0.9971039 0.4326398 0 -0.9015669 0.7302754 0 -0.683153 0.9283925 0 -0.3716012 0.928382 0 -0.3716275 0.98103 0 -0.193856 0.9775565 0 -0.2106732 0.9150782 0 -0.4032765 0.915062 0 -0.4033133 0.681622 0 -0.7317045 0.5202335 0 -0.8540241 0.37188 0 -0.9282808 0.405725 0 -0.9139953 0.4717632 0 -0.8817254 0.535275 0 -0.8446779 0.5958609 0 -0.8030877 0.6532535 0 -0.7571393 0.7571393 0 -0.6532535 0.8030731 0 -0.5958806 0.8446779 0 -0.535275 0.8817254 0 -0.4717632 0.9139839 0 -0.4057505 0.9282808 0 -0.37188 0.8540241 0 -0.5202335 0.7317045 0 -0.681622 -0.1564405 0 -0.9876874 0.0784654 0 -0.9969169 -0.309004 0 -0.9510608 -0.4539761 0 -0.8910139 -0.587767 0 -0.8090303 -0.5878015 0 -0.8090053 -0.707122 0 -0.7070915 -0.8090158 0 -0.587787 -0.8090053 0 -0.5878015 -0.8910016 0 -0.4540003 -0.8910139 0 -0.4539761 -0.9510608 0 -0.309004 -0.9876922 0 -0.1564108 -0.9876874 0 -0.1564405 -0.9876922 0 0.1564108 -0.9876874 0 0.1564405 -0.9510608 0 0.309004 -0.8910016 0 0.4540003 -0.8910139 0 0.4539761 -0.8090303 0 0.587767 -0.8090053 0 0.5878015 -0.587767 0 0.8090303 -0.5878015 0 0.8090053 -0.4539761 0 0.8910139 -0.309004 0 0.9510608 -0.1564405 0 0.9876874 -0.0784654 0 0.9969169 0.0784654 0 0.9969169 0.1564405 0 0.9876874 0.309004 0 0.9510608 0.4539761 0 0.8910139 0.587767 0 0.8090303 0.5878015 0 0.8090053 0.707122 0 0.7070915 0.8090158 0 0.587787 0.8090053 0 0.5878015 0.8910016 0 0.4540003 0.8910139 0 0.4539761 0.9510608 0 0.309004 0.9876922 0 0.1564108 0.9876874 0 0.1564405 0.9876922 0 -0.1564108 0.9876874 0 -0.1564405 0.9510608 0 -0.309004 0.8910016 0 -0.4540003 0.8910139 0 -0.4539761 0.8090303 0 -0.587767 0.8090053 0 -0.5878015 0.587767 0 -0.8090303 0.5878015 0 -0.8090053 0.4539761 0 -0.8910139 0.309004 0 -0.9510608 0.043612 0 -0.9990487 0.08716166 0 -0.9961942 -0.08716166 0 -0.9961942 -0.043612 0 -0.9990487 0.2588307 0 -0.9659227 0 1 -6.27741e-6 0.4226315 0 -0.9063016 0.4225947 0 -0.9063188 0.573571 0 -0.819156 0 1 -3.13879e-6 0.5735505 0 -0.8191702 0 1 2.88909e-6 0.7070915 0 -0.707122 0 1 -2.49375e-6 0 1 3.99148e-6 0.7660631 0 -0.6427654 0.8191459 0 -0.5735853 0.8191702 0 -0.5735505 0.8660449 0 -0.4999665 0.9063188 0 -0.4225947 0.9397026 0 -0.341993 0 1 -1.43139e-6 0.9659227 0 -0.2588307 0.9961968 0 -0.08713132 0.9961942 0 -0.08716166 0.9961968 0 0.08713132 0.9961942 0 0.08716166 0.9659227 0 0.2588307 0.9397026 0 0.341993 0.9396891 0 0.3420298 0.9063188 0 0.4225947 0 1 1.07355e-6 0.8191459 0 0.5735853 0 1 5.14539e-7 0.8191702 0 0.5735505 0.7660631 0 0.6427654 0.7070915 0 0.707122 0 1 -2.88909e-6 0 1 3.13879e-6 0.573571 0 0.819156 0.5735505 0 0.8191702 0.4226315 0 0.9063016 0.4225947 0 0.9063188 0 1 6.27741e-6 0.2588307 0 0.9659227 0.08716166 0 0.9961942 0.043612 0 0.9990487 -0.043612 0 0.9990487 -0.08716166 0 0.9961942 -0.2588307 0 0.9659227 -0.4226315 0 0.9063016 -0.4225947 0 0.9063188 -0.573571 0 0.819156 -0.5735505 0 0.8191702 -0.7070915 0 0.707122 0 1 2.49375e-6 0 1 -3.99148e-6 -0.7660631 0 0.6427654 -0.8191459 0 0.5735853 -0.8191702 0 0.5735505 -0.8660449 0 0.4999665 -0.9063188 0 0.4225947 -0.9397026 0 0.341993 0 1 1.43139e-6 -0.9659227 0 0.2588307 -0.9961968 0 0.08713132 -0.9961942 0 0.08716166 -0.9961968 0 -0.08713132 -0.9961942 0 -0.08716166 -0.9659227 0 -0.2588307 -0.9397026 0 -0.341993 -0.9396891 0 -0.3420298 -0.9063188 0 -0.4225947 0 1 -1.07355e-6 -0.8191459 0 -0.5735853 0 1 -5.14539e-7 -0.8191702 0 -0.5735505 -0.7660631 0 -0.6427654 -0.7070915 0 -0.707122 -0.573571 0 -0.819156 -0.5735505 0 -0.8191702 -0.4226315 0 -0.9063016 -0.4225947 0 -0.9063188 -0.2588307 0 -0.9659227 -0.9848124 -0.1736217 0 -0.9848178 -0.1735921 0 -0.9398113 -0.3416941 -1.52596e-4 -0.9395803 0.3423287 -1.52594e-4 -0.9398113 0.3416941 -1.22077e-4 -0.9848124 0.1736217 0 -0.9848073 0.1736513 0 -0.9395902 -0.3423017 -1.22076e-4 -0.7663141 -0.642466 -4.88312e-4 -0.7657842 -0.6430975 -4.57786e-4 -0.5002973 -0.8658534 -7.62974e-4 -0.4997171 -0.8661885 -7.32455e-4 -0.1737452 -0.9847903 -8.54535e-4 -0.1735328 -0.9848278 -8.54541e-4 0.1737748 -0.9847851 -8.85049e-4 0.1735328 -0.9848277 -9.15579e-4 0.5003334 -0.8658326 -7.01944e-4 0.4997532 -0.8661676 -7.32463e-4 0.7663267 -0.642451 -3.96744e-4 0.7657842 -0.6430976 -4.27267e-4 0.9398113 -0.3416941 -2.13635e-4 0.9395803 -0.3423287 -2.4415e-4 0.9848124 -0.1736217 0 0.9848124 0.1736217 0 0.9398113 0.3416941 -2.13635e-4 0.9395902 0.3423017 -2.13633e-4 0.7663141 0.642466 -4.27273e-4 0.7657842 0.6430976 -3.96748e-4 0.5003334 0.8658326 -7.32463e-4 0.4997532 0.8661676 -7.01943e-4 0.1737452 0.9847904 -7.93497e-4 0.1735328 0.9848278 -7.93502e-4 -0.1737748 0.9847851 -8.24011e-4 -0.1735328 0.9848278 -8.24022e-4 -0.5003334 0.8658326 -6.40905e-4 -0.4997532 0.8661676 -6.71424e-4 -0.7663418 0.6424331 -3.96752e-4 -0.7657992 0.6430796 -4.27275e-4 -2.20985e-5 0 -1 -0.9906696 0.1354117 -0.01541197 -0.9951235 0.09863644 0 -0.9999993 -2.44155e-4 -0.00125128 -0.8660247 0.5000014 0 -0.8660263 0.4999986 1.82462e-6 -0.866025 0.5000009 0 -0.999951 -0.006195306 -0.007721245 -0.9950689 -0.0991559 -0.002471983 -0.9943926 0.1051065 -0.01165813 -1.40654e-6 0 -1 -0.8660248 -0.500001 0 -0.9956673 -0.09225749 -0.01162755 -0.989026 -0.147742 0 3.03664e-6 0 -1 -0.5829806 -0.8124861 -3.05193e-5 -0.5828913 -0.8125503 0 -0.4998123 -0.8661338 3.05192e-5 -0.8660259 -0.4999992 0 -0.8660251 -0.5000006 -9.12308e-7 1.49107e-6 0 -1 -0.5000254 -0.8660107 0 -0.4119465 -0.9112081 3.05191e-5 -4.34871e-6 0 -1 -0.4120708 -0.9111519 0 2.71795e-6 0 -1 0.412034 -0.9111685 3.05188e-5 0.4119097 -0.9112247 0 0.4998123 -0.8661338 0 -3.50278e-6 0 -1 0.5000254 -0.8660107 0 0.5829114 -0.8125358 -3.05189e-5 0.8660251 -0.5000005 0 0.5830353 -0.8124468 0 2.20982e-5 0 -1 0.9906696 -0.1354117 -0.01541197 0.9951235 -0.09863644 0 0.9999993 2.44155e-4 -0.00125128 0.8660247 -0.5000013 0 0.8660264 -0.4999983 0 0.999951 0.006195306 -0.007721245 0.9950689 0.0991559 -0.002471983 0.9943926 -0.1051065 -0.01165813 0.8660247 0.5000014 0 0.9956673 0.09225749 -0.01162755 0.989026 0.147742 0 0.5830008 0.8124717 -3.05188e-5 0.5828913 0.8125503 0 0.4998123 0.8661338 3.05192e-5 0.8660264 0.4999983 0 0.8660256 0.5 3.64924e-6 0.5000254 0.8660107 0 0.4119465 0.9112081 3.05191e-5 0.4120708 0.9111519 0 -0.412034 0.9111685 3.05188e-5 -0.4119097 0.9112247 0 -0.4998123 0.8661338 0 -0.5000254 0.8660107 3.05191e-5 -0.5829114 0.8125358 -3.05189e-5 -0.5830353 0.8124468 0 0.9748455 0.222882 0 0.9748389 0.222911 0 0.9009518 0.4339193 3.0519e-5 0.9009518 -0.4339193 3.0519e-5 0.9748455 -0.222882 0 0.6235965 0.7817465 0 3.04939e-6 0 1 0.6234438 0.7818683 0 0.2223914 0.9749575 0 6.10406e-6 0 1 0.222456 0.9749428 0 -0.2223914 0.9749575 0 -0.222456 0.9749428 0 -0.6235965 0.7817465 0 -3.83148e-6 0 1 -0.6234438 0.7818683 0 -0.9009518 0.4339193 3.0519e-5 -0.9748455 0.222882 0 -3.04939e-6 0 1 -0.9748455 -0.222882 0 -0.9009518 -0.4339193 3.0519e-5 6.93496e-6 0 1 -0.6235965 -0.7817465 0 -0.6234438 -0.7818683 0 -0.2223914 -0.9749575 0 -0.222456 -0.9749428 0 0.2223914 -0.9749575 0 0.222456 -0.9749428 0 0.6235965 -0.7817465 0 0.6234438 -0.7818683 0 -0.6940107 0.04931926 0.7182736 -0.7048652 0.07956284 0.7048652 -0.6893147 0.16154 0.7062225 -0.6850357 -0.1622405 0.7102141 -0.6917296 -0.1698728 0.7018927 -0.6995212 -0.07446581 0.7107216 -0.6957151 -0.07440572 0.7144539 -0.7066749 -0.03494459 0.7066749 -0.6908279 0.1659927 0.7037069 -0.6434693 0.3000048 0.7042333 -0.6923493 0.0619226 0.7189007 -0.6239387 0.3579927 0.6946523 -0.5536231 0.4439362 0.7045724 -0.479549 0.5293564 0.6998675 -0.438069 0.5480899 0.7125259 -0.3556978 0.6145896 0.7041015 -0.3044918 0.6310187 0.7135125 -0.2138463 0.6785583 0.7027294 -0.1426165 0.7059409 0.6937637 -0.01046806 0.7136597 0.7004144 -0.007660269 0.7125279 0.7016021 0.1518958 0.6936789 0.7040861 0.2176029 0.6799404 0.7002358 0.3044576 0.6310108 0.7135342 0.3557044 0.6145706 0.7041147 0.438069 0.5480899 0.7125259 0.479549 0.5293564 0.6998675 0.5536231 0.4439362 0.7045724 0.6240552 0.3535031 0.6968433 0.6528195 0.2958593 0.6973479 0.6917296 0.1698728 0.7018927 0.6850357 0.1622405 0.7102141 0.6995212 0.07446581 0.7107216 0.6940107 -0.04931926 0.7182736 0.7048652 -0.07956284 0.7048652 0.6893147 -0.16154 0.7062225 0.6957151 0.07440572 0.7144539 0.7066749 0.03494459 0.7066749 0.6908279 -0.1659927 0.7037069 0.6434693 -0.3000048 0.7042333 0.6923493 -0.0619226 0.7189007 0.6239387 -0.3579927 0.6946523 0.5536231 -0.4439362 0.7045724 0.479549 -0.5293564 0.6998675 0.438069 -0.5480899 0.7125259 0.3556978 -0.6145896 0.7041015 0.3044642 -0.6310245 0.7135192 -9.12969e-7 0 1 0.2138463 -0.6785583 0.7027294 0.1426165 -0.7059409 0.6937637 0.01046806 -0.7136597 0.7004144 0.007660269 -0.7125279 0.7016021 -0.1518958 -0.6936789 0.7040861 -0.2176029 -0.6799404 0.7002358 -0.3044918 -0.6310187 0.7135125 -0.3556978 -0.6145896 0.7041015 -0.438069 -0.5480899 0.7125259 -0.479549 -0.5293564 0.6998675 -0.5536156 -0.4439607 0.7045629 -0.6240552 -0.3535031 0.6968433 -0.6528136 -0.2958872 0.6973416 0 1 -2.79455e-6 0 1 -1.4915e-6 0 1 1.50419e-6 0 1 -1.20677e-6 0 1 1.70491e-6 0 1 -7.69778e-7 0 1 6.10165e-6 0 1 -8.7771e-7 0 1 8.34195e-6 0 1 -1.68723e-6 0 1 -1.30552e-6 0 1 3.18297e-6 0 1 4.38855e-7 0 1 -1.41974e-6 0 1 2.95182e-6 0 1 -2.94605e-6 0 1 -2.86586e-6 0 1 2.94608e-6 0 1 -1.50419e-6 0 1 2.95202e-6 0 1 1.30506e-6 0 1 2.79455e-6 0 1 1.4915e-6 0 1 1.20677e-6 0 1 -1.70491e-6 0 1 7.69778e-7 0 1 -6.10165e-6 0 1 8.7771e-7 0 1 -8.34195e-6 0 1 1.68723e-6 0 1 1.30552e-6 0 1 -3.18297e-6 0 1 -4.38855e-7 0 1 1.41974e-6 0 1 -2.95182e-6 0 1 2.94605e-6 0 1 2.86586e-6 0 1 -2.94608e-6 0 1 -2.95202e-6 0 1 -1.30506e-6 0 1 1.23405e-6 0 1 3.18161e-7 0 1 -3.37161e-7 0 1 -1.23406e-6 0 1 -3.18159e-7 0 1 3.37162e-7 0.1761578 -0.8571672 0.4839763 0.09042823 -0.8536511 0.5129354 0.3636639 -0.9315302 0 -0.1761578 -0.8571672 0.4839763 -0.3636639 -0.9315302 0 -0.09042823 -0.8536511 0.5129354 0.3310479 -0.8571781 0.394529 0.4460394 -0.8571648 0.2575218 0.5072053 -0.8571736 0.0894224 0.5072053 -0.8571736 -0.0894224 0.4460394 -0.8571648 -0.2575218 0.3310479 -0.8571781 -0.394529 0.1761282 -0.8571718 -0.4839789 0.09042823 -0.8536511 -0.5129354 -0.1761282 -0.8571718 -0.4839789 -0.09042823 -0.8536511 -0.5129354 -0.3310479 -0.8571781 -0.394529 -0.4460394 -0.8571648 -0.2575218 -0.5072053 -0.8571736 -0.0894224 -0.5072053 -0.8571736 0.0894224 -0.4460394 -0.8571648 0.2575218 -0.3310479 -0.8571781 0.394529 -0.4894379 -0.8536552 -0.1781106 -0.1818329 -0.9315353 0.3149268 0.1818329 -0.9315353 -0.3149268 -0.3989788 -0.8536552 -0.3347967 -0.1761282 -0.8571718 0.4839789 0 -0.8571642 0.5150432 0.3989788 -0.8536552 0.3347967 0.4894353 -0.8536506 0.1781402 0.1761578 -0.8571672 -0.4839763 0 -0.8571642 -0.5150432 0 -1 -1.85833e-6 0 -1 5.13557e-7 0 -1 5.47346e-7 0 -1 7.94772e-7 0 -1 -1.47041e-6 0 -1 -2.49303e-7 0 -1 4.21147e-7 0 -1 7.13726e-7 0 -1 -1.33034e-6 0 -1 3.51026e-6 0 -1 -2.34431e-6 0 -1 -3.79669e-7 0 -1 -2.02571e-7 0 -1 6.65995e-7 0 -1 4.37897e-7 0 -1 -4.5533e-7 0 -1 1.83273e-6 0 -1 -3.75453e-7 0 -1 -3.09614e-6 0 -1 -2.74909e-7 0 -1 0 0 -1 -8.01356e-7 0 -1 5.93754e-7 0 -1 -1.44222e-6 0 -1 0 0 -1 1.35293e-7 0 -1 0 0 -1 -2.29858e-7 0 -1 1.90541e-7 0 -1 0 0 -1 1.78127e-7 0 -1 0 0 -1 -6.37211e-7 0 -1 -5.20422e-6 0 -1 1.86934e-6 0 -1 0 0 -1 -7.45722e-7 0 -1 0 0 -1 1.04127e-6 0 -1 2.6553e-7 0 -1 -3.04301e-7 0 -1 0 0 -1 0 0 -1 -3.05947e-7 0 -1 2.60318e-7 0 -1 1.55913e-7 0 -1 5.67946e-7 0 -1 -1.58238e-7 0 -1 -4.66077e-7 0 -1 7.00059e-7 0 -1 -4.38767e-7 0 -1 -1.97431e-7 0 -1 1.59362e-7 0 -1 2.38954e-7 0 -1 -4.84047e-7 0 -1 -3.43727e-6 0 -1 5.85468e-6 0 -1 -2.103e-6 0 -1 6.3387e-7 0 -1 0 0 -1 0 0 -1 -1.83884e-7 0 -1 -3.61723e-7 0 -1 1.98098e-7 0 -1 -1.56456e-7 0 -1 2.16466e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.46617e-6 0 -1 6.74127e-7 0 -1 -3.5198e-7 0 -1 1.6512e-5 0 -1 -2.2766e-7 0 -1 -8.20184e-7 0 -1 5.07419e-7 0 -1 3.7251e-7 0 -1 3.24113e-7 0 -1 -1.28384e-7 0 -1 -1.11499e-6 0 -1 -5.47344e-7 0 -1 1.4704e-6 0 -1 2.49303e-7 0 -1 4.21141e-7 0 -1 -1.17984e-6 0 -1 -7.13726e-7 0 -1 1.33034e-6 0 -1 1.17593e-6 0 -1 -2.3444e-6 0.2234616 -0.4640445 0.8571625 0.3679099 0 0.9298614 0.1167373 -0.5115076 0.8513122 -0.2234616 -0.4640445 0.8571625 -0.1167373 -0.5115076 0.8513122 -0.3679099 0 0.9298614 0.4338826 -0.9009695 0 0.222514 -0.9749296 0 -0.4338826 -0.9009695 0 -0.222514 -0.9749296 0 0.2234616 0.4640445 0.8571625 0.1167373 0.5115076 0.8513122 -0.2234616 0.4640445 0.8571625 -0.1167373 0.5115076 0.8513122 0.4026722 0.3211246 0.8571664 0.5021331 0.1145997 0.8571635 0.5021331 -0.1145997 0.8571635 0.4026722 -0.3211246 0.8571664 -0.4026722 -0.3211246 0.8571664 -0.5021331 -0.1145997 0.8571635 -0.5021331 0.1145997 0.8571635 -0.4026722 0.3211246 0.8571664 0.222514 0.9749296 0 0.4338826 0.9009695 0 -0.4338826 0.9009695 0 -0.222514 0.9749296 0 0.7818415 0.6234773 0 0.9749296 0.222514 0 0.9749296 -0.222514 0 0.7818415 -0.6234773 0 2.09509e-6 0 1 -2.09509e-6 0 1 1.80932e-6 0 1 -2.87382e-6 0 1 -0.7818415 -0.6234773 0 -0.9749296 -0.222514 0 -0.9749296 0.222514 0 -0.7818415 0.6234773 0 2.87385e-6 0 1 -1.18797e-6 0 1 -9.82017e-6 0 1 -2.20982e-5 0 -1 -0.8660251 0.5000005 0 -0.8660247 0.5000013 1.82462e-6 -0.8660264 0.4999983 0 -1.40654e-6 0 -1 -0.8660247 -0.5000014 0 -0.5830008 -0.8124717 -3.05188e-5 -0.4998123 -0.8661338 0 -0.8660264 -0.4999983 0 -0.8660256 -0.5 1.82462e-6 0.5000254 -0.8660107 3.05191e-5 0.8660247 -0.5000014 0 2.20985e-5 0 -1 0.8660263 -0.4999986 9.1231e-7 0.866025 -0.5000009 0 0.8660248 0.500001 0 0.5829806 0.8124861 -3.05193e-5 0.8660259 0.4999992 0 0.8660251 0.5000006 0 0 1 -3.64924e-6 6.93498e-6 0 1 0.3556978 0.6145896 0.7041015 0.5536156 0.4439607 0.7045629 0.6528136 0.2958872 0.6973416 -0.5536231 -0.4439362 0.7045724 -0.6528195 -0.2958593 0.6973479 2.68854e-6 0 -1 -0.8660258 0.4999995 0 -0.8660263 0.4999986 3.64924e-6 -0.8660255 0.5 0 -0.8660259 -0.499999 0 -2.42931e-6 0 -1 -0.5828768 -0.8125606 0 5.60443e-6 0 -1 -0.8660265 -0.4999983 0 -0.8660251 -0.5000006 -1.82462e-6 -1.98809e-6 0 -1 4.34872e-6 0 -1 -2.17436e-6 0 -1 0.4119212 -0.9112195 0 -2.80222e-6 0 -1 4.85862e-6 0 -1 0.8660262 -0.4999986 0 0.8660247 -0.5000013 -3.64923e-6 0.8660269 -0.4999974 0 0.8660258 0.4999995 0 0.5828768 0.8125606 0 0.4998123 0.8661338 0 0.8660269 0.4999974 0 0.8660256 0.5 5.47385e-6 -0.5000254 0.8660107 0 -3.04941e-6 0 1 6.10407e-6 0 1 3.04938e-6 0 1 6.93491e-6 0 1 -6.10411e-6 0 1 6.28828e-6 0 1 -0.6957135 -0.07443606 0.7144523 -0.3044642 0.6310245 0.7135192 -0.2138507 0.6785418 0.702744 -0.1426134 0.705926 0.6937796 0.3044642 0.6310245 0.7135192 0.4795567 0.5293345 0.6998788 0.6923334 -0.06192392 0.7189159 0.3557044 -0.6145706 0.7041147 0.3044918 -0.6310187 0.7135125 0.2138507 -0.6785418 0.702744 -0.3044576 -0.6310108 0.7135342 -0.3557044 -0.6145706 0.7041147 -0.4795567 -0.5293345 0.6998788 0.635944 -0.7717353 0 0.7819901 0.623291 9.15572e-5 0.7465028 0.6653824 1.83116e-4 0.4338579 0.9009814 1.22076e-4 0.9010525 0.4337101 3.05193e-5 0.4341037 0.9008629 0 0.2226077 0.9749081 6.10386e-5 0.2226657 0.9748949 0 -0.2593244 -0.9657903 -1.52598e-4 -0.2590737 -0.9658576 0 0.961336 -0.2753781 2.44157e-4 0.9856551 -0.1687723 2.13636e-4 1 0 1.52593e-4 0.9010525 -0.4337101 2.74674e-4 2.98191e-5 0 1 6.76105e-6 0 1 -0.7074272 -0.7067863 -1.22075e-4 0.9009814 0.4338579 2.74671e-4 0.7467185 -0.6651402 1.83116e-4 0.8148003 -0.5797418 1.22077e-4 0.9009814 -0.4338579 3.0519e-5 0.6236971 -0.7816662 2.74676e-4 -0.8659009 -0.5002156 6.10391e-5 -0.9204894 -0.3907678 -1.52596e-4 -1 -1.22078e-4 3.05194e-5 -0.707122 -0.7070915 1.52594e-4 -1 -1.22074e-4 3.05185e-5 -0.8662019 0.4996944 6.10388e-5 -0.8658668 0.5002745 -1.52597e-4 -0.5002385 0.8658878 -3.05191e-5 -0.5001795 0.8659218 -9.15577e-5 -0.2591667 0.9658326 -6.10379e-5 -0.2593244 0.9657903 0 -0.6359428 0.7717363 0 -0.6359432 0.771736 0 0.3840844 -0.9232981 9.15577e-5 0.482481 -0.8759065 3.05194e-5 0.6234773 -0.7818415 -6.10384e-5 0.2226657 -0.9748949 1.83113e-4 - - - - - - - - - - 0.41842 0.6816 0.36595 0.66181 0.391895 0.673037 0.420745 0.628405 0.391895 0.673037 0.36595 0.66181 0.445377 0.687621 0.36595 0.66181 0.41842 0.6816 0.472617 0.691195 0.36595 0.66181 0.445377 0.687621 0.5 0.692379 0.36595 0.66181 0.472617 0.691195 0.527383 0.691195 0.36595 0.66181 0.5 0.692379 0.411195 0.622189 0.420745 0.628405 0.36595 0.66181 0.40227 0.61531 0.411195 0.622189 0.36595 0.66181 0.289328 0.694466 0.40227 0.61531 0.36595 0.66181 0.139297 0.727973 0.289328 0.694466 0.36595 0.66181 0.554622 0.687621 0.36595 0.66181 0.527383 0.691195 0.58158 0.6816 0.36595 0.66181 0.554622 0.687621 0.608105 0.673037 0.36595 0.66181 0.58158 0.6816 0.63405 0.66181 0.36595 0.66181 0.608105 0.673037 0.570144 0.678603 0.36595 0.66181 0.63405 0.66181 0.572756 0.685048 0.139297 0.727973 0.36595 0.66181 0.570144 0.678603 0.572756 0.685048 0.36595 0.66181 0.430877 0.633909 0.41842 0.6816 0.391895 0.673037 0.420745 0.628405 0.430877 0.633909 0.391895 0.673037 0.452643 0.642594 0.445377 0.687621 0.41842 0.6816 0.441532 0.638652 0.452643 0.642594 0.41842 0.6816 0.430877 0.633909 0.441532 0.638652 0.41842 0.6816 0.47592 0.647939 0.472617 0.691195 0.445377 0.687621 0.464134 0.645699 0.47592 0.647939 0.445377 0.687621 0.452643 0.642594 0.464134 0.645699 0.445377 0.687621 0.5 0.649744 0.5 0.692379 0.472617 0.691195 0.487906 0.649292 0.5 0.649744 0.472617 0.691195 0.47592 0.647939 0.487906 0.649292 0.472617 0.691195 0.512094 0.649292 0.5 0.692379 0.5 0.649744 0.527383 0.691195 0.5 0.692379 0.512094 0.649292 0.5 0.641129 0.5 0.649744 0.487906 0.649292 0.523606 0.63927 0.512094 0.649292 0.5 0.649744 0.523606 0.63927 0.5 0.649744 0.5 0.641129 0.476394 0.63927 0.487906 0.649292 0.47592 0.647939 0.476394 0.63927 0.5 0.641129 0.487906 0.649292 0.476394 0.63927 0.47592 0.647939 0.464134 0.645699 0.453618 0.63377 0.464134 0.645699 0.452643 0.642594 0.453618 0.63377 0.476394 0.63927 0.464134 0.645699 0.453618 0.63377 0.452643 0.642594 0.441532 0.638652 0.432408 0.624844 0.441532 0.638652 0.430877 0.633909 0.432408 0.624844 0.453618 0.63377 0.441532 0.638652 0.432408 0.624844 0.430877 0.633909 0.420745 0.628405 0.413352 0.612819 0.420745 0.628405 0.411195 0.622189 0.413352 0.612819 0.432408 0.624844 0.420745 0.628405 0.413352 0.612819 0.411195 0.622189 0.40227 0.61531 0.289328 0.694466 0.394005 0.607817 0.40227 0.61531 0.396874 0.5981 0.40227 0.61531 0.394005 0.607817 0.396874 0.5981 0.413352 0.612819 0.40227 0.61531 0.140457 0.727862 0.386424 0.599763 0.394005 0.607817 0.396874 0.5981 0.394005 0.607817 0.386424 0.599763 0.289328 0.694466 0.140457 0.727862 0.394005 0.607817 0.132754 0.707196 0.379548 0.591201 0.386424 0.599763 0.383239 0.581138 0.386424 0.599763 0.379548 0.591201 0.140457 0.727862 0.132754 0.707196 0.386424 0.599763 0.383239 0.581138 0.396874 0.5981 0.386424 0.599763 0.333248 0.605095 0.373388 0.582186 0.379548 0.591201 0.383239 0.581138 0.379548 0.591201 0.373388 0.582186 0.330571 0.607593 0.333248 0.605095 0.379548 0.591201 0.327461 0.610323 0.330571 0.607593 0.379548 0.591201 0.323845 0.613315 0.327461 0.610323 0.379548 0.591201 0.319635 0.616601 0.323845 0.613315 0.379548 0.591201 0.314721 0.620221 0.319635 0.616601 0.379548 0.591201 0.308965 0.624217 0.314721 0.620221 0.379548 0.591201 0.302193 0.628634 0.308965 0.624217 0.379548 0.591201 0.294182 0.633523 0.302193 0.628634 0.379548 0.591201 0.284653 0.638929 0.294182 0.633523 0.379548 0.591201 0.273243 0.644892 0.284653 0.638929 0.379548 0.591201 0.259479 0.65143 0.273243 0.644892 0.379548 0.591201 0.242742 0.658515 0.259479 0.65143 0.379548 0.591201 0.222219 0.666031 0.242742 0.658515 0.379548 0.591201 0.132754 0.707196 0.222219 0.666031 0.379548 0.591201 0.344685 0.584139 0.367955 0.572772 0.373388 0.582186 0.372583 0.562393 0.373388 0.582186 0.367955 0.572772 0.345035 0.585014 0.344685 0.584139 0.373388 0.582186 0.345244 0.586047 0.345035 0.585014 0.373388 0.582186 0.345272 0.587164 0.345244 0.586047 0.373388 0.582186 0.345124 0.588337 0.345272 0.587164 0.373388 0.582186 0.344807 0.589577 0.345124 0.588337 0.373388 0.582186 0.344327 0.590879 0.344807 0.589577 0.373388 0.582186 0.34368 0.592256 0.344327 0.590879 0.373388 0.582186 0.34286 0.593718 0.34368 0.592256 0.373388 0.582186 0.341854 0.595279 0.34286 0.593718 0.373388 0.582186 0.340645 0.596951 0.341854 0.595279 0.373388 0.582186 0.33921 0.598752 0.340645 0.596951 0.373388 0.582186 0.337522 0.600697 0.33921 0.598752 0.373388 0.582186 0.335548 0.602804 0.337522 0.600697 0.373388 0.582186 0.333248 0.605095 0.335548 0.602804 0.373388 0.582186 0.372583 0.562393 0.383239 0.581138 0.373388 0.582186 0.323908 0.579438 0.363249 0.563012 0.367955 0.572772 0.364962 0.542321 0.367955 0.572772 0.363249 0.563012 0.326817 0.579302 0.323908 0.579438 0.367955 0.572772 0.329423 0.579262 0.326817 0.579302 0.367955 0.572772 0.331759 0.579311 0.329423 0.579262 0.367955 0.572772 0.333854 0.57944 0.331759 0.579311 0.367955 0.572772 0.335737 0.579648 0.333854 0.57944 0.367955 0.572772 0.337429 0.579929 0.335737 0.579648 0.367955 0.572772 0.338946 0.580286 0.337429 0.579929 0.367955 0.572772 0.340303 0.58072 0.338946 0.580286 0.367955 0.572772 0.34151 0.581239 0.340303 0.58072 0.367955 0.572772 0.342562 0.581844 0.34151 0.581239 0.367955 0.572772 0.34346 0.582547 0.342562 0.581844 0.367955 0.572772 0.34418 0.583337 0.34346 0.582547 0.367955 0.572772 0.344685 0.584139 0.34418 0.583337 0.367955 0.572772 0.364962 0.542321 0.372583 0.562393 0.367955 0.572772 0.273602 0.587993 0.359272 0.552957 0.363249 0.563012 0.360393 0.521376 0.363249 0.563012 0.359272 0.552957 0.282542 0.586041 0.273602 0.587993 0.363249 0.563012 0.290305 0.584437 0.282542 0.586041 0.363249 0.563012 0.297081 0.583127 0.290305 0.584437 0.363249 0.563012 0.303025 0.582066 0.297081 0.583127 0.363249 0.563012 0.30826 0.581219 0.303025 0.582066 0.363249 0.563012 0.31289 0.580555 0.30826 0.581219 0.363249 0.563012 0.316997 0.58005 0.31289 0.580555 0.363249 0.563012 0.32065 0.579683 0.316997 0.58005 0.363249 0.563012 0.323908 0.579438 0.32065 0.579683 0.363249 0.563012 0.360393 0.521376 0.364962 0.542321 0.363249 0.563012 0.109044 0.591111 0.356022 0.542657 0.359272 0.552957 0.358871 0.5 0.359272 0.552957 0.356022 0.542657 0.220382 0.600791 0.109044 0.591111 0.359272 0.552957 0.237063 0.596655 0.220382 0.600791 0.359272 0.552957 0.251195 0.593215 0.237063 0.596655 0.359272 0.552957 0.263251 0.590359 0.251195 0.593215 0.359272 0.552957 0.273602 0.587993 0.263251 0.590359 0.359272 0.552957 0.358871 0.5 0.360393 0.521376 0.359272 0.552957 0.356022 0.457343 0.356022 0.542657 0.353497 0.53216 0.10606 0.554725 0.353497 0.53216 0.356022 0.542657 0.359272 0.447043 0.356022 0.542657 0.356022 0.457343 0.358871 0.5 0.356022 0.542657 0.359272 0.447043 0.109044 0.591111 0.10606 0.554725 0.356022 0.542657 0.353497 0.46784 0.353497 0.53216 0.351695 0.521519 0.10606 0.554725 0.351695 0.521519 0.353497 0.53216 0.356022 0.457343 0.353497 0.53216 0.353497 0.46784 0.351695 0.478481 0.351695 0.521519 0.350615 0.510783 0.104616 0.518251 0.350615 0.510783 0.351695 0.521519 0.353497 0.46784 0.351695 0.521519 0.351695 0.478481 0.10606 0.554725 0.104616 0.518251 0.351695 0.521519 0.350615 0.489217 0.350615 0.510783 0.350256 0.5 0.104616 0.518251 0.350256 0.5 0.350615 0.510783 0.351695 0.478481 0.350615 0.510783 0.350615 0.489217 0.104616 0.481749 0.350615 0.489217 0.350256 0.5 0.104616 0.518251 0.104616 0.481749 0.350256 0.5 0.10606 0.445275 0.351695 0.478481 0.350615 0.489217 0.104616 0.481749 0.10606 0.445275 0.350615 0.489217 0.10606 0.445275 0.353497 0.46784 0.351695 0.478481 0.109044 0.408889 0.356022 0.457343 0.353497 0.46784 0.10606 0.445275 0.109044 0.408889 0.353497 0.46784 0.109044 0.408889 0.359272 0.447043 0.356022 0.457343 0.320682 0.42032 0.363249 0.436988 0.359272 0.447043 0.360393 0.478624 0.359272 0.447043 0.363249 0.436988 0.317033 0.419954 0.320682 0.42032 0.359272 0.447043 0.31293 0.41945 0.317033 0.419954 0.359272 0.447043 0.308305 0.418788 0.31293 0.41945 0.359272 0.447043 0.303074 0.417942 0.308305 0.418788 0.359272 0.447043 0.297136 0.416884 0.303074 0.417942 0.359272 0.447043 0.290366 0.415575 0.297136 0.416884 0.359272 0.447043 0.282609 0.413973 0.290366 0.415575 0.359272 0.447043 0.273677 0.412023 0.282609 0.413973 0.359272 0.447043 0.263334 0.409661 0.273677 0.412023 0.359272 0.447043 0.251287 0.406807 0.263334 0.409661 0.359272 0.447043 0.237166 0.40337 0.251287 0.406807 0.359272 0.447043 0.220499 0.399238 0.237166 0.40337 0.359272 0.447043 0.200685 0.394277 0.220499 0.399238 0.359272 0.447043 0.109044 0.408889 0.200685 0.394277 0.359272 0.447043 0.360393 0.478624 0.358871 0.5 0.359272 0.447043 0.344685 0.415861 0.367955 0.427228 0.363249 0.436988 0.364962 0.457679 0.363249 0.436988 0.367955 0.427228 0.34418 0.416663 0.344685 0.415861 0.363249 0.436988 0.343461 0.417452 0.34418 0.416663 0.363249 0.436988 0.342563 0.418156 0.343461 0.417452 0.363249 0.436988 0.341513 0.41876 0.342563 0.418156 0.363249 0.436988 0.340308 0.419278 0.341513 0.41876 0.363249 0.436988 0.338953 0.419712 0.340308 0.419278 0.363249 0.436988 0.337438 0.420069 0.338953 0.419712 0.363249 0.436988 0.335749 0.420351 0.337438 0.420069 0.363249 0.436988 0.333869 0.420558 0.335749 0.420351 0.363249 0.436988 0.331777 0.420689 0.333869 0.420558 0.363249 0.436988 0.329444 0.420738 0.331777 0.420689 0.363249 0.436988 0.326842 0.420699 0.329444 0.420738 0.363249 0.436988 0.323936 0.420564 0.326842 0.420699 0.363249 0.436988 0.320682 0.42032 0.323936 0.420564 0.363249 0.436988 0.364962 0.457679 0.360393 0.478624 0.363249 0.436988 0.335529 0.397176 0.373388 0.417814 0.367955 0.427228 0.372583 0.437607 0.367955 0.427228 0.373388 0.417814 0.337506 0.399285 0.335529 0.397176 0.367955 0.427228 0.339197 0.401232 0.337506 0.399285 0.367955 0.427228 0.340634 0.403035 0.339197 0.401232 0.367955 0.427228 0.341846 0.404709 0.340634 0.403035 0.367955 0.427228 0.342854 0.406272 0.341846 0.404709 0.367955 0.427228 0.343676 0.407736 0.342854 0.406272 0.367955 0.427228 0.344324 0.409115 0.343676 0.407736 0.367955 0.427228 0.344806 0.410418 0.344324 0.409115 0.367955 0.427228 0.345123 0.411659 0.344806 0.410418 0.367955 0.427228 0.345272 0.412835 0.345123 0.411659 0.367955 0.427228 0.345244 0.413952 0.345272 0.412835 0.367955 0.427228 0.345036 0.414985 0.345244 0.413952 0.367955 0.427228 0.344685 0.415861 0.345036 0.414985 0.367955 0.427228 0.372583 0.437607 0.364962 0.457679 0.367955 0.427228 0.294114 0.366437 0.379548 0.408799 0.373388 0.417814 0.372583 0.437607 0.373388 0.417814 0.379548 0.408799 0.302132 0.371328 0.294114 0.366437 0.373388 0.417814 0.308912 0.375748 0.302132 0.371328 0.373388 0.417814 0.314675 0.379746 0.308912 0.375748 0.373388 0.417814 0.319595 0.383368 0.314675 0.379746 0.373388 0.417814 0.32381 0.386657 0.319595 0.383368 0.373388 0.417814 0.32743 0.389651 0.32381 0.386657 0.373388 0.417814 0.330545 0.392383 0.32743 0.389651 0.373388 0.417814 0.333225 0.394883 0.330545 0.392383 0.373388 0.417814 0.335529 0.397176 0.333225 0.394883 0.373388 0.417814 0.137969 0.278376 0.386424 0.400237 0.379548 0.408799 0.383239 0.418862 0.379548 0.408799 0.386424 0.400237 0.242623 0.341438 0.137969 0.278376 0.379548 0.408799 0.259378 0.348525 0.242623 0.341438 0.379548 0.408799 0.273155 0.355064 0.259378 0.348525 0.379548 0.408799 0.284576 0.361028 0.273155 0.355064 0.379548 0.408799 0.294114 0.366437 0.284576 0.361028 0.379548 0.408799 0.383239 0.418862 0.372583 0.437607 0.379548 0.408799 0.153909 0.243778 0.394005 0.392183 0.386424 0.400237 0.383239 0.418862 0.386424 0.400237 0.394005 0.392183 0.137969 0.278376 0.153909 0.243778 0.386424 0.400237 0.153909 0.243778 0.40227 0.38469 0.394005 0.392183 0.396874 0.4019 0.394005 0.392183 0.40227 0.38469 0.396874 0.4019 0.383239 0.418862 0.394005 0.392183 0.176021 0.210251 0.411195 0.377811 0.40227 0.38469 0.396874 0.4019 0.40227 0.38469 0.411195 0.377811 0.153909 0.243778 0.176021 0.210251 0.40227 0.38469 0.176021 0.210251 0.420745 0.371595 0.411195 0.377811 0.413352 0.387181 0.411195 0.377811 0.420745 0.371595 0.413352 0.387181 0.396874 0.4019 0.411195 0.377811 0.207285 0.17842 0.430877 0.366091 0.420745 0.371595 0.413352 0.387181 0.420745 0.371595 0.430877 0.366091 0.176021 0.210251 0.207285 0.17842 0.420745 0.371595 0.252422 0.149394 0.441532 0.361348 0.430877 0.366091 0.432408 0.375156 0.430877 0.366091 0.441532 0.361348 0.207285 0.17842 0.252422 0.149394 0.430877 0.366091 0.432408 0.375156 0.413352 0.387181 0.430877 0.366091 0.252422 0.149394 0.452643 0.357406 0.441532 0.361348 0.432408 0.375156 0.441532 0.361348 0.452643 0.357406 0.318057 0.12516 0.464134 0.354301 0.452643 0.357406 0.453618 0.36623 0.452643 0.357406 0.464134 0.354301 0.252422 0.149394 0.318057 0.12516 0.452643 0.357406 0.453618 0.36623 0.432408 0.375156 0.452643 0.357406 0.318057 0.12516 0.47592 0.352061 0.464134 0.354301 0.453618 0.36623 0.464134 0.354301 0.47592 0.352061 0.482857 0.3062 0.487906 0.350708 0.47592 0.352061 0.476394 0.36073 0.47592 0.352061 0.487906 0.350708 0.481306 0.30288 0.482857 0.3062 0.47592 0.352061 0.479653 0.299107 0.481306 0.30288 0.47592 0.352061 0.477878 0.294812 0.479653 0.299107 0.47592 0.352061 0.475962 0.289913 0.477878 0.294812 0.47592 0.352061 0.473879 0.28431 0.475962 0.289913 0.47592 0.352061 0.471594 0.277881 0.473879 0.28431 0.47592 0.352061 0.469067 0.270476 0.471594 0.277881 0.47592 0.352061 0.466243 0.261909 0.469067 0.270476 0.47592 0.352061 0.46305 0.251956 0.466243 0.261909 0.47592 0.352061 0.45939 0.240337 0.46305 0.251956 0.47592 0.352061 0.455122 0.226705 0.45939 0.240337 0.47592 0.352061 0.450037 0.210623 0.455122 0.226705 0.47592 0.352061 0.443805 0.19155 0.450037 0.210623 0.47592 0.352061 0.318057 0.12516 0.443805 0.19155 0.47592 0.352061 0.476394 0.36073 0.453618 0.36623 0.47592 0.352061 0.5 0.324989 0.5 0.350256 0.487906 0.350708 0.476394 0.36073 0.487906 0.350708 0.5 0.350256 0.498904 0.324907 0.5 0.324989 0.487906 0.350708 0.497711 0.324634 0.498904 0.324907 0.487906 0.350708 0.496518 0.324169 0.497711 0.324634 0.487906 0.350708 0.495351 0.323529 0.496518 0.324169 0.487906 0.350708 0.494192 0.322717 0.495351 0.323529 0.487906 0.350708 0.493042 0.321738 0.494192 0.322717 0.487906 0.350708 0.491888 0.320587 0.493042 0.321738 0.487906 0.350708 0.49072 0.319251 0.491888 0.320587 0.487906 0.350708 0.489527 0.317717 0.49072 0.319251 0.487906 0.350708 0.488301 0.315965 0.489527 0.317717 0.487906 0.350708 0.487031 0.313968 0.488301 0.315965 0.487906 0.350708 0.485707 0.311699 0.487031 0.313968 0.487906 0.350708 0.48432 0.309124 0.485707 0.311699 0.487906 0.350708 0.482857 0.3062 0.48432 0.309124 0.487906 0.350708 0.501097 0.324907 0.5 0.350256 0.5 0.324989 0.514305 0.311678 0.515693 0.309099 0.5 0.350256 0.512094 0.350708 0.5 0.350256 0.515693 0.309099 0.51298 0.31395 0.514305 0.311678 0.5 0.350256 0.511709 0.31595 0.51298 0.31395 0.5 0.350256 0.510482 0.317705 0.511709 0.31595 0.5 0.350256 0.509288 0.319242 0.510482 0.317705 0.5 0.350256 0.508119 0.320579 0.509288 0.319242 0.5 0.350256 0.506963 0.321733 0.508119 0.320579 0.5 0.350256 0.505813 0.322713 0.506963 0.321733 0.5 0.350256 0.504653 0.323527 0.505813 0.322713 0.5 0.350256 0.503483 0.324169 0.504653 0.323527 0.5 0.350256 0.50229 0.324633 0.503483 0.324169 0.5 0.350256 0.501097 0.324907 0.50229 0.324633 0.5 0.350256 0.5 0.358871 0.5 0.350256 0.512094 0.350708 0.5 0.358871 0.476394 0.36073 0.5 0.350256 0.5 0.05292898 0.5 0.324989 0.498904 0.324907 0.535128 0.05317091 0.501097 0.324907 0.5 0.324989 0.535128 0.05317091 0.5 0.324989 0.5 0.05292898 0.5 0.05292898 0.498904 0.324907 0.497711 0.324634 0.5 0.05292898 0.497711 0.324634 0.496518 0.324169 0.5 0.05292898 0.496518 0.324169 0.495351 0.323529 0.464872 0.05317091 0.495351 0.323529 0.494192 0.322717 0.464872 0.05317091 0.5 0.05292898 0.495351 0.323529 0.464872 0.05317091 0.494192 0.322717 0.493042 0.321738 0.464872 0.05317091 0.493042 0.321738 0.491888 0.320587 0.464872 0.05317091 0.491888 0.320587 0.49072 0.319251 0.431408 0.05385088 0.49072 0.319251 0.489527 0.317717 0.431408 0.05385088 0.464872 0.05317091 0.49072 0.319251 0.431408 0.05385088 0.489527 0.317717 0.488301 0.315965 0.431408 0.05385088 0.488301 0.315965 0.487031 0.313968 0.431408 0.05385088 0.487031 0.313968 0.485707 0.311699 0.400963 0.05484998 0.485707 0.311699 0.48432 0.309124 0.400963 0.05484998 0.431408 0.05385088 0.485707 0.311699 0.400963 0.05484998 0.48432 0.309124 0.482857 0.3062 0.400963 0.05484998 0.482857 0.3062 0.481306 0.30288 0.400963 0.05484998 0.481306 0.30288 0.479653 0.299107 0.374421 0.0559979 0.479653 0.299107 0.477878 0.294812 0.374421 0.0559979 0.400963 0.05484998 0.479653 0.299107 0.374421 0.0559979 0.477878 0.294812 0.475962 0.289913 0.374421 0.0559979 0.475962 0.289913 0.473879 0.28431 0.352196 0.05711793 0.473879 0.28431 0.471594 0.277881 0.352196 0.05711793 0.374421 0.0559979 0.473879 0.28431 0.352196 0.05711793 0.471594 0.277881 0.469067 0.270476 0.334361 0.05804389 0.469067 0.270476 0.466243 0.261909 0.334361 0.05804389 0.352196 0.05711793 0.469067 0.270476 0.334361 0.05804389 0.466243 0.261909 0.46305 0.251956 0.320793 0.058649 0.46305 0.251956 0.45939 0.240337 0.320793 0.058649 0.334361 0.05804389 0.46305 0.251956 0.320793 0.058649 0.45939 0.240337 0.455122 0.226705 0.311296 0.05884498 0.455122 0.226705 0.450037 0.210623 0.311296 0.05884498 0.320793 0.058649 0.455122 0.226705 0.305683 0.058586 0.450037 0.210623 0.443805 0.19155 0.305683 0.058586 0.311296 0.05884498 0.450037 0.210623 0.318057 0.12516 0.435874 0.168828 0.443805 0.19155 0.303827 0.05786496 0.443805 0.19155 0.435874 0.168828 0.303827 0.05786496 0.305683 0.058586 0.443805 0.19155 0.318057 0.12516 0.42519 0.1416079 0.435874 0.168828 0.305683 0.05671089 0.435874 0.168828 0.42519 0.1416079 0.305683 0.05671089 0.303827 0.05786496 0.435874 0.168828 0.318057 0.12516 0.409538 0.108976 0.42519 0.1416079 0.311296 0.0551809 0.42519 0.1416079 0.409538 0.108976 0.311296 0.0551809 0.305683 0.05671089 0.42519 0.1416079 0.298467 0.111704 0.409538 0.108976 0.318057 0.12516 0.298467 0.111704 0.404601 0.09719598 0.409538 0.108976 0.320793 0.053357 0.409538 0.108976 0.404601 0.09719598 0.320793 0.053357 0.311296 0.0551809 0.409538 0.108976 0.228136 0.138631 0.318057 0.12516 0.252422 0.149394 0.228136 0.138631 0.298467 0.111704 0.318057 0.12516 0.18295 0.170279 0.252422 0.149394 0.207285 0.17842 0.18295 0.170279 0.228136 0.138631 0.252422 0.149394 0.18295 0.170279 0.207285 0.17842 0.176021 0.210251 0.153093 0.2044579 0.176021 0.210251 0.153909 0.243778 0.153093 0.2044579 0.18295 0.170279 0.176021 0.210251 0.132639 0.240079 0.153909 0.243778 0.137969 0.278376 0.132639 0.240079 0.153093 0.2044579 0.153909 0.243778 0.1653 0.319117 0.126354 0.313674 0.137969 0.278376 0.118225 0.276575 0.137969 0.278376 0.126354 0.313674 0.1967419 0.326279 0.1653 0.319117 0.137969 0.278376 0.222082 0.333923 0.1967419 0.326279 0.137969 0.278376 0.242623 0.341438 0.222082 0.333923 0.137969 0.278376 0.118225 0.276575 0.132639 0.240079 0.137969 0.278376 0.05599099 0.304626 0.126354 0.313674 0.1653 0.319117 0.1121 0.313201 0.118225 0.276575 0.126354 0.313674 0.054937 0.306901 0.1121 0.313201 0.126354 0.313674 0.05599099 0.304626 0.054937 0.306901 0.126354 0.313674 0.05704993 0.303026 0.1653 0.319117 0.1967419 0.326279 0.05704993 0.303026 0.05599099 0.304626 0.1653 0.319117 0.05808293 0.302169 0.1967419 0.326279 0.222082 0.333923 0.05808293 0.302169 0.05704993 0.303026 0.1967419 0.326279 0.05905896 0.302109 0.222082 0.333923 0.242623 0.341438 0.05905896 0.302109 0.05808293 0.302169 0.222082 0.333923 0.05994492 0.302888 0.242623 0.341438 0.259378 0.348525 0.05994492 0.302888 0.05905896 0.302109 0.242623 0.341438 0.05994492 0.302888 0.259378 0.348525 0.273155 0.355064 0.06070894 0.304527 0.273155 0.355064 0.284576 0.361028 0.06070894 0.304527 0.05994492 0.302888 0.273155 0.355064 0.06070894 0.304527 0.284576 0.361028 0.294114 0.366437 0.06132197 0.307023 0.294114 0.366437 0.302132 0.371328 0.06132197 0.307023 0.06070894 0.304527 0.294114 0.366437 0.06132197 0.307023 0.302132 0.371328 0.308912 0.375748 0.06175798 0.310343 0.308912 0.375748 0.314675 0.379746 0.06175798 0.310343 0.06132197 0.307023 0.308912 0.375748 0.06175798 0.310343 0.314675 0.379746 0.319595 0.383368 0.06175798 0.310343 0.319595 0.383368 0.32381 0.386657 0.06199896 0.314422 0.32381 0.386657 0.32743 0.389651 0.06199896 0.314422 0.06175798 0.310343 0.32381 0.386657 0.06199896 0.314422 0.32743 0.389651 0.330545 0.392383 0.06199896 0.314422 0.330545 0.392383 0.333225 0.394883 0.06199896 0.314422 0.333225 0.394883 0.335529 0.397176 0.06203293 0.31916 0.335529 0.397176 0.337506 0.399285 0.06203293 0.31916 0.06199896 0.314422 0.335529 0.397176 0.06203293 0.31916 0.337506 0.399285 0.339197 0.401232 0.06203293 0.31916 0.339197 0.401232 0.340634 0.403035 0.06203293 0.31916 0.340634 0.403035 0.341846 0.404709 0.06186091 0.324424 0.341846 0.404709 0.342854 0.406272 0.06186091 0.324424 0.06203293 0.31916 0.341846 0.404709 0.06186091 0.324424 0.342854 0.406272 0.343676 0.407736 0.06186091 0.324424 0.343676 0.407736 0.344324 0.409115 0.06186091 0.324424 0.344324 0.409115 0.344806 0.410418 0.06148797 0.330053 0.344806 0.410418 0.345123 0.411659 0.06148797 0.330053 0.06186091 0.324424 0.344806 0.410418 0.06148797 0.330053 0.345123 0.411659 0.345272 0.412835 0.06148797 0.330053 0.345272 0.412835 0.345244 0.413952 0.06148797 0.330053 0.345244 0.413952 0.345036 0.414985 0.06148797 0.330053 0.345036 0.414985 0.344685 0.415861 0.06093198 0.335862 0.344685 0.415861 0.34418 0.416663 0.06148797 0.330053 0.344685 0.415861 0.06093198 0.335862 0.06093198 0.335862 0.34418 0.416663 0.343461 0.417452 0.06093198 0.335862 0.343461 0.417452 0.342563 0.418156 0.06093198 0.335862 0.342563 0.418156 0.341513 0.41876 0.06021493 0.341658 0.341513 0.41876 0.340308 0.419278 0.06021493 0.341658 0.06093198 0.335862 0.341513 0.41876 0.06021493 0.341658 0.340308 0.419278 0.338953 0.419712 0.06021493 0.341658 0.338953 0.419712 0.337438 0.420069 0.06021493 0.341658 0.337438 0.420069 0.335749 0.420351 0.05936592 0.347246 0.335749 0.420351 0.333869 0.420558 0.05936592 0.347246 0.06021493 0.341658 0.335749 0.420351 0.05936592 0.347246 0.333869 0.420558 0.331777 0.420689 0.05936592 0.347246 0.331777 0.420689 0.329444 0.420738 0.05936592 0.347246 0.329444 0.420738 0.326842 0.420699 0.05841588 0.352444 0.326842 0.420699 0.323936 0.420564 0.05841588 0.352444 0.05936592 0.347246 0.326842 0.420699 0.05841588 0.352444 0.323936 0.420564 0.320682 0.42032 0.05841588 0.352444 0.320682 0.42032 0.317033 0.419954 0.05841588 0.352444 0.317033 0.419954 0.31293 0.41945 0.05739796 0.357093 0.31293 0.41945 0.308305 0.418788 0.05739796 0.357093 0.05841588 0.352444 0.31293 0.41945 0.05739796 0.357093 0.308305 0.418788 0.303074 0.417942 0.05739796 0.357093 0.303074 0.417942 0.297136 0.416884 0.05634492 0.361064 0.297136 0.416884 0.290366 0.415575 0.05634492 0.361064 0.05739796 0.357093 0.297136 0.416884 0.05634492 0.361064 0.290366 0.415575 0.282609 0.413973 0.05528599 0.364262 0.282609 0.413973 0.273677 0.412023 0.05528599 0.364262 0.05634492 0.361064 0.282609 0.413973 0.05528599 0.364262 0.273677 0.412023 0.263334 0.409661 0.05425 0.366626 0.263334 0.409661 0.251287 0.406807 0.05425 0.366626 0.05528599 0.364262 0.263334 0.409661 0.05425 0.366626 0.251287 0.406807 0.237166 0.40337 0.05325895 0.368128 0.237166 0.40337 0.220499 0.399238 0.05325895 0.368128 0.05425 0.366626 0.237166 0.40337 0.05233395 0.368768 0.220499 0.399238 0.200685 0.394277 0.05233395 0.368768 0.05325895 0.368128 0.220499 0.399238 0.109044 0.408889 0.176975 0.388339 0.200685 0.394277 0.05149191 0.368572 0.200685 0.394277 0.176975 0.388339 0.05149191 0.368572 0.05233395 0.368768 0.200685 0.394277 0.109044 0.408889 0.148377 0.381224 0.176975 0.388339 0.05074691 0.367583 0.176975 0.388339 0.148377 0.381224 0.05074691 0.367583 0.05149191 0.368572 0.176975 0.388339 0.109044 0.408889 0.113774 0.37266 0.148377 0.381224 0.05010789 0.365862 0.148377 0.381224 0.113774 0.37266 0.05010789 0.365862 0.05074691 0.367583 0.148377 0.381224 0.09362095 0.405221 0.113774 0.37266 0.109044 0.408889 0.09362095 0.405221 0.101465 0.369008 0.113774 0.37266 0.04958397 0.363475 0.113774 0.37266 0.101465 0.369008 0.04958397 0.363475 0.05010789 0.365862 0.113774 0.37266 0.09087496 0.443085 0.109044 0.408889 0.10606 0.445275 0.09087496 0.443085 0.09362095 0.405221 0.109044 0.408889 0.08954995 0.481021 0.10606 0.445275 0.104616 0.481749 0.08954995 0.481021 0.09087496 0.443085 0.10606 0.445275 0.08954995 0.481021 0.104616 0.481749 0.104616 0.518251 0.08954995 0.518979 0.104616 0.518251 0.10606 0.554725 0.08954995 0.518979 0.08954995 0.481021 0.104616 0.518251 0.09087496 0.556915 0.10606 0.554725 0.109044 0.591111 0.09087496 0.556915 0.08954995 0.518979 0.10606 0.554725 0.148292 0.618797 0.113774 0.62734 0.109044 0.591111 0.09362095 0.594779 0.109044 0.591111 0.113774 0.62734 0.176846 0.611693 0.148292 0.618797 0.109044 0.591111 0.200554 0.605755 0.176846 0.611693 0.109044 0.591111 0.220382 0.600791 0.200554 0.605755 0.109044 0.591111 0.09362095 0.594779 0.09087496 0.556915 0.109044 0.591111 0.05010789 0.634138 0.113774 0.62734 0.148292 0.618797 0.101465 0.630992 0.09362095 0.594779 0.113774 0.62734 0.04958397 0.636525 0.101465 0.630992 0.113774 0.62734 0.05010789 0.634138 0.04958397 0.636525 0.113774 0.62734 0.05074691 0.632417 0.148292 0.618797 0.176846 0.611693 0.05074691 0.632417 0.05010789 0.634138 0.148292 0.618797 0.05149191 0.631428 0.176846 0.611693 0.200554 0.605755 0.05149191 0.631428 0.05074691 0.632417 0.176846 0.611693 0.05233395 0.631232 0.200554 0.605755 0.220382 0.600791 0.05233395 0.631232 0.05149191 0.631428 0.200554 0.605755 0.05325895 0.631872 0.220382 0.600791 0.237063 0.596655 0.05325895 0.631872 0.05233395 0.631232 0.220382 0.600791 0.05325895 0.631872 0.237063 0.596655 0.251195 0.593215 0.05425 0.633374 0.251195 0.593215 0.263251 0.590359 0.05425 0.633374 0.05325895 0.631872 0.251195 0.593215 0.05425 0.633374 0.263251 0.590359 0.273602 0.587993 0.05528599 0.635738 0.273602 0.587993 0.282542 0.586041 0.05528599 0.635738 0.05425 0.633374 0.273602 0.587993 0.05528599 0.635738 0.282542 0.586041 0.290305 0.584437 0.05634492 0.638936 0.290305 0.584437 0.297081 0.583127 0.05634492 0.638936 0.05528599 0.635738 0.290305 0.584437 0.05634492 0.638936 0.297081 0.583127 0.303025 0.582066 0.05634492 0.638936 0.303025 0.582066 0.30826 0.581219 0.05739796 0.642907 0.30826 0.581219 0.31289 0.580555 0.05739796 0.642907 0.05634492 0.638936 0.30826 0.581219 0.05739796 0.642907 0.31289 0.580555 0.316997 0.58005 0.05739796 0.642907 0.316997 0.58005 0.32065 0.579683 0.05739796 0.642907 0.32065 0.579683 0.323908 0.579438 0.05841588 0.647556 0.323908 0.579438 0.326817 0.579302 0.05841588 0.647556 0.05739796 0.642907 0.323908 0.579438 0.05841588 0.647556 0.326817 0.579302 0.329423 0.579262 0.05841588 0.647556 0.329423 0.579262 0.331759 0.579311 0.05841588 0.647556 0.331759 0.579311 0.333854 0.57944 0.05936592 0.652754 0.333854 0.57944 0.335737 0.579648 0.05936592 0.652754 0.05841588 0.647556 0.333854 0.57944 0.05936592 0.652754 0.335737 0.579648 0.337429 0.579929 0.05936592 0.652754 0.337429 0.579929 0.338946 0.580286 0.05936592 0.652754 0.338946 0.580286 0.340303 0.58072 0.06021493 0.658342 0.340303 0.58072 0.34151 0.581239 0.06021493 0.658342 0.05936592 0.652754 0.340303 0.58072 0.06021493 0.658342 0.34151 0.581239 0.342562 0.581844 0.06021493 0.658342 0.342562 0.581844 0.34346 0.582547 0.06021493 0.658342 0.34346 0.582547 0.34418 0.583337 0.06021493 0.658342 0.34418 0.583337 0.344685 0.584139 0.06093198 0.664138 0.344685 0.584139 0.345035 0.585014 0.06021493 0.658342 0.344685 0.584139 0.06093198 0.664138 0.06093198 0.664138 0.345035 0.585014 0.345244 0.586047 0.06093198 0.664138 0.345244 0.586047 0.345272 0.587164 0.06093198 0.664138 0.345272 0.587164 0.345124 0.588337 0.06148797 0.669947 0.345124 0.588337 0.344807 0.589577 0.06148797 0.669947 0.06093198 0.664138 0.345124 0.588337 0.06148797 0.669947 0.344807 0.589577 0.344327 0.590879 0.06148797 0.669947 0.344327 0.590879 0.34368 0.592256 0.06148797 0.669947 0.34368 0.592256 0.34286 0.593718 0.06186091 0.675576 0.34286 0.593718 0.341854 0.595279 0.06186091 0.675576 0.06148797 0.669947 0.34286 0.593718 0.06186091 0.675576 0.341854 0.595279 0.340645 0.596951 0.06186091 0.675576 0.340645 0.596951 0.33921 0.598752 0.06186091 0.675576 0.33921 0.598752 0.337522 0.600697 0.06203293 0.68084 0.337522 0.600697 0.335548 0.602804 0.06203293 0.68084 0.06186091 0.675576 0.337522 0.600697 0.06203293 0.68084 0.335548 0.602804 0.333248 0.605095 0.06203293 0.68084 0.333248 0.605095 0.330571 0.607593 0.06203293 0.68084 0.330571 0.607593 0.327461 0.610323 0.06199896 0.685578 0.327461 0.610323 0.323845 0.613315 0.06199896 0.685578 0.06203293 0.68084 0.327461 0.610323 0.06199896 0.685578 0.323845 0.613315 0.319635 0.616601 0.06199896 0.685578 0.319635 0.616601 0.314721 0.620221 0.06175798 0.689657 0.314721 0.620221 0.308965 0.624217 0.06175798 0.689657 0.06199896 0.685578 0.314721 0.620221 0.06175798 0.689657 0.308965 0.624217 0.302193 0.628634 0.06132197 0.692977 0.302193 0.628634 0.294182 0.633523 0.06132197 0.692977 0.06175798 0.689657 0.302193 0.628634 0.06132197 0.692977 0.294182 0.633523 0.284653 0.638929 0.06070894 0.695473 0.284653 0.638929 0.273243 0.644892 0.06070894 0.695473 0.06132197 0.692977 0.284653 0.638929 0.06070894 0.695473 0.273243 0.644892 0.259479 0.65143 0.05994492 0.697112 0.259479 0.65143 0.242742 0.658515 0.05994492 0.697112 0.06070894 0.695473 0.259479 0.65143 0.05905896 0.697891 0.242742 0.658515 0.222219 0.666031 0.05905896 0.697891 0.05994492 0.697112 0.242742 0.658515 0.132754 0.707196 0.196882 0.673684 0.222219 0.666031 0.05808293 0.697831 0.222219 0.666031 0.196882 0.673684 0.05808293 0.697831 0.05905896 0.697891 0.222219 0.666031 0.132754 0.707196 0.165394 0.680865 0.196882 0.673684 0.05704993 0.696974 0.196882 0.673684 0.165394 0.680865 0.05704993 0.696974 0.05808293 0.697831 0.196882 0.673684 0.132754 0.707196 0.126354 0.686326 0.165394 0.680865 0.05599099 0.695374 0.165394 0.680865 0.126354 0.686326 0.05599099 0.695374 0.05704993 0.696974 0.165394 0.680865 0.1121 0.686799 0.126354 0.686326 0.132754 0.707196 0.054937 0.693099 0.126354 0.686326 0.1121 0.686799 0.054937 0.693099 0.05599099 0.695374 0.126354 0.686326 0.1186259 0.724637 0.132754 0.707196 0.140457 0.727862 0.107634 0.686537 0.1121 0.686799 0.132754 0.707196 0.1186259 0.724637 0.107634 0.686537 0.132754 0.707196 0.139297 0.727973 0.140457 0.727862 0.289328 0.694466 0.139297 0.727973 0.138126 0.728074 0.140457 0.727862 0.1186259 0.724637 0.140457 0.727862 0.138126 0.728074 0.283853 0.06577199 0 0.04166793 1 0 1 0.04166793 1 0 0 0.04166793 0.5 0.05103695 0.283853 0.06577199 1 0 1 0.04166793 0.5 0.05103695 1 0 0.177775 0.097413 0 0.08333098 0 0.04166793 1 0.04166793 0 0.04166793 0 0.08333098 0.283853 0.06577199 0.177775 0.097413 0 0.04166793 0.127274 0.134515 0 0.125003 0 0.08333098 1 0.08333098 0 0.08333098 0 0.125003 0.177775 0.097413 0.127274 0.134515 0 0.08333098 1 0.04166793 0 0.08333098 1 0.08333098 0.099577 0.173608 0 0.166664 0 0.125003 0.176712 0 0 0.125003 0 0.166664 0.127274 0.134515 0.099577 0.173608 0 0.125003 1 0.08333098 0 0.125003 1 0.125003 0.176712 0 1 0.125003 0 0.125003 0.08265399 0.213598 0 0.208335 0 0.166664 0 0.01679295 0 0.166664 0 0.208335 0.099577 0.173608 0.08265399 0.213598 0 0.166664 0 0.005507946 0.176712 0 0 0.166664 0 0.01044088 0 0.005507946 0 0.166664 0 0.014256 0 0.01044088 0 0.166664 0 0.01648592 0 0.014256 0 0.166664 0 0.01679295 0 0.01648592 0 0.166664 0.07157099 0.254057 0 0.25 0 0.208335 0 0.09827399 0 0.208335 0 0.25 0.08265399 0.213598 0.07157099 0.254057 0 0.208335 0 0.01503288 0 0.01679295 0 0.208335 0 0.07996296 0 0.01503288 0 0.208335 0 0.086703 0 0.07996296 0 0.208335 0 0.093059 0 0.086703 0 0.208335 0 0.09827399 0 0.093059 0 0.208335 0.06400996 0.294788 0 0.291665 0 0.25 0 0.156387 0 0.25 0 0.291665 0.07157099 0.254057 0.06400996 0.294788 0 0.25 0 0.101663 0 0.09827399 0 0.25 0 0.1034049 0 0.101663 0 0.25 0 0.106204 0 0.1034049 0 0.25 0 0.109592 0 0.106204 0 0.25 0 0.132984 0 0.109592 0 0.25 0 0.156387 0 0.132984 0 0.25 0.05876588 0.335686 0 0.333336 0 0.291665 0 0.226597 0 0.291665 0 0.333336 0.06400996 0.294788 0.05876588 0.335686 0 0.291665 0 0.179791 0 0.156387 0 0.291665 0 0.203194 0 0.179791 0 0.291665 0 0.226597 0 0.203194 0 0.291665 0.05516093 0.376689 0 0.374997 0 0.333336 0 0.322892 0 0.333336 0 0.374997 0.05876588 0.335686 0.05516093 0.376689 0 0.333336 0 0.322892 0 0.319077 0 0.333336 0 0.273404 0 0.333336 0 0.319077 0 0.25 0 0.226597 0 0.333336 0 0.273404 0 0.25 0 0.333336 0.05280488 0.41776 0 0.416669 0 0.374997 0 0.343613 0 0.374997 0 0.416669 0.05516093 0.376689 0.05280488 0.41776 0 0.374997 0 0.338841 0 0.333333 0 0.374997 0 0.327825 0 0.374997 0 0.333333 0 0.343774 0 0.338841 0 0.374997 0 0.34759 0 0.343774 0 0.374997 0 0.34982 0 0.34759 0 0.374997 0 0.350126 0 0.34982 0 0.374997 0 0.348366 0 0.350126 0 0.374997 0 0.343613 0 0.348366 0 0.374997 0 0.327825 0 0.322892 0 0.374997 0.05146998 0.458871 0 0.458332 0 0.416669 0 0.401726 0 0.416669 0 0.458332 0.05280488 0.41776 0.05146998 0.458871 0 0.416669 0 0.367016 0 0.343613 0 0.416669 0 0.390408 0 0.367016 0 0.416669 0 0.393796 0 0.390408 0 0.416669 0 0.396595 0 0.393796 0 0.416669 0 0.401726 0 0.396595 0 0.416669 0.05103695 0.5 0 0.5 0 0.458332 0 0.466317 0 0.458332 0 0.5 0.05146998 0.458871 0.05103695 0.5 0 0.458332 0 0.40694 0 0.401726 0 0.458332 0 0.413296 0 0.40694 0 0.458332 0 0.420036 0 0.413296 0 0.458332 0 0.426392 0 0.420036 0 0.458332 0 0.431608 0 0.426392 0 0.458332 0 0.434996 0 0.431608 0 0.458332 0 0.436739 0 0.434996 0 0.458332 0 0.439537 0 0.436739 0 0.458332 0 0.442925 0 0.439537 0 0.458332 0 0.466317 0 0.442925 0 0.458332 0.05146998 0.541129 0 0.541668 0 0.5 0 0.502595 0 0.5 0 0.541668 0.05103695 0.5 0.05146998 0.541129 0 0.5 0 0.488369 0 0.485528 0 0.5 0 0.466317 0 0.5 0 0.485528 0 0.492486 0 0.488369 0 0.5 0 0.497405 0 0.492486 0 0.5 0 0.502595 0 0.497405 0 0.5 0.05280488 0.58224 0 0.583331 0 0.541668 0 0.559929 0 0.541668 0 0.583331 0.05146998 0.541129 0.05280488 0.58224 0 0.541668 0 0.507514 0 0.502595 0 0.541668 0 0.511631 0 0.507514 0 0.541668 0 0.514472 0 0.511631 0 0.541668 0 0.515658 0 0.514472 0 0.541668 0 0.536526 0 0.515658 0 0.541668 0 0.559929 0 0.536526 0 0.541668 0.05516093 0.623311 0 0.625003 0 0.583331 0 0.606736 0 0.583331 0 0.625003 0.05280488 0.58224 0.05516093 0.623311 0 0.583331 0 0.583332 0 0.559929 0 0.583331 0 0.606736 0 0.583332 0 0.583331 0.05876588 0.664314 0 0.666664 0 0.625003 0 0.65018 0 0.625003 0 0.666664 0.05516093 0.623311 0.05876588 0.664314 0 0.625003 0 0.649874 0 0.651634 0 0.625003 0 0.653542 0 0.625003 0 0.651634 0 0.65018 0 0.649874 0 0.625003 0 0.630139 0 0.606736 0 0.625003 0 0.653542 0 0.630139 0 0.625003 0.06400996 0.705212 0 0.708335 0 0.666664 0 0.723742 0 0.666664 0 0.708335 0.05876588 0.664314 0.06400996 0.705212 0 0.666664 0 0.672175 0 0.666667 0 0.666664 0 0.661159 0 0.666664 0 0.666667 0 0.677108 0 0.672175 0 0.666664 0 0.680923 0 0.677108 0 0.666664 0 0.700349 0 0.680923 0 0.666664 0 0.65241 0 0.65018 0 0.666664 0 0.656226 0 0.65241 0 0.666664 0 0.661159 0 0.656226 0 0.666664 0 0.723742 0 0.700349 0 0.666664 0.07157099 0.745943 0 0.75 0 0.708335 0 0.759726 0 0.708335 0 0.75 0.06400996 0.705212 0.07157099 0.745943 0 0.708335 0 0.727129 0 0.723742 0 0.708335 0 0.729928 0 0.727129 0 0.708335 0 0.73167 0 0.729928 0 0.708335 0 0.735059 0 0.73167 0 0.708335 0 0.740274 0 0.735059 0 0.708335 0 0.746629 0 0.740274 0 0.708335 0 0.75337 0 0.746629 0 0.708335 0 0.759726 0 0.75337 0 0.708335 0.08265399 0.786402 0 0.791665 0 0.75 0 0.869859 0 0.75 0 0.791665 0.07157099 0.745943 0.08265399 0.786402 0 0.75 0 0.764941 0 0.759726 0 0.75 0 0.79965 0 0.764941 0 0.75 0 0.823053 0 0.79965 0 0.75 0 0.846456 0 0.823053 0 0.75 0 0.869859 0 0.846456 0 0.75 0.099577 0.826392 0 0.833336 0 0.791665 0 0.986875 0 0.791665 0 0.833336 0.08265399 0.786402 0.099577 0.826392 0 0.791665 0 0.893262 0 0.869859 0 0.791665 0 0.916665 0 0.893262 0 0.791665 0 0.940069 0 0.916665 0 0.791665 0 0.963472 0 0.940069 0 0.791665 0 0.986875 0 0.963472 0 0.791665 0.127274 0.865485 0 0.874997 0 0.833336 1 0.833336 0 0.833336 0 0.874997 0.099577 0.826392 0.127274 0.865485 0 0.833336 1 0.791665 0 0.833336 1 0.833336 1 0.920037 0 0.833336 1 0.791665 1 0.989721 0 0.986875 0 0.833336 1 0.931608 1 0.989721 0 0.833336 1 0.926393 1 0.931608 0 0.833336 1 0.920037 1 0.926393 0 0.833336 0.177775 0.902587 0 0.916669 0 0.874997 1 0.874997 0 0.874997 0 0.916669 0.127274 0.865485 0.177775 0.902587 0 0.874997 1 0.833336 0 0.874997 1 0.874997 0.283853 0.934228 0 0.958332 0 0.916669 1 0.916669 0 0.916669 0 0.958332 0.177775 0.902587 0.283853 0.934228 0 0.916669 1 0.874997 0 0.916669 1 0.916669 0.5 0.948963 0 1 0 0.958332 1 0.958332 0 0.958332 0 1 0.283853 0.934228 0.5 0.948963 0 0.958332 1 0.916669 0 0.958332 1 0.958332 0.716147 0.934228 0 1 0.5 0.948963 0.716147 0.934228 1 0.958332 0 1 0.5 0.939293 0.5 0.948963 0.283853 0.934228 0.680824 0.926588 0.716147 0.934228 0.5 0.948963 0.680824 0.926588 0.5 0.948963 0.5 0.939293 0.212749 0.899359 0.283853 0.934228 0.177775 0.902587 0.319176 0.926588 0.283853 0.934228 0.212749 0.899359 0.5 0.93828 0.283853 0.934228 0.319176 0.926588 0.5 0.939293 0.283853 0.934228 0.5 0.93828 0.155981 0.865736 0.177775 0.902587 0.127274 0.865485 0.212749 0.899359 0.177775 0.902587 0.155981 0.865736 0.123202 0.829465 0.127274 0.865485 0.099577 0.826392 0.155981 0.865736 0.127274 0.865485 0.123202 0.829465 0.10263 0.79193 0.099577 0.826392 0.08265399 0.786402 0.123202 0.829465 0.099577 0.826392 0.10263 0.79193 0.08892196 0.753714 0.08265399 0.786402 0.07157099 0.745943 0.10263 0.79193 0.08265399 0.786402 0.08892196 0.753714 0.07943099 0.715096 0.07157099 0.745943 0.06400996 0.705212 0.08892196 0.753714 0.07157099 0.745943 0.07943099 0.715096 0.07273697 0.676229 0.06400996 0.705212 0.05876588 0.664314 0.07943099 0.715096 0.06400996 0.705212 0.07273697 0.676229 0.06802499 0.637199 0.05876588 0.664314 0.05516093 0.623311 0.07273697 0.676229 0.05876588 0.664314 0.06802499 0.637199 0.064812 0.598064 0.05516093 0.623311 0.05280488 0.58224 0.06802499 0.637199 0.05516093 0.623311 0.064812 0.598064 0.06280499 0.558862 0.05280488 0.58224 0.05146998 0.541129 0.064812 0.598064 0.05280488 0.58224 0.06280499 0.558862 0.06183898 0.519625 0.05146998 0.541129 0.05103695 0.5 0.06280499 0.558862 0.05146998 0.541129 0.06183898 0.519625 0.06183898 0.480375 0.05103695 0.5 0.05146998 0.458871 0.06183898 0.519625 0.05103695 0.5 0.06183898 0.480375 0.06280499 0.441138 0.05146998 0.458871 0.05280488 0.41776 0.06183898 0.480375 0.05146998 0.458871 0.06280499 0.441138 0.064812 0.401936 0.05280488 0.41776 0.05516093 0.376689 0.06280499 0.441138 0.05280488 0.41776 0.064812 0.401936 0.06802499 0.362801 0.05516093 0.376689 0.05876588 0.335686 0.064812 0.401936 0.05516093 0.376689 0.06802499 0.362801 0.07273697 0.323771 0.05876588 0.335686 0.06400996 0.294788 0.06802499 0.362801 0.05876588 0.335686 0.07273697 0.323771 0.07943099 0.284904 0.06400996 0.294788 0.07157099 0.254057 0.07273697 0.323771 0.06400996 0.294788 0.07943099 0.284904 0.08892196 0.246286 0.07157099 0.254057 0.08265399 0.213598 0.07943099 0.284904 0.07157099 0.254057 0.08892196 0.246286 0.10263 0.20807 0.08265399 0.213598 0.099577 0.173608 0.08892196 0.246286 0.08265399 0.213598 0.10263 0.20807 0.123202 0.170535 0.099577 0.173608 0.127274 0.134515 0.10263 0.20807 0.099577 0.173608 0.123202 0.170535 0.155981 0.134264 0.127274 0.134515 0.177775 0.097413 0.123202 0.170535 0.127274 0.134515 0.155981 0.134264 0.212749 0.100641 0.177775 0.097413 0.283853 0.06577199 0.155981 0.134264 0.177775 0.097413 0.212749 0.100641 0.319176 0.073412 0.283853 0.06577199 0.5 0.05103695 0.212749 0.100641 0.283853 0.06577199 0.319176 0.073412 0.716147 0.06577199 0.5 0.05103695 1 0.04166793 0.5 0.0575369 0.5 0.05103695 0.716147 0.06577199 0.5 0.0575369 0.319176 0.073412 0.5 0.05103695 0.613576 0.599763 0.867246 0.707196 0.859543 0.727862 0.860703 0.727973 0.859543 0.727862 0.867246 0.707196 0.605995 0.607817 0.613576 0.599763 0.859543 0.727862 0.710673 0.694466 0.605995 0.607817 0.859543 0.727862 0.804498 0.722377 0.710673 0.694466 0.859543 0.727862 0.860703 0.727973 0.138126 0.728074 0.859543 0.727862 0.821876 0.739791 0.859543 0.727862 0.138126 0.728074 0.812187 0.724104 0.804498 0.722377 0.859543 0.727862 0.818433 0.727007 0.812187 0.724104 0.859543 0.727862 0.822504 0.730852 0.818433 0.727007 0.859543 0.727862 0.823782 0.735278 0.822504 0.730852 0.859543 0.727862 0.821876 0.739791 0.823782 0.735278 0.859543 0.727862 0.8347 0.680883 0.873646 0.686326 0.867246 0.707196 0.881374 0.724637 0.867246 0.707196 0.873646 0.686326 0.803258 0.673721 0.8347 0.680883 0.867246 0.707196 0.777918 0.666077 0.803258 0.673721 0.867246 0.707196 0.757377 0.658562 0.777918 0.666077 0.867246 0.707196 0.620452 0.591201 0.757377 0.658562 0.867246 0.707196 0.613576 0.599763 0.620452 0.591201 0.867246 0.707196 0.861874 0.728074 0.867246 0.707196 0.881374 0.724637 0.861874 0.728074 0.860703 0.727973 0.867246 0.707196 0.944009 0.695374 0.873646 0.686326 0.8347 0.680883 0.8879 0.686799 0.881374 0.724637 0.873646 0.686326 0.945063 0.693099 0.8879 0.686799 0.873646 0.686326 0.944009 0.695374 0.945063 0.693099 0.873646 0.686326 0.94295 0.696974 0.8347 0.680883 0.803258 0.673721 0.94295 0.696974 0.944009 0.695374 0.8347 0.680883 0.941917 0.697831 0.803258 0.673721 0.777918 0.666077 0.941917 0.697831 0.94295 0.696974 0.803258 0.673721 0.940941 0.697891 0.777918 0.666077 0.757377 0.658562 0.940941 0.697891 0.941917 0.697831 0.777918 0.666077 0.620452 0.591201 0.740622 0.651475 0.757377 0.658562 0.940055 0.697112 0.757377 0.658562 0.740622 0.651475 0.940055 0.697112 0.940941 0.697891 0.757377 0.658562 0.620452 0.591201 0.726845 0.644936 0.740622 0.651475 0.940055 0.697112 0.740622 0.651475 0.726845 0.644936 0.620452 0.591201 0.715424 0.638972 0.726845 0.644936 0.939291 0.695473 0.726845 0.644936 0.715424 0.638972 0.939291 0.695473 0.940055 0.697112 0.726845 0.644936 0.620452 0.591201 0.705886 0.633563 0.715424 0.638972 0.939291 0.695473 0.715424 0.638972 0.705886 0.633563 0.626612 0.582186 0.697868 0.628672 0.705886 0.633563 0.938678 0.692977 0.705886 0.633563 0.697868 0.628672 0.620452 0.591201 0.626612 0.582186 0.705886 0.633563 0.938678 0.692977 0.939291 0.695473 0.705886 0.633563 0.626612 0.582186 0.691088 0.624252 0.697868 0.628672 0.938678 0.692977 0.697868 0.628672 0.691088 0.624252 0.626612 0.582186 0.685325 0.620254 0.691088 0.624252 0.938242 0.689657 0.691088 0.624252 0.685325 0.620254 0.938242 0.689657 0.938678 0.692977 0.691088 0.624252 0.626612 0.582186 0.680405 0.616632 0.685325 0.620254 0.938242 0.689657 0.685325 0.620254 0.680405 0.616632 0.626612 0.582186 0.67619 0.613343 0.680405 0.616632 0.938242 0.689657 0.680405 0.616632 0.67619 0.613343 0.626612 0.582186 0.67257 0.610349 0.67619 0.613343 0.938001 0.685578 0.67619 0.613343 0.67257 0.610349 0.938001 0.685578 0.938242 0.689657 0.67619 0.613343 0.626612 0.582186 0.669455 0.607617 0.67257 0.610349 0.938001 0.685578 0.67257 0.610349 0.669455 0.607617 0.626612 0.582186 0.666775 0.605117 0.669455 0.607617 0.938001 0.685578 0.669455 0.607617 0.666775 0.605117 0.626612 0.582186 0.664471 0.602824 0.666775 0.605117 0.938001 0.685578 0.666775 0.605117 0.664471 0.602824 0.632045 0.572772 0.662494 0.600715 0.664471 0.602824 0.937967 0.68084 0.664471 0.602824 0.662494 0.600715 0.626612 0.582186 0.632045 0.572772 0.664471 0.602824 0.937967 0.68084 0.938001 0.685578 0.664471 0.602824 0.632045 0.572772 0.660803 0.598768 0.662494 0.600715 0.937967 0.68084 0.662494 0.600715 0.660803 0.598768 0.632045 0.572772 0.659366 0.596965 0.660803 0.598768 0.937967 0.68084 0.660803 0.598768 0.659366 0.596965 0.632045 0.572772 0.658154 0.595291 0.659366 0.596965 0.937967 0.68084 0.659366 0.596965 0.658154 0.595291 0.632045 0.572772 0.657146 0.593728 0.658154 0.595291 0.938139 0.675576 0.658154 0.595291 0.657146 0.593728 0.938139 0.675576 0.937967 0.68084 0.658154 0.595291 0.632045 0.572772 0.656324 0.592264 0.657146 0.593728 0.938139 0.675576 0.657146 0.593728 0.656324 0.592264 0.632045 0.572772 0.655676 0.590885 0.656324 0.592264 0.938139 0.675576 0.656324 0.592264 0.655676 0.590885 0.632045 0.572772 0.655194 0.589582 0.655676 0.590885 0.938139 0.675576 0.655676 0.590885 0.655194 0.589582 0.632045 0.572772 0.654877 0.588341 0.655194 0.589582 0.938512 0.669947 0.655194 0.589582 0.654877 0.588341 0.938512 0.669947 0.938139 0.675576 0.655194 0.589582 0.632045 0.572772 0.654728 0.587165 0.654877 0.588341 0.938512 0.669947 0.654877 0.588341 0.654728 0.587165 0.632045 0.572772 0.654756 0.586048 0.654728 0.587165 0.938512 0.669947 0.654728 0.587165 0.654756 0.586048 0.632045 0.572772 0.654964 0.585015 0.654756 0.586048 0.938512 0.669947 0.654756 0.586048 0.654964 0.585015 0.632045 0.572772 0.655315 0.584139 0.654964 0.585015 0.938512 0.669947 0.654964 0.585015 0.655315 0.584139 0.636751 0.563012 0.65582 0.583337 0.655315 0.584139 0.939068 0.664138 0.655315 0.584139 0.65582 0.583337 0.632045 0.572772 0.636751 0.563012 0.655315 0.584139 0.938512 0.669947 0.655315 0.584139 0.939068 0.664138 0.636751 0.563012 0.656539 0.582548 0.65582 0.583337 0.939068 0.664138 0.65582 0.583337 0.656539 0.582548 0.636751 0.563012 0.657437 0.581844 0.656539 0.582548 0.939068 0.664138 0.656539 0.582548 0.657437 0.581844 0.636751 0.563012 0.658487 0.58124 0.657437 0.581844 0.939068 0.664138 0.657437 0.581844 0.658487 0.58124 0.636751 0.563012 0.659692 0.580722 0.658487 0.58124 0.939785 0.658342 0.658487 0.58124 0.659692 0.580722 0.939785 0.658342 0.939068 0.664138 0.658487 0.58124 0.636751 0.563012 0.661047 0.580288 0.659692 0.580722 0.939785 0.658342 0.659692 0.580722 0.661047 0.580288 0.636751 0.563012 0.662562 0.579931 0.661047 0.580288 0.939785 0.658342 0.661047 0.580288 0.662562 0.579931 0.636751 0.563012 0.664251 0.579649 0.662562 0.579931 0.939785 0.658342 0.662562 0.579931 0.664251 0.579649 0.636751 0.563012 0.666131 0.579442 0.664251 0.579649 0.940634 0.652754 0.664251 0.579649 0.666131 0.579442 0.940634 0.652754 0.939785 0.658342 0.664251 0.579649 0.636751 0.563012 0.668223 0.579311 0.666131 0.579442 0.940634 0.652754 0.666131 0.579442 0.668223 0.579311 0.636751 0.563012 0.670556 0.579262 0.668223 0.579311 0.940634 0.652754 0.668223 0.579311 0.670556 0.579262 0.636751 0.563012 0.673158 0.579301 0.670556 0.579262 0.940634 0.652754 0.670556 0.579262 0.673158 0.579301 0.636751 0.563012 0.676064 0.579436 0.673158 0.579301 0.941584 0.647556 0.673158 0.579301 0.676064 0.579436 0.941584 0.647556 0.940634 0.652754 0.673158 0.579301 0.636751 0.563012 0.679318 0.57968 0.676064 0.579436 0.941584 0.647556 0.676064 0.579436 0.679318 0.57968 0.640728 0.552957 0.682967 0.580046 0.679318 0.57968 0.941584 0.647556 0.679318 0.57968 0.682967 0.580046 0.636751 0.563012 0.640728 0.552957 0.679318 0.57968 0.640728 0.552957 0.68707 0.58055 0.682967 0.580046 0.941584 0.647556 0.682967 0.580046 0.68707 0.58055 0.640728 0.552957 0.691695 0.581212 0.68707 0.58055 0.942602 0.642907 0.68707 0.58055 0.691695 0.581212 0.942602 0.642907 0.941584 0.647556 0.68707 0.58055 0.640728 0.552957 0.696926 0.582058 0.691695 0.581212 0.942602 0.642907 0.691695 0.581212 0.696926 0.582058 0.640728 0.552957 0.702864 0.583116 0.696926 0.582058 0.942602 0.642907 0.696926 0.582058 0.702864 0.583116 0.640728 0.552957 0.709634 0.584425 0.702864 0.583116 0.943655 0.638936 0.702864 0.583116 0.709634 0.584425 0.943655 0.638936 0.942602 0.642907 0.702864 0.583116 0.640728 0.552957 0.717391 0.586027 0.709634 0.584425 0.943655 0.638936 0.709634 0.584425 0.717391 0.586027 0.640728 0.552957 0.726323 0.587977 0.717391 0.586027 0.944714 0.635738 0.717391 0.586027 0.726323 0.587977 0.944714 0.635738 0.943655 0.638936 0.717391 0.586027 0.640728 0.552957 0.736666 0.590339 0.726323 0.587977 0.944714 0.635738 0.726323 0.587977 0.736666 0.590339 0.640728 0.552957 0.748713 0.593193 0.736666 0.590339 0.94575 0.633374 0.736666 0.590339 0.748713 0.593193 0.94575 0.633374 0.944714 0.635738 0.736666 0.590339 0.640728 0.552957 0.762834 0.59663 0.748713 0.593193 0.94575 0.633374 0.748713 0.593193 0.762834 0.59663 0.640728 0.552957 0.779501 0.600762 0.762834 0.59663 0.946741 0.631872 0.762834 0.59663 0.779501 0.600762 0.946741 0.631872 0.94575 0.633374 0.762834 0.59663 0.640728 0.552957 0.799315 0.605723 0.779501 0.600762 0.947666 0.631232 0.779501 0.600762 0.799315 0.605723 0.947666 0.631232 0.946741 0.631872 0.779501 0.600762 0.890956 0.591111 0.823025 0.611661 0.799315 0.605723 0.948508 0.631428 0.799315 0.605723 0.823025 0.611661 0.640728 0.552957 0.890956 0.591111 0.799315 0.605723 0.948508 0.631428 0.947666 0.631232 0.799315 0.605723 0.890956 0.591111 0.851623 0.618776 0.823025 0.611661 0.949253 0.632417 0.823025 0.611661 0.851623 0.618776 0.949253 0.632417 0.948508 0.631428 0.823025 0.611661 0.890956 0.591111 0.886226 0.62734 0.851623 0.618776 0.949892 0.634138 0.851623 0.618776 0.886226 0.62734 0.949892 0.634138 0.949253 0.632417 0.851623 0.618776 0.906379 0.594779 0.886226 0.62734 0.890956 0.591111 0.906379 0.594779 0.898535 0.630992 0.886226 0.62734 0.950416 0.636525 0.886226 0.62734 0.898535 0.630992 0.950416 0.636525 0.949892 0.634138 0.886226 0.62734 0.646503 0.53216 0.89394 0.554725 0.890956 0.591111 0.909125 0.556915 0.890956 0.591111 0.89394 0.554725 0.643978 0.542657 0.646503 0.53216 0.890956 0.591111 0.640728 0.552957 0.643978 0.542657 0.890956 0.591111 0.909125 0.556915 0.906379 0.594779 0.890956 0.591111 0.649385 0.510783 0.895384 0.518251 0.89394 0.554725 0.91045 0.518979 0.89394 0.554725 0.895384 0.518251 0.648305 0.521519 0.649385 0.510783 0.89394 0.554725 0.646503 0.53216 0.648305 0.521519 0.89394 0.554725 0.91045 0.518979 0.909125 0.556915 0.89394 0.554725 0.649744 0.5 0.895384 0.481749 0.895384 0.518251 0.91045 0.518979 0.895384 0.518251 0.895384 0.481749 0.649385 0.510783 0.649744 0.5 0.895384 0.518251 0.648305 0.478481 0.89394 0.445275 0.895384 0.481749 0.91045 0.481021 0.895384 0.481749 0.89394 0.445275 0.649385 0.489217 0.648305 0.478481 0.895384 0.481749 0.649744 0.5 0.649385 0.489217 0.895384 0.481749 0.91045 0.481021 0.91045 0.518979 0.895384 0.481749 0.643978 0.457343 0.890956 0.408889 0.89394 0.445275 0.909125 0.443085 0.89394 0.445275 0.890956 0.408889 0.646503 0.46784 0.643978 0.457343 0.89394 0.445275 0.648305 0.478481 0.646503 0.46784 0.89394 0.445275 0.909125 0.443085 0.91045 0.481021 0.89394 0.445275 0.851708 0.381203 0.886226 0.37266 0.890956 0.408889 0.906379 0.405221 0.890956 0.408889 0.886226 0.37266 0.823154 0.388307 0.851708 0.381203 0.890956 0.408889 0.799446 0.394245 0.823154 0.388307 0.890956 0.408889 0.779618 0.399209 0.799446 0.394245 0.890956 0.408889 0.640728 0.447043 0.779618 0.399209 0.890956 0.408889 0.643978 0.457343 0.640728 0.447043 0.890956 0.408889 0.906379 0.405221 0.909125 0.443085 0.890956 0.408889 0.949892 0.365862 0.886226 0.37266 0.851708 0.381203 0.898535 0.369008 0.906379 0.405221 0.886226 0.37266 0.950416 0.363475 0.898535 0.369008 0.886226 0.37266 0.949892 0.365862 0.950416 0.363475 0.886226 0.37266 0.949253 0.367583 0.851708 0.381203 0.823154 0.388307 0.949253 0.367583 0.949892 0.365862 0.851708 0.381203 0.948508 0.368572 0.823154 0.388307 0.799446 0.394245 0.948508 0.368572 0.949253 0.367583 0.823154 0.388307 0.947666 0.368768 0.799446 0.394245 0.779618 0.399209 0.947666 0.368768 0.948508 0.368572 0.799446 0.394245 0.640728 0.447043 0.762937 0.403345 0.779618 0.399209 0.946741 0.368128 0.779618 0.399209 0.762937 0.403345 0.946741 0.368128 0.947666 0.368768 0.779618 0.399209 0.640728 0.447043 0.748805 0.406785 0.762937 0.403345 0.946741 0.368128 0.762937 0.403345 0.748805 0.406785 0.640728 0.447043 0.736749 0.409641 0.748805 0.406785 0.94575 0.366626 0.748805 0.406785 0.736749 0.409641 0.94575 0.366626 0.946741 0.368128 0.748805 0.406785 0.640728 0.447043 0.726398 0.412007 0.736749 0.409641 0.94575 0.366626 0.736749 0.409641 0.726398 0.412007 0.636751 0.436988 0.717458 0.413959 0.726398 0.412007 0.944714 0.364262 0.726398 0.412007 0.717458 0.413959 0.640728 0.447043 0.636751 0.436988 0.726398 0.412007 0.944714 0.364262 0.94575 0.366626 0.726398 0.412007 0.636751 0.436988 0.709695 0.415563 0.717458 0.413959 0.944714 0.364262 0.717458 0.413959 0.709695 0.415563 0.636751 0.436988 0.702919 0.416873 0.709695 0.415563 0.943655 0.361064 0.709695 0.415563 0.702919 0.416873 0.943655 0.361064 0.944714 0.364262 0.709695 0.415563 0.636751 0.436988 0.696975 0.417934 0.702919 0.416873 0.943655 0.361064 0.702919 0.416873 0.696975 0.417934 0.636751 0.436988 0.69174 0.418781 0.696975 0.417934 0.943655 0.361064 0.696975 0.417934 0.69174 0.418781 0.636751 0.436988 0.68711 0.419445 0.69174 0.418781 0.942602 0.357093 0.69174 0.418781 0.68711 0.419445 0.942602 0.357093 0.943655 0.361064 0.69174 0.418781 0.636751 0.436988 0.683003 0.41995 0.68711 0.419445 0.942602 0.357093 0.68711 0.419445 0.683003 0.41995 0.636751 0.436988 0.67935 0.420317 0.683003 0.41995 0.942602 0.357093 0.683003 0.41995 0.67935 0.420317 0.636751 0.436988 0.676092 0.420562 0.67935 0.420317 0.942602 0.357093 0.67935 0.420317 0.676092 0.420562 0.632045 0.427228 0.673183 0.420698 0.676092 0.420562 0.941584 0.352444 0.676092 0.420562 0.673183 0.420698 0.636751 0.436988 0.632045 0.427228 0.676092 0.420562 0.941584 0.352444 0.942602 0.357093 0.676092 0.420562 0.632045 0.427228 0.670577 0.420738 0.673183 0.420698 0.941584 0.352444 0.673183 0.420698 0.670577 0.420738 0.632045 0.427228 0.668241 0.420689 0.670577 0.420738 0.941584 0.352444 0.670577 0.420738 0.668241 0.420689 0.632045 0.427228 0.666146 0.42056 0.668241 0.420689 0.941584 0.352444 0.668241 0.420689 0.666146 0.42056 0.632045 0.427228 0.664263 0.420352 0.666146 0.42056 0.940634 0.347246 0.666146 0.42056 0.664263 0.420352 0.940634 0.347246 0.941584 0.352444 0.666146 0.42056 0.632045 0.427228 0.662571 0.420071 0.664263 0.420352 0.940634 0.347246 0.664263 0.420352 0.662571 0.420071 0.632045 0.427228 0.661054 0.419714 0.662571 0.420071 0.940634 0.347246 0.662571 0.420071 0.661054 0.419714 0.632045 0.427228 0.659697 0.41928 0.661054 0.419714 0.940634 0.347246 0.661054 0.419714 0.659697 0.41928 0.632045 0.427228 0.65849 0.418761 0.659697 0.41928 0.939785 0.341658 0.659697 0.41928 0.65849 0.418761 0.939785 0.341658 0.940634 0.347246 0.659697 0.41928 0.632045 0.427228 0.657438 0.418156 0.65849 0.418761 0.939785 0.341658 0.65849 0.418761 0.657438 0.418156 0.632045 0.427228 0.65654 0.417453 0.657438 0.418156 0.939785 0.341658 0.657438 0.418156 0.65654 0.417453 0.632045 0.427228 0.65582 0.416663 0.65654 0.417453 0.939785 0.341658 0.65654 0.417453 0.65582 0.416663 0.632045 0.427228 0.655315 0.415861 0.65582 0.416663 0.939785 0.341658 0.65582 0.416663 0.655315 0.415861 0.626612 0.417814 0.654965 0.414986 0.655315 0.415861 0.939068 0.335862 0.655315 0.415861 0.654965 0.414986 0.632045 0.427228 0.626612 0.417814 0.655315 0.415861 0.939785 0.341658 0.655315 0.415861 0.939068 0.335862 0.626612 0.417814 0.654756 0.413953 0.654965 0.414986 0.939068 0.335862 0.654965 0.414986 0.654756 0.413953 0.626612 0.417814 0.654728 0.412836 0.654756 0.413953 0.939068 0.335862 0.654756 0.413953 0.654728 0.412836 0.626612 0.417814 0.654876 0.411663 0.654728 0.412836 0.939068 0.335862 0.654728 0.412836 0.654876 0.411663 0.626612 0.417814 0.655193 0.410423 0.654876 0.411663 0.938512 0.330053 0.654876 0.411663 0.655193 0.410423 0.938512 0.330053 0.939068 0.335862 0.654876 0.411663 0.626612 0.417814 0.655673 0.409121 0.655193 0.410423 0.938512 0.330053 0.655193 0.410423 0.655673 0.409121 0.626612 0.417814 0.65632 0.407744 0.655673 0.409121 0.938512 0.330053 0.655673 0.409121 0.65632 0.407744 0.626612 0.417814 0.65714 0.406282 0.65632 0.407744 0.938512 0.330053 0.65632 0.407744 0.65714 0.406282 0.626612 0.417814 0.658146 0.404721 0.65714 0.406282 0.938139 0.324424 0.65714 0.406282 0.658146 0.404721 0.938139 0.324424 0.938512 0.330053 0.65714 0.406282 0.626612 0.417814 0.659355 0.403049 0.658146 0.404721 0.938139 0.324424 0.658146 0.404721 0.659355 0.403049 0.626612 0.417814 0.66079 0.401248 0.659355 0.403049 0.938139 0.324424 0.659355 0.403049 0.66079 0.401248 0.626612 0.417814 0.662478 0.399303 0.66079 0.401248 0.938139 0.324424 0.66079 0.401248 0.662478 0.399303 0.626612 0.417814 0.664452 0.397196 0.662478 0.399303 0.937967 0.31916 0.662478 0.399303 0.664452 0.397196 0.937967 0.31916 0.938139 0.324424 0.662478 0.399303 0.626612 0.417814 0.666752 0.394905 0.664452 0.397196 0.937967 0.31916 0.664452 0.397196 0.666752 0.394905 0.620452 0.408799 0.669429 0.392407 0.666752 0.394905 0.937967 0.31916 0.666752 0.394905 0.669429 0.392407 0.626612 0.417814 0.620452 0.408799 0.666752 0.394905 0.620452 0.408799 0.672539 0.389677 0.669429 0.392407 0.937967 0.31916 0.669429 0.392407 0.672539 0.389677 0.620452 0.408799 0.676155 0.386685 0.672539 0.389677 0.938001 0.314422 0.672539 0.389677 0.676155 0.386685 0.938001 0.314422 0.937967 0.31916 0.672539 0.389677 0.620452 0.408799 0.680365 0.383399 0.676155 0.386685 0.938001 0.314422 0.676155 0.386685 0.680365 0.383399 0.620452 0.408799 0.685279 0.379779 0.680365 0.383399 0.938001 0.314422 0.680365 0.383399 0.685279 0.379779 0.620452 0.408799 0.691035 0.375783 0.685279 0.379779 0.938242 0.310343 0.685279 0.379779 0.691035 0.375783 0.938242 0.310343 0.938001 0.314422 0.685279 0.379779 0.620452 0.408799 0.697807 0.371366 0.691035 0.375783 0.938242 0.310343 0.691035 0.375783 0.697807 0.371366 0.620452 0.408799 0.705818 0.366477 0.697807 0.371366 0.938678 0.307023 0.697807 0.371366 0.705818 0.366477 0.938678 0.307023 0.938242 0.310343 0.697807 0.371366 0.620452 0.408799 0.715347 0.361071 0.705818 0.366477 0.938678 0.307023 0.705818 0.366477 0.715347 0.361071 0.620452 0.408799 0.726757 0.355108 0.715347 0.361071 0.939291 0.304527 0.715347 0.361071 0.726757 0.355108 0.939291 0.304527 0.938678 0.307023 0.715347 0.361071 0.620452 0.408799 0.740521 0.34857 0.726757 0.355108 0.939291 0.304527 0.726757 0.355108 0.740521 0.34857 0.620452 0.408799 0.757258 0.341485 0.740521 0.34857 0.940055 0.302888 0.740521 0.34857 0.757258 0.341485 0.940055 0.302888 0.939291 0.304527 0.740521 0.34857 0.620452 0.408799 0.777781 0.333969 0.757258 0.341485 0.940941 0.302109 0.757258 0.341485 0.777781 0.333969 0.940941 0.302109 0.940055 0.302888 0.757258 0.341485 0.862031 0.278376 0.803118 0.326316 0.777781 0.333969 0.941917 0.302169 0.777781 0.333969 0.803118 0.326316 0.620452 0.408799 0.862031 0.278376 0.777781 0.333969 0.941917 0.302169 0.940941 0.302109 0.777781 0.333969 0.862031 0.278376 0.834606 0.319135 0.803118 0.326316 0.94295 0.303026 0.803118 0.326316 0.834606 0.319135 0.94295 0.303026 0.941917 0.302169 0.803118 0.326316 0.862031 0.278376 0.873646 0.313674 0.834606 0.319135 0.944009 0.304626 0.834606 0.319135 0.873646 0.313674 0.944009 0.304626 0.94295 0.303026 0.834606 0.319135 0.881775 0.276575 0.873646 0.313674 0.862031 0.278376 0.881775 0.276575 0.8879 0.313201 0.873646 0.313674 0.945063 0.306901 0.873646 0.313674 0.8879 0.313201 0.945063 0.306901 0.944009 0.304626 0.873646 0.313674 0.605995 0.392183 0.846091 0.243778 0.862031 0.278376 0.867361 0.240079 0.862031 0.278376 0.846091 0.243778 0.613576 0.400237 0.605995 0.392183 0.862031 0.278376 0.620452 0.408799 0.613576 0.400237 0.862031 0.278376 0.867361 0.240079 0.881775 0.276575 0.862031 0.278376 0.588805 0.377811 0.823979 0.210251 0.846091 0.243778 0.846907 0.2044579 0.846091 0.243778 0.823979 0.210251 0.59773 0.38469 0.588805 0.377811 0.846091 0.243778 0.605995 0.392183 0.59773 0.38469 0.846091 0.243778 0.846907 0.2044579 0.867361 0.240079 0.846091 0.243778 0.579255 0.371595 0.792715 0.17842 0.823979 0.210251 0.846907 0.2044579 0.823979 0.210251 0.792715 0.17842 0.588805 0.377811 0.579255 0.371595 0.823979 0.210251 0.558468 0.361348 0.747578 0.149394 0.792715 0.17842 0.81705 0.170279 0.792715 0.17842 0.747578 0.149394 0.569123 0.366091 0.558468 0.361348 0.792715 0.17842 0.579255 0.371595 0.569123 0.366091 0.792715 0.17842 0.81705 0.170279 0.846907 0.2044579 0.792715 0.17842 0.535866 0.354301 0.681943 0.12516 0.747578 0.149394 0.771864 0.138631 0.747578 0.149394 0.681943 0.12516 0.547357 0.357406 0.535866 0.354301 0.747578 0.149394 0.558468 0.361348 0.547357 0.357406 0.747578 0.149394 0.771864 0.138631 0.81705 0.170279 0.747578 0.149394 0.574844 0.1415269 0.590462 0.108976 0.681943 0.12516 0.701533 0.111704 0.681943 0.12516 0.590462 0.108976 0.564171 0.168705 0.574844 0.1415269 0.681943 0.12516 0.556237 0.191425 0.564171 0.168705 0.681943 0.12516 0.549999 0.210511 0.556237 0.191425 0.681943 0.12516 0.52408 0.352061 0.549999 0.210511 0.681943 0.12516 0.535866 0.354301 0.52408 0.352061 0.681943 0.12516 0.701533 0.111704 0.771864 0.138631 0.681943 0.12516 0.688704 0.0551809 0.590462 0.108976 0.574844 0.1415269 0.595399 0.09719598 0.701533 0.111704 0.590462 0.108976 0.679207 0.053357 0.595399 0.09719598 0.590462 0.108976 0.688704 0.0551809 0.679207 0.053357 0.590462 0.108976 0.694317 0.05671089 0.574844 0.1415269 0.564171 0.168705 0.694317 0.05671089 0.688704 0.0551809 0.574844 0.1415269 0.696173 0.05786496 0.564171 0.168705 0.556237 0.191425 0.696173 0.05786496 0.694317 0.05671089 0.564171 0.168705 0.694317 0.058586 0.556237 0.191425 0.549999 0.210511 0.694317 0.058586 0.696173 0.05786496 0.556237 0.191425 0.52408 0.352061 0.544909 0.2266049 0.549999 0.210511 0.688704 0.05884498 0.549999 0.210511 0.544909 0.2266049 0.688704 0.05884498 0.694317 0.058586 0.549999 0.210511 0.52408 0.352061 0.540637 0.240248 0.544909 0.2266049 0.688704 0.05884498 0.544909 0.2266049 0.540637 0.240248 0.52408 0.352061 0.536975 0.251876 0.540637 0.240248 0.679207 0.058649 0.540637 0.240248 0.536975 0.251876 0.679207 0.058649 0.688704 0.05884498 0.540637 0.240248 0.52408 0.352061 0.53378 0.261837 0.536975 0.251876 0.679207 0.058649 0.536975 0.251876 0.53378 0.261837 0.512094 0.350708 0.530955 0.270411 0.53378 0.261837 0.665639 0.05804389 0.53378 0.261837 0.530955 0.270411 0.52408 0.352061 0.512094 0.350708 0.53378 0.261837 0.665639 0.05804389 0.679207 0.058649 0.53378 0.261837 0.512094 0.350708 0.528426 0.277823 0.530955 0.270411 0.665639 0.05804389 0.530955 0.270411 0.528426 0.277823 0.512094 0.350708 0.52614 0.284258 0.528426 0.277823 0.647804 0.05711793 0.528426 0.277823 0.52614 0.284258 0.647804 0.05711793 0.665639 0.05804389 0.528426 0.277823 0.512094 0.350708 0.524055 0.289866 0.52614 0.284258 0.647804 0.05711793 0.52614 0.284258 0.524055 0.289866 0.512094 0.350708 0.522139 0.29477 0.524055 0.289866 0.647804 0.05711793 0.524055 0.289866 0.522139 0.29477 0.512094 0.350708 0.520363 0.29907 0.522139 0.29477 0.625579 0.0559979 0.522139 0.29477 0.520363 0.29907 0.625579 0.0559979 0.647804 0.05711793 0.522139 0.29477 0.512094 0.350708 0.518709 0.302847 0.520363 0.29907 0.625579 0.0559979 0.520363 0.29907 0.518709 0.302847 0.512094 0.350708 0.517157 0.306172 0.518709 0.302847 0.625579 0.0559979 0.518709 0.302847 0.517157 0.306172 0.512094 0.350708 0.515693 0.309099 0.517157 0.306172 0.625579 0.0559979 0.517157 0.306172 0.515693 0.309099 0.599037 0.05484998 0.515693 0.309099 0.514305 0.311678 0.599037 0.05484998 0.625579 0.0559979 0.515693 0.309099 0.599037 0.05484998 0.514305 0.311678 0.51298 0.31395 0.599037 0.05484998 0.51298 0.31395 0.511709 0.31595 0.599037 0.05484998 0.511709 0.31595 0.510482 0.317705 0.568592 0.05385088 0.510482 0.317705 0.509288 0.319242 0.568592 0.05385088 0.599037 0.05484998 0.510482 0.317705 0.568592 0.05385088 0.509288 0.319242 0.508119 0.320579 0.568592 0.05385088 0.508119 0.320579 0.506963 0.321733 0.568592 0.05385088 0.506963 0.321733 0.505813 0.322713 0.535128 0.05317091 0.505813 0.322713 0.504653 0.323527 0.535128 0.05317091 0.568592 0.05385088 0.505813 0.322713 0.535128 0.05317091 0.504653 0.323527 0.503483 0.324169 0.535128 0.05317091 0.503483 0.324169 0.50229 0.324633 0.535128 0.05317091 0.50229 0.324633 0.501097 0.324907 0.523606 0.36073 0.512094 0.350708 0.52408 0.352061 0.523606 0.36073 0.5 0.358871 0.512094 0.350708 0.523606 0.36073 0.52408 0.352061 0.535866 0.354301 0.546382 0.36623 0.535866 0.354301 0.547357 0.357406 0.546382 0.36623 0.523606 0.36073 0.535866 0.354301 0.546382 0.36623 0.547357 0.357406 0.558468 0.361348 0.567592 0.375156 0.558468 0.361348 0.569123 0.366091 0.567592 0.375156 0.546382 0.36623 0.558468 0.361348 0.567592 0.375156 0.569123 0.366091 0.579255 0.371595 0.586648 0.387181 0.579255 0.371595 0.588805 0.377811 0.586648 0.387181 0.567592 0.375156 0.579255 0.371595 0.586648 0.387181 0.588805 0.377811 0.59773 0.38469 0.603126 0.4019 0.59773 0.38469 0.605995 0.392183 0.603126 0.4019 0.586648 0.387181 0.59773 0.38469 0.603126 0.4019 0.605995 0.392183 0.613576 0.400237 0.616761 0.418862 0.613576 0.400237 0.620452 0.408799 0.616761 0.418862 0.603126 0.4019 0.613576 0.400237 0.616761 0.418862 0.620452 0.408799 0.626612 0.417814 0.627417 0.437607 0.626612 0.417814 0.632045 0.427228 0.627417 0.437607 0.616761 0.418862 0.626612 0.417814 0.635038 0.457679 0.632045 0.427228 0.636751 0.436988 0.635038 0.457679 0.627417 0.437607 0.632045 0.427228 0.639607 0.478624 0.636751 0.436988 0.640728 0.447043 0.639607 0.478624 0.635038 0.457679 0.636751 0.436988 0.641129 0.5 0.640728 0.447043 0.643978 0.457343 0.641129 0.5 0.639607 0.478624 0.640728 0.447043 0.643978 0.542657 0.643978 0.457343 0.646503 0.46784 0.640728 0.552957 0.643978 0.457343 0.643978 0.542657 0.641129 0.5 0.643978 0.457343 0.640728 0.552957 0.646503 0.53216 0.646503 0.46784 0.648305 0.478481 0.643978 0.542657 0.646503 0.46784 0.646503 0.53216 0.648305 0.521519 0.648305 0.478481 0.649385 0.489217 0.646503 0.53216 0.648305 0.478481 0.648305 0.521519 0.649385 0.510783 0.649385 0.489217 0.649744 0.5 0.648305 0.521519 0.649385 0.489217 0.649385 0.510783 0.639607 0.521376 0.640728 0.552957 0.636751 0.563012 0.639607 0.521376 0.641129 0.5 0.640728 0.552957 0.635038 0.542321 0.636751 0.563012 0.632045 0.572772 0.635038 0.542321 0.639607 0.521376 0.636751 0.563012 0.627417 0.562393 0.632045 0.572772 0.626612 0.582186 0.627417 0.562393 0.635038 0.542321 0.632045 0.572772 0.627417 0.562393 0.626612 0.582186 0.620452 0.591201 0.616761 0.581138 0.620452 0.591201 0.613576 0.599763 0.616761 0.581138 0.627417 0.562393 0.620452 0.591201 0.616761 0.581138 0.613576 0.599763 0.605995 0.607817 0.710673 0.694466 0.59773 0.61531 0.605995 0.607817 0.603126 0.5981 0.605995 0.607817 0.59773 0.61531 0.603126 0.5981 0.616761 0.581138 0.605995 0.607817 0.63405 0.66181 0.588805 0.622189 0.59773 0.61531 0.603126 0.5981 0.59773 0.61531 0.588805 0.622189 0.710673 0.694466 0.63405 0.66181 0.59773 0.61531 0.608105 0.673037 0.579255 0.628405 0.588805 0.622189 0.586648 0.612819 0.588805 0.622189 0.579255 0.628405 0.63405 0.66181 0.608105 0.673037 0.588805 0.622189 0.586648 0.612819 0.603126 0.5981 0.588805 0.622189 0.608105 0.673037 0.569123 0.633909 0.579255 0.628405 0.586648 0.612819 0.579255 0.628405 0.569123 0.633909 0.58158 0.6816 0.558468 0.638652 0.569123 0.633909 0.567592 0.624844 0.569123 0.633909 0.558468 0.638652 0.608105 0.673037 0.58158 0.6816 0.569123 0.633909 0.567592 0.624844 0.586648 0.612819 0.569123 0.633909 0.554622 0.687621 0.547357 0.642594 0.558468 0.638652 0.567592 0.624844 0.558468 0.638652 0.547357 0.642594 0.58158 0.6816 0.554622 0.687621 0.558468 0.638652 0.554622 0.687621 0.535866 0.645699 0.547357 0.642594 0.546382 0.63377 0.547357 0.642594 0.535866 0.645699 0.546382 0.63377 0.567592 0.624844 0.547357 0.642594 0.527383 0.691195 0.52408 0.647939 0.535866 0.645699 0.546382 0.63377 0.535866 0.645699 0.52408 0.647939 0.554622 0.687621 0.527383 0.691195 0.535866 0.645699 0.527383 0.691195 0.512094 0.649292 0.52408 0.647939 0.523606 0.63927 0.52408 0.647939 0.512094 0.649292 0.523606 0.63927 0.546382 0.63377 0.52408 0.647939 0.781071 0.744981 0.63405 0.66181 0.710673 0.694466 0.632255 0.677647 0.63405 0.66181 0.781071 0.744981 0.625597 0.670745 0.63405 0.66181 0.632255 0.677647 0.613193 0.672899 0.611195 0.673475 0.63405 0.66181 0.606345 0.673989 0.63405 0.66181 0.611195 0.673475 0.625597 0.670745 0.613193 0.672899 0.63405 0.66181 0.602798 0.674527 0.63405 0.66181 0.606345 0.673989 0.599929 0.674948 0.63405 0.66181 0.602798 0.674527 0.596519 0.675432 0.63405 0.66181 0.599929 0.674948 0.587567 0.676623 0.63405 0.66181 0.596519 0.675432 0.570144 0.678603 0.63405 0.66181 0.587567 0.676623 0.774906 0.741315 0.781071 0.744981 0.710673 0.694466 0.771832 0.736914 0.774906 0.741315 0.710673 0.694466 0.771999 0.732394 0.771832 0.736914 0.710673 0.694466 0.775132 0.728291 0.771999 0.732394 0.710673 0.694466 0.780681 0.725017 0.775132 0.728291 0.710673 0.694466 0.787945 0.722849 0.780681 0.725017 0.710673 0.694466 0.79615 0.721949 0.787945 0.722849 0.710673 0.694466 0.804498 0.722377 0.79615 0.721949 0.710673 0.694466 0.822225 0.902587 1 0.916669 1 0.958332 0.716147 0.934228 0.822225 0.902587 1 0.958332 0.872726 0.865485 1 0.874997 1 0.916669 0.822225 0.902587 0.872726 0.865485 1 0.916669 0.900423 0.826392 1 0.833336 1 0.874997 0.872726 0.865485 0.900423 0.826392 1 0.874997 0.917346 0.786402 1 0.791665 1 0.833336 0.900423 0.826392 0.917346 0.786402 1 0.833336 0.928429 0.745943 1 0.75 1 0.791665 1 0.901726 1 0.791665 1 0.75 0.917346 0.786402 0.928429 0.745943 1 0.791665 1 0.913297 1 0.920037 1 0.791665 1 0.906941 1 0.913297 1 0.791665 1 0.901726 1 0.906941 1 0.791665 0.93599 0.705212 1 0.708335 1 0.75 1 0.843614 1 0.75 1 0.708335 0.928429 0.745943 0.93599 0.705212 1 0.75 1 0.898337 1 0.901726 1 0.75 1 0.896595 1 0.898337 1 0.75 1 0.893796 1 0.896595 1 0.75 1 0.890408 1 0.893796 1 0.75 1 0.867016 1 0.890408 1 0.75 1 0.843614 1 0.867016 1 0.75 0.941234 0.664314 1 0.666664 1 0.708335 1 0.773405 1 0.708335 1 0.666664 0.93599 0.705212 0.941234 0.664314 1 0.708335 1 0.820211 1 0.843614 1 0.708335 1 0.796808 1 0.820211 1 0.708335 1 0.773405 1 0.796808 1 0.708335 0.944839 0.623311 1 0.625003 1 0.666664 1 0.677108 1 0.666664 1 0.625003 0.941234 0.664314 0.944839 0.623311 1 0.666664 1 0.677108 1 0.680923 1 0.666664 1 0.726598 1 0.666664 1 0.680923 1 0.750001 1 0.773405 1 0.666664 1 0.726598 1 0.750001 1 0.666664 0.947195 0.58224 1 0.583331 1 0.625003 1 0.656388 1 0.625003 1 0.583331 0.944839 0.623311 0.947195 0.58224 1 0.625003 1 0.661159 1 0.666667 1 0.625003 1 0.672175 1 0.625003 1 0.666667 1 0.656226 1 0.661159 1 0.625003 1 0.65241 1 0.656226 1 0.625003 1 0.65018 1 0.65241 1 0.625003 1 0.649874 1 0.65018 1 0.625003 1 0.651634 1 0.649874 1 0.625003 1 0.656388 1 0.651634 1 0.625003 1 0.672175 1 0.677108 1 0.625003 0.94853 0.541129 1 0.541668 1 0.583331 1 0.598274 1 0.583331 1 0.541668 0.947195 0.58224 0.94853 0.541129 1 0.583331 1 0.603405 1 0.583331 1 0.598274 1 0.632985 1 0.656388 1 0.583331 1 0.609592 1 0.632985 1 0.583331 1 0.606204 1 0.609592 1 0.583331 1 0.603405 1 0.606204 1 0.583331 0.948963 0.5 1 0.5 1 0.541668 1 0.533683 1 0.541668 1 0.5 0.94853 0.541129 0.948963 0.5 1 0.541668 1 0.59306 1 0.598274 1 0.541668 1 0.586704 1 0.59306 1 0.541668 1 0.579964 1 0.586704 1 0.541668 1 0.573608 1 0.579964 1 0.541668 1 0.568392 1 0.573608 1 0.541668 1 0.565004 1 0.568392 1 0.541668 1 0.563261 1 0.565004 1 0.541668 1 0.560463 1 0.563261 1 0.541668 1 0.557075 1 0.560463 1 0.541668 1 0.533683 1 0.557075 1 0.541668 0.94853 0.458871 1 0.458332 1 0.5 1 0.486877 1 0.5 1 0.458332 0.948963 0.5 0.94853 0.458871 1 0.5 1 0.510281 1 0.533683 1 0.5 1 0.486877 1 0.510281 1 0.5 0.947195 0.41776 1 0.416669 1 0.458332 1 0.440071 1 0.458332 1 0.416669 0.94853 0.458871 0.947195 0.41776 1 0.458332 1 0.463474 1 0.486877 1 0.458332 1 0.440071 1 0.463474 1 0.458332 0.944839 0.376689 1 0.374997 1 0.416669 1 0.393265 1 0.416669 1 0.374997 0.947195 0.41776 0.944839 0.376689 1 0.416669 1 0.416668 1 0.440071 1 0.416669 1 0.393265 1 0.416668 1 0.416669 0.941234 0.335686 1 0.333336 1 0.374997 1 0.34982 1 0.374997 1 0.333336 0.944839 0.376689 0.941234 0.335686 1 0.374997 1 0.350126 1 0.348366 1 0.374997 1 0.346458 1 0.374997 1 0.348366 1 0.34982 1 0.350126 1 0.374997 1 0.369862 1 0.393265 1 0.374997 1 0.346458 1 0.369862 1 0.374997 0.93599 0.294788 1 0.291665 1 0.333336 1 0.276258 1 0.333336 1 0.291665 0.941234 0.335686 0.93599 0.294788 1 0.333336 1 0.327825 1 0.333333 1 0.333336 1 0.338841 1 0.333336 1 0.333333 1 0.322892 1 0.327825 1 0.333336 1 0.319077 1 0.322892 1 0.333336 1 0.299651 1 0.319077 1 0.333336 1 0.34759 1 0.34982 1 0.333336 1 0.343774 1 0.34759 1 0.333336 1 0.338841 1 0.343774 1 0.333336 1 0.276258 1 0.299651 1 0.333336 0.928429 0.254057 1 0.25 1 0.291665 1 0.240274 1 0.291665 1 0.25 0.93599 0.294788 0.928429 0.254057 1 0.291665 1 0.272871 1 0.276258 1 0.291665 1 0.270072 1 0.272871 1 0.291665 1 0.26833 1 0.270072 1 0.291665 1 0.264941 1 0.26833 1 0.291665 1 0.259726 1 0.264941 1 0.291665 1 0.253371 1 0.259726 1 0.291665 1 0.24663 1 0.253371 1 0.291665 1 0.240274 1 0.24663 1 0.291665 0.917346 0.213598 1 0.208335 1 0.25 1 0.179057 1 0.25 1 0.208335 0.928429 0.254057 0.917346 0.213598 1 0.25 1 0.179057 1 0.174849 1 0.25 1 0.153544 1 0.25 1 0.174849 1 0.235059 1 0.240274 1 0.25 1 0.20035 1 0.235059 1 0.25 1 0.1769469 1 0.20035 1 0.25 1 0.153544 1 0.1769469 1 0.25 0.900423 0.173608 1 0.166664 1 0.208335 1 0.164071 1 0.208335 1 0.166664 0.917346 0.213598 0.900423 0.173608 1 0.208335 1 0.1816329 1 0.179057 1 0.208335 1 0.182325 1 0.1816329 1 0.208335 1 0.181138 1 0.182325 1 0.208335 1 0.1782979 1 0.181138 1 0.208335 1 0.17418 1 0.1782979 1 0.208335 1 0.169262 1 0.17418 1 0.208335 1 0.164071 1 0.169262 1 0.208335 0.872726 0.134515 1 0.125003 1 0.166664 1 0.01648592 1 0.166664 1 0.125003 0.900423 0.173608 0.872726 0.134515 1 0.166664 1 0.006086945 0.176712 0 1 0.166664 1 0.159153 1 0.166664 0.176712 0 1 0.01132589 1 0.006086945 1 0.166664 1 0.01503288 1 0.01132589 1 0.166664 1 0.01679295 1 0.01503288 1 0.166664 1 0.01648592 1 0.01679295 1 0.166664 1 0.159153 1 0.164071 1 0.166664 0.822225 0.097413 1 0.08333098 1 0.125003 0.872726 0.134515 0.822225 0.097413 1 0.125003 1 0.005507946 1 0.125003 0.176712 0 1 0.014256 1 0.01648592 1 0.125003 1 0.01044088 1 0.014256 1 0.125003 1 0.005507946 1 0.01044088 1 0.125003 0.716147 0.06577199 1 0.04166793 1 0.08333098 0.822225 0.097413 0.716147 0.06577199 1 0.08333098 0.787251 0.100641 0.716147 0.06577199 0.822225 0.097413 0.5 0.0575369 0.716147 0.06577199 0.5 0.06171995 0.680824 0.073412 0.5 0.06171995 0.716147 0.06577199 0.680824 0.073412 0.716147 0.06577199 0.787251 0.100641 0.844019 0.134264 0.822225 0.097413 0.872726 0.134515 0.787251 0.100641 0.822225 0.097413 0.844019 0.134264 0.876798 0.170535 0.872726 0.134515 0.900423 0.173608 0.844019 0.134264 0.872726 0.134515 0.876798 0.170535 0.89737 0.20807 0.900423 0.173608 0.917346 0.213598 0.876798 0.170535 0.900423 0.173608 0.89737 0.20807 0.911078 0.246286 0.917346 0.213598 0.928429 0.254057 0.89737 0.20807 0.917346 0.213598 0.911078 0.246286 0.920569 0.284904 0.928429 0.254057 0.93599 0.294788 0.911078 0.246286 0.928429 0.254057 0.920569 0.284904 0.927263 0.323771 0.93599 0.294788 0.941234 0.335686 0.920569 0.284904 0.93599 0.294788 0.927263 0.323771 0.931975 0.362801 0.941234 0.335686 0.944839 0.376689 0.927263 0.323771 0.941234 0.335686 0.931975 0.362801 0.935188 0.401936 0.944839 0.376689 0.947195 0.41776 0.931975 0.362801 0.944839 0.376689 0.935188 0.401936 0.937195 0.441138 0.947195 0.41776 0.94853 0.458871 0.935188 0.401936 0.947195 0.41776 0.937195 0.441138 0.938161 0.480375 0.94853 0.458871 0.948963 0.5 0.937195 0.441138 0.94853 0.458871 0.938161 0.480375 0.938161 0.519625 0.948963 0.5 0.94853 0.541129 0.938161 0.480375 0.948963 0.5 0.938161 0.519625 0.937195 0.558862 0.94853 0.541129 0.947195 0.58224 0.938161 0.519625 0.94853 0.541129 0.937195 0.558862 0.935188 0.598064 0.947195 0.58224 0.944839 0.623311 0.937195 0.558862 0.947195 0.58224 0.935188 0.598064 0.931975 0.637199 0.944839 0.623311 0.941234 0.664314 0.935188 0.598064 0.944839 0.623311 0.931975 0.637199 0.927263 0.676229 0.941234 0.664314 0.93599 0.705212 0.931975 0.637199 0.941234 0.664314 0.927263 0.676229 0.920569 0.715096 0.93599 0.705212 0.928429 0.745943 0.927263 0.676229 0.93599 0.705212 0.920569 0.715096 0.911078 0.753714 0.928429 0.745943 0.917346 0.786402 0.920569 0.715096 0.928429 0.745943 0.911078 0.753714 0.89737 0.79193 0.917346 0.786402 0.900423 0.826392 0.911078 0.753714 0.917346 0.786402 0.89737 0.79193 0.876798 0.829465 0.900423 0.826392 0.872726 0.865485 0.89737 0.79193 0.900423 0.826392 0.876798 0.829465 0.844019 0.865736 0.872726 0.865485 0.822225 0.902587 0.876798 0.829465 0.872726 0.865485 0.844019 0.865736 0.787251 0.899359 0.822225 0.902587 0.716147 0.934228 0.844019 0.865736 0.822225 0.902587 0.787251 0.899359 0.787251 0.899359 0.716147 0.934228 0.680824 0.926588 0.572756 0.685048 0.138126 0.728074 0.139297 0.727973 0.14132 0.748839 0.1186259 0.724637 0.138126 0.728074 0.861874 0.728074 0.14132 0.748839 0.138126 0.728074 0.861874 0.728074 0.138126 0.728074 0.860703 0.727973 0.789642 0.74732 0.138126 0.728074 0.781071 0.744981 0.632255 0.677647 0.781071 0.744981 0.138126 0.728074 0.816766 0.743793 0.821876 0.739791 0.138126 0.728074 0.808941 0.746667 0.816766 0.743793 0.138126 0.728074 0.799427 0.74792 0.808941 0.746667 0.138126 0.728074 0.789642 0.74732 0.799427 0.74792 0.138126 0.728074 0.628939 0.678295 0.632255 0.677647 0.138126 0.728074 0.626503 0.675721 0.628939 0.678295 0.138126 0.728074 0.612171 0.681313 0.626503 0.675721 0.138126 0.728074 0.60846 0.681922 0.612171 0.681313 0.138126 0.728074 0.605456 0.6824 0.60846 0.681922 0.138126 0.728074 0.594431 0.684035 0.605456 0.6824 0.138126 0.728074 0.592691 0.684276 0.594431 0.684035 0.138126 0.728074 0.573558 0.686626 0.592691 0.684276 0.138126 0.728074 0.572756 0.685048 0.573558 0.686626 0.138126 0.728074 0.054937 0.693099 0.1121 0.686799 0.107634 0.686537 0.09800899 0.72119 0.107634 0.686537 0.1186259 0.724637 0.09800899 0.72119 0.100049 0.685463 0.107634 0.686537 0.05391293 0.690224 0.107634 0.686537 0.100049 0.685463 0.05391293 0.690224 0.054937 0.693099 0.107634 0.686537 0.14132 0.748839 0.133774 0.762299 0.1186259 0.724637 0.110552 0.760267 0.1186259 0.724637 0.133774 0.762299 0.110552 0.760267 0.09800899 0.72119 0.1186259 0.724637 0.145713 0.76903 0.155531 0.799208 0.133774 0.762299 0.128832 0.798665 0.133774 0.762299 0.155531 0.799208 0.14132 0.748839 0.145713 0.76903 0.133774 0.762299 0.128832 0.798665 0.110552 0.760267 0.133774 0.762299 0.861874 0.728074 0.155531 0.799208 0.145713 0.76903 0.128832 0.798665 0.155531 0.799208 0.159132 0.8075 0.861874 0.728074 0.159132 0.8075 0.155531 0.799208 0.861874 0.728074 0.145713 0.76903 0.14132 0.748839 0.156529 0.835892 0.128832 0.798665 0.159132 0.8075 0.18129 0.84293 0.156529 0.835892 0.159132 0.8075 0.861874 0.728074 0.18129 0.84293 0.159132 0.8075 0.09800899 0.72119 0.090806 0.682597 0.100049 0.685463 0.05294191 0.686829 0.100049 0.685463 0.090806 0.682597 0.05294191 0.686829 0.05391293 0.690224 0.100049 0.685463 0.09800899 0.72119 0.08905798 0.68177 0.090806 0.682597 0.05294191 0.686829 0.090806 0.682597 0.08905798 0.68177 0.07943099 0.715096 0.08905798 0.68177 0.09800899 0.72119 0.07273697 0.676229 0.08405297 0.678615 0.08905798 0.68177 0.05204397 0.682997 0.08905798 0.68177 0.08405297 0.678615 0.07943099 0.715096 0.07273697 0.676229 0.08905798 0.68177 0.05204397 0.682997 0.05294191 0.686829 0.08905798 0.68177 0.08892196 0.753714 0.09800899 0.72119 0.110552 0.760267 0.08892196 0.753714 0.07943099 0.715096 0.09800899 0.72119 0.10263 0.79193 0.110552 0.760267 0.128832 0.798665 0.10263 0.79193 0.08892196 0.753714 0.110552 0.760267 0.123202 0.829465 0.128832 0.798665 0.156529 0.835892 0.123202 0.829465 0.10263 0.79193 0.128832 0.798665 0.18129 0.84293 0.200902 0.870915 0.156529 0.835892 0.155981 0.865736 0.156529 0.835892 0.200902 0.870915 0.155981 0.865736 0.123202 0.829465 0.156529 0.835892 0.217254 0.874569 0.276398 0.901349 0.200902 0.870915 0.212749 0.899359 0.200902 0.870915 0.276398 0.901349 0.18129 0.84293 0.217254 0.874569 0.200902 0.870915 0.212749 0.899359 0.155981 0.865736 0.200902 0.870915 0.861874 0.728074 0.276398 0.901349 0.217254 0.874569 0.319176 0.926588 0.276398 0.901349 0.369932 0.920336 0.861874 0.728074 0.369932 0.920336 0.276398 0.901349 0.319176 0.926588 0.212749 0.899359 0.276398 0.901349 0.861874 0.728074 0.217254 0.874569 0.18129 0.84293 0.5 0.927617 0.319176 0.926588 0.369932 0.920336 0.861874 0.728074 0.5 0.927617 0.369932 0.920336 0.07273697 0.676229 0.07932698 0.673841 0.08405297 0.678615 0.05123299 0.678812 0.08405297 0.678615 0.07932698 0.673841 0.05123299 0.678812 0.05204397 0.682997 0.08405297 0.678615 0.07273697 0.676229 0.07630699 0.668519 0.07932698 0.673841 0.05052191 0.674361 0.07932698 0.673841 0.07630699 0.668519 0.05052191 0.674361 0.05123299 0.678812 0.07932698 0.673841 0.06802499 0.637199 0.074804 0.662852 0.07630699 0.668519 0.04991996 0.669729 0.07630699 0.668519 0.074804 0.662852 0.07273697 0.676229 0.06802499 0.637199 0.07630699 0.668519 0.04991996 0.669729 0.05052191 0.674361 0.07630699 0.668519 0.06802499 0.637199 0.07474899 0.657038 0.074804 0.662852 0.04943597 0.665003 0.074804 0.662852 0.07474899 0.657038 0.04943597 0.665003 0.04991996 0.669729 0.074804 0.662852 0.06802499 0.637199 0.07617199 0.651253 0.07474899 0.657038 0.04883897 0.655613 0.07474899 0.657038 0.07617199 0.651253 0.04907399 0.660269 0.04943597 0.665003 0.07474899 0.657038 0.04883897 0.655613 0.04907399 0.660269 0.07474899 0.657038 0.06802499 0.637199 0.07921898 0.645636 0.07617199 0.651253 0.0487309 0.651122 0.07617199 0.651253 0.07921898 0.645636 0.0487309 0.651122 0.04883897 0.655613 0.07617199 0.651253 0.06802499 0.637199 0.08284699 0.641496 0.07921898 0.645636 0.04875296 0.646882 0.07921898 0.645636 0.08284699 0.641496 0.04875296 0.646882 0.0487309 0.651122 0.07921898 0.645636 0.06802499 0.637199 0.07881098 0.6012 0.08284699 0.641496 0.08416998 0.640307 0.08284699 0.641496 0.07881098 0.6012 0.04875296 0.646882 0.08284699 0.641496 0.08416998 0.640307 0.064812 0.598064 0.07619595 0.56076 0.07881098 0.6012 0.09362095 0.594779 0.07881098 0.6012 0.07619595 0.56076 0.06802499 0.637199 0.064812 0.598064 0.07881098 0.6012 0.09770697 0.632429 0.07881098 0.6012 0.09362095 0.594779 0.09146296 0.635377 0.07881098 0.6012 0.09770697 0.632429 0.08416998 0.640307 0.07881098 0.6012 0.09146296 0.635377 0.06280499 0.558862 0.07493996 0.52026 0.07619595 0.56076 0.09087496 0.556915 0.07619595 0.56076 0.07493996 0.52026 0.064812 0.598064 0.06280499 0.558862 0.07619595 0.56076 0.09362095 0.594779 0.07619595 0.56076 0.09087496 0.556915 0.06183898 0.480375 0.07493996 0.47974 0.07493996 0.52026 0.08954995 0.518979 0.07493996 0.52026 0.07493996 0.47974 0.06183898 0.519625 0.06183898 0.480375 0.07493996 0.52026 0.06280499 0.558862 0.06183898 0.519625 0.07493996 0.52026 0.09087496 0.556915 0.07493996 0.52026 0.08954995 0.518979 0.06280499 0.441138 0.07619595 0.43924 0.07493996 0.47974 0.09087496 0.443085 0.07493996 0.47974 0.07619595 0.43924 0.06183898 0.480375 0.06280499 0.441138 0.07493996 0.47974 0.08954995 0.481021 0.07493996 0.47974 0.09087496 0.443085 0.08954995 0.518979 0.07493996 0.47974 0.08954995 0.481021 0.064812 0.401936 0.07881098 0.3988 0.07619595 0.43924 0.09362095 0.405221 0.07619595 0.43924 0.07881098 0.3988 0.06280499 0.441138 0.064812 0.401936 0.07619595 0.43924 0.09087496 0.443085 0.07619595 0.43924 0.09362095 0.405221 0.06802499 0.362801 0.08284699 0.358504 0.07881098 0.3988 0.08416998 0.359693 0.07881098 0.3988 0.08284699 0.358504 0.064812 0.401936 0.06802499 0.362801 0.07881098 0.3988 0.09362095 0.405221 0.07881098 0.3988 0.09770697 0.367571 0.09146296 0.364623 0.09770697 0.367571 0.07881098 0.3988 0.08416998 0.359693 0.09146296 0.364623 0.07881098 0.3988 0.06802499 0.362801 0.07921898 0.354364 0.08284699 0.358504 0.04875296 0.353118 0.08284699 0.358504 0.07921898 0.354364 0.04890292 0.357021 0.08416998 0.359693 0.08284699 0.358504 0.04875296 0.353118 0.04890292 0.357021 0.08284699 0.358504 0.06802499 0.362801 0.07617199 0.348747 0.07921898 0.354364 0.0487309 0.348878 0.07921898 0.354364 0.07617199 0.348747 0.0487309 0.348878 0.04875296 0.353118 0.07921898 0.354364 0.06802499 0.362801 0.07474899 0.342962 0.07617199 0.348747 0.04883897 0.344387 0.07617199 0.348747 0.07474899 0.342962 0.04883897 0.344387 0.0487309 0.348878 0.07617199 0.348747 0.07273697 0.323771 0.074804 0.337148 0.07474899 0.342962 0.04907399 0.339731 0.07474899 0.342962 0.074804 0.337148 0.06802499 0.362801 0.07273697 0.323771 0.07474899 0.342962 0.04907399 0.339731 0.04883897 0.344387 0.07474899 0.342962 0.07273697 0.323771 0.07630699 0.331481 0.074804 0.337148 0.04943597 0.334997 0.074804 0.337148 0.07630699 0.331481 0.04943597 0.334997 0.04907399 0.339731 0.074804 0.337148 0.07273697 0.323771 0.07932698 0.326159 0.07630699 0.331481 0.05052191 0.325639 0.07630699 0.331481 0.07932698 0.326159 0.04991996 0.330271 0.04943597 0.334997 0.07630699 0.331481 0.05052191 0.325639 0.04991996 0.330271 0.07630699 0.331481 0.07273697 0.323771 0.08405297 0.321385 0.07932698 0.326159 0.05123299 0.321188 0.07932698 0.326159 0.08405297 0.321385 0.05123299 0.321188 0.05052191 0.325639 0.07932698 0.326159 0.07943099 0.284904 0.08905798 0.31823 0.08405297 0.321385 0.05204397 0.317003 0.08405297 0.321385 0.08905798 0.31823 0.07273697 0.323771 0.07943099 0.284904 0.08405297 0.321385 0.05204397 0.317003 0.05123299 0.321188 0.08405297 0.321385 0.07943099 0.284904 0.09811198 0.278421 0.08905798 0.31823 0.090806 0.317403 0.08905798 0.31823 0.09811198 0.278421 0.05204397 0.317003 0.08905798 0.31823 0.090806 0.317403 0.08892196 0.246286 0.110849 0.238966 0.09811198 0.278421 0.118225 0.276575 0.09811198 0.278421 0.110849 0.238966 0.07943099 0.284904 0.08892196 0.246286 0.09811198 0.278421 0.107634 0.313463 0.09811198 0.278421 0.118225 0.276575 0.100049 0.314537 0.09811198 0.278421 0.107634 0.313463 0.090806 0.317403 0.09811198 0.278421 0.100049 0.314537 0.10263 0.20807 0.1294929 0.200211 0.110849 0.238966 0.132639 0.240079 0.110849 0.238966 0.1294929 0.200211 0.08892196 0.246286 0.10263 0.20807 0.110849 0.238966 0.118225 0.276575 0.110849 0.238966 0.132639 0.240079 0.123202 0.170535 0.157901 0.162672 0.1294929 0.200211 0.153093 0.2044579 0.1294929 0.200211 0.157901 0.162672 0.10263 0.20807 0.123202 0.170535 0.1294929 0.200211 0.132639 0.240079 0.1294929 0.200211 0.153093 0.2044579 0.155981 0.134264 0.203741 0.127444 0.157901 0.162672 0.228136 0.138631 0.157901 0.162672 0.203741 0.127444 0.123202 0.170535 0.155981 0.134264 0.157901 0.162672 0.18295 0.170279 0.157901 0.162672 0.228136 0.138631 0.153093 0.2044579 0.157901 0.162672 0.18295 0.170279 0.212749 0.100641 0.28232 0.09709298 0.203741 0.127444 0.298467 0.111704 0.203741 0.127444 0.28232 0.09709298 0.155981 0.134264 0.212749 0.100641 0.203741 0.127444 0.228136 0.138631 0.203741 0.127444 0.298467 0.111704 0.319176 0.073412 0.414707 0.07745295 0.28232 0.09709298 0.412081 0.07901298 0.28232 0.09709298 0.414707 0.07745295 0.212749 0.100641 0.319176 0.073412 0.28232 0.09709298 0.298467 0.111704 0.28232 0.09709298 0.404003 0.093472 0.404943 0.08705997 0.404003 0.093472 0.28232 0.09709298 0.412081 0.07901298 0.404943 0.08705997 0.28232 0.09709298 0.319176 0.073412 0.426158 0.07291197 0.414707 0.07745295 0.374421 0.04727488 0.414707 0.07745295 0.426158 0.07291197 0.352196 0.049272 0.412081 0.07901298 0.414707 0.07745295 0.374421 0.04727488 0.352196 0.049272 0.414707 0.07745295 0.319176 0.073412 0.446539 0.06857496 0.426158 0.07291197 0.400963 0.04550492 0.426158 0.07291197 0.446539 0.06857496 0.400963 0.04550492 0.374421 0.04727488 0.426158 0.07291197 0.5 0.06171995 0.471865 0.06595796 0.446539 0.06857496 0.431408 0.04410696 0.446539 0.06857496 0.471865 0.06595796 0.319176 0.073412 0.5 0.06171995 0.446539 0.06857496 0.431408 0.04410696 0.400963 0.04550492 0.446539 0.06857496 0.5 0.06171995 0.5 0.06507897 0.471865 0.06595796 0.464872 0.04320889 0.471865 0.06595796 0.5 0.06507897 0.464872 0.04320889 0.431408 0.04410696 0.471865 0.06595796 0.680824 0.073412 0.5 0.06507897 0.5 0.06171995 0.528135 0.06595796 0.5 0.06507897 0.680824 0.073412 0.5 0.04289895 0.5 0.06507897 0.528135 0.06595796 0.5 0.04289895 0.464872 0.04320889 0.5 0.06507897 0.5 0.0575369 0.5 0.06171995 0.319176 0.073412 0.5 0.927617 0.5 0.93828 0.319176 0.926588 0.630065 0.920337 0.5 0.93828 0.5 0.927617 0.680824 0.926588 0.5 0.939293 0.5 0.93828 0.630065 0.920337 0.680824 0.926588 0.5 0.93828 0.861874 0.728074 0.630065 0.920337 0.5 0.927617 0.09362095 0.405221 0.09770697 0.367571 0.101465 0.369008 0.04958397 0.363475 0.101465 0.369008 0.09770697 0.367571 0.04918098 0.360502 0.09770697 0.367571 0.09146296 0.364623 0.04918098 0.360502 0.04958397 0.363475 0.09770697 0.367571 0.101465 0.630992 0.09770697 0.632429 0.09362095 0.594779 0.04918098 0.639498 0.09770697 0.632429 0.101465 0.630992 0.04918098 0.639498 0.09146296 0.635377 0.09770697 0.632429 0.04958397 0.636525 0.04918098 0.639498 0.101465 0.630992 0.04890292 0.642979 0.08416998 0.640307 0.09146296 0.635377 0.04918098 0.639498 0.04890292 0.642979 0.09146296 0.635377 0.04890292 0.357021 0.09146296 0.364623 0.08416998 0.359693 0.04890292 0.357021 0.04918098 0.360502 0.09146296 0.364623 0.04890292 0.642979 0.04875296 0.646882 0.08416998 0.640307 0.298467 0.111704 0.404003 0.093472 0.404601 0.09719598 0.320793 0.053357 0.404601 0.09719598 0.404003 0.093472 0.334361 0.051346 0.404003 0.093472 0.404943 0.08705997 0.334361 0.051346 0.320793 0.053357 0.404003 0.093472 0.1121 0.313201 0.107634 0.313463 0.118225 0.276575 0.05391293 0.309776 0.107634 0.313463 0.1121 0.313201 0.05391293 0.309776 0.100049 0.314537 0.107634 0.313463 0.054937 0.306901 0.05391293 0.309776 0.1121 0.313201 0.05294191 0.313171 0.090806 0.317403 0.100049 0.314537 0.05391293 0.309776 0.05294191 0.313171 0.100049 0.314537 0.352196 0.049272 0.404943 0.08705997 0.412081 0.07901298 0.352196 0.049272 0.334361 0.051346 0.404943 0.08705997 0.05294191 0.313171 0.05204397 0.317003 0.090806 0.317403 0.723603 0.901349 0.787251 0.899359 0.680824 0.926588 0.630065 0.920337 0.723603 0.901349 0.680824 0.926588 0.799099 0.870914 0.844019 0.865736 0.787251 0.899359 0.723603 0.901349 0.799099 0.870914 0.787251 0.899359 0.843472 0.835892 0.876798 0.829465 0.844019 0.865736 0.799099 0.870914 0.843472 0.835892 0.844019 0.865736 0.871169 0.798665 0.89737 0.79193 0.876798 0.829465 0.843472 0.835892 0.871169 0.798665 0.876798 0.829465 0.889448 0.760267 0.911078 0.753714 0.89737 0.79193 0.871169 0.798665 0.889448 0.760267 0.89737 0.79193 0.901991 0.72119 0.920569 0.715096 0.911078 0.753714 0.889448 0.760267 0.901991 0.72119 0.911078 0.753714 0.915947 0.678615 0.927263 0.676229 0.920569 0.715096 0.910942 0.68177 0.915947 0.678615 0.920569 0.715096 0.901991 0.72119 0.910942 0.68177 0.920569 0.715096 0.925251 0.657038 0.931975 0.637199 0.927263 0.676229 0.925196 0.662852 0.925251 0.657038 0.927263 0.676229 0.923693 0.668519 0.925196 0.662852 0.927263 0.676229 0.920673 0.673841 0.923693 0.668519 0.927263 0.676229 0.915947 0.678615 0.920673 0.673841 0.927263 0.676229 0.921189 0.6012 0.935188 0.598064 0.931975 0.637199 0.917153 0.641496 0.921189 0.6012 0.931975 0.637199 0.920781 0.645636 0.917153 0.641496 0.931975 0.637199 0.923828 0.651253 0.920781 0.645636 0.931975 0.637199 0.925251 0.657038 0.923828 0.651253 0.931975 0.637199 0.923804 0.56076 0.937195 0.558862 0.935188 0.598064 0.921189 0.6012 0.923804 0.56076 0.935188 0.598064 0.92506 0.52026 0.938161 0.519625 0.937195 0.558862 0.923804 0.56076 0.92506 0.52026 0.937195 0.558862 0.92506 0.47974 0.938161 0.480375 0.938161 0.519625 0.92506 0.52026 0.92506 0.47974 0.938161 0.519625 0.92506 0.47974 0.937195 0.441138 0.938161 0.480375 0.923804 0.43924 0.935188 0.401936 0.937195 0.441138 0.92506 0.47974 0.923804 0.43924 0.937195 0.441138 0.921189 0.3988 0.931975 0.362801 0.935188 0.401936 0.923804 0.43924 0.921189 0.3988 0.935188 0.401936 0.923693 0.331481 0.927263 0.323771 0.931975 0.362801 0.925196 0.337148 0.923693 0.331481 0.931975 0.362801 0.925251 0.342962 0.925196 0.337148 0.931975 0.362801 0.923828 0.348747 0.925251 0.342962 0.931975 0.362801 0.920781 0.354364 0.923828 0.348747 0.931975 0.362801 0.917153 0.358504 0.920781 0.354364 0.931975 0.362801 0.921189 0.3988 0.917153 0.358504 0.931975 0.362801 0.910942 0.31823 0.920569 0.284904 0.927263 0.323771 0.915947 0.321385 0.910942 0.31823 0.927263 0.323771 0.920673 0.326159 0.915947 0.321385 0.927263 0.323771 0.923693 0.331481 0.920673 0.326159 0.927263 0.323771 0.901888 0.278421 0.911078 0.246286 0.920569 0.284904 0.910942 0.31823 0.901888 0.278421 0.920569 0.284904 0.889151 0.238966 0.89737 0.20807 0.911078 0.246286 0.901888 0.278421 0.889151 0.238966 0.911078 0.246286 0.870507 0.200211 0.876798 0.170535 0.89737 0.20807 0.889151 0.238966 0.870507 0.200211 0.89737 0.20807 0.842099 0.162672 0.844019 0.134264 0.876798 0.170535 0.870507 0.200211 0.842099 0.162672 0.876798 0.170535 0.796259 0.127444 0.787251 0.100641 0.844019 0.134264 0.842099 0.162672 0.796259 0.127444 0.844019 0.134264 0.71768 0.09709298 0.680824 0.073412 0.787251 0.100641 0.796259 0.127444 0.71768 0.09709298 0.787251 0.100641 0.553461 0.06857496 0.528135 0.06595796 0.680824 0.073412 0.573842 0.07291197 0.553461 0.06857496 0.680824 0.073412 0.585293 0.07745295 0.573842 0.07291197 0.680824 0.073412 0.71768 0.09709298 0.585293 0.07745295 0.680824 0.073412 0.568592 0.04410696 0.528135 0.06595796 0.553461 0.06857496 0.535128 0.04320889 0.5 0.04289895 0.528135 0.06595796 0.568592 0.04410696 0.535128 0.04320889 0.528135 0.06595796 0.599037 0.04550492 0.553461 0.06857496 0.573842 0.07291197 0.599037 0.04550492 0.568592 0.04410696 0.553461 0.06857496 0.625579 0.04727488 0.573842 0.07291197 0.585293 0.07745295 0.625579 0.04727488 0.599037 0.04550492 0.573842 0.07291197 0.587919 0.07901298 0.585293 0.07745295 0.71768 0.09709298 0.625579 0.04727488 0.585293 0.07745295 0.587919 0.07901298 0.701533 0.111704 0.71768 0.09709298 0.796259 0.127444 0.595997 0.093472 0.71768 0.09709298 0.701533 0.111704 0.595057 0.08705997 0.71768 0.09709298 0.595997 0.093472 0.587919 0.07901298 0.71768 0.09709298 0.595057 0.08705997 0.771864 0.138631 0.796259 0.127444 0.842099 0.162672 0.701533 0.111704 0.796259 0.127444 0.771864 0.138631 0.81705 0.170279 0.842099 0.162672 0.870507 0.200211 0.771864 0.138631 0.842099 0.162672 0.81705 0.170279 0.867361 0.240079 0.870507 0.200211 0.889151 0.238966 0.846907 0.2044579 0.870507 0.200211 0.867361 0.240079 0.81705 0.170279 0.870507 0.200211 0.846907 0.2044579 0.881775 0.276575 0.889151 0.238966 0.901888 0.278421 0.867361 0.240079 0.889151 0.238966 0.881775 0.276575 0.909194 0.317403 0.901888 0.278421 0.910942 0.31823 0.881775 0.276575 0.901888 0.278421 0.892366 0.313463 0.899951 0.314537 0.892366 0.313463 0.901888 0.278421 0.909194 0.317403 0.899951 0.314537 0.901888 0.278421 0.947956 0.317003 0.910942 0.31823 0.915947 0.321385 0.947058 0.313171 0.909194 0.317403 0.910942 0.31823 0.947956 0.317003 0.947058 0.313171 0.910942 0.31823 0.948767 0.321188 0.915947 0.321385 0.920673 0.326159 0.948767 0.321188 0.947956 0.317003 0.915947 0.321385 0.949478 0.325639 0.920673 0.326159 0.923693 0.331481 0.949478 0.325639 0.948767 0.321188 0.920673 0.326159 0.95008 0.330271 0.923693 0.331481 0.925196 0.337148 0.95008 0.330271 0.949478 0.325639 0.923693 0.331481 0.950564 0.334997 0.925196 0.337148 0.925251 0.342962 0.950564 0.334997 0.95008 0.330271 0.925196 0.337148 0.951161 0.344387 0.925251 0.342962 0.923828 0.348747 0.950926 0.339731 0.950564 0.334997 0.925251 0.342962 0.951161 0.344387 0.950926 0.339731 0.925251 0.342962 0.951269 0.348878 0.923828 0.348747 0.920781 0.354364 0.951269 0.348878 0.951161 0.344387 0.923828 0.348747 0.951247 0.353118 0.920781 0.354364 0.917153 0.358504 0.951247 0.353118 0.951269 0.348878 0.920781 0.354364 0.91583 0.359693 0.917153 0.358504 0.921189 0.3988 0.951247 0.353118 0.917153 0.358504 0.91583 0.359693 0.906379 0.405221 0.921189 0.3988 0.923804 0.43924 0.902293 0.367571 0.921189 0.3988 0.906379 0.405221 0.908537 0.364623 0.921189 0.3988 0.902293 0.367571 0.91583 0.359693 0.921189 0.3988 0.908537 0.364623 0.909125 0.443085 0.923804 0.43924 0.92506 0.47974 0.906379 0.405221 0.923804 0.43924 0.909125 0.443085 0.91045 0.481021 0.92506 0.47974 0.92506 0.52026 0.909125 0.443085 0.92506 0.47974 0.91045 0.481021 0.909125 0.556915 0.92506 0.52026 0.923804 0.56076 0.91045 0.518979 0.92506 0.52026 0.909125 0.556915 0.91045 0.481021 0.92506 0.52026 0.91045 0.518979 0.906379 0.594779 0.923804 0.56076 0.921189 0.6012 0.909125 0.556915 0.923804 0.56076 0.906379 0.594779 0.91583 0.640307 0.921189 0.6012 0.917153 0.641496 0.906379 0.594779 0.921189 0.6012 0.902293 0.632429 0.908537 0.635377 0.902293 0.632429 0.921189 0.6012 0.91583 0.640307 0.908537 0.635377 0.921189 0.6012 0.951247 0.646882 0.917153 0.641496 0.920781 0.645636 0.951097 0.642979 0.91583 0.640307 0.917153 0.641496 0.951247 0.646882 0.951097 0.642979 0.917153 0.641496 0.951269 0.651122 0.920781 0.645636 0.923828 0.651253 0.951269 0.651122 0.951247 0.646882 0.920781 0.645636 0.951161 0.655613 0.923828 0.651253 0.925251 0.657038 0.951161 0.655613 0.951269 0.651122 0.923828 0.651253 0.950926 0.660269 0.925251 0.657038 0.925196 0.662852 0.950926 0.660269 0.951161 0.655613 0.925251 0.657038 0.950564 0.665003 0.925196 0.662852 0.923693 0.668519 0.950564 0.665003 0.950926 0.660269 0.925196 0.662852 0.949478 0.674361 0.923693 0.668519 0.920673 0.673841 0.95008 0.669729 0.950564 0.665003 0.923693 0.668519 0.949478 0.674361 0.95008 0.669729 0.923693 0.668519 0.948767 0.678812 0.920673 0.673841 0.915947 0.678615 0.948767 0.678812 0.949478 0.674361 0.920673 0.673841 0.947956 0.682997 0.915947 0.678615 0.910942 0.68177 0.947956 0.682997 0.948767 0.678812 0.915947 0.678615 0.909194 0.682597 0.910942 0.68177 0.901991 0.72119 0.947956 0.682997 0.910942 0.68177 0.909194 0.682597 0.881374 0.724637 0.901991 0.72119 0.889448 0.760267 0.899951 0.685463 0.909194 0.682597 0.901991 0.72119 0.892366 0.686537 0.899951 0.685463 0.901991 0.72119 0.881374 0.724637 0.892366 0.686537 0.901991 0.72119 0.866226 0.762299 0.889448 0.760267 0.871169 0.798665 0.866226 0.762299 0.881374 0.724637 0.889448 0.760267 0.844469 0.799208 0.871169 0.798665 0.843472 0.835892 0.844469 0.799208 0.866226 0.762299 0.871169 0.798665 0.818709 0.84293 0.843472 0.835892 0.799099 0.870914 0.840868 0.807501 0.844469 0.799208 0.843472 0.835892 0.818709 0.84293 0.840868 0.807501 0.843472 0.835892 0.782745 0.874569 0.799099 0.870914 0.723603 0.901349 0.818709 0.84293 0.799099 0.870914 0.782745 0.874569 0.861874 0.728074 0.723603 0.901349 0.630065 0.920337 0.861874 0.728074 0.782745 0.874569 0.723603 0.901349 0.861874 0.728074 0.818709 0.84293 0.782745 0.874569 0.947058 0.686829 0.909194 0.682597 0.899951 0.685463 0.947058 0.686829 0.947956 0.682997 0.909194 0.682597 0.946087 0.690224 0.899951 0.685463 0.892366 0.686537 0.946087 0.690224 0.947058 0.686829 0.899951 0.685463 0.8879 0.686799 0.892366 0.686537 0.881374 0.724637 0.946087 0.690224 0.892366 0.686537 0.8879 0.686799 0.861874 0.728074 0.881374 0.724637 0.866226 0.762299 0.854287 0.76903 0.866226 0.762299 0.844469 0.799208 0.85868 0.748839 0.866226 0.762299 0.854287 0.76903 0.85868 0.748839 0.861874 0.728074 0.866226 0.762299 0.861874 0.728074 0.844469 0.799208 0.840868 0.807501 0.861874 0.728074 0.854287 0.76903 0.844469 0.799208 0.861874 0.728074 0.840868 0.807501 0.818709 0.84293 0.85868 0.748839 0.854287 0.76903 0.861874 0.728074 0.945063 0.693099 0.946087 0.690224 0.8879 0.686799 0.881775 0.276575 0.892366 0.313463 0.8879 0.313201 0.945063 0.306901 0.8879 0.313201 0.892366 0.313463 0.946087 0.309776 0.892366 0.313463 0.899951 0.314537 0.946087 0.309776 0.945063 0.306901 0.892366 0.313463 0.595399 0.09719598 0.595997 0.093472 0.701533 0.111704 0.665639 0.051346 0.595997 0.093472 0.595399 0.09719598 0.665639 0.051346 0.595057 0.08705997 0.595997 0.093472 0.679207 0.053357 0.665639 0.051346 0.595399 0.09719598 0.647804 0.049272 0.587919 0.07901298 0.595057 0.08705997 0.665639 0.051346 0.647804 0.049272 0.595057 0.08705997 0.947058 0.313171 0.899951 0.314537 0.909194 0.317403 0.947058 0.313171 0.946087 0.309776 0.899951 0.314537 0.647804 0.049272 0.625579 0.04727488 0.587919 0.07901298 0.906379 0.594779 0.902293 0.632429 0.898535 0.630992 0.950416 0.636525 0.898535 0.630992 0.902293 0.632429 0.950819 0.639498 0.902293 0.632429 0.908537 0.635377 0.950819 0.639498 0.950416 0.636525 0.902293 0.632429 0.898535 0.369008 0.902293 0.367571 0.906379 0.405221 0.950819 0.360502 0.902293 0.367571 0.898535 0.369008 0.950819 0.360502 0.908537 0.364623 0.902293 0.367571 0.950416 0.363475 0.950819 0.360502 0.898535 0.369008 0.951097 0.357021 0.91583 0.359693 0.908537 0.364623 0.950819 0.360502 0.951097 0.357021 0.908537 0.364623 0.951097 0.642979 0.908537 0.635377 0.91583 0.640307 0.951097 0.642979 0.950819 0.639498 0.908537 0.635377 0.951097 0.357021 0.951247 0.353118 0.91583 0.359693 0.5 0.04423195 0.5 0.05292898 0.464872 0.05317091 0.581762 0.04545098 0.535128 0.05317091 0.5 0.05292898 0.581762 0.04545098 0.5 0.05292898 0.5 0.04423195 0.5 0.04423195 0.464872 0.05317091 0.431408 0.05385088 0.418238 0.04545098 0.431408 0.05385088 0.400963 0.05484998 0.5 0.04423195 0.431408 0.05385088 0.418238 0.04545098 0.418238 0.04545098 0.400963 0.05484998 0.374421 0.0559979 0.352514 0.04828697 0.374421 0.0559979 0.352196 0.05711793 0.418238 0.04545098 0.374421 0.0559979 0.352514 0.04828697 0.352514 0.04828697 0.352196 0.05711793 0.334361 0.05804389 0.30825 0.051063 0.334361 0.05804389 0.320793 0.058649 0.352514 0.04828697 0.334361 0.05804389 0.30825 0.051063 0.30825 0.051063 0.320793 0.058649 0.311296 0.05884498 0.2836 0.05242192 0.311296 0.05884498 0.305683 0.058586 0.30825 0.051063 0.311296 0.05884498 0.2836 0.05242192 0.2836 0.05242192 0.305683 0.058586 0.303827 0.05786496 0.275753 0.051759 0.303827 0.05786496 0.305683 0.05671089 0.2836 0.05242192 0.303827 0.05786496 0.275753 0.051759 0.275753 0.051759 0.305683 0.05671089 0.311296 0.0551809 0.2836 0.04914289 0.311296 0.0551809 0.320793 0.053357 0.275753 0.051759 0.311296 0.0551809 0.2836 0.04914289 0.2836 0.04914289 0.320793 0.053357 0.334361 0.051346 0.30825 0.04514497 0.334361 0.051346 0.352196 0.049272 0.2836 0.04914289 0.334361 0.051346 0.30825 0.04514497 0.30825 0.04514497 0.352196 0.049272 0.374421 0.04727488 0.352514 0.04073399 0.374421 0.04727488 0.400963 0.04550492 0.30825 0.04514497 0.374421 0.04727488 0.352514 0.04073399 0.352514 0.04073399 0.400963 0.04550492 0.431408 0.04410696 0.418238 0.037193 0.431408 0.04410696 0.464872 0.04320889 0.352514 0.04073399 0.431408 0.04410696 0.418238 0.037193 0.418238 0.037193 0.464872 0.04320889 0.5 0.04289895 0.5 0.035815 0.5 0.04289895 0.535128 0.04320889 0.418238 0.037193 0.5 0.04289895 0.5 0.035815 0.5 0.035815 0.535128 0.04320889 0.568592 0.04410696 0.581762 0.037193 0.568592 0.04410696 0.599037 0.04550492 0.581762 0.037193 0.5 0.035815 0.568592 0.04410696 0.581762 0.037193 0.599037 0.04550492 0.625579 0.04727488 0.647486 0.04073399 0.625579 0.04727488 0.647804 0.049272 0.581762 0.037193 0.625579 0.04727488 0.647486 0.04073399 0.647486 0.04073399 0.647804 0.049272 0.665639 0.051346 0.69175 0.04514497 0.665639 0.051346 0.679207 0.053357 0.647486 0.04073399 0.665639 0.051346 0.69175 0.04514497 0.69175 0.04514497 0.679207 0.053357 0.688704 0.0551809 0.7164 0.04914289 0.688704 0.0551809 0.694317 0.05671089 0.69175 0.04514497 0.688704 0.0551809 0.7164 0.04914289 0.7164 0.04914289 0.694317 0.05671089 0.696173 0.05786496 0.724247 0.051759 0.696173 0.05786496 0.694317 0.058586 0.7164 0.04914289 0.696173 0.05786496 0.724247 0.051759 0.724247 0.051759 0.694317 0.058586 0.688704 0.05884498 0.7164 0.05242192 0.688704 0.05884498 0.679207 0.058649 0.724247 0.051759 0.688704 0.05884498 0.7164 0.05242192 0.7164 0.05242192 0.679207 0.058649 0.665639 0.05804389 0.69175 0.051063 0.665639 0.05804389 0.647804 0.05711793 0.7164 0.05242192 0.665639 0.05804389 0.69175 0.051063 0.69175 0.051063 0.647804 0.05711793 0.625579 0.0559979 0.647486 0.04828697 0.625579 0.0559979 0.599037 0.05484998 0.69175 0.051063 0.625579 0.0559979 0.647486 0.04828697 0.647486 0.04828697 0.599037 0.05484998 0.568592 0.05385088 0.581762 0.04545098 0.568592 0.05385088 0.535128 0.05317091 0.647486 0.04828697 0.568592 0.05385088 0.581762 0.04545098 0.949034 0.335102 0.939068 0.335862 0.938512 0.330053 0.950353 0.346556 0.939785 0.341658 0.939068 0.335862 0.950353 0.346556 0.939068 0.335862 0.949034 0.335102 0.949034 0.335102 0.938512 0.330053 0.938139 0.324424 0.948251 0.323609 0.938139 0.324424 0.937967 0.31916 0.949034 0.335102 0.938139 0.324424 0.948251 0.323609 0.948251 0.323609 0.937967 0.31916 0.938001 0.314422 0.948135 0.313579 0.938001 0.314422 0.938242 0.310343 0.948251 0.323609 0.938001 0.314422 0.948135 0.313579 0.948135 0.313579 0.938242 0.310343 0.938678 0.307023 0.948705 0.306183 0.938678 0.307023 0.939291 0.304527 0.948135 0.313579 0.938678 0.307023 0.948705 0.306183 0.948705 0.306183 0.939291 0.304527 0.940055 0.302888 0.949865 0.302077 0.940055 0.302888 0.940941 0.302109 0.948705 0.306183 0.940055 0.302888 0.949865 0.302077 0.949865 0.302077 0.940941 0.302109 0.941917 0.302169 0.951434 0.301406 0.941917 0.302169 0.94295 0.303026 0.949865 0.302077 0.941917 0.302169 0.951434 0.301406 0.951434 0.301406 0.94295 0.303026 0.944009 0.304626 0.953194 0.303921 0.944009 0.304626 0.945063 0.306901 0.951434 0.301406 0.944009 0.304626 0.953194 0.303921 0.953194 0.303921 0.945063 0.306901 0.946087 0.309776 0.954941 0.30913 0.946087 0.309776 0.947058 0.313171 0.953194 0.303921 0.946087 0.309776 0.954941 0.30913 0.954941 0.30913 0.947058 0.313171 0.947956 0.317003 0.956512 0.316413 0.947956 0.317003 0.948767 0.321188 0.954941 0.30913 0.947956 0.317003 0.956512 0.316413 0.956512 0.316413 0.948767 0.321188 0.949478 0.325639 0.957791 0.325097 0.949478 0.325639 0.95008 0.330271 0.956512 0.316413 0.949478 0.325639 0.957791 0.325097 0.957791 0.325097 0.95008 0.330271 0.950564 0.334997 0.958702 0.334494 0.950564 0.334997 0.950926 0.339731 0.957791 0.325097 0.950564 0.334997 0.958702 0.334494 0.958702 0.334494 0.950926 0.339731 0.951161 0.344387 0.959204 0.343914 0.951161 0.344387 0.951269 0.348878 0.959204 0.343914 0.958702 0.334494 0.951161 0.344387 0.959204 0.343914 0.951269 0.348878 0.951247 0.353118 0.959276 0.352665 0.951247 0.353118 0.951097 0.357021 0.959204 0.343914 0.951247 0.353118 0.959276 0.352665 0.959276 0.352665 0.951097 0.357021 0.950819 0.360502 0.958916 0.360057 0.950819 0.360502 0.950416 0.363475 0.959276 0.352665 0.950819 0.360502 0.958916 0.360057 0.958916 0.360057 0.950416 0.363475 0.949892 0.365862 0.958138 0.365413 0.949892 0.365862 0.949253 0.367583 0.958916 0.360057 0.949892 0.365862 0.958138 0.365413 0.958138 0.365413 0.949253 0.367583 0.948508 0.368572 0.956975 0.368106 0.948508 0.368572 0.947666 0.368768 0.958138 0.365413 0.948508 0.368572 0.956975 0.368106 0.956975 0.368106 0.947666 0.368768 0.946741 0.368128 0.955491 0.367628 0.946741 0.368128 0.94575 0.366626 0.956975 0.368106 0.946741 0.368128 0.955491 0.367628 0.955491 0.367628 0.94575 0.366626 0.944714 0.364262 0.953787 0.363712 0.944714 0.364262 0.943655 0.361064 0.955491 0.367628 0.944714 0.364262 0.953787 0.363712 0.953787 0.363712 0.943655 0.361064 0.942602 0.357093 0.95201 0.356478 0.942602 0.357093 0.941584 0.352444 0.953787 0.363712 0.942602 0.357093 0.95201 0.356478 0.95201 0.356478 0.941584 0.352444 0.940634 0.347246 0.950353 0.346556 0.940634 0.347246 0.939785 0.341658 0.95201 0.356478 0.940634 0.347246 0.950353 0.346556 0.949034 0.664898 0.939068 0.664138 0.939785 0.658342 0.948251 0.676391 0.938512 0.669947 0.939068 0.664138 0.948251 0.676391 0.939068 0.664138 0.949034 0.664898 0.949034 0.664898 0.939785 0.658342 0.940634 0.652754 0.950353 0.653444 0.940634 0.652754 0.941584 0.647556 0.949034 0.664898 0.940634 0.652754 0.950353 0.653444 0.950353 0.653444 0.941584 0.647556 0.942602 0.642907 0.95201 0.643522 0.942602 0.642907 0.943655 0.638936 0.950353 0.653444 0.942602 0.642907 0.95201 0.643522 0.95201 0.643522 0.943655 0.638936 0.944714 0.635738 0.953787 0.636288 0.944714 0.635738 0.94575 0.633374 0.95201 0.643522 0.944714 0.635738 0.953787 0.636288 0.953787 0.636288 0.94575 0.633374 0.946741 0.631872 0.955491 0.632372 0.946741 0.631872 0.947666 0.631232 0.953787 0.636288 0.946741 0.631872 0.955491 0.632372 0.955491 0.632372 0.947666 0.631232 0.948508 0.631428 0.956975 0.631894 0.948508 0.631428 0.949253 0.632417 0.955491 0.632372 0.948508 0.631428 0.956975 0.631894 0.956975 0.631894 0.949253 0.632417 0.949892 0.634138 0.958138 0.634587 0.949892 0.634138 0.950416 0.636525 0.956975 0.631894 0.949892 0.634138 0.958138 0.634587 0.958138 0.634587 0.950416 0.636525 0.950819 0.639498 0.958916 0.639943 0.950819 0.639498 0.951097 0.642979 0.958138 0.634587 0.950819 0.639498 0.958916 0.639943 0.958916 0.639943 0.951097 0.642979 0.951247 0.646882 0.959276 0.647335 0.951247 0.646882 0.951269 0.651122 0.958916 0.639943 0.951247 0.646882 0.959276 0.647335 0.959276 0.647335 0.951269 0.651122 0.951161 0.655613 0.959204 0.656086 0.951161 0.655613 0.950926 0.660269 0.959276 0.647335 0.951161 0.655613 0.959204 0.656086 0.959204 0.656086 0.950926 0.660269 0.950564 0.665003 0.958702 0.665506 0.950564 0.665003 0.95008 0.669729 0.959204 0.656086 0.950564 0.665003 0.958702 0.665506 0.958702 0.665506 0.95008 0.669729 0.949478 0.674361 0.957791 0.674903 0.949478 0.674361 0.948767 0.678812 0.957791 0.674903 0.958702 0.665506 0.949478 0.674361 0.957791 0.674903 0.948767 0.678812 0.947956 0.682997 0.956512 0.683587 0.947956 0.682997 0.947058 0.686829 0.957791 0.674903 0.947956 0.682997 0.956512 0.683587 0.956512 0.683587 0.947058 0.686829 0.946087 0.690224 0.954941 0.69087 0.946087 0.690224 0.945063 0.693099 0.956512 0.683587 0.946087 0.690224 0.954941 0.69087 0.954941 0.69087 0.945063 0.693099 0.944009 0.695374 0.953194 0.696079 0.944009 0.695374 0.94295 0.696974 0.954941 0.69087 0.944009 0.695374 0.953194 0.696079 0.953194 0.696079 0.94295 0.696974 0.941917 0.697831 0.951434 0.698594 0.941917 0.697831 0.940941 0.697891 0.953194 0.696079 0.941917 0.697831 0.951434 0.698594 0.951434 0.698594 0.940941 0.697891 0.940055 0.697112 0.949865 0.697923 0.940055 0.697112 0.939291 0.695473 0.951434 0.698594 0.940055 0.697112 0.949865 0.697923 0.949865 0.697923 0.939291 0.695473 0.938678 0.692977 0.948705 0.693817 0.938678 0.692977 0.938242 0.689657 0.949865 0.697923 0.938678 0.692977 0.948705 0.693817 0.948705 0.693817 0.938242 0.689657 0.938001 0.685578 0.948135 0.686421 0.938001 0.685578 0.937967 0.68084 0.948705 0.693817 0.938001 0.685578 0.948135 0.686421 0.948135 0.686421 0.937967 0.68084 0.938139 0.675576 0.948251 0.676391 0.938139 0.675576 0.938512 0.669947 0.948135 0.686421 0.938139 0.675576 0.948251 0.676391 0.05096596 0.664898 0.06093198 0.664138 0.06148797 0.669947 0.04964697 0.653444 0.06021493 0.658342 0.06093198 0.664138 0.04964697 0.653444 0.06093198 0.664138 0.05096596 0.664898 0.05096596 0.664898 0.06148797 0.669947 0.06186091 0.675576 0.05174899 0.676391 0.06186091 0.675576 0.06203293 0.68084 0.05096596 0.664898 0.06186091 0.675576 0.05174899 0.676391 0.05174899 0.676391 0.06203293 0.68084 0.06199896 0.685578 0.05186498 0.686421 0.06199896 0.685578 0.06175798 0.689657 0.05174899 0.676391 0.06199896 0.685578 0.05186498 0.686421 0.05186498 0.686421 0.06175798 0.689657 0.06132197 0.692977 0.05129498 0.693817 0.06132197 0.692977 0.06070894 0.695473 0.05186498 0.686421 0.06132197 0.692977 0.05129498 0.693817 0.05129498 0.693817 0.06070894 0.695473 0.05994492 0.697112 0.05013489 0.697923 0.05994492 0.697112 0.05905896 0.697891 0.05129498 0.693817 0.05994492 0.697112 0.05013489 0.697923 0.05013489 0.697923 0.05905896 0.697891 0.05808293 0.697831 0.04856598 0.698594 0.05808293 0.697831 0.05704993 0.696974 0.05013489 0.697923 0.05808293 0.697831 0.04856598 0.698594 0.04856598 0.698594 0.05704993 0.696974 0.05599099 0.695374 0.04680591 0.696079 0.05599099 0.695374 0.054937 0.693099 0.04856598 0.698594 0.05599099 0.695374 0.04680591 0.696079 0.04680591 0.696079 0.054937 0.693099 0.05391293 0.690224 0.0450589 0.69087 0.05391293 0.690224 0.05294191 0.686829 0.04680591 0.696079 0.05391293 0.690224 0.0450589 0.69087 0.0450589 0.69087 0.05294191 0.686829 0.05204397 0.682997 0.0434879 0.683587 0.05204397 0.682997 0.05123299 0.678812 0.0450589 0.69087 0.05204397 0.682997 0.0434879 0.683587 0.0434879 0.683587 0.05123299 0.678812 0.05052191 0.674361 0.0422089 0.674903 0.05052191 0.674361 0.04991996 0.669729 0.0434879 0.683587 0.05052191 0.674361 0.0422089 0.674903 0.0422089 0.674903 0.04991996 0.669729 0.04943597 0.665003 0.04129797 0.665506 0.04943597 0.665003 0.04907399 0.660269 0.0422089 0.674903 0.04943597 0.665003 0.04129797 0.665506 0.04129797 0.665506 0.04907399 0.660269 0.04883897 0.655613 0.04079598 0.656086 0.04883897 0.655613 0.0487309 0.651122 0.04079598 0.656086 0.04129797 0.665506 0.04883897 0.655613 0.04079598 0.656086 0.0487309 0.651122 0.04875296 0.646882 0.04072391 0.647335 0.04875296 0.646882 0.04890292 0.642979 0.04079598 0.656086 0.04875296 0.646882 0.04072391 0.647335 0.04072391 0.647335 0.04890292 0.642979 0.04918098 0.639498 0.04108399 0.639943 0.04918098 0.639498 0.04958397 0.636525 0.04072391 0.647335 0.04918098 0.639498 0.04108399 0.639943 0.04108399 0.639943 0.04958397 0.636525 0.05010789 0.634138 0.04186195 0.634587 0.05010789 0.634138 0.05074691 0.632417 0.04108399 0.639943 0.05010789 0.634138 0.04186195 0.634587 0.04186195 0.634587 0.05074691 0.632417 0.05149191 0.631428 0.04302489 0.631894 0.05149191 0.631428 0.05233395 0.631232 0.04186195 0.634587 0.05149191 0.631428 0.04302489 0.631894 0.04302489 0.631894 0.05233395 0.631232 0.05325895 0.631872 0.04450899 0.632372 0.05325895 0.631872 0.05425 0.633374 0.04302489 0.631894 0.05325895 0.631872 0.04450899 0.632372 0.04450899 0.632372 0.05425 0.633374 0.05528599 0.635738 0.04621297 0.636288 0.05528599 0.635738 0.05634492 0.638936 0.04450899 0.632372 0.05528599 0.635738 0.04621297 0.636288 0.04621297 0.636288 0.05634492 0.638936 0.05739796 0.642907 0.04798996 0.643522 0.05739796 0.642907 0.05841588 0.647556 0.04621297 0.636288 0.05739796 0.642907 0.04798996 0.643522 0.04798996 0.643522 0.05841588 0.647556 0.05936592 0.652754 0.04964697 0.653444 0.05936592 0.652754 0.06021493 0.658342 0.04798996 0.643522 0.05936592 0.652754 0.04964697 0.653444 0.05096596 0.335102 0.06093198 0.335862 0.06021493 0.341658 0.05174899 0.323609 0.06148797 0.330053 0.06093198 0.335862 0.05174899 0.323609 0.06093198 0.335862 0.05096596 0.335102 0.05096596 0.335102 0.06021493 0.341658 0.05936592 0.347246 0.04964697 0.346556 0.05936592 0.347246 0.05841588 0.352444 0.05096596 0.335102 0.05936592 0.347246 0.04964697 0.346556 0.04964697 0.346556 0.05841588 0.352444 0.05739796 0.357093 0.04798996 0.356478 0.05739796 0.357093 0.05634492 0.361064 0.04964697 0.346556 0.05739796 0.357093 0.04798996 0.356478 0.04798996 0.356478 0.05634492 0.361064 0.05528599 0.364262 0.04621297 0.363712 0.05528599 0.364262 0.05425 0.366626 0.04798996 0.356478 0.05528599 0.364262 0.04621297 0.363712 0.04621297 0.363712 0.05425 0.366626 0.05325895 0.368128 0.04450899 0.367628 0.05325895 0.368128 0.05233395 0.368768 0.04621297 0.363712 0.05325895 0.368128 0.04450899 0.367628 0.04450899 0.367628 0.05233395 0.368768 0.05149191 0.368572 0.04302489 0.368106 0.05149191 0.368572 0.05074691 0.367583 0.04450899 0.367628 0.05149191 0.368572 0.04302489 0.368106 0.04302489 0.368106 0.05074691 0.367583 0.05010789 0.365862 0.04186195 0.365413 0.05010789 0.365862 0.04958397 0.363475 0.04302489 0.368106 0.05010789 0.365862 0.04186195 0.365413 0.04186195 0.365413 0.04958397 0.363475 0.04918098 0.360502 0.04108399 0.360057 0.04918098 0.360502 0.04890292 0.357021 0.04186195 0.365413 0.04918098 0.360502 0.04108399 0.360057 0.04108399 0.360057 0.04890292 0.357021 0.04875296 0.353118 0.04072391 0.352665 0.04875296 0.353118 0.0487309 0.348878 0.04108399 0.360057 0.04875296 0.353118 0.04072391 0.352665 0.04072391 0.352665 0.0487309 0.348878 0.04883897 0.344387 0.04079598 0.343914 0.04883897 0.344387 0.04907399 0.339731 0.04072391 0.352665 0.04883897 0.344387 0.04079598 0.343914 0.04079598 0.343914 0.04907399 0.339731 0.04943597 0.334997 0.04129797 0.334494 0.04943597 0.334997 0.04991996 0.330271 0.04079598 0.343914 0.04943597 0.334997 0.04129797 0.334494 0.04129797 0.334494 0.04991996 0.330271 0.05052191 0.325639 0.0422089 0.325097 0.05052191 0.325639 0.05123299 0.321188 0.0422089 0.325097 0.04129797 0.334494 0.05052191 0.325639 0.0422089 0.325097 0.05123299 0.321188 0.05204397 0.317003 0.0434879 0.316413 0.05204397 0.317003 0.05294191 0.313171 0.0422089 0.325097 0.05204397 0.317003 0.0434879 0.316413 0.0434879 0.316413 0.05294191 0.313171 0.05391293 0.309776 0.0450589 0.30913 0.05391293 0.309776 0.054937 0.306901 0.0434879 0.316413 0.05391293 0.309776 0.0450589 0.30913 0.0450589 0.30913 0.054937 0.306901 0.05599099 0.304626 0.04680591 0.303921 0.05599099 0.304626 0.05704993 0.303026 0.0450589 0.30913 0.05599099 0.304626 0.04680591 0.303921 0.04680591 0.303921 0.05704993 0.303026 0.05808293 0.302169 0.04856598 0.301406 0.05808293 0.302169 0.05905896 0.302109 0.04680591 0.303921 0.05808293 0.302169 0.04856598 0.301406 0.04856598 0.301406 0.05905896 0.302109 0.05994492 0.302888 0.05013489 0.302077 0.05994492 0.302888 0.06070894 0.304527 0.04856598 0.301406 0.05994492 0.302888 0.05013489 0.302077 0.05013489 0.302077 0.06070894 0.304527 0.06132197 0.307023 0.05129498 0.306183 0.06132197 0.307023 0.06175798 0.310343 0.05013489 0.302077 0.06132197 0.307023 0.05129498 0.306183 0.05129498 0.306183 0.06175798 0.310343 0.06199896 0.314422 0.05186498 0.313579 0.06199896 0.314422 0.06203293 0.31916 0.05129498 0.306183 0.06199896 0.314422 0.05186498 0.313579 0.05186498 0.313579 0.06203293 0.31916 0.06186091 0.324424 0.05174899 0.323609 0.06186091 0.324424 0.06148797 0.330053 0.05186498 0.313579 0.06186091 0.324424 0.05174899 0.323609 0.5 0.037606 0.176712 0 0 0.005507946 0.545957 0.03811198 1 0.005507946 0.176712 0 0.5 0.037606 0.545957 0.03811198 0.176712 0 0.454043 0.03811198 0 0.005507946 0 0.01044088 0.454043 0.03811198 0.5 0.037606 0 0.005507946 0.415105 0.03943091 0 0.01044088 0 0.014256 0.415105 0.03943091 0.454043 0.03811198 0 0.01044088 0.387738 0.04107195 0 0.014256 0 0.01648592 0.387738 0.04107195 0.415105 0.03943091 0 0.014256 0.373828 0.04248493 0 0.01648592 0 0.01679295 0.373828 0.04248493 0.387738 0.04107195 0 0.01648592 0.373828 0.04326593 0 0.01679295 0 0.01503288 0.373828 0.04326593 0.373828 0.04248493 0 0.01679295 0 0.07996296 0 0.01132589 0 0.01503288 0.387738 0.0432859 0 0.01503288 0 0.01132589 0.387738 0.0432859 0.373828 0.04326593 0 0.01503288 0 0.07996296 0 0.006086945 0 0.01132589 0.415105 0.04273796 0 0.01132589 0 0.006086945 0.415105 0.04273796 0.387738 0.0432859 0 0.01132589 0 0.07360696 0.176712 0 0 0.006086945 0.454043 0.04207295 0 0.006086945 0.176712 0 0 0.07996296 0 0.07360696 0 0.006086945 0.454043 0.04207295 0.415105 0.04273796 0 0.006086945 0.5 0.04177999 0.176712 0 1 0.006086945 0 0.06839197 1 0.159153 0.176712 0 0 0.07360696 0 0.06839197 0.176712 0 0.454043 0.04207295 0.176712 0 0.5 0.04177999 0.545957 0.04207295 1 0.006086945 1 0.01132589 0.545957 0.04207295 0.5 0.04177999 1 0.006086945 0.584895 0.04273796 1 0.01132589 1 0.01503288 0.584895 0.04273796 0.545957 0.04207295 1 0.01132589 0.612262 0.0432859 1 0.01503288 1 0.01679295 0.612262 0.0432859 0.584895 0.04273796 1 0.01503288 0.626172 0.04326593 1 0.01679295 1 0.01648592 0.626172 0.04326593 0.612262 0.0432859 1 0.01679295 0.626172 0.04248493 1 0.01648592 1 0.014256 0.626172 0.04248493 0.626172 0.04326593 1 0.01648592 0.612262 0.04107195 1 0.014256 1 0.01044088 0.612262 0.04107195 0.626172 0.04248493 1 0.014256 0.584895 0.03943091 1 0.01044088 1 0.005507946 0.584895 0.03943091 0.612262 0.04107195 1 0.01044088 0.545957 0.03811198 0.584895 0.03943091 1 0.005507946 0.956644 0.334613 1 0.333333 1 0.327825 0.956938 0.340079 1 0.338841 1 0.333333 0.956644 0.334613 0.956938 0.340079 1 0.333333 0.95608 0.329163 1 0.327825 1 0.322892 0.95608 0.329163 0.956644 0.334613 1 0.327825 0.955296 0.324301 1 0.322892 1 0.319077 0.955296 0.324301 0.95608 0.329163 1 0.322892 1 0.299651 1 0.316847 1 0.319077 0.954371 0.320562 1 0.319077 1 0.316847 0.954371 0.320562 0.955296 0.324301 1 0.319077 1 0.299651 1 0.316541 1 0.316847 0.953407 0.318406 1 0.316847 1 0.316541 0.953407 0.318406 0.954371 0.320562 1 0.316847 1 0.323054 1 0.3183 1 0.316541 0.952525 0.318161 1 0.316541 1 0.3183 1 0.299651 1 0.323054 1 0.316541 0.952525 0.318161 0.953407 0.318406 1 0.316541 1 0.323054 1 0.322007 1 0.3183 0.951849 0.319958 1 0.3183 1 0.322007 0.951849 0.319958 0.952525 0.318161 1 0.3183 1 0.323054 1 0.327247 1 0.322007 0.951481 0.323671 1 0.322007 1 0.327247 0.951481 0.323671 0.951849 0.319958 1 0.322007 1 0.323054 1 0.333333 1 0.327247 0.951481 0.328882 1 0.327247 1 0.333333 0.951481 0.328882 0.951481 0.323671 1 0.327247 1 0.346458 1 0.33942 1 0.333333 0.951849 0.334912 1 0.333333 1 0.33942 1 0.323054 1 0.346458 1 0.333333 0.951481 0.328882 1 0.333333 0.951849 0.334912 1 0.346458 1 0.344659 1 0.33942 0.952525 0.340921 1 0.33942 1 0.344659 0.952525 0.340921 0.951849 0.334912 1 0.33942 1 0.346458 1 0.348366 1 0.344659 0.953407 0.346074 1 0.344659 1 0.348366 0.953407 0.346074 0.952525 0.340921 1 0.344659 0.954371 0.3497 1 0.348366 1 0.350126 0.954371 0.3497 0.953407 0.346074 1 0.348366 0.955296 0.351395 1 0.350126 1 0.34982 0.955296 0.351395 0.954371 0.3497 1 0.350126 0.95608 0.351046 1 0.34982 1 0.34759 0.95608 0.351046 0.955296 0.351395 1 0.34982 0.956644 0.348798 1 0.34759 1 0.343774 0.956644 0.348798 0.95608 0.351046 1 0.34759 0.956938 0.344987 1 0.343774 1 0.338841 0.956938 0.344987 0.956644 0.348798 1 0.343774 0.956938 0.340079 0.956938 0.344987 1 0.338841 0.956644 0.665387 1 0.666667 1 0.661159 0.95608 0.670837 1 0.672175 1 0.666667 0.956644 0.665387 0.95608 0.670837 1 0.666667 0.956938 0.659921 1 0.661159 1 0.656226 0.956938 0.659921 0.956644 0.665387 1 0.661159 0.956938 0.655013 1 0.656226 1 0.65241 0.956938 0.655013 0.956938 0.659921 1 0.656226 0.956644 0.651202 1 0.65241 1 0.65018 0.956644 0.651202 0.956938 0.655013 1 0.65241 0.95608 0.648954 1 0.65018 1 0.649874 0.95608 0.648954 0.956644 0.651202 1 0.65018 0.955296 0.648605 1 0.649874 1 0.651634 0.955296 0.648605 0.95608 0.648954 1 0.649874 1 0.656388 1 0.655341 1 0.651634 0.954371 0.6503 1 0.651634 1 0.655341 0.954371 0.6503 0.955296 0.648605 1 0.651634 1 0.656388 1 0.66058 1 0.655341 0.953407 0.653926 1 0.655341 1 0.66058 0.953407 0.653926 0.954371 0.6503 1 0.655341 1 0.679792 1 0.666667 1 0.66058 0.952525 0.659079 1 0.66058 1 0.666667 1 0.656388 1 0.679792 1 0.66058 0.952525 0.659079 0.953407 0.653926 1 0.66058 1 0.679792 1 0.672753 1 0.666667 0.951849 0.665088 1 0.666667 1 0.672753 0.952525 0.659079 1 0.666667 0.951849 0.665088 1 0.679792 1 0.677993 1 0.672753 0.951481 0.671118 1 0.672753 1 0.677993 0.951481 0.671118 0.951849 0.665088 1 0.672753 1 0.703195 1 0.6817 1 0.677993 0.951481 0.676329 1 0.677993 1 0.6817 1 0.679792 1 0.703195 1 0.677993 0.951481 0.676329 0.951481 0.671118 1 0.677993 1 0.703195 1 0.683459 1 0.6817 0.951849 0.680042 1 0.6817 1 0.683459 0.951849 0.680042 0.951481 0.676329 1 0.6817 1 0.703195 1 0.683153 1 0.683459 0.952525 0.681839 1 0.683459 1 0.683153 0.952525 0.681839 0.951849 0.680042 1 0.683459 1 0.703195 1 0.680923 1 0.683153 0.953407 0.681594 1 0.683153 1 0.680923 0.953407 0.681594 0.952525 0.681839 1 0.683153 0.954371 0.679438 1 0.680923 1 0.677108 1 0.703195 1 0.726598 1 0.680923 0.954371 0.679438 0.953407 0.681594 1 0.680923 0.955296 0.675699 1 0.677108 1 0.672175 0.955296 0.675699 0.954371 0.679438 1 0.677108 0.95608 0.670837 0.955296 0.675699 1 0.672175 0.043356 0.665387 0 0.666667 0 0.672175 0.04306197 0.659921 0 0.661159 0 0.666667 0.043356 0.665387 0.04306197 0.659921 0 0.666667 0.04391998 0.670837 0 0.672175 0 0.677108 0.04391998 0.670837 0.043356 0.665387 0 0.672175 0.04470396 0.675699 0 0.677108 0 0.680923 0.04470396 0.675699 0.04391998 0.670837 0 0.677108 0 0.700349 0 0.683153 0 0.680923 0.04562896 0.679438 0 0.680923 0 0.683153 0.04562896 0.679438 0.04470396 0.675699 0 0.680923 0 0.700349 0 0.683459 0 0.683153 0.04659295 0.681594 0 0.683153 0 0.683459 0.04659295 0.681594 0.04562896 0.679438 0 0.683153 0 0.676946 0 0.6817 0 0.683459 0.04747498 0.681839 0 0.683459 0 0.6817 0 0.700349 0 0.676946 0 0.683459 0.04747498 0.681839 0.04659295 0.681594 0 0.683459 0 0.676946 0 0.677993 0 0.6817 0.04815089 0.680042 0 0.6817 0 0.677993 0.04815089 0.680042 0.04747498 0.681839 0 0.6817 0 0.676946 0 0.672753 0 0.677993 0.04851889 0.676329 0 0.677993 0 0.672753 0.04851889 0.676329 0.04815089 0.680042 0 0.677993 0 0.676946 0 0.666667 0 0.672753 0.04851889 0.671118 0 0.672753 0 0.666667 0.04851889 0.671118 0.04851889 0.676329 0 0.672753 0 0.653542 0 0.66058 0 0.666667 0.04815089 0.665088 0 0.666667 0 0.66058 0 0.676946 0 0.653542 0 0.666667 0.04851889 0.671118 0 0.666667 0.04815089 0.665088 0 0.653542 0 0.655341 0 0.66058 0.04747498 0.659079 0 0.66058 0 0.655341 0.04747498 0.659079 0.04815089 0.665088 0 0.66058 0 0.653542 0 0.651634 0 0.655341 0.04659295 0.653926 0 0.655341 0 0.651634 0.04659295 0.653926 0.04747498 0.659079 0 0.655341 0.04562896 0.6503 0 0.651634 0 0.649874 0.04562896 0.6503 0.04659295 0.653926 0 0.651634 0.04470396 0.648605 0 0.649874 0 0.65018 0.04470396 0.648605 0.04562896 0.6503 0 0.649874 0.04391998 0.648954 0 0.65018 0 0.65241 0.04391998 0.648954 0.04470396 0.648605 0 0.65018 0.043356 0.651202 0 0.65241 0 0.656226 0.043356 0.651202 0.04391998 0.648954 0 0.65241 0.04306197 0.655013 0 0.656226 0 0.661159 0.04306197 0.655013 0.043356 0.651202 0 0.656226 0.04306197 0.659921 0.04306197 0.655013 0 0.661159 0.043356 0.334613 0 0.333333 0 0.338841 0.04391998 0.329163 0 0.327825 0 0.333333 0.043356 0.334613 0.04391998 0.329163 0 0.333333 0.04306197 0.340079 0 0.338841 0 0.343774 0.04306197 0.340079 0.043356 0.334613 0 0.338841 0.04306197 0.344987 0 0.343774 0 0.34759 0.04306197 0.344987 0.04306197 0.340079 0 0.343774 0.043356 0.348798 0 0.34759 0 0.34982 0.043356 0.348798 0.04306197 0.344987 0 0.34759 0.04391998 0.351046 0 0.34982 0 0.350126 0.04391998 0.351046 0.043356 0.348798 0 0.34982 0.04470396 0.351395 0 0.350126 0 0.348366 0.04470396 0.351395 0.04391998 0.351046 0 0.350126 0 0.343613 0 0.344659 0 0.348366 0.04562896 0.3497 0 0.348366 0 0.344659 0.04562896 0.3497 0.04470396 0.351395 0 0.348366 0 0.343613 0 0.33942 0 0.344659 0.04659295 0.346074 0 0.344659 0 0.33942 0.04659295 0.346074 0.04562896 0.3497 0 0.344659 0 0.32021 0 0.333333 0 0.33942 0.04747498 0.340921 0 0.33942 0 0.333333 0 0.343613 0 0.32021 0 0.33942 0.04747498 0.340921 0.04659295 0.346074 0 0.33942 0 0.32021 0 0.327247 0 0.333333 0.04815089 0.334912 0 0.333333 0 0.327247 0.04747498 0.340921 0 0.333333 0.04815089 0.334912 0 0.32021 0 0.322007 0 0.327247 0.04851889 0.328882 0 0.327247 0 0.322007 0.04851889 0.328882 0.04815089 0.334912 0 0.327247 0 0.296807 0 0.3183 0 0.322007 0.04851889 0.323671 0 0.322007 0 0.3183 0 0.32021 0 0.296807 0 0.322007 0.04851889 0.323671 0.04851889 0.328882 0 0.322007 0 0.296807 0 0.316541 0 0.3183 0.04815089 0.319958 0 0.3183 0 0.316541 0.04815089 0.319958 0.04851889 0.323671 0 0.3183 0 0.296807 0 0.316847 0 0.316541 0.04747498 0.318161 0 0.316541 0 0.316847 0.04747498 0.318161 0.04815089 0.319958 0 0.316541 0 0.296807 0 0.319077 0 0.316847 0.04659295 0.318406 0 0.316847 0 0.319077 0.04659295 0.318406 0.04747498 0.318161 0 0.316847 0.04562896 0.320562 0 0.319077 0 0.322892 0 0.296807 0 0.273404 0 0.319077 0.04562896 0.320562 0.04659295 0.318406 0 0.319077 0.04470396 0.324301 0 0.322892 0 0.327825 0.04470396 0.324301 0.04562896 0.320562 0 0.322892 0.04391998 0.329163 0.04470396 0.324301 0 0.327825 0.923174 0.179046 1 0.174849 1 0.179057 1 0.153544 1 0.174849 1 0.169526 0.920605 0.173936 1 0.169526 1 0.174849 0.920605 0.173936 1 0.174849 0.923174 0.179046 0.925585 0.183041 1 0.179057 1 0.1816329 0.923174 0.179046 1 0.179057 0.925585 0.183041 0.927586 0.185431 1 0.1816329 1 0.182325 0.925585 0.183041 1 0.1816329 0.927586 0.185431 0.929004 0.18598 1 0.182325 1 0.181138 0.927586 0.185431 1 0.182325 0.929004 0.18598 0.929737 0.184706 1 0.181138 1 0.1782979 0.929004 0.18598 1 0.181138 0.929737 0.184706 0.929737 0.181836 1 0.1782979 1 0.17418 0.929737 0.184706 1 0.1782979 0.929737 0.181836 0.929004 0.177748 1 0.17418 1 0.169262 0.929737 0.181836 1 0.17418 0.929004 0.177748 0.927586 0.1729159 1 0.169262 1 0.164071 0.929004 0.177748 1 0.169262 0.927586 0.1729159 0.925585 0.167863 1 0.164071 1 0.159153 0.927586 0.1729159 1 0.164071 0.925585 0.167863 0 0.01027894 1 0.155036 1 0.159153 0.923174 0.163123 1 0.159153 1 0.155036 0 0.06839197 0 0.01027894 1 0.159153 0.925585 0.167863 1 0.159153 0.923174 0.163123 1 0.036529 1 0.152195 1 0.155036 0.920605 0.159211 1 0.155036 1 0.152195 1 0.013125 1 0.036529 1 0.155036 0 0.01027894 1 0.013125 1 0.155036 0.920605 0.159211 0.923174 0.163123 1 0.155036 1 0.05993199 1 0.151009 1 0.152195 0.918202 0.156578 1 0.152195 1 0.151009 1 0.036529 1 0.05993199 1 0.152195 0.920605 0.159211 1 0.152195 0.918202 0.156578 1 0.08333498 1 0.1517 1 0.151009 0.916325 0.155576 1 0.151009 1 0.1517 1 0.05993199 1 0.08333498 1 0.151009 0.918202 0.156578 1 0.151009 0.916325 0.155576 1 0.106738 1 0.154276 1 0.1517 0.915291 0.1563979 1 0.1517 1 0.154276 1 0.08333498 1 0.106738 1 0.1517 0.916325 0.155576 1 0.1517 0.915291 0.1563979 1 0.130141 1 0.158484 1 0.154276 0.915291 0.159026 1 0.154276 1 0.158484 1 0.106738 1 0.130141 1 0.154276 0.915291 0.1563979 1 0.154276 0.915291 0.159026 1 0.130141 1 0.163807 1 0.158484 0.916325 0.163197 1 0.158484 1 0.163807 0.915291 0.159026 1 0.158484 0.916325 0.163197 1 0.153544 1 0.169526 1 0.163807 0.918202 0.168399 1 0.163807 1 0.169526 1 0.130141 1 0.153544 1 0.163807 0.916325 0.163197 1 0.163807 0.918202 0.168399 0.918202 0.168399 1 0.169526 0.920605 0.173936 0 0.489719 0 0.48761 0 0.491818 0.04069799 0.491884 0 0.491818 0 0.48761 0 0.489719 0 0.491818 0 0.49714 0.04094499 0.497164 0 0.49714 0 0.491818 0.04094499 0.497164 0 0.491818 0.04069799 0.491884 0 0.466317 0 0.485033 0 0.48761 0.040241 0.487708 0 0.48761 0 0.485033 0 0.489719 0 0.466317 0 0.48761 0.04069799 0.491884 0 0.48761 0.040241 0.487708 0 0.466317 0 0.484342 0 0.485033 0.03964096 0.485149 0 0.485033 0 0.484342 0.040241 0.487708 0 0.485033 0.03964096 0.485149 0 0.466317 0 0.485528 0 0.484342 0.03898096 0.484459 0 0.484342 0 0.485528 0.03964096 0.485149 0 0.484342 0.03898096 0.484459 0.03834092 0.485633 0 0.485528 0 0.488369 0.03898096 0.484459 0 0.485528 0.03834092 0.485633 0.03779596 0.488451 0 0.488369 0 0.492486 0.03834092 0.485633 0 0.488369 0.03779596 0.488451 0.03740197 0.492538 0 0.492486 0 0.497405 0.03779596 0.488451 0 0.492486 0.03740197 0.492538 0.0371949 0.497422 0 0.497405 0 0.502595 0.03740197 0.492538 0 0.497405 0.0371949 0.497422 0.0371949 0.502578 0 0.502595 0 0.507514 0.0371949 0.497422 0 0.502595 0.0371949 0.502578 0.03740197 0.507462 0 0.507514 0 0.511631 0.0371949 0.502578 0 0.507514 0.03740197 0.507462 0.03779596 0.511549 0 0.511631 0 0.514472 0.03779596 0.511549 0.03740197 0.507462 0 0.511631 0.03834092 0.514367 0 0.514472 0 0.515658 0.03779596 0.511549 0 0.514472 0.03834092 0.514367 0 0.513123 0 0.514967 0 0.515658 0.03898096 0.515541 0 0.515658 0 0.514967 0 0.536526 0 0.513123 0 0.515658 0.03834092 0.514367 0 0.515658 0.03898096 0.515541 0 0.513123 0 0.51239 0 0.514967 0.03964096 0.514851 0 0.514967 0 0.51239 0.03898096 0.515541 0 0.514967 0.03964096 0.514851 0 0.513123 0 0.508182 0 0.51239 0.040241 0.512292 0 0.51239 0 0.508182 0.03964096 0.514851 0 0.51239 0.040241 0.512292 0 0.489719 0 0.50286 0 0.508182 0.04069799 0.508116 0 0.508182 0 0.50286 0 0.513123 0 0.489719 0 0.508182 0.040241 0.512292 0 0.508182 0.04069799 0.508116 0 0.489719 0 0.49714 0 0.50286 0.04094499 0.502836 0 0.50286 0 0.49714 0.04069799 0.508116 0 0.50286 0.04094499 0.502836 0.04094499 0.502836 0 0.49714 0.04094499 0.497164 1 0.603405 1 0.598274 1 0.601663 0.968945 0.601212 1 0.601663 1 0.598274 0.968601 0.602937 1 0.603405 1 0.601663 0.968601 0.602937 1 0.601663 0.968945 0.601212 0.969632 0.597855 1 0.598274 1 0.59306 0.968945 0.601212 1 0.598274 0.969632 0.597855 0.9702 0.592675 1 0.59306 1 0.586704 0.969632 0.597855 1 0.59306 0.9702 0.592675 0.970586 0.586352 1 0.586704 1 0.579964 0.9702 0.592675 1 0.586704 0.970586 0.586352 0.970751 0.57964 1 0.579964 1 0.573608 0.970586 0.586352 1 0.579964 0.970751 0.57964 0.970682 0.573307 1 0.573608 1 0.568392 0.970751 0.57964 1 0.573608 0.970682 0.573307 0.970383 0.568105 1 0.568392 1 0.565004 0.970682 0.573307 1 0.568392 0.970383 0.568105 0.969884 0.564721 1 0.565004 1 0.563261 0.970383 0.568105 1 0.565004 0.969884 0.564721 0.96964 0.562981 1 0.563261 1 0.560463 0.969884 0.564721 1 0.563261 0.96964 0.562981 0.969501 0.560192 1 0.560463 1 0.557075 0.96964 0.562981 1 0.560463 0.969501 0.560192 0.969493 0.556819 1 0.557075 1 0.533683 0.969501 0.560192 1 0.557075 0.969493 0.556819 0.969811 0.533533 1 0.533683 1 0.510281 0.969493 0.556819 1 0.533683 0.969811 0.533533 0.969963 0.510235 1 0.510281 1 0.486877 0.969811 0.533533 1 0.510281 0.969963 0.510235 0.969954 0.486936 1 0.486877 1 0.463474 0.969963 0.510235 1 0.486877 0.969954 0.486936 0.969781 0.463637 1 0.463474 1 0.440071 0.969954 0.486936 1 0.463474 0.969781 0.463637 0.969442 0.440341 1 0.440071 1 0.416668 0.969781 0.463637 1 0.440071 0.969442 0.440341 0.968927 0.417047 1 0.416668 1 0.393265 0.969442 0.440341 1 0.416668 0.968927 0.417047 0.96822 0.393758 1 0.393265 1 0.369862 0.968927 0.417047 1 0.393265 0.96822 0.393758 0.967301 0.370474 1 0.369862 1 0.346458 0.96822 0.393758 1 0.369862 0.967301 0.370474 0.96614 0.347199 1 0.346458 1 0.323054 0.967301 0.370474 1 0.346458 0.96614 0.347199 0.964698 0.323933 1 0.323054 1 0.299651 0.96614 0.347199 1 0.323054 0.964698 0.323933 0.96292 0.30068 1 0.299651 1 0.276258 0.964698 0.323933 1 0.299651 0.96292 0.30068 0.960736 0.277455 1 0.276258 1 0.272871 0.96292 0.30068 1 0.276258 0.960736 0.277455 0.960468 0.274088 1 0.272871 1 0.270072 0.960736 0.277455 1 0.272871 0.960468 0.274088 0.960415 0.271295 1 0.270072 1 0.26833 0.960468 0.274088 1 0.270072 0.960415 0.271295 0.960587 0.269544 1 0.26833 1 0.264941 0.960415 0.271295 1 0.26833 0.960587 0.269544 0.960955 0.266136 1 0.264941 1 0.259726 0.960587 0.269544 1 0.264941 0.960955 0.266136 0.960906 0.260927 1 0.259726 1 0.253371 0.960955 0.266136 1 0.259726 0.960906 0.260927 0.960445 0.254602 1 0.253371 1 0.24663 0.960906 0.260927 1 0.253371 0.960445 0.254602 0.959607 0.247915 1 0.24663 1 0.240274 0.960445 0.254602 1 0.24663 0.959607 0.247915 0.958468 0.241631 1 0.240274 1 0.235059 0.959607 0.247915 1 0.240274 0.958468 0.241631 1 0.223742 1 0.23167 1 0.235059 0.95715 0.2365 1 0.235059 1 0.23167 1 0.20035 1 0.223742 1 0.235059 0.958468 0.241631 1 0.235059 0.95715 0.2365 1 0.227129 1 0.229928 1 0.23167 0.955823 0.233199 1 0.23167 1 0.229928 1 0.223742 1 0.227129 1 0.23167 0.95715 0.2365 1 0.23167 0.955823 0.233199 0.955145 0.2315019 1 0.229928 1 0.227129 0.955823 0.233199 1 0.229928 0.955145 0.2315019 0.954414 0.228751 1 0.227129 1 0.223742 0.955145 0.2315019 1 0.227129 0.954414 0.228751 0.953749 0.225406 1 0.223742 1 0.20035 0.954414 0.228751 1 0.223742 0.953749 0.225406 0.949284 0.202284 1 0.20035 1 0.1769469 0.953749 0.225406 1 0.20035 0.949284 0.202284 0.94354 0.179212 1 0.1769469 1 0.153544 0.949284 0.202284 1 0.1769469 0.94354 0.179212 0.935968 0.156224 1 0.153544 1 0.130141 0.94354 0.179212 1 0.153544 0.935968 0.156224 0.925644 0.133368 1 0.130141 1 0.106738 0.935968 0.156224 1 0.130141 0.925644 0.133368 0.910903 0.1107259 1 0.106738 1 0.08333498 0.925644 0.133368 1 0.106738 0.910903 0.1107259 0.888465 0.08846098 1 0.08333498 1 0.05993199 0.910903 0.1107259 1 0.08333498 0.888465 0.08846098 0.851046 0.06695097 1 0.05993199 1 0.036529 0.888465 0.08846098 1 0.05993199 0.851046 0.06695097 0.78022 0.04723989 1 0.036529 1 0.013125 0.851046 0.06695097 1 0.036529 0.78022 0.04723989 0.630814 0.03275698 1 0.013125 0 0.01027894 0.78022 0.04723989 1 0.013125 0.630814 0.03275698 0 0.06500399 0 0.03368192 0 0.01027894 0.395304 0.03172689 0 0.01027894 0 0.03368192 0 0.06839197 0 0.06500399 0 0.01027894 0.630814 0.03275698 0 0.01027894 0.395304 0.03172689 0 0.06046295 0 0.05707496 0 0.03368192 0.232493 0.04508197 0 0.03368192 0 0.05707496 0 0.06326097 0 0.06046295 0 0.03368192 0 0.06500399 0 0.06326097 0 0.03368192 0.395304 0.03172689 0 0.03368192 0.232493 0.04508197 0.155229 0.06441396 0 0.05707496 0 0.06046295 0.232493 0.04508197 0 0.05707496 0.155229 0.06441396 0.147554 0.06739497 0 0.06046295 0 0.06326097 0.155229 0.06441396 0 0.06046295 0.147554 0.06739497 0.141161 0.06983095 0 0.06326097 0 0.06500399 0.147554 0.06739497 0 0.06326097 0.141161 0.06983095 0.136764 0.07129698 0 0.06500399 0 0.06839197 0.141161 0.06983095 0 0.06500399 0.136764 0.07129698 0.128619 0.07417595 0 0.06839197 0 0.07360696 0.136764 0.07129698 0 0.06839197 0.128619 0.07417595 0.118999 0.07885497 0 0.07360696 0 0.07996296 0.128619 0.07417595 0 0.07360696 0.118999 0.07885497 0.10973 0.08473497 0 0.07996296 0 0.086703 0.118999 0.07885497 0 0.07996296 0.10973 0.08473497 0.101967 0.09110599 0 0.086703 0 0.093059 0.10973 0.08473497 0 0.086703 0.101967 0.09110599 0.096255 0.09721797 0 0.093059 0 0.09827399 0.101967 0.09110599 0 0.093059 0.096255 0.09721797 0.092785 0.102316 0 0.09827399 0 0.101663 0.096255 0.09721797 0 0.09827399 0.092785 0.102316 0.09158998 0.105714 0 0.101663 0 0.1034049 0.092785 0.102316 0 0.101663 0.09158998 0.105714 0.09097295 0.107458 0 0.1034049 0 0.106204 0.09158998 0.105714 0 0.1034049 0.09097295 0.107458 0.08931499 0.110195 0 0.106204 0 0.109592 0.09097295 0.107458 0 0.106204 0.08931499 0.110195 0.086977 0.113471 0 0.109592 0 0.132984 0.08931499 0.110195 0 0.109592 0.086977 0.113471 0.07291001 0.1361359 0 0.132984 0 0.156387 0.086977 0.113471 0 0.132984 0.07291001 0.1361359 0.06298798 0.159011 0 0.156387 0 0.179791 0.07291001 0.1361359 0 0.156387 0.06298798 0.159011 0.05567795 0.182012 0 0.179791 0 0.203194 0.06298798 0.159011 0 0.179791 0.05567795 0.182012 0.05011296 0.205094 0 0.203194 0 0.226597 0.05567795 0.182012 0 0.203194 0.05011296 0.205094 0.04577493 0.228233 0 0.226597 0 0.25 0.05011296 0.205094 0 0.226597 0.04577493 0.228233 0.04233098 0.251413 0 0.25 0 0.273404 0.04577493 0.228233 0 0.25 0.04233098 0.251413 0.03956395 0.274623 0 0.273404 0 0.296807 0.04233098 0.251413 0 0.273404 0.03956395 0.274623 0.03732198 0.297856 0 0.296807 0 0.32021 0.03956395 0.274623 0 0.296807 0.03732198 0.297856 0.03549891 0.321106 0 0.32021 0 0.343613 0.03732198 0.297856 0 0.32021 0.03549891 0.321106 0.03401988 0.34437 0 0.343613 0 0.367016 0.03549891 0.321106 0 0.343613 0.03401988 0.34437 0.03282696 0.367644 0 0.367016 0 0.390408 0.03401988 0.34437 0 0.367016 0.03282696 0.367644 0.03188097 0.390915 0 0.390408 0 0.393796 0.03282696 0.367644 0 0.390408 0.03188097 0.390915 0.03169095 0.394284 0 0.393796 0 0.396595 0.03188097 0.390915 0 0.393796 0.03169095 0.394284 0 0.401726 0 0.398337 0 0.396595 0.03139895 0.397063 0 0.396595 0 0.398337 0.03169095 0.394284 0 0.396595 0.03139895 0.397063 0.03105497 0.398788 0 0.398337 0 0.401726 0.03139895 0.397063 0 0.398337 0.03105497 0.398788 0.03036797 0.402145 0 0.401726 0 0.40694 0.03105497 0.398788 0 0.401726 0.03036797 0.402145 0.02979993 0.407325 0 0.40694 0 0.413296 0.03036797 0.402145 0 0.40694 0.02979993 0.407325 0.02941393 0.413648 0 0.413296 0 0.420036 0.02979993 0.407325 0 0.413296 0.02941393 0.413648 0.02924895 0.42036 0 0.420036 0 0.426392 0.02941393 0.413648 0 0.420036 0.02924895 0.42036 0.02931797 0.426693 0 0.426392 0 0.431608 0.02924895 0.42036 0 0.426392 0.02931797 0.426693 0.02961695 0.431895 0 0.431608 0 0.434996 0.02931797 0.426693 0 0.431608 0.02961695 0.431895 0.03011596 0.435279 0 0.434996 0 0.436739 0.02961695 0.431895 0 0.434996 0.03011596 0.435279 0.03035998 0.437019 0 0.436739 0 0.439537 0.03011596 0.435279 0 0.436739 0.03035998 0.437019 0.03049898 0.439808 0 0.439537 0 0.442925 0.03035998 0.437019 0 0.439537 0.03049898 0.439808 0.0305069 0.443181 0 0.442925 0 0.466317 0.03049898 0.439808 0 0.442925 0.0305069 0.443181 0.03018891 0.466468 0 0.466317 0 0.489719 0.0305069 0.443181 0 0.466317 0.03018891 0.466468 0.03003698 0.489766 0 0.489719 0 0.513123 0.03018891 0.466468 0 0.489719 0.03003698 0.489766 0.03004598 0.513066 0 0.513123 0 0.536526 0.03003698 0.489766 0 0.513123 0.03004598 0.513066 0.03021889 0.536364 0 0.536526 0 0.559929 0.03004598 0.513066 0 0.536526 0.03021889 0.536364 0.03055799 0.559661 0 0.559929 0 0.583332 0.03021889 0.536364 0 0.559929 0.03055799 0.559661 0.03107392 0.582954 0 0.583332 0 0.606736 0.03055799 0.559661 0 0.583332 0.03107392 0.582954 0.03178 0.606243 0 0.606736 0 0.630139 0.03107392 0.582954 0 0.606736 0.03178 0.606243 0.03269892 0.629527 0 0.630139 0 0.653542 0.03178 0.606243 0 0.630139 0.03269892 0.629527 0.0338599 0.652802 0 0.653542 0 0.676946 0.03269892 0.629527 0 0.653542 0.0338599 0.652802 0.03530198 0.676068 0 0.676946 0 0.700349 0.0338599 0.652802 0 0.676946 0.03530198 0.676068 0.03707993 0.69932 0 0.700349 0 0.723742 0.03530198 0.676068 0 0.700349 0.03707993 0.69932 0.03926396 0.722545 0 0.723742 0 0.727129 0.03707993 0.69932 0 0.723742 0.03926396 0.722545 0.03953188 0.725912 0 0.727129 0 0.729928 0.03926396 0.722545 0 0.727129 0.03953188 0.725912 0.03958499 0.728705 0 0.729928 0 0.73167 0.03953188 0.725912 0 0.729928 0.03958499 0.728705 0.03941297 0.730456 0 0.73167 0 0.735059 0.03958499 0.728705 0 0.73167 0.03941297 0.730456 0.03904491 0.733864 0 0.735059 0 0.740274 0.03941297 0.730456 0 0.735059 0.03904491 0.733864 0.03909397 0.739073 0 0.740274 0 0.746629 0.03904491 0.733864 0 0.740274 0.03909397 0.739073 0.03955495 0.745398 0 0.746629 0 0.75337 0.03909397 0.739073 0 0.746629 0.03955495 0.745398 0.04039299 0.752085 0 0.75337 0 0.759726 0.03955495 0.745398 0 0.75337 0.04039299 0.752085 0.04153198 0.758369 0 0.759726 0 0.764941 0.04039299 0.752085 0 0.759726 0.04153198 0.758369 0 0.776258 0 0.76833 0 0.764941 0.04284989 0.7635 0 0.764941 0 0.76833 0 0.79965 0 0.776258 0 0.764941 0.04153198 0.758369 0 0.764941 0.04284989 0.7635 0 0.772871 0 0.770072 0 0.76833 0.04417693 0.766801 0 0.76833 0 0.770072 0 0.776258 0 0.772871 0 0.76833 0.04284989 0.7635 0 0.76833 0.04417693 0.766801 0.04485493 0.768498 0 0.770072 0 0.772871 0.04417693 0.766801 0 0.770072 0.04485493 0.768498 0.04558593 0.771249 0 0.772871 0 0.776258 0.04485493 0.768498 0 0.772871 0.04558593 0.771249 0.04625093 0.774594 0 0.776258 0 0.79965 0.04558593 0.771249 0 0.776258 0.04625093 0.774594 0.05071598 0.797716 0 0.79965 0 0.823053 0.04625093 0.774594 0 0.79965 0.05071598 0.797716 0.05645996 0.820789 0 0.823053 0 0.846456 0.05071598 0.797716 0 0.823053 0.05645996 0.820789 0.06403195 0.843776 0 0.846456 0 0.869859 0.05645996 0.820789 0 0.846456 0.06403195 0.843776 0.07435697 0.866632 0 0.869859 0 0.893262 0.06403195 0.843776 0 0.869859 0.07435697 0.866632 0.08909696 0.889274 0 0.893262 0 0.916665 0.07435697 0.866632 0 0.893262 0.08909696 0.889274 0.111535 0.91154 0 0.916665 0 0.940069 0.08909696 0.889274 0 0.916665 0.111535 0.91154 0.148955 0.93305 0 0.940069 0 0.963472 0.111535 0.91154 0 0.940069 0.148955 0.93305 0.2197819 0.95276 0 0.963472 0 0.986875 0.148955 0.93305 0 0.963472 0.2197819 0.95276 0.36919 0.967243 0 0.986875 1 0.989721 0.2197819 0.95276 0 0.986875 0.36919 0.967243 1 0.934996 1 0.966318 1 0.989721 0.604699 0.968273 1 0.989721 1 0.966318 1 0.931608 1 0.934996 1 0.989721 0.36919 0.967243 1 0.989721 0.604699 0.968273 1 0.939537 1 0.942925 1 0.966318 0.767508 0.954918 1 0.966318 1 0.942925 1 0.936739 1 0.939537 1 0.966318 1 0.934996 1 0.936739 1 0.966318 0.604699 0.968273 1 0.966318 0.767508 0.954918 0.844771 0.935586 1 0.942925 1 0.939537 0.767508 0.954918 1 0.942925 0.844771 0.935586 0.852446 0.932605 1 0.939537 1 0.936739 0.844771 0.935586 1 0.939537 0.852446 0.932605 0.858839 0.930169 1 0.936739 1 0.934996 0.852446 0.932605 1 0.936739 0.858839 0.930169 0.863236 0.928703 1 0.934996 1 0.931608 0.858839 0.930169 1 0.934996 0.863236 0.928703 0.871381 0.925824 1 0.931608 1 0.926393 0.863236 0.928703 1 0.931608 0.871381 0.925824 0.881001 0.921145 1 0.926393 1 0.920037 0.871381 0.925824 1 0.926393 0.881001 0.921145 0.89027 0.915265 1 0.920037 1 0.913297 0.881001 0.921145 1 0.920037 0.89027 0.915265 0.898033 0.908894 1 0.913297 1 0.906941 0.89027 0.915265 1 0.913297 0.898033 0.908894 0.903745 0.902782 1 0.906941 1 0.901726 0.898033 0.908894 1 0.906941 0.903745 0.902782 0.907215 0.897684 1 0.901726 1 0.898337 0.903745 0.902782 1 0.901726 0.907215 0.897684 0.90841 0.894286 1 0.898337 1 0.896595 0.907215 0.897684 1 0.898337 0.90841 0.894286 0.909027 0.892542 1 0.896595 1 0.893796 0.90841 0.894286 1 0.896595 0.909027 0.892542 0.910685 0.889805 1 0.893796 1 0.890408 0.909027 0.892542 1 0.893796 0.910685 0.889805 0.913023 0.886529 1 0.890408 1 0.867016 0.910685 0.889805 1 0.890408 0.913023 0.886529 0.92709 0.863865 1 0.867016 1 0.843614 0.92709 0.863865 0.913023 0.886529 1 0.867016 0.937011 0.84099 1 0.843614 1 0.820211 0.92709 0.863865 1 0.843614 0.937011 0.84099 0.944322 0.81799 1 0.820211 1 0.796808 0.937011 0.84099 1 0.820211 0.944322 0.81799 0.949886 0.794909 1 0.796808 1 0.773405 0.944322 0.81799 1 0.796808 0.949886 0.794909 0.954225 0.77177 1 0.773405 1 0.750001 0.949886 0.794909 1 0.773405 0.954225 0.77177 0.957669 0.74859 1 0.750001 1 0.726598 0.954225 0.77177 1 0.750001 0.957669 0.74859 0.960436 0.72538 1 0.726598 1 0.703195 0.957669 0.74859 1 0.726598 0.960436 0.72538 0.962678 0.702147 1 0.703195 1 0.679792 0.960436 0.72538 1 0.703195 0.962678 0.702147 0.964501 0.678896 1 0.679792 1 0.656388 0.962678 0.702147 1 0.679792 0.964501 0.678896 0.96598 0.655631 1 0.656388 1 0.632985 0.964501 0.678896 1 0.656388 0.96598 0.655631 0.967173 0.632357 1 0.632985 1 0.609592 0.96598 0.655631 1 0.632985 0.967173 0.632357 0.968119 0.609085 1 0.609592 1 0.606204 0.967173 0.632357 1 0.609592 0.968119 0.609085 0.968309 0.605716 1 0.606204 1 0.603405 0.968119 0.609085 1 0.606204 0.968309 0.605716 0.968309 0.605716 1 0.603405 0.968601 0.602937 0.5 0.647895 0.5 0.641129 0.476394 0.63927 0.524909 0.645933 0.523606 0.63927 0.5 0.641129 0.524909 0.645933 0.5 0.641129 0.5 0.647895 0.475091 0.645933 0.476394 0.63927 0.453618 0.63377 0.475091 0.645933 0.5 0.647895 0.476394 0.63927 0.451088 0.640133 0.453618 0.63377 0.432408 0.624844 0.475091 0.645933 0.453618 0.63377 0.451088 0.640133 0.428782 0.63073 0.432408 0.624844 0.413352 0.612819 0.451088 0.640133 0.432408 0.624844 0.428782 0.63073 0.408801 0.618079 0.413352 0.612819 0.396874 0.5981 0.428782 0.63073 0.413352 0.612819 0.408801 0.618079 0.391582 0.602624 0.396874 0.5981 0.383239 0.581138 0.408801 0.618079 0.396874 0.5981 0.391582 0.602624 0.377376 0.584839 0.383239 0.581138 0.372583 0.562393 0.391582 0.602624 0.383239 0.581138 0.377376 0.584839 0.366304 0.565207 0.372583 0.562393 0.364962 0.542321 0.377376 0.584839 0.372583 0.562393 0.366304 0.565207 0.358407 0.544216 0.364962 0.542321 0.360393 0.521376 0.366304 0.565207 0.364962 0.542321 0.358407 0.544216 0.353679 0.522332 0.360393 0.521376 0.358871 0.5 0.358407 0.544216 0.360393 0.521376 0.353679 0.522332 0.352105 0.5 0.358871 0.5 0.360393 0.478624 0.353679 0.522332 0.358871 0.5 0.352105 0.5 0.353679 0.477668 0.360393 0.478624 0.364962 0.457679 0.352105 0.5 0.360393 0.478624 0.353679 0.477668 0.358407 0.455784 0.364962 0.457679 0.372583 0.437607 0.353679 0.477668 0.364962 0.457679 0.358407 0.455784 0.366304 0.434793 0.372583 0.437607 0.383239 0.418862 0.358407 0.455784 0.372583 0.437607 0.366304 0.434793 0.377376 0.415161 0.383239 0.418862 0.396874 0.4019 0.366304 0.434793 0.383239 0.418862 0.377376 0.415161 0.391582 0.397376 0.396874 0.4019 0.413352 0.387181 0.377376 0.415161 0.396874 0.4019 0.391582 0.397376 0.408801 0.381921 0.413352 0.387181 0.432408 0.375156 0.391582 0.397376 0.413352 0.387181 0.408801 0.381921 0.428782 0.36927 0.432408 0.375156 0.453618 0.36623 0.408801 0.381921 0.432408 0.375156 0.428782 0.36927 0.451088 0.359867 0.453618 0.36623 0.476394 0.36073 0.428782 0.36927 0.453618 0.36623 0.451088 0.359867 0.475091 0.354067 0.476394 0.36073 0.5 0.358871 0.451088 0.359867 0.476394 0.36073 0.475091 0.354067 0.5 0.352105 0.5 0.358871 0.523606 0.36073 0.475091 0.354067 0.5 0.358871 0.5 0.352105 0.524909 0.354067 0.523606 0.36073 0.546382 0.36623 0.5 0.352105 0.523606 0.36073 0.524909 0.354067 0.548912 0.359867 0.546382 0.36623 0.567592 0.375156 0.524909 0.354067 0.546382 0.36623 0.548912 0.359867 0.571218 0.36927 0.567592 0.375156 0.586648 0.387181 0.548912 0.359867 0.567592 0.375156 0.571218 0.36927 0.591199 0.381921 0.586648 0.387181 0.603126 0.4019 0.571218 0.36927 0.586648 0.387181 0.591199 0.381921 0.608418 0.397376 0.603126 0.4019 0.616761 0.418862 0.591199 0.381921 0.603126 0.4019 0.608418 0.397376 0.622624 0.415161 0.616761 0.418862 0.627417 0.437607 0.608418 0.397376 0.616761 0.418862 0.622624 0.415161 0.633696 0.434793 0.627417 0.437607 0.635038 0.457679 0.622624 0.415161 0.627417 0.437607 0.633696 0.434793 0.641593 0.455784 0.635038 0.457679 0.639607 0.478624 0.633696 0.434793 0.635038 0.457679 0.641593 0.455784 0.646321 0.477668 0.639607 0.478624 0.641129 0.5 0.641593 0.455784 0.639607 0.478624 0.646321 0.477668 0.647895 0.5 0.641129 0.5 0.639607 0.521376 0.646321 0.477668 0.641129 0.5 0.647895 0.5 0.646321 0.522332 0.639607 0.521376 0.635038 0.542321 0.647895 0.5 0.639607 0.521376 0.646321 0.522332 0.641593 0.544216 0.635038 0.542321 0.627417 0.562393 0.646321 0.522332 0.635038 0.542321 0.641593 0.544216 0.633696 0.565207 0.627417 0.562393 0.616761 0.581138 0.641593 0.544216 0.627417 0.562393 0.633696 0.565207 0.622624 0.584839 0.616761 0.581138 0.603126 0.5981 0.633696 0.565207 0.616761 0.581138 0.622624 0.584839 0.608418 0.602624 0.603126 0.5981 0.586648 0.612819 0.622624 0.584839 0.603126 0.5981 0.608418 0.602624 0.591199 0.618079 0.586648 0.612819 0.567592 0.624844 0.608418 0.602624 0.586648 0.612819 0.591199 0.618079 0.571218 0.63073 0.567592 0.624844 0.546382 0.63377 0.591199 0.618079 0.567592 0.624844 0.571218 0.63073 0.548912 0.640133 0.546382 0.63377 0.523606 0.63927 0.571218 0.63073 0.546382 0.63377 0.548912 0.640133 0.548912 0.640133 0.523606 0.63927 0.524909 0.645933 0.479433 0.388274 0.488756 0.377892 0.5 0.377401 0.5 0.371307 0.5 0.377401 0.488756 0.377892 0.5 0.386474 0.5 0.377401 0.511244 0.377892 0.511867 0.371825 0.511244 0.377892 0.5 0.377401 0.5 0.386474 0.479433 0.388274 0.5 0.377401 0.511867 0.371825 0.5 0.377401 0.5 0.371307 0.479433 0.388274 0.477627 0.379359 0.488756 0.377892 0.488133 0.371825 0.488756 0.377892 0.477627 0.379359 0.5 0.371307 0.488756 0.377892 0.488133 0.371825 0.459653 0.393598 0.466721 0.381786 0.477627 0.379359 0.476391 0.373374 0.477627 0.379359 0.466721 0.381786 0.479433 0.388274 0.459653 0.393598 0.477627 0.379359 0.488133 0.371825 0.477627 0.379359 0.476391 0.373374 0.459653 0.393598 0.456143 0.385146 0.466721 0.381786 0.464891 0.375934 0.466721 0.381786 0.456143 0.385146 0.476391 0.373374 0.466721 0.381786 0.464891 0.375934 0.441373 0.402224 0.445987 0.389403 0.456143 0.385146 0.453746 0.379477 0.456143 0.385146 0.445987 0.389403 0.459653 0.393598 0.441373 0.402224 0.456143 0.385146 0.464891 0.375934 0.456143 0.385146 0.453746 0.379477 0.441373 0.402224 0.43634 0.394511 0.445987 0.389403 0.443057 0.383963 0.445987 0.389403 0.43634 0.394511 0.453746 0.379477 0.445987 0.389403 0.443057 0.383963 0.425177 0.413816 0.427276 0.40042 0.43634 0.394511 0.432915 0.389344 0.43634 0.394511 0.427276 0.40042 0.441373 0.402224 0.425177 0.413816 0.43634 0.394511 0.443057 0.383963 0.43634 0.394511 0.432915 0.389344 0.425177 0.413816 0.418857 0.407073 0.427276 0.40042 0.423397 0.395565 0.427276 0.40042 0.418857 0.407073 0.432915 0.389344 0.427276 0.40042 0.423397 0.395565 0.411503 0.427949 0.411136 0.414408 0.418857 0.407073 0.414568 0.402564 0.418857 0.407073 0.411136 0.414408 0.425177 0.413816 0.411503 0.427949 0.418857 0.407073 0.423397 0.395565 0.418857 0.407073 0.414568 0.402564 0.400648 0.444146 0.404153 0.42236 0.411136 0.414408 0.406482 0.410276 0.411136 0.414408 0.404153 0.42236 0.411503 0.427949 0.400648 0.444146 0.411136 0.414408 0.414568 0.402564 0.411136 0.414408 0.406482 0.410276 0.400648 0.444146 0.397941 0.430862 0.404153 0.42236 0.399179 0.418631 0.404153 0.42236 0.397941 0.430862 0.406482 0.410276 0.404153 0.42236 0.399179 0.418631 0.392799 0.4619 0.392524 0.439847 0.397941 0.430862 0.392692 0.427557 0.397941 0.430862 0.392524 0.439847 0.400648 0.444146 0.392799 0.4619 0.397941 0.430862 0.399179 0.418631 0.397941 0.430862 0.392692 0.427557 0.388059 0.480691 0.387919 0.449245 0.392524 0.439847 0.387043 0.436983 0.392524 0.439847 0.387919 0.449245 0.392799 0.4619 0.388059 0.480691 0.392524 0.439847 0.392692 0.427557 0.392524 0.439847 0.387043 0.436983 0.38414 0.541014 0.38414 0.458986 0.387919 0.449245 0.382247 0.446835 0.387919 0.449245 0.38414 0.458986 0.386474 0.5 0.38414 0.541014 0.387919 0.449245 0.388059 0.480691 0.386474 0.5 0.387919 0.449245 0.387043 0.436983 0.387919 0.449245 0.382247 0.446835 0.381195 0.531 0.381195 0.469 0.38414 0.458986 0.378314 0.457043 0.38414 0.458986 0.381195 0.469 0.38414 0.541014 0.381195 0.531 0.38414 0.458986 0.382247 0.446835 0.38414 0.458986 0.378314 0.457043 0.379088 0.52078 0.379088 0.47922 0.381195 0.469 0.375251 0.467534 0.381195 0.469 0.379088 0.47922 0.381195 0.531 0.379088 0.52078 0.381195 0.469 0.378314 0.457043 0.381195 0.469 0.375251 0.467534 0.377823 0.510424 0.377823 0.489576 0.379088 0.47922 0.37306 0.478238 0.379088 0.47922 0.377823 0.489576 0.379088 0.52078 0.377823 0.510424 0.379088 0.47922 0.375251 0.467534 0.379088 0.47922 0.37306 0.478238 0.377823 0.510424 0.377401 0.5 0.377823 0.489576 0.371745 0.489083 0.377823 0.489576 0.377401 0.5 0.37306 0.478238 0.377823 0.489576 0.371745 0.489083 0.371307 0.5 0.377401 0.5 0.377823 0.510424 0.371745 0.489083 0.377401 0.5 0.371307 0.5 0.371745 0.510917 0.377823 0.510424 0.379088 0.52078 0.371307 0.5 0.377823 0.510424 0.371745 0.510917 0.37306 0.521762 0.379088 0.52078 0.381195 0.531 0.371745 0.510917 0.379088 0.52078 0.37306 0.521762 0.375251 0.532466 0.381195 0.531 0.38414 0.541014 0.37306 0.521762 0.381195 0.531 0.375251 0.532466 0.386474 0.5 0.387919 0.550755 0.38414 0.541014 0.378314 0.542957 0.38414 0.541014 0.387919 0.550755 0.375251 0.532466 0.38414 0.541014 0.378314 0.542957 0.388059 0.519309 0.392524 0.560153 0.387919 0.550755 0.382247 0.553165 0.387919 0.550755 0.392524 0.560153 0.386474 0.5 0.388059 0.519309 0.387919 0.550755 0.378314 0.542957 0.387919 0.550755 0.382247 0.553165 0.392799 0.5381 0.397941 0.569138 0.392524 0.560153 0.387043 0.563017 0.392524 0.560153 0.397941 0.569138 0.388059 0.519309 0.392799 0.5381 0.392524 0.560153 0.382247 0.553165 0.392524 0.560153 0.387043 0.563017 0.400648 0.555854 0.404153 0.57764 0.397941 0.569138 0.392692 0.572443 0.397941 0.569138 0.404153 0.57764 0.392799 0.5381 0.400648 0.555854 0.397941 0.569138 0.387043 0.563017 0.397941 0.569138 0.392692 0.572443 0.411503 0.572051 0.411136 0.585592 0.404153 0.57764 0.399179 0.581369 0.404153 0.57764 0.411136 0.585592 0.400648 0.555854 0.411503 0.572051 0.404153 0.57764 0.392692 0.572443 0.404153 0.57764 0.399179 0.581369 0.411503 0.572051 0.418857 0.592927 0.411136 0.585592 0.406482 0.589724 0.411136 0.585592 0.418857 0.592927 0.399179 0.581369 0.411136 0.585592 0.406482 0.589724 0.425177 0.586184 0.427276 0.59958 0.418857 0.592927 0.414568 0.597436 0.418857 0.592927 0.427276 0.59958 0.411503 0.572051 0.425177 0.586184 0.418857 0.592927 0.406482 0.589724 0.418857 0.592927 0.414568 0.597436 0.441373 0.597776 0.43634 0.605489 0.427276 0.59958 0.423397 0.604435 0.427276 0.59958 0.43634 0.605489 0.425177 0.586184 0.441373 0.597776 0.427276 0.59958 0.414568 0.597436 0.427276 0.59958 0.423397 0.604435 0.441373 0.597776 0.445987 0.610597 0.43634 0.605489 0.432915 0.610656 0.43634 0.605489 0.445987 0.610597 0.423397 0.604435 0.43634 0.605489 0.432915 0.610656 0.459653 0.606402 0.456143 0.614854 0.445987 0.610597 0.443057 0.616037 0.445987 0.610597 0.456143 0.614854 0.441373 0.597776 0.459653 0.606402 0.445987 0.610597 0.432915 0.610656 0.445987 0.610597 0.443057 0.616037 0.459653 0.606402 0.466721 0.618214 0.456143 0.614854 0.453746 0.620523 0.456143 0.614854 0.466721 0.618214 0.443057 0.616037 0.456143 0.614854 0.453746 0.620523 0.479433 0.611726 0.477627 0.620641 0.466721 0.618214 0.464891 0.624066 0.466721 0.618214 0.477627 0.620641 0.459653 0.606402 0.479433 0.611726 0.466721 0.618214 0.453746 0.620523 0.466721 0.618214 0.464891 0.624066 0.479433 0.611726 0.488756 0.622108 0.477627 0.620641 0.476391 0.626626 0.477627 0.620641 0.488756 0.622108 0.464891 0.624066 0.477627 0.620641 0.476391 0.626626 0.5 0.613526 0.5 0.622599 0.488756 0.622108 0.488133 0.628175 0.488756 0.622108 0.5 0.622599 0.479433 0.611726 0.5 0.613526 0.488756 0.622108 0.476391 0.626626 0.488756 0.622108 0.488133 0.628175 0.520567 0.611726 0.511244 0.622108 0.5 0.622599 0.5 0.628693 0.5 0.622599 0.511244 0.622108 0.520567 0.611726 0.5 0.622599 0.5 0.613526 0.488133 0.628175 0.5 0.622599 0.5 0.628693 0.520567 0.611726 0.522373 0.620641 0.511244 0.622108 0.511867 0.628175 0.511244 0.622108 0.522373 0.620641 0.511867 0.628175 0.5 0.628693 0.511244 0.622108 0.540347 0.606402 0.533279 0.618214 0.522373 0.620641 0.523609 0.626626 0.522373 0.620641 0.533279 0.618214 0.520567 0.611726 0.540347 0.606402 0.522373 0.620641 0.511867 0.628175 0.522373 0.620641 0.523609 0.626626 0.540347 0.606402 0.543857 0.614854 0.533279 0.618214 0.535109 0.624066 0.533279 0.618214 0.543857 0.614854 0.523609 0.626626 0.533279 0.618214 0.535109 0.624066 0.558627 0.597776 0.554013 0.610597 0.543857 0.614854 0.546254 0.620523 0.543857 0.614854 0.554013 0.610597 0.540347 0.606402 0.558627 0.597776 0.543857 0.614854 0.535109 0.624066 0.543857 0.614854 0.546254 0.620523 0.558627 0.597776 0.56366 0.605489 0.554013 0.610597 0.556943 0.616037 0.554013 0.610597 0.56366 0.605489 0.546254 0.620523 0.554013 0.610597 0.556943 0.616037 0.574823 0.586184 0.572724 0.59958 0.56366 0.605489 0.567085 0.610656 0.56366 0.605489 0.572724 0.59958 0.558627 0.597776 0.574823 0.586184 0.56366 0.605489 0.556943 0.616037 0.56366 0.605489 0.567085 0.610656 0.574823 0.586184 0.581143 0.592927 0.572724 0.59958 0.576603 0.604435 0.572724 0.59958 0.581143 0.592927 0.567085 0.610656 0.572724 0.59958 0.576603 0.604435 0.588497 0.572051 0.588864 0.585592 0.581143 0.592927 0.585432 0.597436 0.581143 0.592927 0.588864 0.585592 0.574823 0.586184 0.588497 0.572051 0.581143 0.592927 0.576603 0.604435 0.581143 0.592927 0.585432 0.597436 0.599352 0.555854 0.595847 0.57764 0.588864 0.585592 0.593518 0.589724 0.588864 0.585592 0.595847 0.57764 0.588497 0.572051 0.599352 0.555854 0.588864 0.585592 0.585432 0.597436 0.588864 0.585592 0.593518 0.589724 0.599352 0.555854 0.602059 0.569138 0.595847 0.57764 0.600821 0.581369 0.595847 0.57764 0.602059 0.569138 0.593518 0.589724 0.595847 0.57764 0.600821 0.581369 0.607201 0.5381 0.607476 0.560153 0.602059 0.569138 0.607308 0.572443 0.602059 0.569138 0.607476 0.560153 0.599352 0.555854 0.607201 0.5381 0.602059 0.569138 0.600821 0.581369 0.602059 0.569138 0.607308 0.572443 0.611941 0.519309 0.612081 0.550755 0.607476 0.560153 0.612957 0.563017 0.607476 0.560153 0.612081 0.550755 0.607201 0.5381 0.611941 0.519309 0.607476 0.560153 0.607308 0.572443 0.607476 0.560153 0.612957 0.563017 0.61586 0.458986 0.61586 0.541014 0.612081 0.550755 0.617753 0.553165 0.612081 0.550755 0.61586 0.541014 0.613526 0.5 0.61586 0.458986 0.612081 0.550755 0.611941 0.519309 0.613526 0.5 0.612081 0.550755 0.612957 0.563017 0.612081 0.550755 0.617753 0.553165 0.618805 0.469 0.618805 0.531 0.61586 0.541014 0.621686 0.542957 0.61586 0.541014 0.618805 0.531 0.61586 0.458986 0.618805 0.469 0.61586 0.541014 0.617753 0.553165 0.61586 0.541014 0.621686 0.542957 0.620912 0.47922 0.620912 0.52078 0.618805 0.531 0.624749 0.532466 0.618805 0.531 0.620912 0.52078 0.618805 0.469 0.620912 0.47922 0.618805 0.531 0.621686 0.542957 0.618805 0.531 0.624749 0.532466 0.622177 0.489576 0.622177 0.510424 0.620912 0.52078 0.62694 0.521762 0.620912 0.52078 0.622177 0.510424 0.620912 0.47922 0.622177 0.489576 0.620912 0.52078 0.624749 0.532466 0.620912 0.52078 0.62694 0.521762 0.622177 0.489576 0.622599 0.5 0.622177 0.510424 0.628255 0.510917 0.622177 0.510424 0.622599 0.5 0.62694 0.521762 0.622177 0.510424 0.628255 0.510917 0.628693 0.5 0.622599 0.5 0.622177 0.489576 0.628255 0.510917 0.622599 0.5 0.628693 0.5 0.628255 0.489083 0.622177 0.489576 0.620912 0.47922 0.628693 0.5 0.622177 0.489576 0.628255 0.489083 0.62694 0.478238 0.620912 0.47922 0.618805 0.469 0.628255 0.489083 0.620912 0.47922 0.62694 0.478238 0.624749 0.467534 0.618805 0.469 0.61586 0.458986 0.62694 0.478238 0.618805 0.469 0.624749 0.467534 0.613526 0.5 0.612081 0.449245 0.61586 0.458986 0.621686 0.457043 0.61586 0.458986 0.612081 0.449245 0.624749 0.467534 0.61586 0.458986 0.621686 0.457043 0.611941 0.480691 0.607476 0.439847 0.612081 0.449245 0.617753 0.446835 0.612081 0.449245 0.607476 0.439847 0.613526 0.5 0.611941 0.480691 0.612081 0.449245 0.621686 0.457043 0.612081 0.449245 0.617753 0.446835 0.607201 0.4619 0.602059 0.430862 0.607476 0.439847 0.612957 0.436983 0.607476 0.439847 0.602059 0.430862 0.611941 0.480691 0.607201 0.4619 0.607476 0.439847 0.617753 0.446835 0.607476 0.439847 0.612957 0.436983 0.599352 0.444146 0.595847 0.42236 0.602059 0.430862 0.607308 0.427557 0.602059 0.430862 0.595847 0.42236 0.607201 0.4619 0.599352 0.444146 0.602059 0.430862 0.612957 0.436983 0.602059 0.430862 0.607308 0.427557 0.588497 0.427949 0.588864 0.414408 0.595847 0.42236 0.600821 0.418631 0.595847 0.42236 0.588864 0.414408 0.599352 0.444146 0.588497 0.427949 0.595847 0.42236 0.607308 0.427557 0.595847 0.42236 0.600821 0.418631 0.588497 0.427949 0.581143 0.407073 0.588864 0.414408 0.593518 0.410276 0.588864 0.414408 0.581143 0.407073 0.600821 0.418631 0.588864 0.414408 0.593518 0.410276 0.574823 0.413816 0.572724 0.40042 0.581143 0.407073 0.585432 0.402564 0.581143 0.407073 0.572724 0.40042 0.588497 0.427949 0.574823 0.413816 0.581143 0.407073 0.593518 0.410276 0.581143 0.407073 0.585432 0.402564 0.558627 0.402224 0.56366 0.394511 0.572724 0.40042 0.576603 0.395565 0.572724 0.40042 0.56366 0.394511 0.574823 0.413816 0.558627 0.402224 0.572724 0.40042 0.585432 0.402564 0.572724 0.40042 0.576603 0.395565 0.558627 0.402224 0.554013 0.389403 0.56366 0.394511 0.567085 0.389344 0.56366 0.394511 0.554013 0.389403 0.576603 0.395565 0.56366 0.394511 0.567085 0.389344 0.540347 0.393598 0.543857 0.385146 0.554013 0.389403 0.556943 0.383963 0.554013 0.389403 0.543857 0.385146 0.558627 0.402224 0.540347 0.393598 0.554013 0.389403 0.567085 0.389344 0.554013 0.389403 0.556943 0.383963 0.540347 0.393598 0.533279 0.381786 0.543857 0.385146 0.546254 0.379477 0.543857 0.385146 0.533279 0.381786 0.556943 0.383963 0.543857 0.385146 0.546254 0.379477 0.520567 0.388274 0.522373 0.379359 0.533279 0.381786 0.535109 0.375934 0.533279 0.381786 0.522373 0.379359 0.540347 0.393598 0.520567 0.388274 0.533279 0.381786 0.546254 0.379477 0.533279 0.381786 0.535109 0.375934 0.520567 0.388274 0.511244 0.377892 0.522373 0.379359 0.523609 0.373374 0.522373 0.379359 0.511244 0.377892 0.535109 0.375934 0.522373 0.379359 0.523609 0.373374 0.520567 0.388274 0.5 0.386474 0.511244 0.377892 0.523609 0.373374 0.511244 0.377892 0.511867 0.371825 0.5 0.631153 0.5 0.613526 0.479433 0.611726 0.524113 0.629042 0.520567 0.611726 0.5 0.613526 0.524113 0.629042 0.5 0.613526 0.5 0.631153 0.475887 0.629042 0.479433 0.611726 0.459653 0.606402 0.475887 0.629042 0.5 0.631153 0.479433 0.611726 0.452769 0.62281 0.459653 0.606402 0.441373 0.597776 0.475887 0.629042 0.459653 0.606402 0.452769 0.62281 0.43152 0.612738 0.441373 0.597776 0.425177 0.586184 0.452769 0.62281 0.441373 0.597776 0.43152 0.612738 0.412826 0.599252 0.425177 0.586184 0.411503 0.572051 0.43152 0.612738 0.425177 0.586184 0.412826 0.599252 0.397163 0.58287 0.411503 0.572051 0.400648 0.555854 0.412826 0.599252 0.411503 0.572051 0.397163 0.58287 0.384825 0.564169 0.400648 0.555854 0.392799 0.5381 0.397163 0.58287 0.400648 0.555854 0.384825 0.564169 0.375959 0.543737 0.392799 0.5381 0.388059 0.519309 0.384825 0.564169 0.392799 0.5381 0.375959 0.543737 0.370626 0.522155 0.388059 0.519309 0.386474 0.5 0.375959 0.543737 0.388059 0.519309 0.370626 0.522155 0.368847 0.5 0.386474 0.5 0.388059 0.480691 0.370626 0.522155 0.386474 0.5 0.368847 0.5 0.370626 0.477845 0.388059 0.480691 0.392799 0.4619 0.368847 0.5 0.388059 0.480691 0.370626 0.477845 0.375959 0.456263 0.392799 0.4619 0.400648 0.444146 0.370626 0.477845 0.392799 0.4619 0.375959 0.456263 0.384825 0.435831 0.400648 0.444146 0.411503 0.427949 0.375959 0.456263 0.400648 0.444146 0.384825 0.435831 0.397163 0.41713 0.411503 0.427949 0.425177 0.413816 0.384825 0.435831 0.411503 0.427949 0.397163 0.41713 0.412826 0.400748 0.425177 0.413816 0.441373 0.402224 0.397163 0.41713 0.425177 0.413816 0.412826 0.400748 0.43152 0.387262 0.441373 0.402224 0.459653 0.393598 0.412826 0.400748 0.441373 0.402224 0.43152 0.387262 0.452769 0.37719 0.459653 0.393598 0.479433 0.388274 0.43152 0.387262 0.459653 0.393598 0.452769 0.37719 0.475887 0.370958 0.479433 0.388274 0.5 0.386474 0.452769 0.37719 0.479433 0.388274 0.475887 0.370958 0.5 0.368847 0.5 0.386474 0.520567 0.388274 0.475887 0.370958 0.5 0.386474 0.5 0.368847 0.524113 0.370958 0.520567 0.388274 0.540347 0.393598 0.5 0.368847 0.520567 0.388274 0.524113 0.370958 0.547231 0.37719 0.540347 0.393598 0.558627 0.402224 0.524113 0.370958 0.540347 0.393598 0.547231 0.37719 0.56848 0.387262 0.558627 0.402224 0.574823 0.413816 0.547231 0.37719 0.558627 0.402224 0.56848 0.387262 0.587174 0.400748 0.574823 0.413816 0.588497 0.427949 0.56848 0.387262 0.574823 0.413816 0.587174 0.400748 0.602837 0.41713 0.588497 0.427949 0.599352 0.444146 0.587174 0.400748 0.588497 0.427949 0.602837 0.41713 0.615175 0.435831 0.599352 0.444146 0.607201 0.4619 0.602837 0.41713 0.599352 0.444146 0.615175 0.435831 0.624041 0.456263 0.607201 0.4619 0.611941 0.480691 0.615175 0.435831 0.607201 0.4619 0.624041 0.456263 0.629374 0.477845 0.611941 0.480691 0.613526 0.5 0.624041 0.456263 0.611941 0.480691 0.629374 0.477845 0.631153 0.5 0.613526 0.5 0.611941 0.519309 0.629374 0.477845 0.613526 0.5 0.631153 0.5 0.629374 0.522155 0.611941 0.519309 0.607201 0.5381 0.631153 0.5 0.611941 0.519309 0.629374 0.522155 0.624041 0.543737 0.607201 0.5381 0.599352 0.555854 0.629374 0.522155 0.607201 0.5381 0.624041 0.543737 0.615175 0.564169 0.599352 0.555854 0.588497 0.572051 0.624041 0.543737 0.599352 0.555854 0.615175 0.564169 0.602837 0.58287 0.588497 0.572051 0.574823 0.586184 0.615175 0.564169 0.588497 0.572051 0.602837 0.58287 0.587174 0.599252 0.574823 0.586184 0.558627 0.597776 0.602837 0.58287 0.574823 0.586184 0.587174 0.599252 0.56848 0.612738 0.558627 0.597776 0.540347 0.606402 0.587174 0.599252 0.558627 0.597776 0.56848 0.612738 0.547231 0.62281 0.540347 0.606402 0.520567 0.611726 0.56848 0.612738 0.540347 0.606402 0.547231 0.62281 0.547231 0.62281 0.520567 0.611726 0.524113 0.629042 0.781071 0.744706 0.781071 0.744981 0.774906 0.741315 0.789643 0.747046 0.789642 0.74732 0.781071 0.744981 0.789643 0.747046 0.781071 0.744981 0.781071 0.744706 0.774905 0.741041 0.774906 0.741315 0.771832 0.736914 0.774905 0.741041 0.781071 0.744706 0.774906 0.741315 0.771832 0.73664 0.771832 0.736914 0.771999 0.732394 0.774905 0.741041 0.771832 0.736914 0.771832 0.73664 0.771999 0.73212 0.771999 0.732394 0.775132 0.728291 0.771832 0.73664 0.771999 0.732394 0.771999 0.73212 0.775132 0.728019 0.775132 0.728291 0.780681 0.725017 0.771999 0.73212 0.775132 0.728291 0.775132 0.728019 0.780681 0.724746 0.780681 0.725017 0.787945 0.722849 0.775132 0.728019 0.780681 0.725017 0.780681 0.724746 0.787943 0.722579 0.787945 0.722849 0.79615 0.721949 0.780681 0.724746 0.787945 0.722849 0.787943 0.722579 0.796148 0.721678 0.79615 0.721949 0.804498 0.722377 0.787943 0.722579 0.79615 0.721949 0.796148 0.721678 0.804496 0.722106 0.804498 0.722377 0.812187 0.724104 0.796148 0.721678 0.804498 0.722377 0.804496 0.722106 0.812187 0.723833 0.812187 0.724104 0.818433 0.727007 0.804496 0.722106 0.812187 0.724104 0.812187 0.723833 0.818434 0.726736 0.818433 0.727007 0.822504 0.730852 0.812187 0.723833 0.818433 0.727007 0.818434 0.726736 0.822505 0.73058 0.822504 0.730852 0.823782 0.735278 0.818434 0.726736 0.822504 0.730852 0.822505 0.73058 0.823782 0.735006 0.823782 0.735278 0.821876 0.739791 0.822505 0.73058 0.823782 0.735278 0.823782 0.735006 0.821876 0.739518 0.821876 0.739791 0.816766 0.743793 0.823782 0.735006 0.821876 0.739791 0.821876 0.739518 0.816767 0.743518 0.816766 0.743793 0.808941 0.746667 0.821876 0.739518 0.816766 0.743793 0.816767 0.743518 0.808942 0.746393 0.808941 0.746667 0.799427 0.74792 0.816767 0.743518 0.808941 0.746667 0.808942 0.746393 0.799429 0.747645 0.799427 0.74792 0.789642 0.74732 0.808942 0.746393 0.799427 0.74792 0.799429 0.747645 0.799429 0.747645 0.789642 0.74732 0.789643 0.747046 0.613709 0.675886 0.612955 0.674981 0.613419 0.67453 0.333935 0.137095 0.350175 0.119667 0.358368 0.101512 0.358368 0.138327 0.358368 0.101512 0.350175 0.119667 0.336072 0.04615491 0.333935 0.137095 0.358368 0.101512 0.336072 0.08344095 0.336072 0.04615491 0.358368 0.101512 0.346599 0.1142 0.336072 0.08344095 0.358368 0.101512 0.346599 0.1142 0.358368 0.101512 0.358368 0.138327 0.350177 0.15623 0.350175 0.119667 0.333935 0.137095 0.355256 0.147317 0.358368 0.138327 0.350175 0.119667 0.350177 0.15623 0.355256 0.147317 0.350175 0.119667 0.336072 0.04615491 0.227566 0.176816 0.333935 0.137095 0.333935 0.173372 0.333935 0.137095 0.227566 0.176816 0.343078 0.164954 0.350177 0.15623 0.333935 0.137095 0.333935 0.173372 0.343078 0.164954 0.333935 0.137095 0.317545 0.03269398 0.1847569 0.180042 0.227566 0.176816 0.227566 0.212281 0.227566 0.176816 0.1847569 0.180042 0.336072 0.04615491 0.317545 0.03269398 0.227566 0.176816 0.282938 0.1970019 0.227566 0.176816 0.227566 0.212281 0.282938 0.1970019 0.333935 0.173372 0.227566 0.176816 0.295205 0.0214039 0.141672 0.178286 0.1847569 0.180042 0.1848379 0.215431 0.1847569 0.180042 0.141672 0.178286 0.317545 0.03269398 0.295205 0.0214039 0.1847569 0.180042 0.1848379 0.215431 0.227566 0.212281 0.1847569 0.180042 0.204008 8.87e-4 0.02921998 0.1419939 0.141672 0.178286 0.141672 0.2137179 0.141672 0.178286 0.02921998 0.1419939 0.295205 0.0214039 0.204008 8.87e-4 0.141672 0.178286 0.141672 0.2137179 0.1848379 0.215431 0.141672 0.178286 0.173942 0 0.01057791 0.125002 0.02921998 0.1419939 0.02921998 0.178183 0.02921998 0.1419939 0.01057791 0.125002 0.204008 8.87e-4 0.173942 0 0.02921998 0.1419939 0.08334696 0.200248 0.141672 0.2137179 0.02921998 0.1419939 0.08334696 0.200248 0.02921998 0.1419939 0.02921998 0.178183 0.143866 0.001635909 0 0.1069329 0.01057791 0.125002 0.01055091 0.161449 0.01057791 0.125002 0 0.1069329 0.173942 0 0.143866 0.001635909 0.01057791 0.125002 0.01055091 0.161449 0.02921998 0.178183 0.01057791 0.125002 0.05453389 0.024535 0.01605898 0.05052691 0 0.1069329 0 0.143678 0 0.1069329 0.01605898 0.05052691 0.143866 0.001635909 0.05453389 0.024535 0 0.1069329 0 0.143678 0.01055091 0.161449 0 0.1069329 0.05453389 0.024535 0.03322392 0.036502 0.01605898 0.05052691 0.01605898 0.08779197 0.01605898 0.05052691 0.03322392 0.036502 0.008482992 0.119022 0 0.143678 0.01605898 0.05052691 0.008482992 0.119022 0.01605898 0.05052691 0.01605898 0.08779197 0.03322297 0.07382398 0.03322392 0.036502 0.05453389 0.024535 0.02406793 0.08056998 0.01605898 0.08779197 0.03322392 0.036502 0.03322297 0.07382398 0.02406793 0.08056998 0.03322392 0.036502 0.05453389 0.06188297 0.05453389 0.024535 0.143866 0.001635909 0.04341393 0.067586 0.03322297 0.07382398 0.05453389 0.024535 0.05453389 0.06188297 0.04341393 0.067586 0.05453389 0.024535 0.143866 0.03897297 0.143866 0.001635909 0.173942 0 0.1002179 0.05478292 0.143866 0.001635909 0.143866 0.03897297 0.1002179 0.05478292 0.05453389 0.06188297 0.143866 0.001635909 0.173886 0.03733396 0.173942 0 0.204008 8.87e-4 0.173886 0.03733396 0.143866 0.03897297 0.173942 0 0.204008 0.03822195 0.204008 8.87e-4 0.295205 0.0214039 0.204008 0.03822195 0.173886 0.03733396 0.204008 8.87e-4 0.295205 0.05875498 0.295205 0.0214039 0.317545 0.03269398 0.2486619 0.05288589 0.295205 0.0214039 0.295205 0.05875498 0.2486619 0.05288589 0.204008 0.03822195 0.295205 0.0214039 0.317583 0.07005 0.317545 0.03269398 0.336072 0.04615491 0.317583 0.07005 0.295205 0.05875498 0.317545 0.03269398 0.336072 0.08344095 0.317583 0.07005 0.336072 0.04615491 0.08078396 0.08863699 0.1172479 0.090801 0.08357697 0.107119 0.08357697 0.190131 0.08357697 0.107119 0.1172479 0.090801 0.06155788 0.09965795 0.08357697 0.107119 0.065732 0.129598 0.06574499 0.211666 0.065732 0.129598 0.08357697 0.107119 0.06155788 0.09965795 0.08078396 0.08863699 0.08357697 0.107119 0.06574499 0.211666 0.08357697 0.107119 0.08357697 0.190131 0.129029 0.07377696 0.160117 0.08267599 0.1172479 0.090801 0.117224 0.174398 0.1172479 0.090801 0.160117 0.08267599 0.103591 0.07995098 0.129029 0.07377696 0.1172479 0.090801 0.08078396 0.08863699 0.103591 0.07995098 0.1172479 0.090801 0.117224 0.174398 0.08357697 0.190131 0.1172479 0.090801 0.156136 0.07024699 0.205742 0.08360797 0.160117 0.08267599 0.160197 0.1665109 0.160117 0.08267599 0.205742 0.08360797 0.129029 0.07377696 0.156136 0.07024699 0.160117 0.08267599 0.117224 0.174398 0.160117 0.08267599 0.160197 0.1665109 0.156136 0.07024699 0.247259 0.09347897 0.205742 0.08360797 0.205662 0.1674129 0.205742 0.08360797 0.247259 0.09347897 0.160197 0.1665109 0.205742 0.08360797 0.205662 0.1674129 0.314085 0.1183969 0.278278 0.1112779 0.247259 0.09347897 0.247322 0.177003 0.247259 0.09347897 0.278278 0.1112779 0.301697 0.104713 0.314085 0.1183969 0.247259 0.09347897 0.156136 0.07024699 0.301697 0.104713 0.247259 0.09347897 0.205662 0.1674129 0.247259 0.09347897 0.247322 0.177003 0.320473 0.1334339 0.292175 0.134587 0.278278 0.1112779 0.278235 0.194094 0.278278 0.1112779 0.292175 0.134587 0.314085 0.1183969 0.320473 0.1334339 0.278278 0.1112779 0.247322 0.177003 0.278278 0.1112779 0.278235 0.194094 0.311915 0.164897 0.283919 0.15957 0.292175 0.134587 0.292169 0.216461 0.292175 0.134587 0.283919 0.15957 0.319983 0.149186 0.311915 0.164897 0.292175 0.134587 0.320473 0.1334339 0.319983 0.149186 0.292175 0.134587 0.278235 0.194094 0.292175 0.134587 0.292169 0.216461 0.295979 0.179591 0.251867 0.180778 0.283919 0.15957 0.283919 0.240176 0.283919 0.15957 0.251867 0.180778 0.295979 0.179591 0.283919 0.15957 0.311915 0.164897 0.292169 0.216461 0.283919 0.15957 0.283919 0.240176 0.242545 0.201826 0.201238 0.192508 0.251867 0.180778 0.251892 0.260161 0.251867 0.180778 0.201238 0.192508 0.272525 0.192218 0.242545 0.201826 0.251867 0.180778 0.295979 0.179591 0.272525 0.192218 0.251867 0.180778 0.283919 0.240176 0.251867 0.180778 0.251892 0.260161 0.2078509 0.207578 0.144269 0.19112 0.201238 0.192508 0.201138 0.271189 0.201238 0.192508 0.144269 0.19112 0.242545 0.201826 0.2078509 0.207578 0.201238 0.192508 0.251892 0.260161 0.201238 0.192508 0.201138 0.271189 0.2078509 0.207578 0.09662997 0.177091 0.144269 0.19112 0.1443679 0.269892 0.144269 0.19112 0.09662997 0.177091 0.201138 0.271189 0.144269 0.19112 0.1443679 0.269892 0.035703 0.142795 0.06920498 0.15461 0.09662997 0.177091 0.096565 0.256675 0.09662997 0.177091 0.06920498 0.15461 0.04064291 0.158603 0.035703 0.142795 0.09662997 0.177091 0.2078509 0.207578 0.04064291 0.158603 0.09662997 0.177091 0.1443679 0.269892 0.09662997 0.177091 0.096565 0.256675 0.03806895 0.1272439 0.065732 0.129598 0.06920498 0.15461 0.06923395 0.23552 0.06920498 0.15461 0.065732 0.129598 0.035703 0.142795 0.03806895 0.1272439 0.06920498 0.15461 0.096565 0.256675 0.06920498 0.15461 0.06923395 0.23552 0.04697996 0.1126829 0.06155788 0.09965795 0.065732 0.129598 0.03806895 0.1272439 0.04697996 0.1126829 0.065732 0.129598 0.06923395 0.23552 0.065732 0.129598 0.06574499 0.211666 0.350177 0.15623 0.311915 0.164897 0.319983 0.149186 0.333935 0.173372 0.295979 0.179591 0.311915 0.164897 0.343078 0.164954 0.311915 0.164897 0.350177 0.15623 0.333935 0.173372 0.311915 0.164897 0.343078 0.164954 0.358368 0.138327 0.319983 0.149186 0.320473 0.1334339 0.355256 0.147317 0.319983 0.149186 0.358368 0.138327 0.350177 0.15623 0.319983 0.149186 0.355256 0.147317 0.346599 0.1142 0.320473 0.1334339 0.314085 0.1183969 0.346599 0.1142 0.358368 0.138327 0.320473 0.1334339 0.336072 0.08344095 0.314085 0.1183969 0.301697 0.104713 0.346599 0.1142 0.314085 0.1183969 0.336072 0.08344095 0.18399 0.06942796 0.284279 0.09286099 0.301697 0.104713 0.317583 0.07005 0.301697 0.104713 0.284279 0.09286099 0.156136 0.07024699 0.18399 0.06942796 0.301697 0.104713 0.336072 0.08344095 0.301697 0.104713 0.317583 0.07005 0.2116799 0.07134097 0.262817 0.08319199 0.284279 0.09286099 0.295205 0.05875498 0.284279 0.09286099 0.262817 0.08319199 0.18399 0.06942796 0.2116799 0.07134097 0.284279 0.09286099 0.317583 0.07005 0.284279 0.09286099 0.295205 0.05875498 0.2116799 0.07134097 0.238285 0.07595998 0.262817 0.08319199 0.295205 0.05875498 0.262817 0.08319199 0.238285 0.07595998 0.2486619 0.05288589 0.238285 0.07595998 0.2116799 0.07134097 0.2486619 0.05288589 0.295205 0.05875498 0.238285 0.07595998 0.204008 0.03822195 0.2116799 0.07134097 0.18399 0.06942796 0.2486619 0.05288589 0.2116799 0.07134097 0.204008 0.03822195 0.173886 0.03733396 0.18399 0.06942796 0.156136 0.07024699 0.204008 0.03822195 0.18399 0.06942796 0.173886 0.03733396 0.143866 0.03897297 0.156136 0.07024699 0.129029 0.07377696 0.173886 0.03733396 0.156136 0.07024699 0.143866 0.03897297 0.1002179 0.05478292 0.129029 0.07377696 0.103591 0.07995098 0.1002179 0.05478292 0.143866 0.03897297 0.129029 0.07377696 0.1002179 0.05478292 0.103591 0.07995098 0.08078396 0.08863699 0.05453389 0.06188297 0.08078396 0.08863699 0.06155788 0.09965795 0.1002179 0.05478292 0.08078396 0.08863699 0.05453389 0.06188297 0.03322297 0.07382398 0.06155788 0.09965795 0.04697996 0.1126829 0.04341393 0.067586 0.06155788 0.09965795 0.03322297 0.07382398 0.05453389 0.06188297 0.06155788 0.09965795 0.04341393 0.067586 0.01605898 0.08779197 0.04697996 0.1126829 0.03806895 0.1272439 0.02406793 0.08056998 0.04697996 0.1126829 0.01605898 0.08779197 0.03322297 0.07382398 0.04697996 0.1126829 0.02406793 0.08056998 0.008482992 0.119022 0.03806895 0.1272439 0.035703 0.142795 0.008482992 0.119022 0.01605898 0.08779197 0.03806895 0.1272439 0 0.143678 0.035703 0.142795 0.04064291 0.158603 0.008482992 0.119022 0.035703 0.142795 0 0.143678 0.170899 0.208939 0.05334889 0.1737959 0.04064291 0.158603 0.01055091 0.161449 0.04064291 0.158603 0.05334889 0.1737959 0.2078509 0.207578 0.170899 0.208939 0.04064291 0.158603 0 0.143678 0.04064291 0.158603 0.01055091 0.161449 0.1344929 0.205772 0.07381296 0.18739 0.05334889 0.1737959 0.02921998 0.178183 0.05334889 0.1737959 0.07381296 0.18739 0.170899 0.208939 0.1344929 0.205772 0.05334889 0.1737959 0.01055091 0.161449 0.05334889 0.1737959 0.02921998 0.178183 0.1344929 0.205772 0.101366 0.198364 0.07381296 0.18739 0.02921998 0.178183 0.07381296 0.18739 0.101366 0.198364 0.08334696 0.200248 0.101366 0.198364 0.1344929 0.205772 0.08334696 0.200248 0.02921998 0.178183 0.101366 0.198364 0.141672 0.2137179 0.1344929 0.205772 0.170899 0.208939 0.08334696 0.200248 0.1344929 0.205772 0.141672 0.2137179 0.1848379 0.215431 0.170899 0.208939 0.2078509 0.207578 0.141672 0.2137179 0.170899 0.208939 0.1848379 0.215431 0.227566 0.212281 0.2078509 0.207578 0.242545 0.201826 0.1848379 0.215431 0.2078509 0.207578 0.227566 0.212281 0.282938 0.1970019 0.242545 0.201826 0.272525 0.192218 0.282938 0.1970019 0.227566 0.212281 0.242545 0.201826 0.282938 0.1970019 0.272525 0.192218 0.295979 0.179591 0.282938 0.1970019 0.295979 0.179591 0.333935 0.173372 0.251892 0.260161 0.06574499 0.211666 0.08357697 0.190131 0.283919 0.240176 0.251892 0.260161 0.08357697 0.190131 0.117224 0.174398 0.283919 0.240176 0.08357697 0.190131 0.201138 0.271189 0.06923395 0.23552 0.06574499 0.211666 0.251892 0.260161 0.201138 0.271189 0.06574499 0.211666 0.1443679 0.269892 0.096565 0.256675 0.06923395 0.23552 0.201138 0.271189 0.1443679 0.269892 0.06923395 0.23552 0.117224 0.174398 0.292169 0.216461 0.283919 0.240176 0.160197 0.1665109 0.278235 0.194094 0.292169 0.216461 0.117224 0.174398 0.160197 0.1665109 0.292169 0.216461 0.205662 0.1674129 0.247322 0.177003 0.278235 0.194094 0.160197 0.1665109 0.205662 0.1674129 0.278235 0.194094 0.570144 0.678603 0.570884 0.680087 0.572756 0.685048 0.612171 0.681313 0.610516 0.676473 0.612269 0.677237 0.615852 0.676043 0.614732 0.676094 0.614325 0.674243 0.614732 0.676094 0.613419 0.67453 0.614325 0.674243 0.523609 0.626626 0.524909 0.645933 0.5 0.647895 0.5 0.628693 0.5 0.647895 0.475091 0.645933 0.511867 0.628175 0.5 0.647895 0.5 0.628693 0.511867 0.628175 0.523609 0.626626 0.5 0.647895 0.546254 0.620523 0.548912 0.640133 0.524909 0.645933 0.535109 0.624066 0.546254 0.620523 0.524909 0.645933 0.523609 0.626626 0.535109 0.624066 0.524909 0.645933 0.567085 0.610656 0.571218 0.63073 0.548912 0.640133 0.556943 0.616037 0.567085 0.610656 0.548912 0.640133 0.546254 0.620523 0.556943 0.616037 0.548912 0.640133 0.585432 0.597436 0.591199 0.618079 0.571218 0.63073 0.576603 0.604435 0.585432 0.597436 0.571218 0.63073 0.567085 0.610656 0.576603 0.604435 0.571218 0.63073 0.607308 0.572443 0.608418 0.602624 0.591199 0.618079 0.600821 0.581369 0.607308 0.572443 0.591199 0.618079 0.593518 0.589724 0.600821 0.581369 0.591199 0.618079 0.585432 0.597436 0.593518 0.589724 0.591199 0.618079 0.621686 0.542957 0.622624 0.584839 0.608418 0.602624 0.617753 0.553165 0.621686 0.542957 0.608418 0.602624 0.612957 0.563017 0.617753 0.553165 0.608418 0.602624 0.607308 0.572443 0.612957 0.563017 0.608418 0.602624 0.628255 0.510917 0.633696 0.565207 0.622624 0.584839 0.62694 0.521762 0.628255 0.510917 0.622624 0.584839 0.624749 0.532466 0.62694 0.521762 0.622624 0.584839 0.621686 0.542957 0.624749 0.532466 0.622624 0.584839 0.641593 0.455784 0.641593 0.544216 0.633696 0.565207 0.633696 0.434793 0.641593 0.455784 0.633696 0.565207 0.628255 0.510917 0.633696 0.434793 0.633696 0.565207 0.646321 0.477668 0.646321 0.522332 0.641593 0.544216 0.641593 0.455784 0.646321 0.477668 0.641593 0.544216 0.646321 0.477668 0.647895 0.5 0.646321 0.522332 0.624749 0.467534 0.622624 0.415161 0.633696 0.434793 0.62694 0.478238 0.624749 0.467534 0.633696 0.434793 0.628255 0.489083 0.62694 0.478238 0.633696 0.434793 0.628693 0.5 0.628255 0.489083 0.633696 0.434793 0.628255 0.510917 0.628693 0.5 0.633696 0.434793 0.612957 0.436983 0.608418 0.397376 0.622624 0.415161 0.617753 0.446835 0.612957 0.436983 0.622624 0.415161 0.621686 0.457043 0.617753 0.446835 0.622624 0.415161 0.624749 0.467534 0.621686 0.457043 0.622624 0.415161 0.593518 0.410276 0.591199 0.381921 0.608418 0.397376 0.600821 0.418631 0.593518 0.410276 0.608418 0.397376 0.607308 0.427557 0.600821 0.418631 0.608418 0.397376 0.612957 0.436983 0.607308 0.427557 0.608418 0.397376 0.576603 0.395565 0.571218 0.36927 0.591199 0.381921 0.585432 0.402564 0.576603 0.395565 0.591199 0.381921 0.593518 0.410276 0.585432 0.402564 0.591199 0.381921 0.556943 0.383963 0.548912 0.359867 0.571218 0.36927 0.567085 0.389344 0.556943 0.383963 0.571218 0.36927 0.576603 0.395565 0.567085 0.389344 0.571218 0.36927 0.535109 0.375934 0.524909 0.354067 0.548912 0.359867 0.546254 0.379477 0.535109 0.375934 0.548912 0.359867 0.556943 0.383963 0.546254 0.379477 0.548912 0.359867 0.5 0.371307 0.5 0.352105 0.524909 0.354067 0.511867 0.371825 0.5 0.371307 0.524909 0.354067 0.523609 0.373374 0.511867 0.371825 0.524909 0.354067 0.535109 0.375934 0.523609 0.373374 0.524909 0.354067 0.476391 0.373374 0.475091 0.354067 0.5 0.352105 0.488133 0.371825 0.476391 0.373374 0.5 0.352105 0.5 0.371307 0.488133 0.371825 0.5 0.352105 0.453746 0.379477 0.451088 0.359867 0.475091 0.354067 0.464891 0.375934 0.453746 0.379477 0.475091 0.354067 0.476391 0.373374 0.464891 0.375934 0.475091 0.354067 0.432915 0.389344 0.428782 0.36927 0.451088 0.359867 0.443057 0.383963 0.432915 0.389344 0.451088 0.359867 0.453746 0.379477 0.443057 0.383963 0.451088 0.359867 0.414568 0.402564 0.408801 0.381921 0.428782 0.36927 0.423397 0.395565 0.414568 0.402564 0.428782 0.36927 0.432915 0.389344 0.423397 0.395565 0.428782 0.36927 0.392692 0.427557 0.391582 0.397376 0.408801 0.381921 0.399179 0.418631 0.392692 0.427557 0.408801 0.381921 0.406482 0.410276 0.399179 0.418631 0.408801 0.381921 0.414568 0.402564 0.406482 0.410276 0.408801 0.381921 0.378314 0.457043 0.377376 0.415161 0.391582 0.397376 0.382247 0.446835 0.378314 0.457043 0.391582 0.397376 0.387043 0.436983 0.382247 0.446835 0.391582 0.397376 0.392692 0.427557 0.387043 0.436983 0.391582 0.397376 0.371745 0.489083 0.366304 0.434793 0.377376 0.415161 0.37306 0.478238 0.371745 0.489083 0.377376 0.415161 0.375251 0.467534 0.37306 0.478238 0.377376 0.415161 0.378314 0.457043 0.375251 0.467534 0.377376 0.415161 0.358407 0.544216 0.358407 0.455784 0.366304 0.434793 0.366304 0.565207 0.358407 0.544216 0.366304 0.434793 0.371745 0.489083 0.366304 0.565207 0.366304 0.434793 0.353679 0.522332 0.353679 0.477668 0.358407 0.455784 0.358407 0.544216 0.353679 0.522332 0.358407 0.455784 0.353679 0.522332 0.352105 0.5 0.353679 0.477668 0.375251 0.532466 0.377376 0.584839 0.366304 0.565207 0.37306 0.521762 0.375251 0.532466 0.366304 0.565207 0.371745 0.510917 0.37306 0.521762 0.366304 0.565207 0.371307 0.5 0.371745 0.510917 0.366304 0.565207 0.371745 0.489083 0.371307 0.5 0.366304 0.565207 0.387043 0.563017 0.391582 0.602624 0.377376 0.584839 0.382247 0.553165 0.387043 0.563017 0.377376 0.584839 0.378314 0.542957 0.382247 0.553165 0.377376 0.584839 0.375251 0.532466 0.378314 0.542957 0.377376 0.584839 0.406482 0.589724 0.408801 0.618079 0.391582 0.602624 0.399179 0.581369 0.406482 0.589724 0.391582 0.602624 0.392692 0.572443 0.399179 0.581369 0.391582 0.602624 0.387043 0.563017 0.392692 0.572443 0.391582 0.602624 0.423397 0.604435 0.428782 0.63073 0.408801 0.618079 0.414568 0.597436 0.423397 0.604435 0.408801 0.618079 0.406482 0.589724 0.414568 0.597436 0.408801 0.618079 0.443057 0.616037 0.451088 0.640133 0.428782 0.63073 0.432915 0.610656 0.443057 0.616037 0.428782 0.63073 0.423397 0.604435 0.432915 0.610656 0.428782 0.63073 0.464891 0.624066 0.475091 0.645933 0.451088 0.640133 0.453746 0.620523 0.464891 0.624066 0.451088 0.640133 0.443057 0.616037 0.453746 0.620523 0.451088 0.640133 0.488133 0.628175 0.5 0.628693 0.475091 0.645933 0.476391 0.626626 0.488133 0.628175 0.475091 0.645933 0.464891 0.624066 0.476391 0.626626 0.475091 0.645933 0.524113 0.370958 0.524113 0.629042 0.5 0.631153 0.5 0.368847 0.524113 0.370958 0.5 0.631153 0.475887 0.629042 0.5 0.368847 0.5 0.631153 0.547231 0.37719 0.547231 0.62281 0.524113 0.629042 0.524113 0.370958 0.547231 0.37719 0.524113 0.629042 0.56848 0.387262 0.56848 0.612738 0.547231 0.62281 0.547231 0.37719 0.56848 0.387262 0.547231 0.62281 0.587174 0.400748 0.587174 0.599252 0.56848 0.612738 0.56848 0.387262 0.587174 0.400748 0.56848 0.612738 0.602837 0.41713 0.602837 0.58287 0.587174 0.599252 0.587174 0.400748 0.602837 0.41713 0.587174 0.599252 0.615175 0.435831 0.615175 0.564169 0.602837 0.58287 0.602837 0.41713 0.615175 0.435831 0.602837 0.58287 0.624041 0.456263 0.624041 0.543737 0.615175 0.564169 0.615175 0.435831 0.624041 0.456263 0.615175 0.564169 0.629374 0.477845 0.629374 0.522155 0.624041 0.543737 0.624041 0.456263 0.629374 0.477845 0.624041 0.543737 0.629374 0.477845 0.631153 0.5 0.629374 0.522155 0.475887 0.629042 0.475887 0.370958 0.5 0.368847 0.452769 0.62281 0.452769 0.37719 0.475887 0.370958 0.475887 0.629042 0.452769 0.62281 0.475887 0.370958 0.43152 0.612738 0.43152 0.387262 0.452769 0.37719 0.452769 0.62281 0.43152 0.612738 0.452769 0.37719 0.412826 0.599252 0.412826 0.400748 0.43152 0.387262 0.43152 0.612738 0.412826 0.599252 0.43152 0.387262 0.397163 0.58287 0.397163 0.41713 0.412826 0.400748 0.412826 0.599252 0.397163 0.58287 0.412826 0.400748 0.384825 0.564169 0.384825 0.435831 0.397163 0.41713 0.397163 0.58287 0.384825 0.564169 0.397163 0.41713 0.375959 0.543737 0.375959 0.456263 0.384825 0.435831 0.384825 0.564169 0.375959 0.543737 0.384825 0.435831 0.370626 0.522155 0.370626 0.477845 0.375959 0.456263 0.375959 0.543737 0.370626 0.522155 0.375959 0.456263 0.370626 0.522155 0.368847 0.5 0.370626 0.477845 0.5 0.04423195 0.5 0.04177999 0.545957 0.04207295 0.418238 0.04545098 0.454043 0.04207295 0.5 0.04177999 0.5 0.04423195 0.418238 0.04545098 0.5 0.04177999 0.581762 0.04545098 0.545957 0.04207295 0.584895 0.04273796 0.581762 0.04545098 0.5 0.04423195 0.545957 0.04207295 0.581762 0.04545098 0.584895 0.04273796 0.612262 0.0432859 0.581762 0.04545098 0.612262 0.0432859 0.626172 0.04326593 0.647486 0.04073399 0.626172 0.04326593 0.626172 0.04248493 0.647486 0.04828697 0.581762 0.04545098 0.626172 0.04326593 0.647486 0.04073399 0.647486 0.04828697 0.626172 0.04326593 0.647486 0.04073399 0.626172 0.04248493 0.612262 0.04107195 0.647486 0.04073399 0.612262 0.04107195 0.584895 0.03943091 0.581762 0.037193 0.584895 0.03943091 0.545957 0.03811198 0.581762 0.037193 0.647486 0.04073399 0.584895 0.03943091 0.581762 0.037193 0.545957 0.03811198 0.5 0.037606 0.5 0.035815 0.5 0.037606 0.454043 0.03811198 0.581762 0.037193 0.5 0.037606 0.5 0.035815 0.418238 0.037193 0.454043 0.03811198 0.415105 0.03943091 0.418238 0.037193 0.5 0.035815 0.454043 0.03811198 0.418238 0.037193 0.415105 0.03943091 0.387738 0.04107195 0.418238 0.037193 0.387738 0.04107195 0.373828 0.04248493 0.352514 0.04828697 0.373828 0.04248493 0.373828 0.04326593 0.352514 0.04073399 0.418238 0.037193 0.373828 0.04248493 0.352514 0.04828697 0.352514 0.04073399 0.373828 0.04248493 0.352514 0.04828697 0.373828 0.04326593 0.387738 0.0432859 0.352514 0.04828697 0.387738 0.0432859 0.415105 0.04273796 0.418238 0.04545098 0.415105 0.04273796 0.454043 0.04207295 0.418238 0.04545098 0.352514 0.04828697 0.415105 0.04273796 0.949034 0.335102 0.951849 0.334912 0.952525 0.340921 0.948251 0.323609 0.951481 0.328882 0.951849 0.334912 0.949034 0.335102 0.948251 0.323609 0.951849 0.334912 0.950353 0.346556 0.952525 0.340921 0.953407 0.346074 0.950353 0.346556 0.949034 0.335102 0.952525 0.340921 0.950353 0.346556 0.953407 0.346074 0.954371 0.3497 0.950353 0.346556 0.954371 0.3497 0.955296 0.351395 0.959276 0.352665 0.955296 0.351395 0.95608 0.351046 0.95201 0.356478 0.950353 0.346556 0.955296 0.351395 0.959276 0.352665 0.95201 0.356478 0.955296 0.351395 0.959276 0.352665 0.95608 0.351046 0.956644 0.348798 0.959276 0.352665 0.956644 0.348798 0.956938 0.344987 0.959204 0.343914 0.956938 0.344987 0.956938 0.340079 0.959204 0.343914 0.959276 0.352665 0.956938 0.344987 0.959204 0.343914 0.956938 0.340079 0.956644 0.334613 0.958702 0.334494 0.956644 0.334613 0.95608 0.329163 0.959204 0.343914 0.956644 0.334613 0.958702 0.334494 0.957791 0.325097 0.95608 0.329163 0.955296 0.324301 0.957791 0.325097 0.958702 0.334494 0.95608 0.329163 0.957791 0.325097 0.955296 0.324301 0.954371 0.320562 0.957791 0.325097 0.954371 0.320562 0.953407 0.318406 0.948135 0.313579 0.953407 0.318406 0.952525 0.318161 0.956512 0.316413 0.957791 0.325097 0.953407 0.318406 0.948135 0.313579 0.956512 0.316413 0.953407 0.318406 0.948135 0.313579 0.952525 0.318161 0.951849 0.319958 0.948135 0.313579 0.951849 0.319958 0.951481 0.323671 0.948251 0.323609 0.951481 0.323671 0.951481 0.328882 0.948251 0.323609 0.948135 0.313579 0.951481 0.323671 0.949034 0.664898 0.951849 0.665088 0.951481 0.671118 0.950353 0.653444 0.952525 0.659079 0.951849 0.665088 0.949034 0.664898 0.950353 0.653444 0.951849 0.665088 0.948251 0.676391 0.951481 0.671118 0.951481 0.676329 0.948251 0.676391 0.949034 0.664898 0.951481 0.671118 0.948251 0.676391 0.951481 0.676329 0.951849 0.680042 0.948251 0.676391 0.951849 0.680042 0.952525 0.681839 0.956512 0.683587 0.952525 0.681839 0.953407 0.681594 0.948135 0.686421 0.948251 0.676391 0.952525 0.681839 0.956512 0.683587 0.948135 0.686421 0.952525 0.681839 0.956512 0.683587 0.953407 0.681594 0.954371 0.679438 0.956512 0.683587 0.954371 0.679438 0.955296 0.675699 0.957791 0.674903 0.955296 0.675699 0.95608 0.670837 0.957791 0.674903 0.956512 0.683587 0.955296 0.675699 0.957791 0.674903 0.95608 0.670837 0.956644 0.665387 0.958702 0.665506 0.956644 0.665387 0.956938 0.659921 0.957791 0.674903 0.956644 0.665387 0.958702 0.665506 0.959204 0.656086 0.956938 0.659921 0.956938 0.655013 0.959204 0.656086 0.958702 0.665506 0.956938 0.659921 0.959204 0.656086 0.956938 0.655013 0.956644 0.651202 0.959204 0.656086 0.956644 0.651202 0.95608 0.648954 0.95201 0.643522 0.95608 0.648954 0.955296 0.648605 0.959276 0.647335 0.959204 0.656086 0.95608 0.648954 0.95201 0.643522 0.959276 0.647335 0.95608 0.648954 0.95201 0.643522 0.955296 0.648605 0.954371 0.6503 0.95201 0.643522 0.954371 0.6503 0.953407 0.653926 0.950353 0.653444 0.953407 0.653926 0.952525 0.659079 0.950353 0.653444 0.95201 0.643522 0.953407 0.653926 0.05096596 0.664898 0.04815089 0.665088 0.04747498 0.659079 0.05174899 0.676391 0.04851889 0.671118 0.04815089 0.665088 0.05096596 0.664898 0.05174899 0.676391 0.04815089 0.665088 0.04964697 0.653444 0.04747498 0.659079 0.04659295 0.653926 0.04964697 0.653444 0.05096596 0.664898 0.04747498 0.659079 0.04964697 0.653444 0.04659295 0.653926 0.04562896 0.6503 0.04964697 0.653444 0.04562896 0.6503 0.04470396 0.648605 0.04072391 0.647335 0.04470396 0.648605 0.04391998 0.648954 0.04798996 0.643522 0.04964697 0.653444 0.04470396 0.648605 0.04072391 0.647335 0.04798996 0.643522 0.04470396 0.648605 0.04072391 0.647335 0.04391998 0.648954 0.043356 0.651202 0.04072391 0.647335 0.043356 0.651202 0.04306197 0.655013 0.04079598 0.656086 0.04306197 0.655013 0.04306197 0.659921 0.04079598 0.656086 0.04072391 0.647335 0.04306197 0.655013 0.04079598 0.656086 0.04306197 0.659921 0.043356 0.665387 0.04129797 0.665506 0.043356 0.665387 0.04391998 0.670837 0.04079598 0.656086 0.043356 0.665387 0.04129797 0.665506 0.0422089 0.674903 0.04391998 0.670837 0.04470396 0.675699 0.0422089 0.674903 0.04129797 0.665506 0.04391998 0.670837 0.0422089 0.674903 0.04470396 0.675699 0.04562896 0.679438 0.0422089 0.674903 0.04562896 0.679438 0.04659295 0.681594 0.05186498 0.686421 0.04659295 0.681594 0.04747498 0.681839 0.0434879 0.683587 0.0422089 0.674903 0.04659295 0.681594 0.05186498 0.686421 0.0434879 0.683587 0.04659295 0.681594 0.05186498 0.686421 0.04747498 0.681839 0.04815089 0.680042 0.05186498 0.686421 0.04815089 0.680042 0.04851889 0.676329 0.05174899 0.676391 0.04851889 0.676329 0.04851889 0.671118 0.05174899 0.676391 0.05186498 0.686421 0.04851889 0.676329 0.05096596 0.335102 0.04815089 0.334912 0.04851889 0.328882 0.04964697 0.346556 0.04747498 0.340921 0.04815089 0.334912 0.05096596 0.335102 0.04964697 0.346556 0.04815089 0.334912 0.05174899 0.323609 0.04851889 0.328882 0.04851889 0.323671 0.05174899 0.323609 0.05096596 0.335102 0.04851889 0.328882 0.05174899 0.323609 0.04851889 0.323671 0.04815089 0.319958 0.05174899 0.323609 0.04815089 0.319958 0.04747498 0.318161 0.0434879 0.316413 0.04747498 0.318161 0.04659295 0.318406 0.05186498 0.313579 0.05174899 0.323609 0.04747498 0.318161 0.0434879 0.316413 0.05186498 0.313579 0.04747498 0.318161 0.0434879 0.316413 0.04659295 0.318406 0.04562896 0.320562 0.0434879 0.316413 0.04562896 0.320562 0.04470396 0.324301 0.0422089 0.325097 0.04470396 0.324301 0.04391998 0.329163 0.0422089 0.325097 0.0434879 0.316413 0.04470396 0.324301 0.0422089 0.325097 0.04391998 0.329163 0.043356 0.334613 0.04129797 0.334494 0.043356 0.334613 0.04306197 0.340079 0.0422089 0.325097 0.043356 0.334613 0.04129797 0.334494 0.04079598 0.343914 0.04306197 0.340079 0.04306197 0.344987 0.04079598 0.343914 0.04129797 0.334494 0.04306197 0.340079 0.04079598 0.343914 0.04306197 0.344987 0.043356 0.348798 0.04079598 0.343914 0.043356 0.348798 0.04391998 0.351046 0.04798996 0.356478 0.04391998 0.351046 0.04470396 0.351395 0.04072391 0.352665 0.04079598 0.343914 0.04391998 0.351046 0.04798996 0.356478 0.04072391 0.352665 0.04391998 0.351046 0.04798996 0.356478 0.04470396 0.351395 0.04562896 0.3497 0.04798996 0.356478 0.04562896 0.3497 0.04659295 0.346074 0.04964697 0.346556 0.04659295 0.346074 0.04747498 0.340921 0.04964697 0.346556 0.04798996 0.356478 0.04659295 0.346074 0.30825 0.051063 0.30825 0.04514497 0.352514 0.04073399 0.352514 0.04828697 0.30825 0.051063 0.352514 0.04073399 0.2836 0.05242192 0.2836 0.04914289 0.30825 0.04514497 0.30825 0.051063 0.2836 0.05242192 0.30825 0.04514497 0.2836 0.05242192 0.275753 0.051759 0.2836 0.04914289 0.69175 0.04514497 0.69175 0.051063 0.647486 0.04828697 0.647486 0.04073399 0.69175 0.04514497 0.647486 0.04828697 0.7164 0.04914289 0.7164 0.05242192 0.69175 0.051063 0.69175 0.04514497 0.7164 0.04914289 0.69175 0.051063 0.7164 0.04914289 0.724247 0.051759 0.7164 0.05242192 0.948705 0.306183 0.954941 0.30913 0.956512 0.316413 0.948135 0.313579 0.948705 0.306183 0.956512 0.316413 0.949865 0.302077 0.953194 0.303921 0.954941 0.30913 0.948705 0.306183 0.949865 0.302077 0.954941 0.30913 0.949865 0.302077 0.951434 0.301406 0.953194 0.303921 0.958916 0.360057 0.953787 0.363712 0.95201 0.356478 0.959276 0.352665 0.958916 0.360057 0.95201 0.356478 0.958138 0.365413 0.955491 0.367628 0.953787 0.363712 0.958916 0.360057 0.958138 0.365413 0.953787 0.363712 0.958138 0.365413 0.956975 0.368106 0.955491 0.367628 0.953787 0.636288 0.958916 0.639943 0.959276 0.647335 0.95201 0.643522 0.953787 0.636288 0.959276 0.647335 0.955491 0.632372 0.958138 0.634587 0.958916 0.639943 0.953787 0.636288 0.955491 0.632372 0.958916 0.639943 0.955491 0.632372 0.956975 0.631894 0.958138 0.634587 0.954941 0.69087 0.948705 0.693817 0.948135 0.686421 0.956512 0.683587 0.954941 0.69087 0.948135 0.686421 0.953194 0.696079 0.949865 0.697923 0.948705 0.693817 0.954941 0.69087 0.953194 0.696079 0.948705 0.693817 0.953194 0.696079 0.951434 0.698594 0.949865 0.697923 0.05129498 0.693817 0.0450589 0.69087 0.0434879 0.683587 0.05186498 0.686421 0.05129498 0.693817 0.0434879 0.683587 0.05013489 0.697923 0.04680591 0.696079 0.0450589 0.69087 0.05129498 0.693817 0.05013489 0.697923 0.0450589 0.69087 0.05013489 0.697923 0.04856598 0.698594 0.04680591 0.696079 0.04108399 0.639943 0.04621297 0.636288 0.04798996 0.643522 0.04072391 0.647335 0.04108399 0.639943 0.04798996 0.643522 0.04186195 0.634587 0.04450899 0.632372 0.04621297 0.636288 0.04108399 0.639943 0.04186195 0.634587 0.04621297 0.636288 0.04186195 0.634587 0.04302489 0.631894 0.04450899 0.632372 0.04621297 0.363712 0.04108399 0.360057 0.04072391 0.352665 0.04798996 0.356478 0.04621297 0.363712 0.04072391 0.352665 0.04450899 0.367628 0.04186195 0.365413 0.04108399 0.360057 0.04621297 0.363712 0.04450899 0.367628 0.04108399 0.360057 0.04450899 0.367628 0.04302489 0.368106 0.04186195 0.365413 0.0450589 0.30913 0.05129498 0.306183 0.05186498 0.313579 0.0434879 0.316413 0.0450589 0.30913 0.05186498 0.313579 0.04680591 0.303921 0.05013489 0.302077 0.05129498 0.306183 0.0450589 0.30913 0.04680591 0.303921 0.05129498 0.306183 0.04680591 0.303921 0.04856598 0.301406 0.05013489 0.302077 0.925585 0.167863 0.923174 0.163123 0.905676 0.172876 0.920605 0.159211 0.905676 0.172876 0.923174 0.163123 0.927586 0.1729159 0.925585 0.167863 0.905676 0.172876 0.929004 0.177748 0.927586 0.1729159 0.905676 0.172876 0.929737 0.181836 0.929004 0.177748 0.905676 0.172876 0.929737 0.184706 0.929737 0.181836 0.905676 0.172876 0.929004 0.18598 0.929737 0.184706 0.905676 0.172876 0.927586 0.185431 0.929004 0.18598 0.905676 0.172876 0.925585 0.183041 0.927586 0.185431 0.905676 0.172876 0.923174 0.179046 0.925585 0.183041 0.905676 0.172876 0.920605 0.173936 0.923174 0.179046 0.905676 0.172876 0.918202 0.168399 0.920605 0.173936 0.905676 0.172876 0.916325 0.163197 0.918202 0.168399 0.905676 0.172876 0.915291 0.159026 0.916325 0.163197 0.905676 0.172876 0.915291 0.1563979 0.915291 0.159026 0.905676 0.172876 0.916325 0.155576 0.915291 0.1563979 0.905676 0.172876 0.918202 0.156578 0.916325 0.155576 0.905676 0.172876 0.920605 0.159211 0.918202 0.156578 0.905676 0.172876 0.0371949 0.502578 0.03740197 0.507462 0.04821991 0.5 0.03779596 0.511549 0.04821991 0.5 0.03740197 0.507462 0.0371949 0.497422 0.0371949 0.502578 0.04821991 0.5 0.03740197 0.492538 0.0371949 0.497422 0.04821991 0.5 0.03779596 0.488451 0.03740197 0.492538 0.04821991 0.5 0.03834092 0.485633 0.03779596 0.488451 0.04821991 0.5 0.03898096 0.484459 0.03834092 0.485633 0.04821991 0.5 0.03964096 0.485149 0.03898096 0.484459 0.04821991 0.5 0.040241 0.487708 0.03964096 0.485149 0.04821991 0.5 0.04069799 0.491884 0.040241 0.487708 0.04821991 0.5 0.04094499 0.497164 0.04069799 0.491884 0.04821991 0.5 0.04094499 0.502836 0.04094499 0.497164 0.04821991 0.5 0.04069799 0.508116 0.04094499 0.502836 0.04821991 0.5 0.040241 0.512292 0.04069799 0.508116 0.04821991 0.5 0.03964096 0.514851 0.040241 0.512292 0.04821991 0.5 0.03898096 0.515541 0.03964096 0.514851 0.04821991 0.5 0.03834092 0.514367 0.03898096 0.515541 0.04821991 0.5 0.03779596 0.511549 0.03834092 0.514367 0.04821991 0.5 0.08909696 0.889274 0.910685 0.889805 0.913023 0.886529 0.07435697 0.866632 0.08909696 0.889274 0.913023 0.886529 0.92709 0.863865 0.07435697 0.866632 0.913023 0.886529 0.111535 0.91154 0.909027 0.892542 0.910685 0.889805 0.08909696 0.889274 0.111535 0.91154 0.910685 0.889805 0.111535 0.91154 0.90841 0.894286 0.909027 0.892542 0.852446 0.932605 0.907215 0.897684 0.90841 0.894286 0.844771 0.935586 0.852446 0.932605 0.90841 0.894286 0.148955 0.93305 0.844771 0.935586 0.90841 0.894286 0.111535 0.91154 0.148955 0.93305 0.90841 0.894286 0.863236 0.928703 0.903745 0.902782 0.907215 0.897684 0.858839 0.930169 0.863236 0.928703 0.907215 0.897684 0.852446 0.932605 0.858839 0.930169 0.907215 0.897684 0.871381 0.925824 0.898033 0.908894 0.903745 0.902782 0.863236 0.928703 0.871381 0.925824 0.903745 0.902782 0.881001 0.921145 0.89027 0.915265 0.898033 0.908894 0.871381 0.925824 0.881001 0.921145 0.898033 0.908894 0.2197819 0.95276 0.767508 0.954918 0.844771 0.935586 0.148955 0.93305 0.2197819 0.95276 0.844771 0.935586 0.36919 0.967243 0.604699 0.968273 0.767508 0.954918 0.2197819 0.95276 0.36919 0.967243 0.767508 0.954918 0.92709 0.863865 0.06403195 0.843776 0.07435697 0.866632 0.937011 0.84099 0.05645996 0.820789 0.06403195 0.843776 0.92709 0.863865 0.937011 0.84099 0.06403195 0.843776 0.944322 0.81799 0.05071598 0.797716 0.05645996 0.820789 0.937011 0.84099 0.944322 0.81799 0.05645996 0.820789 0.949886 0.794909 0.04625093 0.774594 0.05071598 0.797716 0.944322 0.81799 0.949886 0.794909 0.05071598 0.797716 0.954225 0.77177 0.04558593 0.771249 0.04625093 0.774594 0.949886 0.794909 0.954225 0.77177 0.04625093 0.774594 0.954225 0.77177 0.04485493 0.768498 0.04558593 0.771249 0.04039299 0.752085 0.04417693 0.766801 0.04485493 0.768498 0.03955495 0.745398 0.04039299 0.752085 0.04485493 0.768498 0.957669 0.74859 0.03955495 0.745398 0.04485493 0.768498 0.954225 0.77177 0.957669 0.74859 0.04485493 0.768498 0.04153198 0.758369 0.04284989 0.7635 0.04417693 0.766801 0.04039299 0.752085 0.04153198 0.758369 0.04417693 0.766801 0.957669 0.74859 0.03909397 0.739073 0.03955495 0.745398 0.957669 0.74859 0.03904491 0.733864 0.03909397 0.739073 0.960436 0.72538 0.03941297 0.730456 0.03904491 0.733864 0.957669 0.74859 0.960436 0.72538 0.03904491 0.733864 0.960436 0.72538 0.03958499 0.728705 0.03941297 0.730456 0.960436 0.72538 0.03953188 0.725912 0.03958499 0.728705 0.960436 0.72538 0.03926396 0.722545 0.03953188 0.725912 0.962678 0.702147 0.03707993 0.69932 0.03926396 0.722545 0.960436 0.72538 0.962678 0.702147 0.03926396 0.722545 0.964501 0.678896 0.03530198 0.676068 0.03707993 0.69932 0.962678 0.702147 0.964501 0.678896 0.03707993 0.69932 0.96598 0.655631 0.0338599 0.652802 0.03530198 0.676068 0.964501 0.678896 0.96598 0.655631 0.03530198 0.676068 0.967173 0.632357 0.03269892 0.629527 0.0338599 0.652802 0.96598 0.655631 0.967173 0.632357 0.0338599 0.652802 0.968119 0.609085 0.03178 0.606243 0.03269892 0.629527 0.967173 0.632357 0.968119 0.609085 0.03269892 0.629527 0.970751 0.57964 0.03107392 0.582954 0.03178 0.606243 0.970586 0.586352 0.970751 0.57964 0.03178 0.606243 0.9702 0.592675 0.970586 0.586352 0.03178 0.606243 0.969632 0.597855 0.9702 0.592675 0.03178 0.606243 0.968945 0.601212 0.969632 0.597855 0.03178 0.606243 0.968601 0.602937 0.968945 0.601212 0.03178 0.606243 0.968309 0.605716 0.968601 0.602937 0.03178 0.606243 0.968119 0.609085 0.968309 0.605716 0.03178 0.606243 0.969501 0.560192 0.03055799 0.559661 0.03107392 0.582954 0.96964 0.562981 0.969501 0.560192 0.03107392 0.582954 0.969884 0.564721 0.96964 0.562981 0.03107392 0.582954 0.970383 0.568105 0.969884 0.564721 0.03107392 0.582954 0.970682 0.573307 0.970383 0.568105 0.03107392 0.582954 0.970751 0.57964 0.970682 0.573307 0.03107392 0.582954 0.969493 0.556819 0.03021889 0.536364 0.03055799 0.559661 0.969501 0.560192 0.969493 0.556819 0.03055799 0.559661 0.969811 0.533533 0.03004598 0.513066 0.03021889 0.536364 0.969493 0.556819 0.969811 0.533533 0.03021889 0.536364 0.969963 0.510235 0.03003698 0.489766 0.03004598 0.513066 0.969811 0.533533 0.969963 0.510235 0.03004598 0.513066 0.969954 0.486936 0.03018891 0.466468 0.03003698 0.489766 0.969963 0.510235 0.969954 0.486936 0.03003698 0.489766 0.969781 0.463637 0.0305069 0.443181 0.03018891 0.466468 0.969954 0.486936 0.969781 0.463637 0.03018891 0.466468 0.969442 0.440341 0.03049898 0.439808 0.0305069 0.443181 0.969781 0.463637 0.969442 0.440341 0.0305069 0.443181 0.968927 0.417047 0.03035998 0.437019 0.03049898 0.439808 0.969442 0.440341 0.968927 0.417047 0.03049898 0.439808 0.968927 0.417047 0.03011596 0.435279 0.03035998 0.437019 0.968927 0.417047 0.02961695 0.431895 0.03011596 0.435279 0.968927 0.417047 0.02931797 0.426693 0.02961695 0.431895 0.968927 0.417047 0.02924895 0.42036 0.02931797 0.426693 0.96822 0.393758 0.02941393 0.413648 0.02924895 0.42036 0.968927 0.417047 0.96822 0.393758 0.02924895 0.42036 0.96822 0.393758 0.02979993 0.407325 0.02941393 0.413648 0.96822 0.393758 0.03036797 0.402145 0.02979993 0.407325 0.96822 0.393758 0.03105497 0.398788 0.03036797 0.402145 0.96822 0.393758 0.03139895 0.397063 0.03105497 0.398788 0.96822 0.393758 0.03169095 0.394284 0.03139895 0.397063 0.96822 0.393758 0.03188097 0.390915 0.03169095 0.394284 0.967301 0.370474 0.03282696 0.367644 0.03188097 0.390915 0.96822 0.393758 0.967301 0.370474 0.03188097 0.390915 0.96614 0.347199 0.03401988 0.34437 0.03282696 0.367644 0.967301 0.370474 0.96614 0.347199 0.03282696 0.367644 0.964698 0.323933 0.03549891 0.321106 0.03401988 0.34437 0.96614 0.347199 0.964698 0.323933 0.03401988 0.34437 0.96292 0.30068 0.03732198 0.297856 0.03549891 0.321106 0.964698 0.323933 0.96292 0.30068 0.03549891 0.321106 0.960736 0.277455 0.03956395 0.274623 0.03732198 0.297856 0.96292 0.30068 0.960736 0.277455 0.03732198 0.297856 0.960955 0.266136 0.04233098 0.251413 0.03956395 0.274623 0.960587 0.269544 0.960955 0.266136 0.03956395 0.274623 0.960415 0.271295 0.960587 0.269544 0.03956395 0.274623 0.960468 0.274088 0.960415 0.271295 0.03956395 0.274623 0.960736 0.277455 0.960468 0.274088 0.03956395 0.274623 0.955145 0.2315019 0.04577493 0.228233 0.04233098 0.251413 0.960445 0.254602 0.955145 0.2315019 0.04233098 0.251413 0.960906 0.260927 0.960445 0.254602 0.04233098 0.251413 0.960955 0.266136 0.960906 0.260927 0.04233098 0.251413 0.953749 0.225406 0.05011296 0.205094 0.04577493 0.228233 0.954414 0.228751 0.953749 0.225406 0.04577493 0.228233 0.955145 0.2315019 0.954414 0.228751 0.04577493 0.228233 0.949284 0.202284 0.05567795 0.182012 0.05011296 0.205094 0.953749 0.225406 0.949284 0.202284 0.05011296 0.205094 0.94354 0.179212 0.06298798 0.159011 0.05567795 0.182012 0.949284 0.202284 0.94354 0.179212 0.05567795 0.182012 0.935968 0.156224 0.07291001 0.1361359 0.06298798 0.159011 0.94354 0.179212 0.935968 0.156224 0.06298798 0.159011 0.925644 0.133368 0.086977 0.113471 0.07291001 0.1361359 0.935968 0.156224 0.925644 0.133368 0.07291001 0.1361359 0.910903 0.1107259 0.08931499 0.110195 0.086977 0.113471 0.925644 0.133368 0.910903 0.1107259 0.086977 0.113471 0.888465 0.08846098 0.09097295 0.107458 0.08931499 0.110195 0.910903 0.1107259 0.888465 0.08846098 0.08931499 0.110195 0.888465 0.08846098 0.09158998 0.105714 0.09097295 0.107458 0.147554 0.06739497 0.092785 0.102316 0.09158998 0.105714 0.155229 0.06441396 0.147554 0.06739497 0.09158998 0.105714 0.851046 0.06695097 0.155229 0.06441396 0.09158998 0.105714 0.888465 0.08846098 0.851046 0.06695097 0.09158998 0.105714 0.136764 0.07129698 0.096255 0.09721797 0.092785 0.102316 0.141161 0.06983095 0.136764 0.07129698 0.092785 0.102316 0.147554 0.06739497 0.141161 0.06983095 0.092785 0.102316 0.128619 0.07417595 0.101967 0.09110599 0.096255 0.09721797 0.136764 0.07129698 0.128619 0.07417595 0.096255 0.09721797 0.118999 0.07885497 0.10973 0.08473497 0.101967 0.09110599 0.128619 0.07417595 0.118999 0.07885497 0.101967 0.09110599 0.78022 0.04723989 0.232493 0.04508197 0.155229 0.06441396 0.851046 0.06695097 0.78022 0.04723989 0.155229 0.06441396 0.630814 0.03275698 0.395304 0.03172689 0.232493 0.04508197 0.78022 0.04723989 0.630814 0.03275698 0.232493 0.04508197 0.959607 0.247915 0.955823 0.233199 0.955145 0.2315019 0.960445 0.254602 0.959607 0.247915 0.955145 0.2315019 0.958468 0.241631 0.95715 0.2365 0.955823 0.233199 0.959607 0.247915 0.958468 0.241631 0.955823 0.233199 0.793904 0.704525 0.797654 0.704855 0.791151 0.705626 0.789631 0.707205 0.791151 0.705626 0.797654 0.704855 0.793904 0.730504 0.793904 0.704525 0.791151 0.705626 0.793904 0.730504 0.791151 0.705626 0.791151 0.731643 0.789631 0.707205 0.791151 0.731643 0.791151 0.705626 0.805754 0.708676 0.804359 0.710328 0.797654 0.704855 0.801579 0.711528 0.797654 0.704855 0.804359 0.710328 0.805526 0.706919 0.805754 0.708676 0.797654 0.704855 0.80377 0.705402 0.805526 0.706919 0.797654 0.704855 0.800859 0.704402 0.80377 0.705402 0.797654 0.704855 0.797354 0.704093 0.800859 0.704402 0.797654 0.704855 0.793904 0.704525 0.797354 0.704093 0.797654 0.704855 0.789676 0.708969 0.789631 0.707205 0.797654 0.704855 0.791329 0.710569 0.789676 0.708969 0.797654 0.704855 0.794294 0.711664 0.791329 0.710569 0.797654 0.704855 0.79797 0.712011 0.794294 0.711664 0.797654 0.704855 0.801579 0.711528 0.79797 0.712011 0.797654 0.704855 0.804359 0.736489 0.804359 0.710328 0.805754 0.708676 0.801579 0.737723 0.804359 0.710328 0.804359 0.736489 0.801579 0.737723 0.801579 0.711528 0.804359 0.710328 0.805754 0.734789 0.805754 0.708676 0.805526 0.706919 0.805754 0.734789 0.804359 0.736489 0.805754 0.708676 0.805526 0.732978 0.805526 0.706919 0.80377 0.705402 0.805526 0.732978 0.805754 0.734789 0.805526 0.706919 0.80377 0.731412 0.80377 0.705402 0.800859 0.704402 0.80377 0.731412 0.805526 0.732978 0.80377 0.705402 0.800859 0.730378 0.800859 0.704402 0.797354 0.704093 0.800859 0.730378 0.80377 0.731412 0.800859 0.704402 0.797354 0.730057 0.797354 0.704093 0.793904 0.704525 0.797354 0.730057 0.800859 0.730378 0.797354 0.704093 0.793904 0.730504 0.797354 0.730057 0.793904 0.704525 0.804496 0.722106 0.793904 0.730504 0.791151 0.731643 0.789631 0.733273 0.791151 0.731643 0.789631 0.707205 0.774905 0.741041 0.791151 0.731643 0.789631 0.733273 0.774905 0.741041 0.804496 0.722106 0.791151 0.731643 0.818434 0.726736 0.804359 0.736489 0.805754 0.734789 0.789643 0.747046 0.801579 0.737723 0.804359 0.736489 0.818434 0.726736 0.789643 0.747046 0.804359 0.736489 0.818434 0.726736 0.805754 0.734789 0.805526 0.732978 0.818434 0.726736 0.805526 0.732978 0.80377 0.731412 0.812187 0.723833 0.80377 0.731412 0.800859 0.730378 0.812187 0.723833 0.818434 0.726736 0.80377 0.731412 0.812187 0.723833 0.800859 0.730378 0.797354 0.730057 0.812187 0.723833 0.797354 0.730057 0.793904 0.730504 0.804496 0.722106 0.812187 0.723833 0.793904 0.730504 0.789631 0.733273 0.789631 0.707205 0.789676 0.708969 0.789676 0.735091 0.789676 0.708969 0.791329 0.710569 0.789676 0.735091 0.789631 0.733273 0.789676 0.708969 0.791329 0.736737 0.791329 0.710569 0.794294 0.711664 0.791329 0.736737 0.789676 0.735091 0.791329 0.710569 0.794294 0.737862 0.794294 0.711664 0.79797 0.712011 0.794294 0.737862 0.791329 0.736737 0.794294 0.711664 0.79797 0.738218 0.79797 0.712011 0.801579 0.711528 0.79797 0.738218 0.794294 0.737862 0.79797 0.712011 0.801579 0.737723 0.79797 0.738218 0.801579 0.711528 0.774905 0.741041 0.789631 0.733273 0.789676 0.735091 0.774905 0.741041 0.789676 0.735091 0.791329 0.736737 0.781071 0.744706 0.791329 0.736737 0.794294 0.737862 0.774905 0.741041 0.791329 0.736737 0.781071 0.744706 0.781071 0.744706 0.794294 0.737862 0.79797 0.738218 0.781071 0.744706 0.79797 0.738218 0.801579 0.737723 0.789643 0.747046 0.781071 0.744706 0.801579 0.737723 0.822505 0.73058 0.799429 0.747645 0.789643 0.747046 0.818434 0.726736 0.822505 0.73058 0.789643 0.747046 0.823782 0.735006 0.808942 0.746393 0.799429 0.747645 0.822505 0.73058 0.823782 0.735006 0.799429 0.747645 0.821876 0.739518 0.816767 0.743518 0.808942 0.746393 0.823782 0.735006 0.821876 0.739518 0.808942 0.746393 0.771832 0.73664 0.796148 0.721678 0.804496 0.722106 0.774905 0.741041 0.771832 0.73664 0.804496 0.722106 0.771999 0.73212 0.787943 0.722579 0.796148 0.721678 0.771832 0.73664 0.771999 0.73212 0.796148 0.721678 0.775132 0.728019 0.780681 0.724746 0.787943 0.722579 0.771999 0.73212 0.775132 0.728019 0.787943 0.722579 0.612171 0.681313 0.617035 0.677427 0.626503 0.675721 0.613709 0.675886 0.613059 0.675478 0.612955 0.674981 0.592691 0.684276 0.593424 0.682522 0.594431 0.684035 0.606345 0.673989 0.609942 0.674382 0.609692 0.675451 0.570884 0.680087 0.586475 0.683443 0.572756 0.685048 0.5917 0.682757 0.576058 0.679537 0.588474 0.678057 0.612171 0.681313 0.606345 0.673989 0.609692 0.675451 0.612171 0.681313 0.612269 0.677237 0.614602 0.677581 0.612171 0.681313 0.614602 0.677581 0.617035 0.677427 0.588474 0.678057 0.587567 0.676623 0.596519 0.675432 0.5917 0.682757 0.588474 0.678057 0.596519 0.675432 0.615852 0.676043 0.623617 0.672628 0.625244 0.674377 0.342309 0.05052691 0.325144 0.036502 0.303833 0.024535 0.303833 0.06188297 0.303833 0.024535 0.325144 0.036502 0.214502 0.001635909 0.342309 0.05052691 0.303833 0.024535 0.214502 0.03897297 0.214502 0.001635909 0.303833 0.024535 0.258136 0.05477899 0.214502 0.03897297 0.303833 0.024535 0.258136 0.05477899 0.303833 0.024535 0.303833 0.06188297 0.325145 0.07382398 0.325144 0.036502 0.342309 0.05052691 0.314953 0.067586 0.303833 0.06188297 0.325144 0.036502 0.325145 0.07382398 0.314953 0.067586 0.325144 0.036502 0.214502 0.001635909 0.358368 0.1069329 0.342309 0.05052691 0.342309 0.08779197 0.342309 0.05052691 0.358368 0.1069329 0.3343 0.08056998 0.325145 0.07382398 0.342309 0.05052691 0.342309 0.08779197 0.3343 0.08056998 0.342309 0.05052691 0.184426 0 0.34779 0.125002 0.358368 0.1069329 0.358368 0.143678 0.358368 0.1069329 0.34779 0.125002 0.214502 0.001635909 0.184426 0 0.358368 0.1069329 0.349882 0.119013 0.358368 0.1069329 0.358368 0.143678 0.349882 0.119013 0.342309 0.08779197 0.358368 0.1069329 0.154359 8.87e-4 0.329148 0.1419939 0.34779 0.125002 0.347817 0.161449 0.34779 0.125002 0.329148 0.1419939 0.184426 0 0.154359 8.87e-4 0.34779 0.125002 0.347817 0.161449 0.358368 0.143678 0.34779 0.125002 0.06316298 0.0214039 0.216696 0.178286 0.329148 0.1419939 0.329148 0.178183 0.329148 0.1419939 0.216696 0.178286 0.154359 8.87e-4 0.06316298 0.0214039 0.329148 0.1419939 0.329148 0.178183 0.347817 0.161449 0.329148 0.1419939 0.04082298 0.03269398 0.173611 0.180042 0.216696 0.178286 0.216696 0.2137179 0.216696 0.178286 0.173611 0.180042 0.06316298 0.0214039 0.04082298 0.03269398 0.216696 0.178286 0.275039 0.200242 0.329148 0.178183 0.216696 0.178286 0.275039 0.200242 0.216696 0.178286 0.216696 0.2137179 0.02229595 0.04615491 0.130801 0.176816 0.173611 0.180042 0.17353 0.215431 0.173611 0.180042 0.130801 0.176816 0.04082298 0.03269398 0.02229595 0.04615491 0.173611 0.180042 0.17353 0.215431 0.216696 0.2137179 0.173611 0.180042 0 0.101512 0.024432 0.137095 0.130801 0.176816 0.130801 0.212281 0.130801 0.176816 0.024432 0.137095 0.02229595 0.04615491 0 0.101512 0.130801 0.176816 0.130801 0.212281 0.17353 0.215431 0.130801 0.176816 0 0.101512 0.008192956 0.119667 0.024432 0.137095 0.024432 0.173372 0.024432 0.137095 0.008192956 0.119667 0.07544696 0.197008 0.130801 0.212281 0.024432 0.137095 0.07544696 0.197008 0.024432 0.137095 0.024432 0.173372 0.008190989 0.15623 0.008192956 0.119667 0 0.101512 0.01528996 0.164954 0.024432 0.173372 0.008192956 0.119667 0.008190989 0.15623 0.01528996 0.164954 0.008192956 0.119667 0 0.138327 0 0.101512 0.02229595 0.04615491 0.003111958 0.147317 0.008190989 0.15623 0 0.101512 0 0.138327 0.003111958 0.147317 0 0.101512 0.02229595 0.08344095 0.02229595 0.04615491 0.04082298 0.03269398 0.011765 0.1142089 0.02229595 0.04615491 0.02229595 0.08344095 0.011765 0.1142089 0 0.138327 0.02229595 0.04615491 0.04078495 0.07005 0.04082298 0.03269398 0.06316298 0.0214039 0.04078495 0.07005 0.02229595 0.08344095 0.04082298 0.03269398 0.06316298 0.05875498 0.06316298 0.0214039 0.154359 8.87e-4 0.06316298 0.05875498 0.04078495 0.07005 0.06316298 0.0214039 0.154359 0.03822195 0.154359 8.87e-4 0.184426 0 0.109691 0.05288892 0.154359 8.87e-4 0.154359 0.03822195 0.109691 0.05288892 0.06316298 0.05875498 0.154359 8.87e-4 0.184482 0.03733396 0.184426 0 0.214502 0.001635909 0.184482 0.03733396 0.154359 0.03822195 0.184426 0 0.214502 0.03897297 0.184482 0.03733396 0.214502 0.001635909 0.03838497 0.149186 0.06619298 0.134587 0.074449 0.15957 0.074449 0.240176 0.074449 0.15957 0.06619298 0.134587 0.04645293 0.164897 0.074449 0.15957 0.1065 0.180778 0.106475 0.260161 0.1065 0.180778 0.074449 0.15957 0.04645293 0.164897 0.03838497 0.149186 0.074449 0.15957 0.106475 0.260161 0.074449 0.15957 0.074449 0.240176 0.04428297 0.1183969 0.08008998 0.1112779 0.06619298 0.134587 0.06619799 0.216461 0.06619298 0.134587 0.08008998 0.1112779 0.03789496 0.1334339 0.04428297 0.1183969 0.06619298 0.134587 0.03838497 0.149186 0.03789496 0.1334339 0.06619298 0.134587 0.06619799 0.216461 0.074449 0.240176 0.06619298 0.134587 0.05666995 0.104713 0.111109 0.09347897 0.08008998 0.1112779 0.08013296 0.194094 0.08008998 0.1112779 0.111109 0.09347897 0.04428297 0.1183969 0.05666995 0.104713 0.08008998 0.1112779 0.06619799 0.216461 0.08008998 0.1112779 0.08013296 0.194094 0.05666995 0.104713 0.152626 0.08360797 0.111109 0.09347897 0.111045 0.177003 0.111109 0.09347897 0.152626 0.08360797 0.08013296 0.194094 0.111109 0.09347897 0.111045 0.177003 0.229339 0.07377696 0.198251 0.08267599 0.152626 0.08360797 0.152706 0.1674129 0.152626 0.08360797 0.198251 0.08267599 0.202231 0.07024598 0.229339 0.07377696 0.152626 0.08360797 0.05666995 0.104713 0.202231 0.07024598 0.152626 0.08360797 0.111045 0.177003 0.152626 0.08360797 0.152706 0.1674129 0.254777 0.07995098 0.24112 0.090801 0.198251 0.08267599 0.198171 0.1665109 0.198251 0.08267599 0.24112 0.090801 0.229339 0.07377696 0.254777 0.07995098 0.198251 0.08267599 0.152706 0.1674129 0.198251 0.08267599 0.198171 0.1665109 0.296809 0.09965795 0.274791 0.107119 0.24112 0.090801 0.241144 0.174398 0.24112 0.090801 0.274791 0.107119 0.277583 0.08863699 0.296809 0.09965795 0.24112 0.090801 0.254777 0.07995098 0.277583 0.08863699 0.24112 0.090801 0.198171 0.1665109 0.24112 0.090801 0.241144 0.174398 0.311388 0.1126829 0.292636 0.129598 0.274791 0.107119 0.274791 0.190131 0.274791 0.107119 0.292636 0.129598 0.311388 0.1126829 0.274791 0.107119 0.296809 0.09965795 0.241144 0.174398 0.274791 0.107119 0.274791 0.190131 0.322665 0.142795 0.289163 0.15461 0.292636 0.129598 0.292623 0.211666 0.292636 0.129598 0.289163 0.15461 0.320298 0.1272439 0.322665 0.142795 0.292636 0.129598 0.311388 0.1126829 0.320298 0.1272439 0.292636 0.129598 0.274791 0.190131 0.292636 0.129598 0.292623 0.211666 0.317725 0.158603 0.261738 0.177091 0.289163 0.15461 0.289134 0.23552 0.289163 0.15461 0.261738 0.177091 0.322665 0.142795 0.317725 0.158603 0.289163 0.15461 0.292623 0.211666 0.289163 0.15461 0.289134 0.23552 0.317725 0.158603 0.214099 0.19112 0.261738 0.177091 0.261803 0.256675 0.261738 0.177091 0.214099 0.19112 0.289134 0.23552 0.261738 0.177091 0.261803 0.256675 0.115823 0.201826 0.15713 0.192508 0.214099 0.19112 0.214 0.269892 0.214099 0.19112 0.15713 0.192508 0.150517 0.207578 0.115823 0.201826 0.214099 0.19112 0.317725 0.158603 0.150517 0.207578 0.214099 0.19112 0.261803 0.256675 0.214099 0.19112 0.214 0.269892 0.08584296 0.192218 0.1065 0.180778 0.15713 0.192508 0.15723 0.271189 0.15713 0.192508 0.1065 0.180778 0.115823 0.201826 0.08584296 0.192218 0.15713 0.192508 0.214 0.269892 0.15713 0.192508 0.15723 0.271189 0.06238889 0.179591 0.04645293 0.164897 0.1065 0.180778 0.08584296 0.192218 0.06238889 0.179591 0.1065 0.180778 0.15723 0.271189 0.1065 0.180778 0.106475 0.260161 0.325145 0.07382398 0.296809 0.09965795 0.277583 0.08863699 0.342309 0.08779197 0.311388 0.1126829 0.296809 0.09965795 0.3343 0.08056998 0.296809 0.09965795 0.325145 0.07382398 0.342309 0.08779197 0.296809 0.09965795 0.3343 0.08056998 0.303833 0.06188297 0.277583 0.08863699 0.254777 0.07995098 0.314953 0.067586 0.277583 0.08863699 0.303833 0.06188297 0.325145 0.07382398 0.277583 0.08863699 0.314953 0.067586 0.258136 0.05477899 0.254777 0.07995098 0.229339 0.07377696 0.258136 0.05477899 0.303833 0.06188297 0.254777 0.07995098 0.214502 0.03897297 0.229339 0.07377696 0.202231 0.07024598 0.258136 0.05477899 0.229339 0.07377696 0.214502 0.03897297 0.07408797 0.09286099 0.174377 0.06942796 0.202231 0.07024598 0.184482 0.03733396 0.202231 0.07024598 0.174377 0.06942796 0.05666995 0.104713 0.07408797 0.09286099 0.202231 0.07024598 0.214502 0.03897297 0.202231 0.07024598 0.184482 0.03733396 0.09555095 0.08319199 0.146687 0.07134097 0.174377 0.06942796 0.154359 0.03822195 0.174377 0.06942796 0.146687 0.07134097 0.07408797 0.09286099 0.09555095 0.08319199 0.174377 0.06942796 0.184482 0.03733396 0.174377 0.06942796 0.154359 0.03822195 0.09555095 0.08319199 0.120083 0.07595998 0.146687 0.07134097 0.154359 0.03822195 0.146687 0.07134097 0.120083 0.07595998 0.109691 0.05288892 0.120083 0.07595998 0.09555095 0.08319199 0.109691 0.05288892 0.154359 0.03822195 0.120083 0.07595998 0.06316298 0.05875498 0.09555095 0.08319199 0.07408797 0.09286099 0.109691 0.05288892 0.09555095 0.08319199 0.06316298 0.05875498 0.04078495 0.07005 0.07408797 0.09286099 0.05666995 0.104713 0.06316298 0.05875498 0.07408797 0.09286099 0.04078495 0.07005 0.02229595 0.08344095 0.05666995 0.104713 0.04428297 0.1183969 0.04078495 0.07005 0.05666995 0.104713 0.02229595 0.08344095 0.011765 0.1142089 0.04428297 0.1183969 0.03789496 0.1334339 0.011765 0.1142089 0.02229595 0.08344095 0.04428297 0.1183969 0.011765 0.1142089 0.03789496 0.1334339 0.03838497 0.149186 0 0.138327 0.03838497 0.149186 0.04645293 0.164897 0.011765 0.1142089 0.03838497 0.149186 0 0.138327 0.008190989 0.15623 0.04645293 0.164897 0.06238889 0.179591 0.003111958 0.147317 0.04645293 0.164897 0.008190989 0.15623 0 0.138327 0.04645293 0.164897 0.003111958 0.147317 0.024432 0.173372 0.06238889 0.179591 0.08584296 0.192218 0.01528996 0.164954 0.06238889 0.179591 0.024432 0.173372 0.008190989 0.15623 0.06238889 0.179591 0.01528996 0.164954 0.07544696 0.197008 0.08584296 0.192218 0.115823 0.201826 0.07544696 0.197008 0.024432 0.173372 0.08584296 0.192218 0.130801 0.212281 0.115823 0.201826 0.150517 0.207578 0.07544696 0.197008 0.115823 0.201826 0.130801 0.212281 0.305019 0.1737959 0.187469 0.208939 0.150517 0.207578 0.17353 0.215431 0.150517 0.207578 0.187469 0.208939 0.317725 0.158603 0.305019 0.1737959 0.150517 0.207578 0.130801 0.212281 0.150517 0.207578 0.17353 0.215431 0.284555 0.18739 0.223875 0.205772 0.187469 0.208939 0.216696 0.2137179 0.187469 0.208939 0.223875 0.205772 0.305019 0.1737959 0.284555 0.18739 0.187469 0.208939 0.17353 0.215431 0.187469 0.208939 0.216696 0.2137179 0.284555 0.18739 0.257002 0.198364 0.223875 0.205772 0.216696 0.2137179 0.223875 0.205772 0.257002 0.198364 0.275039 0.200242 0.257002 0.198364 0.284555 0.18739 0.275039 0.200242 0.216696 0.2137179 0.257002 0.198364 0.329148 0.178183 0.284555 0.18739 0.305019 0.1737959 0.275039 0.200242 0.284555 0.18739 0.329148 0.178183 0.347817 0.161449 0.305019 0.1737959 0.317725 0.158603 0.329148 0.178183 0.305019 0.1737959 0.347817 0.161449 0.358368 0.143678 0.317725 0.158603 0.322665 0.142795 0.347817 0.161449 0.317725 0.158603 0.358368 0.143678 0.349882 0.119013 0.322665 0.142795 0.320298 0.1272439 0.349882 0.119013 0.358368 0.143678 0.322665 0.142795 0.349882 0.119013 0.320298 0.1272439 0.311388 0.1126829 0.349882 0.119013 0.311388 0.1126829 0.342309 0.08779197 0.292623 0.211666 0.106475 0.260161 0.074449 0.240176 0.274791 0.190131 0.292623 0.211666 0.074449 0.240176 0.06619799 0.216461 0.274791 0.190131 0.074449 0.240176 0.289134 0.23552 0.15723 0.271189 0.106475 0.260161 0.292623 0.211666 0.289134 0.23552 0.106475 0.260161 0.261803 0.256675 0.214 0.269892 0.15723 0.271189 0.289134 0.23552 0.261803 0.256675 0.15723 0.271189 0.06619799 0.216461 0.241144 0.174398 0.274791 0.190131 0.08013296 0.194094 0.198171 0.1665109 0.241144 0.174398 0.06619799 0.216461 0.08013296 0.194094 0.241144 0.174398 0.111045 0.177003 0.152706 0.1674129 0.198171 0.1665109 0.08013296 0.194094 0.111045 0.177003 0.198171 0.1665109 0.596519 0.675432 0.600809 0.681464 0.593424 0.682522 0.605456 0.6824 0.602798 0.674527 0.60846 0.681922 0.5917 0.682757 0.596519 0.675432 0.593424 0.682522 0.592691 0.684276 0.5917 0.682757 0.593424 0.682522 0.606345 0.673989 0.611195 0.673475 0.609942 0.674382 0.605456 0.6824 0.599929 0.674948 0.602798 0.674527 0.614732 0.676094 0.613709 0.675886 0.613419 0.67453 0.612171 0.681313 0.609692 0.675451 0.610516 0.676473 0.221676 0.076415 0.228778 0.06542396 0.231067 0.05431389 0.231067 0.09010797 0.231067 0.05431389 0.228778 0.06542396 0.2084169 0.02196598 0.221676 0.076415 0.231067 0.05431389 0.2084169 0.05698388 0.2084169 0.02196598 0.231067 0.05431389 0.219349 0.07703197 0.2084169 0.05698388 0.231067 0.05431389 0.219349 0.07703197 0.231067 0.05431389 0.231067 0.09010797 0.228779 0.101449 0.228778 0.06542396 0.221676 0.076415 0.230514 0.09576499 0.231067 0.09010797 0.228778 0.06542396 0.228779 0.101449 0.230514 0.09576499 0.228778 0.06542396 0.2084169 0.02196598 0.165968 0.105017 0.221676 0.076415 0.221676 0.11265 0.221676 0.076415 0.165968 0.105017 0.225836 0.1070989 0.228779 0.101449 0.221676 0.076415 0.221676 0.11265 0.225836 0.1070989 0.221676 0.076415 0.1941699 0.01452893 0.141587 0.109355 0.165968 0.105017 0.165968 0.141715 0.165968 0.105017 0.141587 0.109355 0.2084169 0.02196598 0.1941699 0.01452893 0.165968 0.105017 0.1946499 0.13104 0.165968 0.105017 0.165968 0.141715 0.1946499 0.13104 0.221676 0.11265 0.165968 0.105017 0.177541 0.008550941 0.115783 0.110963 0.141587 0.109355 0.141635 0.146107 0.141587 0.109355 0.115783 0.110963 0.1941699 0.01452893 0.177541 0.008550941 0.141587 0.109355 0.141635 0.146107 0.165968 0.141715 0.141587 0.109355 0.112595 0 0.03735792 0.09701299 0.115783 0.110963 0.115783 0.147741 0.115783 0.110963 0.03735792 0.09701299 0.177541 0.008550941 0.112595 0 0.115783 0.110963 0.115783 0.147741 0.141635 0.146107 0.115783 0.110963 0.09207201 9.39e-4 0.02028298 0.08810698 0.03735792 0.09701299 0.03735792 0.133594 0.03735792 0.09701299 0.02028298 0.08810698 0.112595 0 0.09207201 9.39e-4 0.03735792 0.09701299 0.07601499 0.144931 0.115783 0.147741 0.03735792 0.09701299 0.07601499 0.144931 0.03735792 0.09701299 0.03735792 0.133594 0.072084 0.003530979 0.007672965 0.077874 0.02028298 0.08810698 0.0202549 0.124527 0.02028298 0.08810698 0.007672965 0.077874 0.09207201 9.39e-4 0.072084 0.003530979 0.02028298 0.08810698 0.0202549 0.124527 0.03735792 0.133594 0.02028298 0.08810698 0.01787292 0.02307999 0 0.04186993 0.007672965 0.077874 0.007672965 0.114136 0.007672965 0.077874 0 0.04186993 0.072084 0.003530979 0.01787292 0.02307999 0.007672965 0.077874 0.007672965 0.114136 0.0202549 0.124527 0.007672965 0.077874 0.01787292 0.02307999 0.007120907 0.03195095 0 0.04186993 0 0.07738399 0 0.04186993 0.007120907 0.03195095 0.003691971 0.09920495 0.007672965 0.114136 0 0.04186993 0.003691971 0.09920495 0 0.04186993 0 0.07738399 0.007119953 0.06722599 0.007120907 0.03195095 0.01787292 0.02307999 0.003072977 0.07218897 0 0.07738399 0.007120907 0.03195095 0.007119953 0.06722599 0.003072977 0.07218897 0.007120907 0.03195095 0.01787292 0.05812793 0.01787292 0.02307999 0.072084 0.003530979 0.01207488 0.06252896 0.007119953 0.06722599 0.01787292 0.02307999 0.01787292 0.05812793 0.01207488 0.06252896 0.01787292 0.02307999 0.072084 0.0380389 0.072084 0.003530979 0.09207201 9.39e-4 0.04555189 0.05188 0.072084 0.003530979 0.072084 0.0380389 0.04555189 0.05188 0.01787292 0.05812793 0.072084 0.003530979 0.09203398 0.03537493 0.09207201 9.39e-4 0.112595 0 0.09203398 0.03537493 0.072084 0.0380389 0.09207201 9.39e-4 0.112595 0.03440499 0.112595 0 0.177541 0.008550941 0.112595 0.03440499 0.09203398 0.03537493 0.112595 0 0.177541 0.04320293 0.177541 0.008550941 0.1941699 0.01452893 0.144758 0.04276198 0.177541 0.008550941 0.177541 0.04320293 0.144758 0.04276198 0.112595 0.03440499 0.177541 0.008550941 0.194199 0.04935991 0.1941699 0.01452893 0.2084169 0.02196598 0.194199 0.04935991 0.177541 0.04320293 0.1941699 0.01452893 0.2084169 0.05698388 0.194199 0.04935991 0.2084169 0.02196598 0.03849589 0.07850599 0.06323999 0.07756197 0.04547095 0.09017497 0.04547095 0.174154 0.04547095 0.09017497 0.06323999 0.07756197 0.0288819 0.08688497 0.04547095 0.09017497 0.04032593 0.105791 0.04032999 0.190173 0.04032593 0.105791 0.04547095 0.09017497 0.0288819 0.08688497 0.03849589 0.07850599 0.04547095 0.09017497 0.04032999 0.190173 0.04547095 0.09017497 0.04547095 0.174154 0.06674897 0.06594896 0.08962798 0.06983798 0.06323999 0.07756197 0.06322699 0.161152 0.06323999 0.07756197 0.08962798 0.06983798 0.05133491 0.07146096 0.06674897 0.06594896 0.06323999 0.07756197 0.03849589 0.07850599 0.05133491 0.07146096 0.06323999 0.07756197 0.06322699 0.161152 0.04547095 0.174154 0.06323999 0.07756197 0.08403599 0.06212395 0.120066 0.06797796 0.08962798 0.06983798 0.08967995 0.15314 0.08962798 0.06983798 0.120066 0.06797796 0.06674897 0.06594896 0.08403599 0.06212395 0.08962798 0.06983798 0.06322699 0.161152 0.08962798 0.06983798 0.08967995 0.15314 0.08403599 0.06212395 0.14944 0.07219898 0.120066 0.06797796 0.120012 0.151219 0.120066 0.06797796 0.14944 0.07219898 0.08967995 0.15314 0.120066 0.06797796 0.120012 0.151219 0.197353 0.08498495 0.173032 0.08201897 0.14944 0.07219898 0.149487 0.1556079 0.14944 0.07219898 0.173032 0.08201897 0.187016 0.07688599 0.197353 0.08498495 0.14944 0.07219898 0.08403599 0.06212395 0.187016 0.07688599 0.14944 0.07219898 0.120012 0.151219 0.14944 0.07219898 0.149487 0.1556079 0.20397 0.09416896 0.186221 0.09607499 0.173032 0.08201897 0.172998 0.165726 0.173032 0.08201897 0.186221 0.09607499 0.197353 0.08498495 0.20397 0.09416896 0.173032 0.08201897 0.149487 0.1556079 0.173032 0.08201897 0.172998 0.165726 0.2040629 0.114252 0.1857039 0.112134 0.186221 0.09607499 0.186221 0.180233 0.186221 0.09607499 0.1857039 0.112134 0.206341 0.104068 0.2040629 0.114252 0.186221 0.09607499 0.20397 0.09416896 0.206341 0.104068 0.186221 0.09607499 0.172998 0.165726 0.186221 0.09607499 0.186221 0.180233 0.196956 0.124158 0.170198 0.1269879 0.1857039 0.112134 0.1857039 0.196672 0.1857039 0.112134 0.170198 0.1269879 0.196956 0.124158 0.1857039 0.112134 0.2040629 0.114252 0.186221 0.180233 0.1857039 0.112134 0.1857039 0.196672 0.169111 0.1407 0.14199 0.137073 0.170198 0.1269879 0.17021 0.2117969 0.170198 0.1269879 0.14199 0.137073 0.185159 0.133168 0.169111 0.1407 0.170198 0.1269879 0.196956 0.124158 0.185159 0.133168 0.170198 0.1269879 0.1857039 0.196672 0.170198 0.1269879 0.17021 0.2117969 0.149623 0.146199 0.1069779 0.1396279 0.14199 0.137073 0.1419309 0.222053 0.14199 0.137073 0.1069779 0.1396279 0.169111 0.1407 0.149623 0.146199 0.14199 0.137073 0.17021 0.2117969 0.14199 0.137073 0.1419309 0.222053 0.149623 0.146199 0.07377398 0.133904 0.1069779 0.1396279 0.107041 0.2246299 0.1069779 0.1396279 0.07377398 0.133904 0.1419309 0.222053 0.1069779 0.1396279 0.107041 0.2246299 0.025074 0.116427 0.04997491 0.121523 0.07377398 0.133904 0.07372295 0.218811 0.07377398 0.133904 0.04997491 0.121523 0.03318893 0.126172 0.025074 0.116427 0.07377398 0.133904 0.149623 0.146199 0.03318893 0.126172 0.07377398 0.133904 0.107041 0.2246299 0.07377398 0.133904 0.07372295 0.218811 0.021761 0.106279 0.04032593 0.105791 0.04997491 0.121523 0.05000597 0.206275 0.04997491 0.121523 0.04032593 0.105791 0.025074 0.116427 0.021761 0.106279 0.04997491 0.121523 0.07372295 0.218811 0.04997491 0.121523 0.05000597 0.206275 0.02313596 0.09628099 0.0288819 0.08688497 0.04032593 0.105791 0.021761 0.106279 0.02313596 0.09628099 0.04032593 0.105791 0.05000597 0.206275 0.04032593 0.105791 0.04032999 0.190173 0.228779 0.101449 0.2040629 0.114252 0.206341 0.104068 0.221676 0.11265 0.196956 0.124158 0.2040629 0.114252 0.225836 0.1070989 0.2040629 0.114252 0.228779 0.101449 0.221676 0.11265 0.2040629 0.114252 0.225836 0.1070989 0.231067 0.09010797 0.206341 0.104068 0.20397 0.09416896 0.230514 0.09576499 0.206341 0.104068 0.231067 0.09010797 0.228779 0.101449 0.206341 0.104068 0.230514 0.09576499 0.219349 0.07703197 0.20397 0.09416896 0.197353 0.08498495 0.219349 0.07703197 0.231067 0.09010797 0.20397 0.09416896 0.2084169 0.05698388 0.197353 0.08498495 0.187016 0.07688599 0.219349 0.07703197 0.197353 0.08498495 0.2084169 0.05698388 0.102491 0.06008398 0.173574 0.070149 0.187016 0.07688599 0.194199 0.04935991 0.187016 0.07688599 0.173574 0.070149 0.08403599 0.06212395 0.102491 0.06008398 0.187016 0.07688599 0.2084169 0.05698388 0.187016 0.07688599 0.194199 0.04935991 0.121402 0.05988097 0.157689 0.06497997 0.173574 0.070149 0.177541 0.04320293 0.173574 0.070149 0.157689 0.06497997 0.102491 0.06008398 0.121402 0.05988097 0.173574 0.070149 0.194199 0.04935991 0.173574 0.070149 0.177541 0.04320293 0.121402 0.05988097 0.140052 0.06152492 0.157689 0.06497997 0.177541 0.04320293 0.157689 0.06497997 0.140052 0.06152492 0.144758 0.04276198 0.140052 0.06152492 0.121402 0.05988097 0.144758 0.04276198 0.177541 0.04320293 0.140052 0.06152492 0.112595 0.03440499 0.121402 0.05988097 0.102491 0.06008398 0.144758 0.04276198 0.121402 0.05988097 0.112595 0.03440499 0.09203398 0.03537493 0.102491 0.06008398 0.08403599 0.06212395 0.112595 0.03440499 0.102491 0.06008398 0.09203398 0.03537493 0.072084 0.0380389 0.08403599 0.06212395 0.06674897 0.06594896 0.09203398 0.03537493 0.08403599 0.06212395 0.072084 0.0380389 0.04555189 0.05188 0.06674897 0.06594896 0.05133491 0.07146096 0.04555189 0.05188 0.072084 0.0380389 0.06674897 0.06594896 0.04555189 0.05188 0.05133491 0.07146096 0.03849589 0.07850599 0.01787292 0.05812793 0.03849589 0.07850599 0.0288819 0.08688497 0.04555189 0.05188 0.03849589 0.07850599 0.01787292 0.05812793 0.007119953 0.06722599 0.0288819 0.08688497 0.02313596 0.09628099 0.01207488 0.06252896 0.0288819 0.08688497 0.007119953 0.06722599 0.01787292 0.05812793 0.0288819 0.08688497 0.01207488 0.06252896 0 0.07738399 0.02313596 0.09628099 0.021761 0.106279 0.003072977 0.07218897 0.02313596 0.09628099 0 0.07738399 0.007119953 0.06722599 0.02313596 0.09628099 0.003072977 0.07218897 0.003691971 0.09920495 0.021761 0.106279 0.025074 0.116427 0.003691971 0.09920495 0 0.07738399 0.021761 0.106279 0.007672965 0.114136 0.025074 0.116427 0.03318893 0.126172 0.003691971 0.09920495 0.025074 0.116427 0.007672965 0.114136 0.127829 0.149228 0.045937 0.13492 0.03318893 0.126172 0.0202549 0.124527 0.03318893 0.126172 0.045937 0.13492 0.149623 0.146199 0.127829 0.149228 0.03318893 0.126172 0.007672965 0.114136 0.03318893 0.126172 0.0202549 0.124527 0.105107 0.149534 0.06281095 0.1420699 0.045937 0.13492 0.03735792 0.133594 0.045937 0.13492 0.06281095 0.1420699 0.127829 0.149228 0.105107 0.149534 0.045937 0.13492 0.0202549 0.124527 0.045937 0.13492 0.03735792 0.133594 0.105107 0.149534 0.082946 0.14708 0.06281095 0.1420699 0.03735792 0.133594 0.06281095 0.1420699 0.082946 0.14708 0.07601499 0.144931 0.082946 0.14708 0.105107 0.149534 0.07601499 0.144931 0.03735792 0.133594 0.082946 0.14708 0.115783 0.147741 0.105107 0.149534 0.127829 0.149228 0.07601499 0.144931 0.105107 0.149534 0.115783 0.147741 0.141635 0.146107 0.127829 0.149228 0.149623 0.146199 0.115783 0.147741 0.127829 0.149228 0.141635 0.146107 0.165968 0.141715 0.149623 0.146199 0.169111 0.1407 0.141635 0.146107 0.149623 0.146199 0.165968 0.141715 0.1946499 0.13104 0.169111 0.1407 0.185159 0.133168 0.1946499 0.13104 0.165968 0.141715 0.169111 0.1407 0.1946499 0.13104 0.185159 0.133168 0.196956 0.124158 0.1946499 0.13104 0.196956 0.124158 0.221676 0.11265 0.17021 0.2117969 0.04032999 0.190173 0.04547095 0.174154 0.1857039 0.196672 0.17021 0.2117969 0.04547095 0.174154 0.06322699 0.161152 0.1857039 0.196672 0.04547095 0.174154 0.1419309 0.222053 0.05000597 0.206275 0.04032999 0.190173 0.17021 0.2117969 0.1419309 0.222053 0.04032999 0.190173 0.107041 0.2246299 0.07372295 0.218811 0.05000597 0.206275 0.1419309 0.222053 0.107041 0.2246299 0.05000597 0.206275 0.06322699 0.161152 0.186221 0.180233 0.1857039 0.196672 0.08967995 0.15314 0.172998 0.165726 0.186221 0.180233 0.06322699 0.161152 0.08967995 0.15314 0.186221 0.180233 0.120012 0.151219 0.149487 0.1556079 0.172998 0.165726 0.08967995 0.15314 0.120012 0.151219 0.172998 0.165726 0.615852 0.676043 0.614325 0.674243 0.623617 0.672628 0.623617 0.673838 0.623617 0.672628 0.614325 0.674243 0.623617 0.673838 0.625244 0.675594 0.623617 0.672628 0.573558 0.687887 0.572756 0.685048 0.572756 0.686304 0.586475 0.684694 0.586475 0.683443 0.570884 0.680087 0.572756 0.686304 0.586475 0.683443 0.586475 0.684694 0.570884 0.681325 0.570884 0.680087 0.570144 0.678603 0.586475 0.684694 0.570884 0.680087 0.570884 0.681325 0.570884 0.681325 0.570144 0.678603 0.570144 0.679836 0.623617 0.673838 0.614325 0.674243 0.614325 0.67546 0.609942 0.675599 0.609942 0.674382 0.611195 0.673475 0.609692 0.676672 0.609942 0.674382 0.609942 0.675599 0.611194 0.674689 0.611195 0.673475 0.613193 0.672899 0.609942 0.675599 0.611195 0.673475 0.611194 0.674689 0.613193 0.67411 0.613193 0.672899 0.625597 0.670745 0.611194 0.674689 0.613193 0.672899 0.613193 0.67411 0.613193 0.67411 0.625597 0.670745 0.625597 0.671948 0.617035 0.678656 0.617035 0.677427 0.614602 0.677581 0.626503 0.676944 0.617035 0.677427 0.617035 0.678656 0.614325 0.67546 0.613419 0.67453 0.613419 0.675748 0.614325 0.67546 0.614325 0.674243 0.613419 0.67453 0.610516 0.677697 0.610516 0.676473 0.609692 0.675451 0.612268 0.678465 0.610516 0.676473 0.610516 0.677697 0.572756 0.686304 0.572756 0.685048 0.586475 0.683443 0.610516 0.677697 0.609692 0.675451 0.609692 0.676672 0.628939 0.679527 0.625597 0.671948 0.632255 0.678876 0.614325 0.67546 0.613193 0.67411 0.625597 0.671948 0.628939 0.679527 0.626503 0.676944 0.625597 0.671948 0.625244 0.675594 0.625597 0.671948 0.626503 0.676944 0.623617 0.673838 0.625597 0.671948 0.625244 0.675594 0.623617 0.673838 0.614325 0.67546 0.625597 0.671948 0.612955 0.6762 0.611194 0.674689 0.613193 0.67411 0.613419 0.675748 0.612955 0.6762 0.613193 0.67411 0.614325 0.67546 0.613419 0.675748 0.613193 0.67411 0.612268 0.678465 0.609942 0.675599 0.611194 0.674689 0.614601 0.67881 0.612268 0.678465 0.611194 0.674689 0.613059 0.676699 0.614601 0.67881 0.611194 0.674689 0.612955 0.6762 0.613059 0.676699 0.611194 0.674689 0.610516 0.677697 0.609692 0.676672 0.609942 0.675599 0.612268 0.678465 0.610516 0.677697 0.609942 0.675599 0.615852 0.677267 0.617035 0.678656 0.614601 0.67881 0.614732 0.677317 0.615852 0.677267 0.614601 0.67881 0.61371 0.677109 0.614732 0.677317 0.614601 0.67881 0.613059 0.676699 0.61371 0.677109 0.614601 0.67881 0.625244 0.675594 0.626503 0.676944 0.617035 0.678656 0.615852 0.677267 0.625244 0.675594 0.617035 0.678656 0.60846 0.683168 0.602798 0.675745 0.606345 0.675205 0.612171 0.682556 0.60846 0.683168 0.606345 0.675205 0.600809 0.682707 0.596519 0.676654 0.599929 0.676167 0.605456 0.683647 0.600809 0.682707 0.599929 0.676167 0.594431 0.685288 0.593424 0.683769 0.600809 0.682707 0.605456 0.683647 0.594431 0.685288 0.600809 0.682707 0.570884 0.681325 0.570144 0.679836 0.587567 0.677849 0.576058 0.680774 0.570884 0.681325 0.587567 0.677849 0.588474 0.679288 0.576058 0.680774 0.587567 0.677849 0.576058 0.680774 0.586475 0.684694 0.570884 0.681325 0.573558 0.687887 0.572756 0.686304 0.586475 0.684694 0.5917 0.684006 0.573558 0.687887 0.586475 0.684694 0.576058 0.680774 0.5917 0.684006 0.586475 0.684694 0.5917 0.684006 0.592691 0.68553 0.573558 0.687887 0.613419 0.675748 0.613419 0.67453 0.612955 0.674981 0.626503 0.676944 0.626503 0.675721 0.617035 0.677427 0.628939 0.679527 0.626503 0.675721 0.626503 0.676944 0.632255 0.678876 0.632255 0.677647 0.628939 0.678295 0.625597 0.671948 0.625597 0.670745 0.632255 0.677647 0.625597 0.671948 0.632255 0.677647 0.632255 0.678876 0.628939 0.679527 0.628939 0.678295 0.626503 0.675721 0.628939 0.679527 0.632255 0.678876 0.628939 0.678295 0.625244 0.675594 0.625244 0.674377 0.623617 0.672628 0.615852 0.677267 0.615852 0.676043 0.625244 0.674377 0.615852 0.677267 0.625244 0.674377 0.625244 0.675594 0.609692 0.676672 0.609692 0.675451 0.609942 0.674382 0.612268 0.678465 0.612269 0.677237 0.610516 0.676473 0.614601 0.67881 0.612269 0.677237 0.612268 0.678465 0.612955 0.6762 0.612955 0.674981 0.613059 0.675478 0.613419 0.675748 0.612955 0.674981 0.612955 0.6762 0.613059 0.676699 0.613059 0.675478 0.613709 0.675886 0.612955 0.6762 0.613059 0.675478 0.613059 0.676699 0.61371 0.677109 0.613709 0.675886 0.614732 0.676094 0.613059 0.676699 0.613709 0.675886 0.61371 0.677109 0.614732 0.677317 0.614732 0.676094 0.615852 0.676043 0.61371 0.677109 0.614732 0.676094 0.614732 0.677317 0.614732 0.677317 0.615852 0.676043 0.615852 0.677267 0.606345 0.675205 0.606345 0.673989 0.612171 0.681313 0.602798 0.675745 0.602798 0.674527 0.606345 0.673989 0.602798 0.675745 0.606345 0.673989 0.606345 0.675205 0.612171 0.682556 0.612171 0.681313 0.60846 0.681922 0.612171 0.682556 0.606345 0.675205 0.612171 0.681313 0.60846 0.683168 0.60846 0.681922 0.602798 0.674527 0.612171 0.682556 0.60846 0.681922 0.60846 0.683168 0.588474 0.679288 0.588474 0.678057 0.576058 0.679537 0.588474 0.679288 0.587567 0.677849 0.588474 0.678057 0.576058 0.680774 0.576058 0.679537 0.5917 0.682757 0.588474 0.679288 0.576058 0.679537 0.576058 0.680774 0.5917 0.684006 0.5917 0.682757 0.592691 0.684276 0.576058 0.680774 0.5917 0.682757 0.5917 0.684006 0.592691 0.68553 0.592691 0.684276 0.573558 0.686626 0.5917 0.684006 0.592691 0.684276 0.592691 0.68553 0.573558 0.687887 0.573558 0.686626 0.572756 0.685048 0.592691 0.68553 0.573558 0.686626 0.573558 0.687887 0.593424 0.683769 0.593424 0.682522 0.600809 0.681464 0.594431 0.685288 0.594431 0.684035 0.593424 0.682522 0.605456 0.683647 0.594431 0.684035 0.594431 0.685288 0.60846 0.683168 0.602798 0.674527 0.602798 0.675745 0.599929 0.676167 0.599929 0.674948 0.605456 0.6824 0.596519 0.676654 0.596519 0.675432 0.599929 0.674948 0.596519 0.676654 0.599929 0.674948 0.599929 0.676167 0.605456 0.683647 0.605456 0.6824 0.594431 0.684035 0.605456 0.683647 0.599929 0.676167 0.605456 0.6824 0.600809 0.682707 0.596519 0.675432 0.596519 0.676654 0.587567 0.677849 0.587567 0.676623 0.588474 0.678057 0.570144 0.679836 0.570144 0.678603 0.587567 0.676623 0.570144 0.679836 0.587567 0.676623 0.587567 0.677849 0.594431 0.685288 0.593424 0.682522 0.593424 0.683769 0.600809 0.682707 0.600809 0.681464 0.596519 0.675432 0.593424 0.683769 0.600809 0.681464 0.600809 0.682707 0.614601 0.67881 0.614602 0.677581 0.612269 0.677237 0.617035 0.678656 0.614602 0.677581 0.614601 0.67881 - - - - - - - - - - - - - - -

0 0 0 1 0 1 2 0 2 3 1 3 4 2 4 5 3 5 6 4 6 1 4 7 0 4 8 7 5 9 1 5 10 6 5 11 8 6 12 1 6 13 7 6 14 9 7 15 1 7 16 8 7 17 10 8 18 3 1 19 5 3 20 11 9 21 10 8 22 5 3 23 12 10 24 11 9 25 5 3 26 13 11 27 14 11 28 15 11 29 16 12 30 1 12 31 9 12 32 17 13 33 1 13 34 16 13 35 18 14 36 1 14 37 17 14 38 19 15 39 1 15 40 18 15 41 20 11 42 15 11 43 21 11 44 22 11 45 13 11 46 15 11 47 20 11 48 22 11 49 15 11 50 23 16 51 24 17 52 4 2 53 3 1 54 23 16 55 4 2 56 25 18 57 26 19 58 24 17 59 27 20 60 25 18 61 24 17 62 23 16 63 27 20 64 24 17 65 28 21 66 29 22 67 26 19 68 30 23 69 28 21 70 26 19 71 25 18 72 30 23 73 26 19 74 31 24 75 32 25 76 29 22 77 33 26 78 31 24 79 29 22 80 28 21 81 33 26 82 29 22 83 34 27 84 35 28 85 36 29 86 37 30 87 35 28 88 34 27 89 38 31 90 39 31 91 40 31 92 41 32 93 42 32 94 39 32 95 41 31 96 39 31 97 38 31 98 43 31 99 40 31 100 44 31 101 43 33 102 38 33 103 40 33 104 43 31 105 44 31 106 45 31 107 46 31 108 45 31 109 47 31 110 46 31 111 43 31 112 45 31 113 46 31 114 47 31 115 48 31 116 49 31 117 48 31 118 50 31 119 49 31 120 46 31 121 48 31 122 49 31 123 50 31 124 51 31 125 52 31 126 51 31 127 53 31 128 52 31 129 49 31 130 51 31 131 52 31 132 53 31 133 54 31 134 12 10 135 55 34 136 11 9 137 56 31 138 54 31 139 57 31 140 56 35 141 52 35 142 54 35 143 58 36 144 59 37 145 55 34 146 56 38 147 57 38 148 60 38 149 12 10 150 58 36 151 55 34 152 61 39 153 62 40 154 59 37 155 63 41 156 60 41 157 64 41 158 58 36 159 61 39 160 59 37 161 63 42 162 56 42 163 60 42 164 65 43 165 66 44 166 62 40 167 63 31 168 64 31 169 67 31 170 68 45 171 65 43 172 62 40 173 69 46 174 68 45 175 62 40 176 70 47 177 69 46 178 62 40 179 71 48 180 70 47 181 62 40 182 72 49 183 71 48 184 62 40 185 73 50 186 72 49 187 62 40 188 74 51 189 73 50 190 62 40 191 75 52 192 74 51 193 62 40 194 76 53 195 75 52 196 62 40 197 77 54 198 76 53 199 62 40 200 78 55 201 77 54 202 62 40 203 79 56 204 78 55 205 62 40 206 80 57 207 79 56 208 62 40 209 61 39 210 80 57 211 62 40 212 81 58 213 82 59 214 66 44 215 83 60 216 67 60 217 84 60 218 85 61 219 81 58 220 66 44 221 86 62 222 85 61 223 66 44 224 87 63 225 86 62 226 66 44 227 88 64 228 87 63 229 66 44 230 89 65 231 88 64 232 66 44 233 90 66 234 89 65 235 66 44 236 91 67 237 90 66 238 66 44 239 92 68 240 91 67 241 66 44 242 93 69 243 92 68 244 66 44 245 94 70 246 93 69 247 66 44 248 95 71 249 94 70 250 66 44 251 96 72 252 95 71 253 66 44 254 97 73 255 96 72 256 66 44 257 65 43 258 97 73 259 66 44 260 83 31 261 63 31 262 67 31 263 98 74 264 99 75 265 82 59 266 100 31 267 84 31 268 101 31 269 102 76 270 98 74 271 82 59 272 103 77 273 102 76 274 82 59 275 104 78 276 103 77 277 82 59 278 105 79 279 104 78 280 82 59 281 106 80 282 105 79 283 82 59 284 107 81 285 106 80 286 82 59 287 108 82 288 107 81 289 82 59 290 109 83 291 108 82 292 82 59 293 110 84 294 109 83 295 82 59 296 111 85 297 110 84 298 82 59 299 112 86 300 111 85 301 82 59 302 113 87 303 112 86 304 82 59 305 81 58 306 113 87 307 82 59 308 100 31 309 83 31 310 84 31 311 114 88 312 115 89 313 99 75 314 116 31 315 101 31 316 117 31 317 118 90 318 114 88 319 99 75 320 119 91 321 118 90 322 99 75 323 120 92 324 119 91 325 99 75 326 121 93 327 120 92 328 99 75 329 122 94 330 121 93 331 99 75 332 123 95 333 122 94 334 99 75 335 124 96 336 123 95 337 99 75 338 125 97 339 124 96 340 99 75 341 98 74 342 125 97 343 99 75 344 116 98 345 100 98 346 101 98 347 126 99 348 127 100 349 115 89 350 128 101 351 117 101 352 129 101 353 130 102 354 126 99 355 115 89 356 131 103 357 130 102 358 115 89 359 132 104 360 131 103 361 115 89 362 133 105 363 132 104 364 115 89 365 114 88 366 133 105 367 115 89 368 128 106 369 116 106 370 117 106 371 134 31 372 129 31 373 135 31 374 136 107 375 137 108 376 127 100 377 138 31 378 129 31 379 134 31 380 128 109 381 129 109 382 138 109 383 126 99 384 136 107 385 127 100 386 139 31 387 135 31 388 140 31 389 136 107 390 141 110 391 137 108 392 134 31 393 135 31 394 139 31 395 142 31 396 140 31 397 143 31 398 144 111 399 145 112 400 141 110 401 139 31 402 140 31 403 142 31 404 136 107 405 144 111 406 141 110 407 146 31 408 143 31 409 147 31 410 144 111 411 148 113 412 145 112 413 142 31 414 143 31 415 146 31 416 149 114 417 150 115 418 148 113 419 144 111 420 149 114 421 148 113 422 151 116 423 152 117 424 150 115 425 149 114 426 151 116 427 150 115 428 151 116 429 153 118 430 152 117 431 154 119 432 155 120 433 153 118 434 151 116 435 154 119 436 153 118 437 154 119 438 156 121 439 155 120 440 157 122 441 158 123 442 156 121 443 159 31 444 138 31 445 160 31 446 161 124 447 157 122 448 156 121 449 162 125 450 161 124 451 156 121 452 163 126 453 162 125 454 156 121 455 164 127 456 163 126 457 156 121 458 165 128 459 164 127 460 156 121 461 166 129 462 165 128 463 156 121 464 167 130 465 166 129 466 156 121 467 168 131 468 167 130 469 156 121 470 169 132 471 168 131 472 156 121 473 170 133 474 169 132 475 156 121 476 171 134 477 170 133 478 156 121 479 172 135 480 171 134 481 156 121 482 173 136 483 172 135 484 156 121 485 154 119 486 173 136 487 156 121 488 159 137 489 128 137 490 138 137 491 174 138 492 175 139 493 158 123 494 176 31 495 160 31 496 177 31 497 178 140 498 174 138 499 158 123 500 179 141 501 178 140 502 158 123 503 180 142 504 179 141 505 158 123 506 181 143 507 180 142 508 158 123 509 182 144 510 181 143 511 158 123 512 183 145 513 182 144 514 158 123 515 184 146 516 183 145 517 158 123 518 185 147 519 184 146 520 158 123 521 186 148 522 185 147 523 158 123 524 187 149 525 186 148 526 158 123 527 188 150 528 187 149 529 158 123 530 189 151 531 188 150 532 158 123 533 190 152 534 189 151 535 158 123 536 157 122 537 190 152 538 158 123 539 176 31 540 159 31 541 160 31 542 191 153 543 192 154 544 175 139 545 193 155 546 177 155 547 194 155 548 195 156 549 191 153 550 175 139 551 196 157 552 195 156 553 175 139 554 197 158 555 196 157 556 175 139 557 198 159 558 197 158 559 175 139 560 199 160 561 198 159 562 175 139 563 200 161 564 199 160 565 175 139 566 201 162 567 200 161 568 175 139 569 202 163 570 201 162 571 175 139 572 203 164 573 202 163 574 175 139 575 204 165 576 203 164 577 175 139 578 205 166 579 204 165 580 175 139 581 206 167 582 205 166 583 175 139 584 174 138 585 206 167 586 175 139 587 193 31 588 176 31 589 177 31 590 207 168 591 208 169 592 192 154 593 193 31 594 194 31 595 209 31 596 210 170 597 207 168 598 192 154 599 211 171 600 210 170 601 192 154 602 212 172 603 211 171 604 192 154 605 213 173 606 212 172 607 192 154 608 214 174 609 213 173 610 192 154 611 215 175 612 214 174 613 192 154 614 216 176 615 215 175 616 192 154 617 217 177 618 216 176 619 192 154 620 191 153 621 217 177 622 192 154 623 218 178 624 219 179 625 208 169 626 220 180 627 209 180 628 221 180 629 222 181 630 218 178 631 208 169 632 223 182 633 222 181 634 208 169 635 224 183 636 223 182 637 208 169 638 225 184 639 224 183 640 208 169 641 207 168 642 225 184 643 208 169 644 220 185 645 193 185 646 209 185 647 226 186 648 227 187 649 219 179 650 220 31 651 221 31 652 228 31 653 218 178 654 226 186 655 219 179 656 226 186 657 229 188 658 227 187 659 230 31 660 228 31 661 231 31 662 230 31 663 220 31 664 228 31 665 232 189 666 233 190 667 229 188 668 230 31 669 231 31 670 234 31 671 226 186 672 232 189 673 229 188 674 232 189 675 235 191 676 233 190 677 236 31 678 234 31 679 237 31 680 236 31 681 230 31 682 234 31 683 238 192 684 239 193 685 235 191 686 236 31 687 237 31 688 240 31 689 232 189 690 238 192 691 235 191 692 241 194 693 242 195 694 239 193 695 243 31 696 240 31 697 244 31 698 238 192 699 241 194 700 239 193 701 243 31 702 236 31 703 240 31 704 241 194 705 245 196 706 242 195 707 243 197 708 244 197 709 246 197 710 247 198 711 248 199 712 245 196 713 249 31 714 246 31 715 250 31 716 241 194 717 247 198 718 245 196 719 249 200 720 243 200 721 246 200 722 247 198 723 251 201 724 248 199 725 249 31 726 250 31 727 252 31 728 253 202 729 254 203 730 251 201 731 255 31 732 252 31 733 256 31 734 257 204 735 253 202 736 251 201 737 258 205 738 257 204 739 251 201 740 259 206 741 258 205 742 251 201 743 260 207 744 259 206 745 251 201 746 261 208 747 260 207 748 251 201 749 262 209 750 261 208 751 251 201 752 263 210 753 262 209 754 251 201 755 264 211 756 263 210 757 251 201 758 265 212 759 264 211 760 251 201 761 266 213 762 265 212 763 251 201 764 267 214 765 266 213 766 251 201 767 268 215 768 267 214 769 251 201 770 269 216 771 268 215 772 251 201 773 247 198 774 269 216 775 251 201 776 255 31 777 249 31 778 252 31 779 270 217 780 271 218 781 254 203 782 255 219 783 256 219 784 272 219 785 273 220 786 270 217 787 254 203 788 274 221 789 273 220 790 254 203 791 275 222 792 274 221 793 254 203 794 276 223 795 275 222 796 254 203 797 277 224 798 276 223 799 254 203 800 278 225 801 277 224 802 254 203 803 279 226 804 278 225 805 254 203 806 280 227 807 279 226 808 254 203 809 281 228 810 280 227 811 254 203 812 282 229 813 281 228 814 254 203 815 283 230 816 282 229 817 254 203 818 284 231 819 283 230 820 254 203 821 285 232 822 284 231 823 254 203 824 253 202 825 285 232 826 254 203 827 286 233 828 287 234 829 288 235 830 289 236 831 290 237 832 287 234 833 291 238 834 287 234 835 290 237 836 292 239 837 289 236 838 287 234 839 293 240 840 292 239 841 287 234 842 294 241 843 293 240 844 287 234 845 295 242 846 294 241 847 287 234 848 296 243 849 295 242 850 287 234 851 297 244 852 296 243 853 287 234 854 298 245 855 297 244 856 287 234 857 299 246 858 298 245 859 287 234 860 300 247 861 299 246 862 287 234 863 301 248 864 300 247 865 287 234 866 286 233 867 301 248 868 287 234 869 302 31 870 272 31 871 303 31 872 302 31 873 255 31 874 272 31 875 304 249 876 305 250 877 306 251 878 307 252 879 308 253 880 309 254 881 307 252 882 309 254 883 310 255 884 304 249 885 306 251 886 311 256 887 304 249 888 311 256 889 312 257 890 304 249 891 312 257 892 313 258 893 314 259 894 313 258 895 315 260 896 314 259 897 304 249 898 313 258 899 314 259 900 315 260 901 316 261 902 314 259 903 316 261 904 317 262 905 314 259 906 317 262 907 318 263 908 319 264 909 318 263 910 320 265 911 319 264 912 314 259 913 318 263 914 319 264 915 320 265 916 321 266 917 319 264 918 321 266 919 322 267 920 319 264 921 322 267 922 323 268 923 324 269 924 323 268 925 325 270 926 324 269 927 319 264 928 323 268 929 324 269 930 325 270 931 326 271 932 324 269 933 326 271 934 327 272 935 324 269 936 327 272 937 328 273 938 329 274 939 328 273 940 330 275 941 329 274 942 324 269 943 328 273 944 329 274 945 330 275 946 331 276 947 329 274 948 331 276 949 332 277 950 333 278 951 332 277 952 334 279 953 333 278 954 329 274 955 332 277 956 333 278 957 334 279 958 335 280 959 336 281 960 335 280 961 337 282 962 336 281 963 333 278 964 335 280 965 336 281 966 337 282 967 338 283 968 339 284 969 338 283 970 340 285 971 339 284 972 336 281 973 338 283 974 339 284 975 340 285 976 341 286 977 342 287 978 341 286 979 343 288 980 342 287 981 339 284 982 341 286 983 344 289 984 343 288 985 345 290 986 344 289 987 342 287 988 343 288 989 247 198 990 346 291 991 269 216 992 347 292 993 345 290 994 348 293 995 347 292 996 344 289 997 345 290 998 247 198 999 349 294 1000 346 291 1001 350 295 1002 348 293 1003 351 296 1004 350 295 1005 347 292 1006 348 293 1007 247 198 1008 352 297 1009 349 294 1010 353 298 1011 351 296 1012 354 299 1013 353 298 1014 350 295 1015 351 296 1016 355 300 1017 356 301 1018 357 302 1019 355 300 1020 358 303 1021 356 301 1022 359 304 1023 354 299 1024 360 305 1025 359 304 1026 353 298 1027 354 299 1028 361 306 1029 357 302 1030 362 307 1031 361 306 1032 355 300 1033 357 302 1034 363 308 1035 362 307 1036 364 309 1037 363 308 1038 361 306 1039 362 307 1040 363 308 1041 364 309 1042 365 310 1043 366 311 1044 365 310 1045 367 312 1046 366 311 1047 363 308 1048 365 310 1049 368 313 1050 367 312 1051 369 314 1052 368 313 1053 366 311 1054 367 312 1055 370 315 1056 371 316 1057 218 178 1058 372 317 1059 369 314 1060 373 318 1061 374 319 1062 370 315 1063 218 178 1064 375 320 1065 374 319 1066 218 178 1067 222 181 1068 375 320 1069 218 178 1070 372 317 1071 368 313 1072 369 314 1073 376 321 1074 377 322 1075 378 323 1076 379 324 1077 372 317 1078 373 318 1079 380 325 1080 381 326 1081 377 322 1082 376 321 1083 380 325 1084 377 322 1085 382 327 1086 378 323 1087 383 328 1088 382 327 1089 376 321 1090 378 323 1091 384 329 1092 383 328 1093 385 330 1094 384 329 1095 382 327 1096 383 328 1097 386 331 1098 385 330 1099 387 332 1100 386 331 1101 384 329 1102 385 330 1103 388 333 1104 387 332 1105 389 334 1106 388 333 1107 386 331 1108 387 332 1109 388 333 1110 389 334 1111 390 335 1112 391 336 1113 390 335 1114 392 337 1115 391 336 1116 388 333 1117 390 335 1118 391 336 1119 392 337 1120 393 338 1121 394 339 1122 393 338 1123 395 340 1124 394 339 1125 391 336 1126 393 338 1127 394 339 1128 395 340 1129 396 341 1130 397 342 1131 396 341 1132 398 343 1133 397 342 1134 394 339 1135 396 341 1136 397 342 1137 398 343 1138 399 344 1139 397 342 1140 399 344 1141 400 345 1142 401 346 1143 400 345 1144 402 347 1145 401 346 1146 397 342 1147 400 345 1148 401 346 1149 402 347 1150 403 348 1151 401 346 1152 403 348 1153 404 349 1154 401 346 1155 404 349 1156 405 350 1157 406 351 1158 405 350 1159 407 352 1160 406 351 1161 401 346 1162 405 350 1163 406 351 1164 407 352 1165 408 353 1166 406 351 1167 408 353 1168 409 354 1169 406 351 1170 409 354 1171 410 355 1172 411 356 1173 410 355 1174 412 357 1175 411 356 1176 406 351 1177 410 355 1178 411 356 1179 412 357 1180 413 358 1181 411 356 1182 413 358 1183 414 359 1184 411 356 1185 414 359 1186 415 360 1187 416 361 1188 415 360 1189 417 362 1190 416 361 1191 411 356 1192 415 360 1193 416 361 1194 417 362 1195 418 363 1196 416 361 1197 418 363 1198 419 364 1199 416 361 1200 419 364 1201 420 365 1202 416 361 1203 420 365 1204 421 366 1205 422 367 1206 423 368 1207 424 369 1208 416 361 1209 421 366 1210 425 370 1211 422 367 1212 424 369 1213 426 371 1214 422 367 1215 426 371 1216 427 372 1217 422 367 1218 427 372 1219 428 373 1220 429 374 1221 428 373 1222 430 375 1223 429 374 1224 422 367 1225 428 373 1226 429 374 1227 430 375 1228 431 376 1229 429 374 1230 431 376 1231 432 377 1232 429 374 1233 432 377 1234 433 378 1235 434 379 1236 433 378 1237 435 380 1238 434 379 1239 429 374 1240 433 378 1241 434 379 1242 435 380 1243 436 381 1244 434 379 1245 436 381 1246 437 382 1247 434 379 1248 437 382 1249 438 383 1250 439 384 1251 438 383 1252 440 385 1253 439 384 1254 434 379 1255 438 383 1256 439 384 1257 440 385 1258 441 386 1259 439 384 1260 441 386 1261 442 387 1262 439 384 1263 442 387 1264 443 388 1265 444 389 1266 443 388 1267 445 390 1268 444 389 1269 439 384 1270 443 388 1271 444 389 1272 445 390 1273 446 391 1274 444 389 1275 446 391 1276 447 392 1277 448 393 1278 447 392 1279 449 394 1280 448 393 1281 444 389 1282 447 392 1283 448 393 1284 449 394 1285 450 395 1286 451 396 1287 450 395 1288 452 397 1289 451 396 1290 448 393 1291 450 395 1292 451 396 1293 452 397 1294 453 398 1295 454 399 1296 453 398 1297 455 400 1298 454 399 1299 451 396 1300 453 398 1301 454 399 1302 455 400 1303 456 401 1304 457 402 1305 456 401 1306 458 403 1307 457 402 1308 454 399 1309 456 401 1310 459 404 1311 458 403 1312 460 405 1313 459 404 1314 457 402 1315 458 403 1316 154 119 1317 461 406 1318 173 136 1319 462 407 1320 460 405 1321 463 408 1322 462 407 1323 459 404 1324 460 405 1325 154 119 1326 464 409 1327 461 406 1328 465 410 1329 463 408 1330 466 411 1331 465 410 1332 462 407 1333 463 408 1334 154 119 1335 467 412 1336 464 409 1337 468 413 1338 466 411 1339 469 414 1340 468 413 1341 465 410 1342 466 411 1343 470 415 1344 471 416 1345 472 417 1346 470 415 1347 473 418 1348 471 416 1349 474 419 1350 469 414 1351 475 420 1352 474 419 1353 468 413 1354 469 414 1355 476 421 1356 472 417 1357 477 422 1358 476 421 1359 470 415 1360 472 417 1361 478 423 1362 477 422 1363 479 424 1364 478 423 1365 476 421 1366 477 422 1367 478 423 1368 479 424 1369 480 425 1370 481 426 1371 480 425 1372 482 427 1373 481 426 1374 478 423 1375 480 425 1376 483 428 1377 482 427 1378 484 429 1379 483 428 1380 481 426 1381 482 427 1382 485 430 1383 486 431 1384 126 99 1385 487 432 1386 484 429 1387 488 433 1388 489 434 1389 485 430 1390 126 99 1391 490 435 1392 489 434 1393 126 99 1394 130 102 1395 490 435 1396 126 99 1397 487 432 1398 483 428 1399 484 429 1400 491 436 1401 492 437 1402 493 438 1403 494 439 1404 487 432 1405 488 433 1406 495 440 1407 496 441 1408 492 437 1409 491 436 1410 495 440 1411 492 437 1412 497 442 1413 493 438 1414 498 443 1415 497 442 1416 491 436 1417 493 438 1418 499 444 1419 498 443 1420 500 445 1421 499 444 1422 497 442 1423 498 443 1424 501 446 1425 500 445 1426 502 447 1427 501 446 1428 499 444 1429 500 445 1430 503 448 1431 502 447 1432 504 449 1433 503 448 1434 501 446 1435 502 447 1436 503 448 1437 504 449 1438 505 450 1439 506 451 1440 505 450 1441 507 452 1442 506 451 1443 503 448 1444 505 450 1445 506 451 1446 507 452 1447 508 453 1448 509 454 1449 508 453 1450 510 455 1451 509 454 1452 506 451 1453 508 453 1454 509 454 1455 510 455 1456 511 456 1457 512 457 1458 511 456 1459 513 458 1460 512 457 1461 509 454 1462 511 456 1463 512 457 1464 513 458 1465 514 459 1466 512 457 1467 514 459 1468 515 460 1469 516 461 1470 515 460 1471 517 462 1472 516 461 1473 512 457 1474 515 460 1475 516 461 1476 517 462 1477 518 463 1478 516 461 1479 518 463 1480 519 464 1481 516 461 1482 519 464 1483 520 465 1484 521 466 1485 520 465 1486 522 467 1487 521 466 1488 516 461 1489 520 465 1490 521 466 1491 522 467 1492 523 468 1493 521 466 1494 523 468 1495 524 469 1496 521 466 1497 524 469 1498 525 470 1499 526 471 1500 525 470 1501 527 472 1502 526 471 1503 521 466 1504 525 470 1505 526 471 1506 527 472 1507 528 473 1508 526 471 1509 528 473 1510 529 474 1511 526 471 1512 529 474 1513 530 475 1514 531 476 1515 530 475 1516 532 477 1517 531 476 1518 526 471 1519 530 475 1520 531 476 1521 532 477 1522 533 478 1523 531 476 1524 533 478 1525 534 479 1526 531 476 1527 534 479 1528 535 480 1529 531 476 1530 535 480 1531 536 481 1532 537 482 1533 538 483 1534 539 484 1535 531 476 1536 536 481 1537 540 485 1538 537 482 1539 539 484 1540 541 486 1541 537 482 1542 541 486 1543 542 487 1544 537 482 1545 542 487 1546 543 488 1547 544 489 1548 543 488 1549 545 490 1550 544 489 1551 537 482 1552 543 488 1553 544 489 1554 545 490 1555 546 491 1556 544 489 1557 546 491 1558 547 492 1559 544 489 1560 547 492 1561 548 493 1562 549 494 1563 548 493 1564 550 495 1565 549 494 1566 544 489 1567 548 493 1568 549 494 1569 550 495 1570 551 496 1571 549 494 1572 551 496 1573 552 497 1574 549 494 1575 552 497 1576 553 498 1577 554 499 1578 553 498 1579 555 500 1580 554 499 1581 549 494 1582 553 498 1583 554 499 1584 555 500 1585 556 501 1586 554 499 1587 556 501 1588 557 502 1589 554 499 1590 557 502 1591 558 503 1592 559 504 1593 558 503 1594 560 505 1595 559 504 1596 554 499 1597 558 503 1598 559 504 1599 560 505 1600 561 506 1601 559 504 1602 561 506 1603 562 507 1604 563 508 1605 562 507 1606 564 509 1607 563 508 1608 559 504 1609 562 507 1610 563 508 1611 564 509 1612 565 510 1613 566 511 1614 565 510 1615 567 512 1616 566 511 1617 563 508 1618 565 510 1619 566 511 1620 567 512 1621 568 513 1622 569 514 1623 568 513 1624 570 515 1625 569 514 1626 566 511 1627 568 513 1628 569 514 1629 570 515 1630 571 516 1631 572 517 1632 571 516 1633 573 518 1634 572 517 1635 569 514 1636 571 516 1637 574 519 1638 573 518 1639 575 520 1640 574 519 1641 572 517 1642 573 518 1643 61 39 1644 576 521 1645 80 57 1646 577 522 1647 575 520 1648 578 523 1649 577 522 1650 574 519 1651 575 520 1652 61 39 1653 579 524 1654 576 521 1655 580 525 1656 578 523 1657 581 526 1658 580 525 1659 577 522 1660 578 523 1661 61 39 1662 582 527 1663 579 524 1664 583 528 1665 581 526 1666 584 529 1667 583 528 1668 580 525 1669 581 526 1670 585 530 1671 586 531 1672 587 532 1673 588 533 1674 584 529 1675 589 534 1676 588 533 1677 583 528 1678 584 529 1679 590 535 1680 587 532 1681 591 536 1682 592 537 1683 585 530 1684 587 532 1685 590 535 1686 592 537 1687 587 532 1688 13 11 1689 593 11 1690 14 11 1691 594 11 1692 595 538 1693 591 536 1694 590 535 1695 591 536 1696 595 538 1697 596 539 1698 597 540 1699 598 541 1700 599 542 1701 600 542 1702 601 542 1703 602 541 1704 596 539 1705 598 541 1706 603 543 1707 604 544 1708 605 544 1709 606 545 1710 607 545 1711 597 540 1712 599 542 1713 601 542 1714 608 542 1715 596 539 1716 606 545 1717 597 540 1718 609 546 1719 610 546 1720 607 545 1721 611 542 1722 608 542 1723 612 542 1724 606 545 1725 609 546 1726 607 545 1727 599 542 1728 608 542 1729 611 542 1730 613 547 1731 614 547 1732 610 546 1733 615 542 1734 612 542 1735 616 542 1736 609 546 1737 613 547 1738 610 546 1739 611 542 1740 612 542 1741 617 542 1742 615 542 1743 617 542 1744 612 542 1745 618 548 1746 619 548 1747 614 547 1748 620 542 1749 616 542 1750 621 542 1751 613 547 1752 618 548 1753 614 547 1754 622 542 1755 615 542 1756 616 542 1757 623 542 1758 622 542 1759 616 542 1760 624 542 1761 623 542 1762 616 542 1763 625 542 1764 624 542 1765 616 542 1766 620 542 1767 625 542 1768 616 542 1769 626 549 1770 627 549 1771 619 548 1772 628 542 1773 621 542 1774 629 542 1775 618 548 1776 626 549 1777 619 548 1778 630 542 1779 620 542 1780 621 542 1781 631 542 1782 630 542 1783 621 542 1784 632 542 1785 631 542 1786 621 542 1787 633 542 1788 632 542 1789 621 542 1790 628 542 1791 633 542 1792 621 542 1793 634 550 1794 635 550 1795 627 549 1796 636 542 1797 629 542 1798 637 542 1799 626 549 1800 634 550 1801 627 549 1802 638 542 1803 628 542 1804 629 542 1805 639 542 1806 638 542 1807 629 542 1808 640 542 1809 639 542 1810 629 542 1811 641 542 1812 640 542 1813 629 542 1814 642 542 1815 641 542 1816 629 542 1817 636 542 1818 642 542 1819 629 542 1820 643 551 1821 644 551 1822 635 550 1823 645 542 1824 637 542 1825 646 542 1826 634 550 1827 643 551 1828 635 550 1829 647 542 1830 636 542 1831 637 542 1832 648 542 1833 647 542 1834 637 542 1835 645 542 1836 648 542 1837 637 542 1838 649 552 1839 650 552 1840 644 551 1841 651 542 1842 646 542 1843 652 542 1844 643 551 1845 649 552 1846 644 551 1847 651 542 1848 653 542 1849 646 542 1850 654 542 1851 646 542 1852 653 542 1853 655 542 1854 645 542 1855 646 542 1856 654 542 1857 655 542 1858 646 542 1859 656 553 1860 657 553 1861 650 552 1862 658 542 1863 652 542 1864 659 542 1865 649 552 1866 656 553 1867 650 552 1868 660 542 1869 661 542 1870 652 542 1871 662 542 1872 652 542 1873 661 542 1874 663 542 1875 660 542 1876 652 542 1877 664 542 1878 663 542 1879 652 542 1880 665 542 1881 664 542 1882 652 542 1883 666 542 1884 665 542 1885 652 542 1886 667 542 1887 666 542 1888 652 542 1889 658 542 1890 667 542 1891 652 542 1892 662 542 1893 651 542 1894 652 542 1895 668 554 1896 669 554 1897 657 553 1898 670 542 1899 659 542 1900 671 542 1901 656 553 1902 668 554 1903 657 553 1904 672 542 1905 658 542 1906 659 542 1907 673 542 1908 672 542 1909 659 542 1910 674 542 1911 673 542 1912 659 542 1913 675 542 1914 674 542 1915 659 542 1916 670 542 1917 675 542 1918 659 542 1919 676 555 1920 677 555 1921 669 554 1922 678 542 1923 671 542 1924 679 542 1925 668 554 1926 676 555 1927 669 554 1928 680 542 1929 670 542 1930 671 542 1931 681 542 1932 680 542 1933 671 542 1934 682 542 1935 681 542 1936 671 542 1937 683 542 1938 682 542 1939 671 542 1940 684 542 1941 683 542 1942 671 542 1943 685 542 1944 684 542 1945 671 542 1946 686 542 1947 685 542 1948 671 542 1949 687 542 1950 686 542 1951 671 542 1952 688 542 1953 687 542 1954 671 542 1955 678 542 1956 688 542 1957 671 542 1958 689 556 1959 690 557 1960 677 555 1961 691 542 1962 679 542 1963 692 542 1964 676 555 1965 689 556 1966 677 555 1967 693 542 1968 694 542 1969 679 542 1970 678 542 1971 679 542 1972 694 542 1973 695 542 1974 693 542 1975 679 542 1976 696 542 1977 695 542 1978 679 542 1979 691 542 1980 696 542 1981 679 542 1982 697 558 1983 698 558 1984 690 557 1985 699 542 1986 692 542 1987 700 542 1988 689 556 1989 697 558 1990 690 557 1991 701 542 1992 691 542 1993 692 542 1994 702 542 1995 701 542 1996 692 542 1997 703 542 1998 702 542 1999 692 542 2000 704 542 2001 703 542 2002 692 542 2003 705 542 2004 704 542 2005 692 542 2006 699 542 2007 705 542 2008 692 542 2009 706 559 2010 707 559 2011 698 558 2012 708 542 2013 700 542 2014 709 542 2015 697 558 2016 706 559 2017 698 558 2018 710 542 2019 699 542 2020 700 542 2021 708 542 2022 710 542 2023 700 542 2024 711 560 2025 712 560 2026 707 559 2027 713 542 2028 709 542 2029 714 542 2030 706 559 2031 711 560 2032 707 559 2033 715 542 2034 716 542 2035 709 542 2036 717 542 2037 709 542 2038 716 542 2039 713 542 2040 715 542 2041 709 542 2042 718 542 2043 708 542 2044 709 542 2045 717 542 2046 718 542 2047 709 542 2048 719 561 2049 720 561 2050 712 560 2051 721 542 2052 714 542 2053 722 542 2054 711 560 2055 719 561 2056 712 560 2057 723 542 2058 724 542 2059 714 542 2060 725 542 2061 714 542 2062 724 542 2063 726 542 2064 723 542 2065 714 542 2066 727 542 2067 726 542 2068 714 542 2069 728 542 2070 727 542 2071 714 542 2072 729 542 2073 713 542 2074 714 542 2075 730 542 2076 729 542 2077 714 542 2078 725 542 2079 730 542 2080 714 542 2081 721 542 2082 728 542 2083 714 542 2084 731 562 2085 732 562 2086 720 561 2087 733 542 2088 722 542 2089 734 542 2090 719 561 2091 731 562 2092 720 561 2093 735 542 2094 721 542 2095 722 542 2096 736 542 2097 735 542 2098 722 542 2099 737 542 2100 736 542 2101 722 542 2102 738 542 2103 737 542 2104 722 542 2105 739 542 2106 738 542 2107 722 542 2108 740 542 2109 739 542 2110 722 542 2111 741 542 2112 740 542 2113 722 542 2114 733 542 2115 741 542 2116 722 542 2117 742 563 2118 743 563 2119 732 562 2120 744 542 2121 734 542 2122 745 542 2123 731 562 2124 742 563 2125 732 562 2126 746 542 2127 733 542 2128 734 542 2129 747 542 2130 746 542 2131 734 542 2132 748 542 2133 747 542 2134 734 542 2135 749 542 2136 748 542 2137 734 542 2138 744 542 2139 749 542 2140 734 542 2141 750 564 2142 751 564 2143 743 563 2144 752 542 2145 745 542 2146 753 542 2147 742 563 2148 750 564 2149 743 563 2150 754 542 2151 744 542 2152 745 542 2153 755 542 2154 754 542 2155 745 542 2156 756 542 2157 755 542 2158 745 542 2159 757 542 2160 756 542 2161 745 542 2162 752 542 2163 757 542 2164 745 542 2165 758 565 2166 759 565 2167 751 564 2168 760 542 2169 753 542 2170 761 542 2171 750 564 2172 758 565 2173 751 564 2174 762 542 2175 753 542 2176 760 542 2177 763 542 2178 753 542 2179 762 542 2180 764 542 2181 752 542 2182 753 542 2183 765 542 2184 764 542 2185 753 542 2186 766 542 2187 765 542 2188 753 542 2189 763 542 2190 766 542 2191 753 542 2192 767 566 2193 768 566 2194 759 565 2195 769 542 2196 761 542 2197 770 542 2198 758 565 2199 767 566 2200 759 565 2201 760 542 2202 761 542 2203 769 542 2204 771 567 2205 772 567 2206 768 566 2207 773 542 2208 770 542 2209 774 542 2210 767 566 2211 771 567 2212 768 566 2213 769 542 2214 770 542 2215 773 542 2216 775 568 2217 776 568 2218 772 567 2219 777 542 2220 774 542 2221 778 542 2222 771 567 2223 775 568 2224 772 567 2225 773 542 2226 774 542 2227 777 542 2228 779 569 2229 780 570 2230 781 570 2231 779 569 2232 782 571 2233 780 570 2234 783 572 2235 784 573 2236 785 574 2237 786 575 2238 787 576 2239 788 577 2240 786 575 2241 788 577 2242 789 578 2243 790 579 2244 785 574 2245 791 580 2246 792 581 2247 785 574 2248 790 579 2249 793 582 2250 785 574 2251 792 581 2252 783 572 2253 785 574 2254 793 582 2255 794 583 2256 791 580 2257 795 584 2258 790 579 2259 791 580 2260 794 583 2261 796 585 2262 795 584 2263 797 586 2264 794 583 2265 795 584 2266 796 585 2267 798 587 2268 797 586 2269 799 588 2270 796 585 2271 797 586 2272 798 587 2273 800 589 2274 799 588 2275 801 590 2276 798 587 2277 799 588 2278 800 589 2279 802 591 2280 801 590 2281 803 592 2282 800 589 2283 801 590 2284 802 591 2285 804 593 2286 803 592 2287 805 594 2288 802 591 2289 803 592 2290 804 593 2291 806 595 2292 805 594 2293 807 596 2294 804 593 2295 805 594 2296 806 595 2297 808 597 2298 807 596 2299 809 598 2300 806 595 2301 807 596 2302 808 597 2303 810 599 2304 809 598 2305 811 600 2306 808 597 2307 809 598 2308 810 599 2309 812 601 2310 811 600 2311 813 602 2312 810 599 2313 811 600 2314 812 601 2315 814 603 2316 813 602 2317 815 604 2318 812 601 2319 813 602 2320 814 603 2321 816 605 2322 815 604 2323 817 606 2324 814 603 2325 815 604 2326 816 605 2327 818 607 2328 817 606 2329 819 608 2330 816 605 2331 817 606 2332 818 607 2333 820 609 2334 819 608 2335 821 610 2336 818 607 2337 819 608 2338 820 609 2339 822 611 2340 821 610 2341 823 612 2342 820 609 2343 821 610 2344 822 611 2345 824 613 2346 823 612 2347 825 614 2348 822 611 2349 823 612 2350 824 613 2351 826 615 2352 825 614 2353 827 616 2354 824 613 2355 825 614 2356 826 615 2357 828 617 2358 827 616 2359 829 618 2360 826 615 2361 827 616 2362 828 617 2363 830 619 2364 829 618 2365 831 620 2366 828 617 2367 829 618 2368 830 619 2369 832 621 2370 831 620 2371 833 622 2372 830 619 2373 831 620 2374 832 621 2375 834 623 2376 833 622 2377 835 624 2378 832 621 2379 833 622 2380 834 623 2381 836 625 2382 835 624 2383 837 626 2384 834 623 2385 835 624 2386 836 625 2387 838 543 2388 604 544 2389 603 543 2390 839 627 2391 840 628 2392 841 629 2393 842 630 2394 836 625 2395 837 626 2396 843 631 2397 844 632 2398 845 633 2399 846 634 2400 847 635 2401 848 636 2402 849 637 2403 843 631 2404 845 633 2405 850 638 2406 849 637 2407 845 633 2408 851 11 2409 852 11 2410 853 11 2411 854 11 2412 855 11 2413 853 11 2414 856 639 2415 853 639 2416 855 639 2417 857 11 2418 851 11 2419 853 11 2420 858 11 2421 857 11 2422 853 11 2423 859 11 2424 858 11 2425 853 11 2426 860 11 2427 859 11 2428 853 11 2429 856 11 2430 860 11 2431 853 11 2432 861 640 2433 862 641 2434 844 632 2435 863 642 2436 848 636 2437 864 643 2438 865 644 2439 861 640 2440 844 632 2441 866 645 2442 865 644 2443 844 632 2444 867 646 2445 866 645 2446 844 632 2447 868 647 2448 867 646 2449 844 632 2450 843 631 2451 868 647 2452 844 632 2453 869 648 2454 848 636 2455 863 642 2456 869 648 2457 846 634 2458 848 636 2459 870 649 2460 871 650 2461 872 651 2462 873 652 2463 863 642 2464 864 643 2465 874 653 2466 875 654 2467 871 650 2468 870 649 2469 874 653 2470 871 650 2471 876 655 2472 872 651 2473 877 656 2474 876 655 2475 870 649 2476 872 651 2477 878 657 2478 877 656 2479 879 658 2480 878 657 2481 876 655 2482 877 656 2483 880 659 2484 879 658 2485 881 660 2486 880 659 2487 878 657 2488 879 658 2489 868 647 2490 882 661 2491 867 646 2492 883 662 2493 881 660 2494 884 663 2495 883 662 2496 880 659 2497 881 660 2498 868 647 2499 885 664 2500 882 661 2501 883 662 2502 884 663 2503 886 665 2504 868 647 2505 887 666 2506 885 664 2507 888 667 2508 886 665 2509 889 668 2510 888 667 2511 883 662 2512 886 665 2513 868 647 2514 890 669 2515 887 666 2516 888 667 2517 889 668 2518 891 670 2519 892 671 2520 893 672 2521 890 669 2522 894 673 2523 891 670 2524 895 674 2525 868 647 2526 892 671 2527 890 669 2528 894 673 2529 888 667 2530 891 670 2531 892 671 2532 896 675 2533 893 672 2534 894 673 2535 895 674 2536 897 676 2537 892 671 2538 898 677 2539 896 675 2540 899 678 2541 897 676 2542 900 679 2543 899 678 2544 894 673 2545 897 676 2546 892 671 2547 901 680 2548 898 677 2549 899 678 2550 900 679 2551 902 681 2552 892 671 2553 903 682 2554 901 680 2555 899 678 2556 902 681 2557 904 683 2558 892 671 2559 905 684 2560 903 682 2561 906 685 2562 904 683 2563 907 686 2564 906 685 2565 899 678 2566 904 683 2567 892 671 2568 908 687 2569 905 684 2570 906 685 2571 907 686 2572 909 688 2573 892 671 2574 910 689 2575 908 687 2576 906 685 2577 909 688 2578 911 690 2579 892 691 2580 912 691 2581 910 691 2582 906 685 2583 911 690 2584 913 692 2585 914 693 2586 915 694 2587 912 695 2588 916 696 2589 913 692 2590 917 697 2591 892 671 2592 914 693 2593 912 695 2594 916 696 2595 906 685 2596 913 692 2597 914 693 2598 918 698 2599 915 694 2600 916 696 2601 917 697 2602 919 699 2603 914 693 2604 920 700 2605 918 698 2606 916 696 2607 919 699 2608 921 701 2609 914 693 2610 922 702 2611 920 700 2612 916 696 2613 921 701 2614 923 703 2615 914 693 2616 924 704 2617 922 702 2618 925 705 2619 923 703 2620 926 706 2621 925 705 2622 916 696 2623 923 703 2624 914 693 2625 927 707 2626 924 704 2627 925 705 2628 926 706 2629 928 708 2630 914 693 2631 929 709 2632 927 707 2633 925 705 2634 928 708 2635 930 710 2636 914 693 2637 931 711 2638 929 709 2639 925 705 2640 930 710 2641 932 712 2642 914 693 2643 933 713 2644 931 711 2645 934 714 2646 932 712 2647 935 715 2648 934 714 2649 925 705 2650 932 712 2651 914 693 2652 936 716 2653 933 713 2654 934 714 2655 935 715 2656 937 717 2657 914 693 2658 938 718 2659 936 716 2660 934 714 2661 937 717 2662 939 719 2663 914 693 2664 940 720 2665 938 718 2666 934 714 2667 939 719 2668 941 721 2669 914 693 2670 942 722 2671 940 720 2672 934 714 2673 941 721 2674 943 723 2675 944 724 2676 945 725 2677 942 722 2678 946 726 2679 947 727 2680 948 728 2681 914 693 2682 944 724 2683 942 722 2684 934 714 2685 943 723 2686 949 729 2687 944 724 2688 950 730 2689 945 725 2690 946 726 2691 948 728 2692 951 731 2693 944 724 2694 952 732 2695 950 730 2696 946 726 2697 951 731 2698 953 733 2699 944 724 2700 954 734 2701 952 732 2702 946 726 2703 953 733 2704 955 735 2705 944 724 2706 956 736 2707 954 734 2708 957 737 2709 955 735 2710 958 738 2711 957 737 2712 946 726 2713 955 735 2714 944 724 2715 959 739 2716 956 736 2717 957 737 2718 958 738 2719 960 740 2720 944 724 2721 961 741 2722 959 739 2723 957 737 2724 960 740 2725 962 742 2726 944 724 2727 963 743 2728 961 741 2729 957 737 2730 962 742 2731 964 744 2732 944 724 2733 965 745 2734 963 743 2735 966 746 2736 964 744 2737 967 747 2738 966 746 2739 957 737 2740 964 744 2741 944 724 2742 968 748 2743 965 745 2744 966 746 2745 967 747 2746 969 749 2747 944 724 2748 970 750 2749 968 748 2750 966 746 2751 969 749 2752 971 751 2753 944 724 2754 972 752 2755 970 750 2756 966 746 2757 971 751 2758 973 753 2759 944 724 2760 974 754 2761 972 752 2762 975 755 2763 973 753 2764 976 756 2765 975 755 2766 966 746 2767 973 753 2768 944 757 2769 977 757 2770 974 757 2771 975 755 2772 976 756 2773 978 758 2774 979 759 2775 980 760 2776 977 761 2777 975 755 2778 978 758 2779 981 762 2780 944 724 2781 979 759 2782 977 761 2783 979 759 2784 982 763 2785 980 760 2786 975 755 2787 981 762 2788 983 764 2789 979 759 2790 984 765 2791 982 763 2792 985 766 2793 983 764 2794 986 767 2795 985 766 2796 975 755 2797 983 764 2798 979 759 2799 987 768 2800 984 765 2801 985 766 2802 986 767 2803 988 769 2804 979 759 2805 989 770 2806 987 768 2807 985 766 2808 988 769 2809 990 771 2810 979 759 2811 991 772 2812 989 770 2813 992 773 2814 990 771 2815 993 774 2816 992 773 2817 985 766 2818 990 771 2819 979 759 2820 994 775 2821 991 772 2822 992 773 2823 993 774 2824 995 776 2825 979 759 2826 996 777 2827 994 775 2828 997 778 2829 995 776 2830 998 779 2831 997 778 2832 992 773 2833 995 776 2834 979 759 2835 999 780 2836 996 777 2837 997 778 2838 998 779 2839 1000 781 2840 979 759 2841 1001 782 2842 999 780 2843 1002 783 2844 1000 781 2845 1003 784 2846 1002 783 2847 997 778 2848 1000 781 2849 979 759 2850 1004 785 2851 1001 782 2852 1002 783 2853 1003 784 2854 1005 786 2855 979 759 2856 1006 787 2857 1004 785 2858 1007 788 2859 1005 786 2860 1008 789 2861 1007 788 2862 1002 783 2863 1005 786 2864 979 759 2865 1009 790 2866 1006 787 2867 1010 791 2868 1008 789 2869 1011 792 2870 1010 791 2871 1007 788 2872 1008 789 2873 1012 793 2874 1013 794 2875 1009 790 2876 1014 795 2877 1011 792 2878 1015 796 2879 979 759 2880 1012 793 2881 1009 790 2882 1014 795 2883 1010 791 2884 1011 792 2885 1012 793 2886 1016 797 2887 1013 794 2888 1017 798 2889 1015 796 2890 1018 799 2891 1017 798 2892 1014 795 2893 1015 796 2894 1012 793 2895 1019 800 2896 1016 797 2897 1020 801 2898 1018 799 2899 1021 802 2900 1020 801 2901 1017 798 2902 1018 799 2903 1022 803 2904 1023 804 2905 1024 805 2906 1022 803 2907 1025 806 2908 1023 804 2909 1026 807 2910 1021 802 2911 1027 808 2912 1026 807 2913 1020 801 2914 1021 802 2915 1028 809 2916 1029 810 2917 1012 793 2918 1030 811 2919 1024 805 2920 1031 812 2921 1032 813 2922 1028 809 2923 1012 793 2924 979 759 2925 1032 813 2926 1012 793 2927 1030 811 2928 1022 803 2929 1024 805 2930 1033 814 2931 1034 815 2932 1029 810 2933 1035 816 2934 1031 812 2935 1036 817 2936 1037 818 2937 1033 814 2938 1029 810 2939 1028 809 2940 1037 818 2941 1029 810 2942 1035 816 2943 1030 811 2944 1031 812 2945 1038 819 2946 1039 820 2947 1034 815 2948 1035 816 2949 1036 817 2950 1040 821 2951 1033 814 2952 1038 819 2953 1034 815 2954 1041 822 2955 1042 823 2956 1039 820 2957 1043 824 2958 1040 821 2959 1044 825 2960 1045 826 2961 1041 822 2962 1039 820 2963 1038 819 2964 1045 826 2965 1039 820 2966 1043 824 2967 1035 816 2968 1040 821 2969 1046 827 2970 1047 828 2971 1042 823 2972 1048 829 2973 1044 825 2974 1049 830 2975 1050 831 2976 1046 827 2977 1042 823 2978 1041 822 2979 1050 831 2980 1042 823 2981 1048 829 2982 1043 824 2983 1044 825 2984 1051 832 2985 1052 833 2986 1047 828 2987 1053 834 2988 1049 830 2989 1054 835 2990 1055 836 2991 1051 832 2992 1047 828 2993 1056 837 2994 1055 836 2995 1047 828 2996 1057 838 2997 1056 837 2998 1047 828 2999 1058 839 3000 1057 838 3001 1047 828 3002 1046 827 3003 1058 839 3004 1047 828 3005 1053 834 3006 1048 829 3007 1049 830 3008 1059 840 3009 1060 841 3010 1061 842 3011 1062 843 3012 1053 834 3013 1054 835 3014 1063 844 3015 1064 845 3016 1060 841 3017 1059 840 3018 1063 844 3019 1060 841 3020 1065 846 3021 1061 842 3022 1066 847 3023 1065 846 3024 1059 840 3025 1061 842 3026 1067 848 3027 1066 847 3028 1068 849 3029 1067 848 3030 1065 846 3031 1066 847 3032 1069 850 3033 1068 849 3034 1070 851 3035 1069 850 3036 1067 848 3037 1068 849 3038 1058 839 3039 1071 852 3040 1057 838 3041 1072 853 3042 1070 851 3043 1073 854 3044 1072 853 3045 1069 850 3046 1070 851 3047 1058 839 3048 1074 855 3049 1071 852 3050 1072 853 3051 1073 854 3052 1075 856 3053 1058 839 3054 1076 857 3055 1074 855 3056 1077 858 3057 1075 856 3058 1078 859 3059 1077 858 3060 1072 853 3061 1075 856 3062 1058 839 3063 1079 860 3064 1076 857 3065 1077 858 3066 1078 859 3067 1080 861 3068 1081 862 3069 1082 863 3070 1079 860 3071 1083 864 3072 1080 861 3073 1084 865 3074 1058 839 3075 1081 862 3076 1079 860 3077 1083 864 3078 1077 858 3079 1080 861 3080 1081 862 3081 1085 866 3082 1082 863 3083 1083 864 3084 1084 865 3085 1086 867 3086 1081 862 3087 1087 868 3088 1085 866 3089 1088 869 3090 1086 867 3091 1089 870 3092 1088 869 3093 1083 864 3094 1086 867 3095 1081 862 3096 1090 871 3097 1087 868 3098 1088 869 3099 1089 870 3100 1091 872 3101 1081 862 3102 1092 873 3103 1090 871 3104 1088 869 3105 1091 872 3106 1093 874 3107 1081 862 3108 1094 875 3109 1092 873 3110 1095 876 3111 1093 874 3112 1096 877 3113 1095 876 3114 1088 869 3115 1093 874 3116 1081 862 3117 1097 878 3118 1094 875 3119 1095 876 3120 1096 877 3121 1098 879 3122 1081 862 3123 1099 880 3124 1097 878 3125 1095 876 3126 1098 879 3127 1100 881 3128 1081 882 3129 1101 882 3130 1099 882 3131 1095 876 3132 1100 881 3133 1102 883 3134 1103 884 3135 1104 885 3136 1101 886 3137 1105 887 3138 1102 883 3139 1106 888 3140 1081 862 3141 1103 884 3142 1101 886 3143 1105 887 3144 1095 876 3145 1102 883 3146 1103 884 3147 1107 889 3148 1104 885 3149 1105 887 3150 1106 888 3151 1108 890 3152 1103 884 3153 1109 891 3154 1107 889 3155 1105 887 3156 1108 890 3157 1110 892 3158 1103 884 3159 1111 893 3160 1109 891 3161 1105 887 3162 1110 892 3163 1112 894 3164 1103 884 3165 1113 895 3166 1111 893 3167 1114 896 3168 1112 894 3169 1115 897 3170 1114 896 3171 1105 887 3172 1112 894 3173 1103 884 3174 1116 898 3175 1113 895 3176 1114 896 3177 1115 897 3178 1117 899 3179 1103 884 3180 1118 900 3181 1116 898 3182 1114 896 3183 1117 899 3184 1119 901 3185 1103 884 3186 1120 902 3187 1118 900 3188 1114 896 3189 1119 901 3190 1121 903 3191 1103 884 3192 1122 904 3193 1120 902 3194 1123 905 3195 1121 903 3196 1124 906 3197 1123 905 3198 1114 896 3199 1121 903 3200 1103 884 3201 1125 907 3202 1122 904 3203 1123 905 3204 1124 906 3205 1126 908 3206 1103 884 3207 1127 909 3208 1125 907 3209 1123 905 3210 1126 908 3211 1128 910 3212 1103 884 3213 1129 911 3214 1127 909 3215 1123 905 3216 1128 910 3217 1130 912 3218 1103 884 3219 1131 913 3220 1129 911 3221 1123 905 3222 1130 912 3223 1132 914 3224 1133 915 3225 1134 916 3226 1131 913 3227 1135 917 3228 1136 918 3229 1137 919 3230 1103 884 3231 1133 915 3232 1131 913 3233 1123 905 3234 1132 914 3235 1138 920 3236 1133 915 3237 1139 921 3238 1134 916 3239 1135 917 3240 1137 919 3241 1140 922 3242 1133 915 3243 1141 923 3244 1139 921 3245 1135 917 3246 1140 922 3247 1142 924 3248 1133 915 3249 1143 925 3250 1141 923 3251 1135 917 3252 1142 924 3253 1144 926 3254 1133 915 3255 1145 927 3256 1143 925 3257 1146 928 3258 1144 926 3259 1147 929 3260 1146 928 3261 1135 917 3262 1144 926 3263 1133 915 3264 1148 930 3265 1145 927 3266 1146 928 3267 1147 929 3268 1149 931 3269 1133 915 3270 1150 932 3271 1148 930 3272 1146 928 3273 1149 931 3274 1151 933 3275 1133 915 3276 1152 934 3277 1150 932 3278 1146 928 3279 1151 933 3280 1153 935 3281 1133 915 3282 1154 936 3283 1152 934 3284 1155 937 3285 1153 935 3286 1156 938 3287 1155 937 3288 1146 928 3289 1153 935 3290 1133 915 3291 1157 939 3292 1154 936 3293 1155 937 3294 1156 938 3295 1158 940 3296 1133 915 3297 1159 941 3298 1157 939 3299 1155 937 3300 1158 940 3301 1160 942 3302 1133 915 3303 1161 943 3304 1159 941 3305 1155 937 3306 1160 942 3307 1162 944 3308 1133 915 3309 1163 945 3310 1161 943 3311 1164 946 3312 1162 944 3313 1165 947 3314 1164 946 3315 1155 937 3316 1162 944 3317 1133 948 3318 1166 948 3319 1163 948 3320 1164 946 3321 1165 947 3322 1167 949 3323 1168 950 3324 1169 951 3325 1166 952 3326 1164 946 3327 1167 949 3328 1170 953 3329 1133 915 3330 1168 950 3331 1166 952 3332 1168 950 3333 1171 954 3334 1169 951 3335 1164 946 3336 1170 953 3337 1172 955 3338 1168 950 3339 1173 956 3340 1171 954 3341 1174 957 3342 1172 955 3343 1175 958 3344 1174 957 3345 1164 946 3346 1172 955 3347 1168 950 3348 1176 959 3349 1173 956 3350 1174 957 3351 1175 958 3352 1177 960 3353 1168 950 3354 1178 961 3355 1176 959 3356 1174 957 3357 1177 960 3358 1179 962 3359 1168 950 3360 1180 963 3361 1178 961 3362 1181 964 3363 1179 962 3364 1182 965 3365 1181 964 3366 1174 957 3367 1179 962 3368 1168 950 3369 1183 966 3370 1180 963 3371 1181 964 3372 1182 965 3373 1184 967 3374 1168 950 3375 1185 968 3376 1183 966 3377 1186 969 3378 1184 967 3379 1187 970 3380 1186 969 3381 1181 964 3382 1184 967 3383 1168 950 3384 1188 971 3385 1185 968 3386 1186 969 3387 1187 970 3388 1189 972 3389 1168 950 3390 1190 973 3391 1188 971 3392 1191 974 3393 1189 972 3394 1192 975 3395 1191 974 3396 1186 969 3397 1189 972 3398 1168 950 3399 1193 976 3400 1190 973 3401 1191 974 3402 1192 975 3403 1194 977 3404 1168 950 3405 1195 978 3406 1193 976 3407 1196 979 3408 1194 977 3409 1197 980 3410 1196 979 3411 1191 974 3412 1194 977 3413 1168 950 3414 1198 981 3415 1195 978 3416 1199 982 3417 1197 980 3418 1200 983 3419 1199 982 3420 1196 979 3421 1197 980 3422 1201 984 3423 1202 985 3424 1198 981 3425 1203 986 3426 1200 983 3427 1204 987 3428 1168 950 3429 1201 984 3430 1198 981 3431 1203 986 3432 1199 982 3433 1200 983 3434 1201 984 3435 1205 988 3436 1202 985 3437 1206 989 3438 1204 987 3439 1207 990 3440 1206 989 3441 1203 986 3442 1204 987 3443 1201 984 3444 1208 991 3445 1205 988 3446 1209 992 3447 1207 990 3448 1210 993 3449 1209 992 3450 1206 989 3451 1207 990 3452 1211 994 3453 1212 995 3454 1213 996 3455 1211 994 3456 1214 997 3457 1212 995 3458 1215 998 3459 1210 993 3460 1216 999 3461 1215 998 3462 1209 992 3463 1210 993 3464 1217 1000 3465 1218 1001 3466 1201 984 3467 1219 1002 3468 1213 996 3469 1220 1003 3470 1221 1004 3471 1217 1000 3472 1201 984 3473 1168 950 3474 1221 1004 3475 1201 984 3476 1219 1002 3477 1211 994 3478 1213 996 3479 1222 1005 3480 1223 1006 3481 1218 1001 3482 1224 1007 3483 1220 1003 3484 1225 1008 3485 1226 1009 3486 1222 1005 3487 1218 1001 3488 1217 1000 3489 1226 1009 3490 1218 1001 3491 1224 1007 3492 1219 1002 3493 1220 1003 3494 1227 1010 3495 1228 1011 3496 1223 1006 3497 1224 1007 3498 1225 1008 3499 1229 1012 3500 1222 1005 3501 1227 1010 3502 1223 1006 3503 1230 1013 3504 1231 1014 3505 1228 1011 3506 1232 1015 3507 1229 1012 3508 1233 1016 3509 1234 1017 3510 1230 1013 3511 1228 1011 3512 1227 1010 3513 1234 1017 3514 1228 1011 3515 1232 1015 3516 1224 1007 3517 1229 1012 3518 1235 1018 3519 1236 1019 3520 1231 1014 3521 1237 1020 3522 1233 1016 3523 1238 1021 3524 1239 1022 3525 1235 1018 3526 1231 1014 3527 1230 1013 3528 1239 1022 3529 1231 1014 3530 1237 1020 3531 1232 1015 3532 1233 1016 3533 1240 1023 3534 1241 1024 3535 1236 1019 3536 1242 1025 3537 1238 1021 3538 1243 1026 3539 1244 1027 3540 1240 1023 3541 1236 1019 3542 1245 1028 3543 1244 1027 3544 1236 1019 3545 1246 1029 3546 1245 1028 3547 1236 1019 3548 1247 1030 3549 1246 1029 3550 1236 1019 3551 1235 1018 3552 1247 1030 3553 1236 1019 3554 1242 1025 3555 1237 1020 3556 1238 1021 3557 1248 1031 3558 1249 1032 3559 1250 1033 3560 1251 1034 3561 1242 1025 3562 1243 1026 3563 1252 1035 3564 1253 1036 3565 1249 1032 3566 1248 1031 3567 1252 1035 3568 1249 1032 3569 1254 1037 3570 1250 1033 3571 1255 1038 3572 1254 1037 3573 1248 1031 3574 1250 1033 3575 1256 1039 3576 1255 1038 3577 1257 1040 3578 1256 1039 3579 1254 1037 3580 1255 1038 3581 1258 1041 3582 1257 1040 3583 1259 1042 3584 1258 1041 3585 1256 1039 3586 1257 1040 3587 1247 1030 3588 1260 1043 3589 1246 1029 3590 1261 1044 3591 1259 1042 3592 1262 1045 3593 1261 1044 3594 1258 1041 3595 1259 1042 3596 1247 1030 3597 1263 1046 3598 1260 1043 3599 1261 1044 3600 1262 1045 3601 1264 1047 3602 1247 1030 3603 1265 1048 3604 1263 1046 3605 1266 1049 3606 1264 1047 3607 1267 1050 3608 1266 1049 3609 1261 1044 3610 1264 1047 3611 1247 1030 3612 1268 1051 3613 1265 1048 3614 1266 1049 3615 1267 1050 3616 1269 1052 3617 291 238 3618 1270 1053 3619 1268 1051 3620 1271 1054 3621 1269 1052 3622 1272 1055 3623 1247 1030 3624 291 238 3625 1268 1051 3626 1271 1054 3627 1266 1049 3628 1269 1052 3629 291 238 3630 1273 1056 3631 1270 1053 3632 1271 1054 3633 1272 1055 3634 1274 1057 3635 291 238 3636 1275 1058 3637 1273 1056 3638 1276 1059 3639 1274 1057 3640 1277 1060 3641 1276 1059 3642 1271 1054 3643 1274 1057 3644 291 238 3645 1278 1061 3646 1275 1058 3647 1276 1059 3648 1277 1060 3649 1279 1062 3650 291 238 3651 1280 1063 3652 1278 1061 3653 1276 1059 3654 1279 1062 3655 1281 1064 3656 291 238 3657 1282 1065 3658 1280 1063 3659 1283 1066 3660 1281 1064 3661 1284 1067 3662 1283 1066 3663 1276 1059 3664 1281 1064 3665 291 238 3666 1285 1068 3667 1282 1065 3668 1283 1066 3669 1284 1067 3670 1286 1069 3671 291 238 3672 1287 1070 3673 1285 1068 3674 1283 1066 3675 1286 1069 3676 1288 1071 3677 291 1072 3678 290 1072 3679 1287 1072 3680 1283 1066 3681 1288 1071 3682 1289 1073 3683 1290 1074 3684 1289 1073 3685 1291 1075 3686 1290 1074 3687 1283 1066 3688 1289 1073 3689 1290 1074 3690 1291 1075 3691 1292 1076 3692 1290 1074 3693 1292 1076 3694 1293 1077 3695 1290 1074 3696 1293 1077 3697 1294 1078 3698 1295 1079 3699 1294 1078 3700 1296 1080 3701 1295 1079 3702 1290 1074 3703 1294 1078 3704 1295 1079 3705 1296 1080 3706 1297 1081 3707 1295 1079 3708 1297 1081 3709 1298 1082 3710 1295 1079 3711 1298 1082 3712 1299 1083 3713 307 252 3714 1299 1083 3715 1300 1084 3716 307 252 3717 1295 1079 3718 1299 1083 3719 307 252 3720 1300 1084 3721 1301 1085 3722 307 252 3723 1301 1085 3724 1302 1086 3725 307 252 3726 1302 1086 3727 308 253 3728 1303 31 3729 303 31 3730 1304 31 3731 1303 1087 3732 302 1087 3733 303 1087 3734 1303 31 3735 1304 31 3736 1305 31 3737 1306 31 3738 1305 31 3739 1307 31 3740 1306 31 3741 1303 31 3742 1305 31 3743 1306 31 3744 1307 31 3745 1308 31 3746 1309 31 3747 1308 31 3748 1310 31 3749 1309 31 3750 1306 31 3751 1308 31 3752 1309 31 3753 1310 31 3754 1311 31 3755 1312 31 3756 1311 31 3757 1313 31 3758 1312 31 3759 1309 31 3760 1311 31 3761 1312 31 3762 1313 31 3763 1314 31 3764 1315 31 3765 1314 31 3766 1316 31 3767 1315 1088 3768 1312 1088 3769 1314 1088 3770 1315 1089 3771 1316 1089 3772 1317 1089 3773 1318 180 3774 1317 180 3775 1319 180 3776 1318 1090 3777 1315 1090 3778 1317 1090 3779 1318 31 3780 1319 31 3781 1320 31 3782 1321 155 3783 1320 155 3784 1322 155 3785 1321 31 3786 1318 31 3787 1320 31 3788 1323 31 3789 1322 31 3790 1324 31 3791 1323 31 3792 1321 31 3793 1322 31 3794 1325 31 3795 1324 31 3796 1326 31 3797 1325 1091 3798 1323 1091 3799 1324 1091 3800 1327 1092 3801 1326 1092 3802 1328 1092 3803 1327 1093 3804 1325 1093 3805 1326 1093 3806 1329 31 3807 1328 31 3808 1330 31 3809 1331 31 3810 1328 31 3811 1329 31 3812 1327 1094 3813 1328 1094 3814 1331 1094 3815 1332 31 3816 1330 31 3817 1333 31 3818 1329 31 3819 1330 31 3820 1332 31 3821 1334 31 3822 1333 31 3823 1335 31 3824 1332 31 3825 1333 31 3826 1334 31 3827 1336 31 3828 1335 31 3829 1337 31 3830 1334 31 3831 1335 31 3832 1336 31 3833 1338 31 3834 1331 31 3835 1339 31 3836 1338 1095 3837 1327 1095 3838 1331 1095 3839 1340 31 3840 1339 31 3841 1341 31 3842 1340 31 3843 1338 31 3844 1339 31 3845 1342 60 3846 1341 60 3847 1343 60 3848 1342 31 3849 1340 31 3850 1341 31 3851 1342 31 3852 1343 31 3853 1344 31 3854 1345 41 3855 1344 41 3856 1346 41 3857 1345 1096 3858 1342 1096 3859 1344 1096 3860 1345 31 3861 1346 31 3862 1347 31 3863 850 638 3864 1348 1097 3865 849 637 3866 1349 31 3867 1347 31 3868 1350 31 3869 1349 31 3870 1345 31 3871 1347 31 3872 1351 1098 3873 1352 1099 3874 1348 1097 3875 1349 31 3876 1350 31 3877 1353 31 3878 850 638 3879 1351 1098 3880 1348 1097 3881 1354 1100 3882 1355 1101 3883 1352 1099 3884 1356 31 3885 1353 31 3886 1357 31 3887 1351 1098 3888 1354 1100 3889 1352 1099 3890 1356 31 3891 1349 31 3892 1353 31 3893 1354 1100 3894 1358 1102 3895 1355 1101 3896 1356 31 3897 1357 31 3898 1359 31 3899 1360 1103 3900 1361 1104 3901 1358 1102 3902 1362 31 3903 1359 31 3904 1363 31 3905 1354 1100 3906 1360 1103 3907 1358 1102 3908 1362 31 3909 1356 31 3910 1359 31 3911 1364 1105 3912 1365 1106 3913 1361 1104 3914 1362 1107 3915 1363 1107 3916 1366 1107 3917 1360 1103 3918 1364 1105 3919 1361 1104 3920 1364 1105 3921 1367 1108 3922 1365 1106 3923 1368 31 3924 1366 31 3925 1369 31 3926 1368 1109 3927 1362 1109 3928 1366 1109 3929 37 30 3930 1370 1110 3931 1367 1108 3932 1368 31 3933 1369 31 3934 1371 31 3935 1364 1105 3936 37 30 3937 1367 1108 3938 37 30 3939 34 27 3940 1370 1110 3941 41 31 3942 1371 31 3943 42 31 3944 41 31 3945 1368 31 3946 1371 31 3947 1372 11 3948 21 11 3949 852 11 3950 1373 11 3951 21 11 3952 1372 11 3953 1374 11 3954 21 11 3955 1373 11 3956 1375 11 3957 1376 11 3958 21 11 3959 1377 11 3960 21 11 3961 1376 11 3962 1374 11 3963 1375 11 3964 21 11 3965 1378 11 3966 21 11 3967 1377 11 3968 1379 11 3969 21 11 3970 1378 11 3971 1380 11 3972 21 11 3973 1379 11 3974 1381 11 3975 21 11 3976 1380 11 3977 20 11 3978 21 11 3979 1381 11 3980 1382 11 3981 1372 11 3982 852 11 3983 1383 11 3984 1382 11 3985 852 11 3986 1384 11 3987 1383 11 3988 852 11 3989 1385 1111 3990 1384 1111 3991 852 1111 3992 1386 11 3993 1385 11 3994 852 11 3995 1387 1112 3996 1386 1112 3997 852 1112 3998 1388 11 3999 1387 11 4000 852 11 4001 851 11 4002 1388 11 4003 852 11 4004 1389 1113 4005 1390 1113 4006 782 571 4007 779 569 4008 1389 1113 4009 782 571 4010 1391 1114 4011 1392 1114 4012 1390 1113 4013 1389 1113 4014 1391 1114 4015 1390 1113 4016 1393 1115 4017 1394 1115 4018 1392 1114 4019 1391 1114 4020 1393 1115 4021 1392 1114 4022 1395 1116 4023 1396 1116 4024 1394 1115 4025 1393 1115 4026 1395 1116 4027 1394 1115 4028 1397 1117 4029 1398 1117 4030 1396 1116 4031 1399 542 4032 762 542 4033 1400 542 4034 1395 1116 4035 1397 1117 4036 1396 1116 4037 1401 542 4038 763 542 4039 762 542 4040 1402 542 4041 1401 542 4042 762 542 4043 1399 542 4044 1402 542 4045 762 542 4046 1403 1118 4047 1404 1118 4048 1398 1117 4049 1405 542 4050 1400 542 4051 1406 542 4052 1397 1117 4053 1403 1118 4054 1398 1117 4055 1407 542 4056 1399 542 4057 1400 542 4058 1408 542 4059 1407 542 4060 1400 542 4061 1409 542 4062 1408 542 4063 1400 542 4064 1410 542 4065 1409 542 4066 1400 542 4067 1411 542 4068 1410 542 4069 1400 542 4070 1405 542 4071 1411 542 4072 1400 542 4073 1412 1119 4074 1413 1119 4075 1404 1118 4076 1414 542 4077 1406 542 4078 1415 542 4079 1403 1118 4080 1412 1119 4081 1404 1118 4082 1416 542 4083 1405 542 4084 1406 542 4085 1417 542 4086 1416 542 4087 1406 542 4088 1414 542 4089 1417 542 4090 1406 542 4091 1418 1120 4092 1419 1120 4093 1413 1119 4094 1420 542 4095 1415 542 4096 1421 542 4097 1412 1119 4098 1418 1120 4099 1413 1119 4100 1420 542 4101 1422 542 4102 1415 542 4103 1423 542 4104 1415 542 4105 1422 542 4106 1424 542 4107 1414 542 4108 1415 542 4109 1423 542 4110 1424 542 4111 1415 542 4112 1425 1121 4113 1426 1121 4114 1419 1120 4115 1427 542 4116 1421 542 4117 1428 542 4118 1418 1120 4119 1425 1121 4120 1419 1120 4121 1429 542 4122 1430 542 4123 1421 542 4124 1431 542 4125 1421 542 4126 1430 542 4127 1432 542 4128 1429 542 4129 1421 542 4130 1433 542 4131 1432 542 4132 1421 542 4133 1434 542 4134 1433 542 4135 1421 542 4136 1435 542 4137 1434 542 4138 1421 542 4139 1436 542 4140 1435 542 4141 1421 542 4142 1427 542 4143 1436 542 4144 1421 542 4145 1431 542 4146 1420 542 4147 1421 542 4148 1437 1122 4149 1438 1122 4150 1426 1121 4151 1439 542 4152 1428 542 4153 1440 542 4154 1425 1121 4155 1437 1122 4156 1426 1121 4157 1441 542 4158 1428 542 4159 1439 542 4160 1442 542 4161 1427 542 4162 1428 542 4163 1443 542 4164 1442 542 4165 1428 542 4166 1444 542 4167 1443 542 4168 1428 542 4169 1441 542 4170 1444 542 4171 1428 542 4172 1445 1123 4173 1446 1123 4174 1438 1122 4175 1447 542 4176 1440 542 4177 1448 542 4178 1437 1122 4179 1445 1123 4180 1438 1122 4181 1449 542 4182 1439 542 4183 1440 542 4184 1450 542 4185 1449 542 4186 1440 542 4187 1451 542 4188 1450 542 4189 1440 542 4190 1452 542 4191 1451 542 4192 1440 542 4193 1453 542 4194 1452 542 4195 1440 542 4196 1454 542 4197 1453 542 4198 1440 542 4199 1455 542 4200 1454 542 4201 1440 542 4202 1456 542 4203 1455 542 4204 1440 542 4205 1457 542 4206 1456 542 4207 1440 542 4208 1447 542 4209 1457 542 4210 1440 542 4211 1458 1124 4212 1459 1125 4213 1446 1123 4214 1460 542 4215 1448 542 4216 1461 542 4217 1445 1123 4218 1458 1124 4219 1446 1123 4220 1462 542 4221 1447 542 4222 1448 542 4223 1460 542 4224 1462 542 4225 1448 542 4226 1463 1126 4227 1464 1126 4228 1459 1125 4229 1465 542 4230 1461 542 4231 1466 542 4232 1458 1124 4233 1463 1126 4234 1459 1125 4235 1467 542 4236 1460 542 4237 1461 542 4238 1465 542 4239 1467 542 4240 1461 542 4241 1468 1127 4242 1469 1127 4243 1464 1126 4244 1470 542 4245 1466 542 4246 1471 542 4247 1463 1126 4248 1468 1127 4249 1464 1126 4250 1472 542 4251 1465 542 4252 1466 542 4253 1470 542 4254 1472 542 4255 1466 542 4256 1473 1128 4257 1474 1128 4258 1469 1127 4259 1475 542 4260 1471 542 4261 1476 542 4262 1468 1127 4263 1473 1128 4264 1469 1127 4265 1477 542 4266 1478 542 4267 1471 542 4268 1479 542 4269 1471 542 4270 1478 542 4271 1475 542 4272 1477 542 4273 1471 542 4274 1480 542 4275 1470 542 4276 1471 542 4277 1479 542 4278 1480 542 4279 1471 542 4280 1481 1129 4281 1482 1129 4282 1474 1128 4283 1483 542 4284 1476 542 4285 1484 542 4286 1473 1128 4287 1481 1129 4288 1474 1128 4289 1485 542 4290 1486 542 4291 1476 542 4292 1487 542 4293 1476 542 4294 1486 542 4295 1488 542 4296 1485 542 4297 1476 542 4298 1489 542 4299 1488 542 4300 1476 542 4301 1490 542 4302 1489 542 4303 1476 542 4304 1491 542 4305 1475 542 4306 1476 542 4307 1492 542 4308 1491 542 4309 1476 542 4310 1487 542 4311 1492 542 4312 1476 542 4313 1483 542 4314 1490 542 4315 1476 542 4316 1493 1130 4317 1494 1130 4318 1482 1129 4319 1495 542 4320 1484 542 4321 1496 542 4322 1481 1129 4323 1493 1130 4324 1482 1129 4325 1497 542 4326 1483 542 4327 1484 542 4328 1498 542 4329 1497 542 4330 1484 542 4331 1499 542 4332 1498 542 4333 1484 542 4334 1500 542 4335 1499 542 4336 1484 542 4337 1501 542 4338 1500 542 4339 1484 542 4340 1502 542 4341 1501 542 4342 1484 542 4343 1503 542 4344 1502 542 4345 1484 542 4346 1495 542 4347 1503 542 4348 1484 542 4349 1504 1131 4350 1505 1131 4351 1494 1130 4352 1506 542 4353 1496 542 4354 1507 542 4355 1493 1130 4356 1504 1131 4357 1494 1130 4358 1506 542 4359 1508 542 4360 1496 542 4361 1509 542 4362 1496 542 4363 1508 542 4364 1510 542 4365 1495 542 4366 1496 542 4367 1511 542 4368 1510 542 4369 1496 542 4370 1512 542 4371 1511 542 4372 1496 542 4373 1509 542 4374 1512 542 4375 1496 542 4376 1513 1132 4377 1514 1132 4378 1505 1131 4379 1515 542 4380 1507 542 4381 1516 542 4382 1504 1131 4383 1513 1132 4384 1505 1131 4385 1517 542 4386 1506 542 4387 1507 542 4388 1518 542 4389 1517 542 4390 1507 542 4391 1519 542 4392 1518 542 4393 1507 542 4394 1520 542 4395 1519 542 4396 1507 542 4397 1521 542 4398 1520 542 4399 1507 542 4400 1522 542 4401 1521 542 4402 1507 542 4403 1515 542 4404 1522 542 4405 1507 542 4406 1523 1133 4407 1524 1133 4408 1514 1132 4409 1525 542 4410 1516 542 4411 617 542 4412 1513 1132 4413 1523 1133 4414 1514 1132 4415 1526 542 4416 1527 542 4417 1516 542 4418 1528 542 4419 1516 542 4420 1527 542 4421 1529 542 4422 1526 542 4423 1516 542 4424 1530 542 4425 1529 542 4426 1516 542 4427 1531 542 4428 1530 542 4429 1516 542 4430 1525 542 4431 1531 542 4432 1516 542 4433 1528 542 4434 1515 542 4435 1516 542 4436 1532 1134 4437 1533 1134 4438 1524 1133 4439 1523 1133 4440 1532 1134 4441 1524 1133 4442 1534 542 4443 617 542 4444 615 542 4445 1535 542 4446 1525 542 4447 617 542 4448 1536 542 4449 1535 542 4450 617 542 4451 1534 542 4452 1536 542 4453 617 542 4454 838 543 4455 603 543 4456 1533 1134 4457 1532 1134 4458 838 543 4459 1533 1134 4460 1537 1135 4461 841 629 4462 1538 1136 4463 839 627 4464 841 629 4465 1539 1137 4466 1540 1138 4467 1539 1137 4468 841 629 4469 1540 1138 4470 841 629 4471 1537 1135 4472 1541 1139 4473 1538 1136 4474 1542 1140 4475 1537 1135 4476 1538 1136 4477 1541 1139 4478 1543 1141 4479 1542 1140 4480 1544 1142 4481 1541 1139 4482 1542 1140 4483 1543 1141 4484 1545 1143 4485 1544 1142 4486 1546 1144 4487 1543 1141 4488 1544 1142 4489 1545 1143 4490 1547 1145 4491 1546 1144 4492 1548 1146 4493 1545 1143 4494 1546 1144 4495 1547 1145 4496 1549 1147 4497 1548 1146 4498 1550 1148 4499 1547 1145 4500 1548 1146 4501 1549 1147 4502 1551 1149 4503 1550 1148 4504 1552 1150 4505 1549 1147 4506 1550 1148 4507 1551 1149 4508 1553 1151 4509 1552 1150 4510 1554 1152 4511 1551 1149 4512 1552 1150 4513 1553 1151 4514 1555 1153 4515 1554 1152 4516 1556 1154 4517 1553 1151 4518 1554 1152 4519 1555 1153 4520 1557 1155 4521 1556 1154 4522 1558 1156 4523 1555 1153 4524 1556 1154 4525 1557 1155 4526 1559 1157 4527 1558 1156 4528 1560 1158 4529 1557 1155 4530 1558 1156 4531 1559 1157 4532 1561 1159 4533 1560 1158 4534 1562 1160 4535 1559 1157 4536 1560 1158 4537 1561 1159 4538 1563 1161 4539 1562 1160 4540 1564 1162 4541 1561 1159 4542 1562 1160 4543 1563 1161 4544 1565 1163 4545 1564 1162 4546 1566 1164 4547 1563 1161 4548 1564 1162 4549 1565 1163 4550 1567 1165 4551 1566 1164 4552 1568 1166 4553 1565 1163 4554 1566 1164 4555 1567 1165 4556 1569 1167 4557 1568 1166 4558 1570 1168 4559 1567 1165 4560 1568 1166 4561 1569 1167 4562 1571 1169 4563 1570 1168 4564 1572 1170 4565 1569 1167 4566 1570 1168 4567 1571 1169 4568 1573 1171 4569 1572 1170 4570 1574 1172 4571 1571 1169 4572 1572 1170 4573 1573 1171 4574 1575 1173 4575 1574 1172 4576 1576 1174 4577 1573 1171 4578 1574 1172 4579 1575 1173 4580 1577 1175 4581 1576 1174 4582 1578 1176 4583 1575 1173 4584 1576 1174 4585 1577 1175 4586 1579 1177 4587 1578 1176 4588 1580 1178 4589 1577 1175 4590 1578 1176 4591 1579 1177 4592 1581 1179 4593 1580 1178 4594 787 576 4595 1579 1177 4596 1580 1178 4597 1581 1179 4598 1581 1179 4599 787 576 4600 786 575 4601 22 1180 4602 855 1180 4603 13 1180 4604 1582 1181 4605 590 535 4606 595 538 4607 1583 1182 4608 1584 1182 4609 1585 1182 4610 1586 11 4611 855 11 4612 854 11 4613 1587 11 4614 855 11 4615 1372 11 4616 1373 11 4617 1372 11 4618 855 11 4619 1588 11 4620 856 11 4621 855 11 4622 1589 1183 4623 1588 1183 4624 855 1183 4625 1590 11 4626 1589 11 4627 855 11 4628 1587 11 4629 1590 11 4630 855 11 4631 1591 11 4632 1373 11 4633 855 11 4634 1592 11 4635 1591 11 4636 855 11 4637 1593 11 4638 1592 11 4639 855 11 4640 1594 11 4641 1593 11 4642 855 11 4643 1595 11 4644 1594 11 4645 855 11 4646 1596 11 4647 1595 11 4648 855 11 4649 1597 11 4650 1596 11 4651 855 11 4652 1598 11 4653 1597 11 4654 855 11 4655 22 11 4656 1598 11 4657 855 11 4658 588 533 4659 589 534 4660 1599 1184 4661 1600 1185 4662 592 537 4663 590 535 4664 1600 1185 4665 1601 1186 4666 592 537 4667 1602 1187 4668 1599 1184 4669 1603 1188 4670 1602 1187 4671 588 533 4672 1599 1184 4673 1582 1181 4674 1604 1189 4675 590 535 4676 1605 1190 4677 590 535 4678 1604 1189 4679 1605 1190 4680 1600 1185 4681 590 535 4682 1606 1191 4683 1607 1192 4684 1604 1189 4685 1608 1193 4686 1604 1189 4687 1607 1192 4688 1582 1181 4689 1606 1191 4690 1604 1189 4691 1608 1193 4692 1605 1190 4693 1604 1189 4694 1583 1194 4695 1609 1194 4696 1610 1194 4697 1608 1193 4698 1607 1192 4699 1611 1195 4700 1583 1196 4701 1612 1196 4702 1609 1196 4703 1583 1197 4704 1610 1197 4705 1584 1197 4706 1613 1198 4707 1608 1193 4708 1611 1195 4709 1614 1199 4710 1613 1198 4711 1611 1195 4712 1583 1200 4713 1615 1200 4714 1612 1200 4715 1600 1185 4716 1616 1201 4717 1601 1186 4718 1617 1202 4719 1603 1188 4720 1618 1203 4721 1617 1202 4722 1602 1187 4723 1603 1188 4724 1600 1185 4725 1619 1204 4726 1616 1201 4727 1617 1202 4728 1618 1203 4729 1620 1205 4730 802 591 4731 1619 1204 4732 1600 1185 4733 804 593 4734 1621 1206 4735 1619 1204 4736 1622 1207 4737 1620 1205 4738 1623 1208 4739 802 591 4740 804 593 4741 1619 1204 4742 1622 1207 4743 1617 1202 4744 1620 1205 4745 800 589 4746 1600 1185 4747 1605 1190 4748 800 589 4749 802 591 4750 1600 1185 4751 798 587 4752 1605 1190 4753 1608 1193 4754 798 587 4755 800 589 4756 1605 1190 4757 796 585 4758 1608 1193 4759 1613 1198 4760 796 585 4761 798 587 4762 1608 1193 4763 1614 1199 4764 1624 1209 4765 1613 1198 4766 794 583 4767 1613 1198 4768 1624 1209 4769 794 583 4770 796 585 4771 1613 1198 4772 1625 1210 4773 1626 1211 4774 1624 1209 4775 790 579 4776 1624 1209 4777 1626 1211 4778 1614 1199 4779 1625 1210 4780 1624 1209 4781 790 579 4782 794 583 4783 1624 1209 4784 1583 1212 4785 1627 1212 4786 1628 1212 4787 792 581 4788 1626 1211 4789 1629 1213 4790 1583 1214 4791 1630 1214 4792 1627 1214 4793 792 581 4794 790 579 4795 1626 1211 4796 1583 1215 4797 1628 1215 4798 1615 1215 4799 1631 1216 4800 792 581 4801 1629 1213 4802 1583 1217 4803 1632 1217 4804 1630 1217 4805 804 593 4806 1633 1218 4807 1621 1206 4808 1634 1219 4809 1623 1208 4810 1635 1220 4811 1634 1219 4812 1622 1207 4813 1623 1208 4814 804 593 4815 1636 1221 4816 1633 1218 4817 1637 1222 4818 1635 1220 4819 1638 1223 4820 1637 1222 4821 1634 1219 4822 1635 1220 4823 806 595 4824 1639 1224 4825 1636 1221 4826 1640 1225 4827 1638 1223 4828 1641 1226 4829 804 593 4830 806 595 4831 1636 1221 4832 1640 1225 4833 1637 1222 4834 1638 1223 4835 806 595 4836 1642 1227 4837 1639 1224 4838 1643 1228 4839 1644 1229 4840 1645 1230 4841 1646 1231 4842 1640 1225 4843 1641 1226 4844 806 595 4845 1647 1232 4846 1642 1227 4847 1648 1233 4848 1645 1230 4849 1649 1234 4850 1650 1235 4851 1643 1228 4852 1645 1230 4853 1648 1233 4854 1650 1235 4855 1645 1230 4856 806 595 4857 1651 1236 4858 1647 1232 4859 1652 1237 4860 1649 1234 4861 1653 1238 4862 1652 1237 4863 1648 1233 4864 1649 1234 4865 806 595 4866 1654 1239 4867 1651 1236 4868 1655 1240 4869 1653 1238 4870 1656 1241 4871 1655 1240 4872 1652 1237 4873 1653 1238 4874 806 595 4875 1657 1242 4876 1654 1239 4877 1658 1243 4878 1654 1239 4879 1657 1242 4880 1655 1240 4881 1656 1241 4882 1659 1244 4883 808 597 4884 1660 1245 4885 1657 1242 4886 487 432 4887 1657 1242 4888 1660 1245 4889 806 595 4890 808 597 4891 1657 1242 4892 1661 1246 4893 1657 1242 4894 487 432 4895 1662 1247 4896 1657 1242 4897 1661 1246 4898 1658 1243 4899 1657 1242 4900 1662 1247 4901 810 599 4902 1663 1248 4903 1660 1245 4904 483 428 4905 1660 1245 4906 1663 1248 4907 808 597 4908 810 599 4909 1660 1245 4910 487 432 4911 1660 1245 4912 483 428 4913 814 603 4914 1664 1249 4915 1663 1248 4916 481 426 4917 1663 1248 4918 1664 1249 4919 812 601 4920 814 603 4921 1663 1248 4922 810 599 4923 812 601 4924 1663 1248 4925 483 428 4926 1663 1248 4927 481 426 4928 816 605 4929 1665 1250 4930 1664 1249 4931 476 421 4932 1664 1249 4933 1665 1250 4934 814 603 4935 816 605 4936 1664 1249 4937 478 423 4938 1664 1249 4939 476 421 4940 481 426 4941 1664 1249 4942 478 423 4943 818 607 4944 1666 1251 4945 1665 1250 4946 470 415 4947 1665 1250 4948 1666 1251 4949 816 605 4950 818 607 4951 1665 1250 4952 476 421 4953 1665 1250 4954 470 415 4955 820 609 4956 1667 1252 4957 1666 1251 4958 1668 1253 4959 1666 1251 4960 1667 1252 4961 818 607 4962 820 609 4963 1666 1251 4964 470 415 4965 1666 1251 4966 1669 1254 4967 1670 1255 4968 1669 1254 4969 1666 1251 4970 1668 1253 4971 1670 1255 4972 1666 1251 4973 820 609 4974 1671 1256 4975 1667 1252 4976 1672 1257 4977 1673 1258 4978 1674 1259 4979 1675 1260 4980 1676 1261 4981 1673 1258 4982 1672 1257 4983 1675 1260 4984 1673 1258 4985 820 609 4986 1677 1262 4987 1671 1256 4988 1678 1263 4989 1674 1259 4990 1679 1264 4991 1678 1263 4992 1672 1257 4993 1674 1259 4994 820 609 4995 1680 1265 4996 1677 1262 4997 1681 1266 4998 1679 1264 4999 1682 1267 5000 1681 1266 5001 1678 1263 5002 1679 1264 5003 822 611 5004 1683 1268 5005 1680 1265 5006 1684 1269 5007 1682 1267 5008 1685 1270 5009 820 609 5010 822 611 5011 1680 1265 5012 1684 1269 5013 1681 1266 5014 1682 1267 5015 822 611 5016 1686 1271 5017 1683 1268 5018 1687 1272 5019 1688 1273 5020 1689 1274 5021 1690 729 5022 1684 1269 5023 1685 1270 5024 822 611 5025 1691 1275 5026 1686 1271 5027 1692 1276 5028 1689 1274 5029 1693 1277 5030 1694 1278 5031 1687 1272 5032 1689 1274 5033 1692 1276 5034 1694 1278 5035 1689 1274 5036 822 611 5037 1695 1279 5038 1691 1275 5039 1696 1280 5040 1693 1277 5041 1697 1281 5042 1696 1280 5043 1692 1276 5044 1693 1277 5045 824 613 5046 1698 1282 5047 1695 1279 5048 1699 1283 5049 1697 1281 5050 1700 1284 5051 822 611 5052 824 613 5053 1695 1279 5054 1699 1283 5055 1696 1280 5056 1697 1281 5057 824 613 5058 1701 1285 5059 1698 1282 5060 1702 1286 5061 1698 1282 5062 1701 1285 5063 1699 1283 5064 1700 1284 5065 1703 1287 5066 826 615 5067 1704 1288 5068 1701 1285 5069 372 317 5070 1701 1285 5071 1704 1288 5072 824 613 5073 826 615 5074 1701 1285 5075 1705 1289 5076 1701 1285 5077 372 317 5078 1706 1290 5079 1701 1285 5080 1705 1289 5081 1702 1286 5082 1701 1285 5083 1706 1290 5084 828 617 5085 1707 1291 5086 1704 1288 5087 368 313 5088 1704 1288 5089 1707 1291 5090 826 615 5091 828 617 5092 1704 1288 5093 372 317 5094 1704 1288 5095 368 313 5096 830 619 5097 1708 1292 5098 1707 1291 5099 366 311 5100 1707 1291 5101 1708 1292 5102 828 617 5103 830 619 5104 1707 1291 5105 368 313 5106 1707 1291 5107 366 311 5108 832 621 5109 1709 1293 5110 1708 1292 5111 361 306 5112 1708 1292 5113 1709 1293 5114 830 619 5115 832 621 5116 1708 1292 5117 363 308 5118 1708 1292 5119 361 306 5120 366 311 5121 1708 1292 5122 363 308 5123 834 623 5124 1710 1294 5125 1709 1293 5126 355 300 5127 1709 1293 5128 1710 1294 5129 832 621 5130 834 623 5131 1709 1293 5132 361 306 5133 1709 1293 5134 355 300 5135 836 625 5136 1711 1295 5137 1710 1294 5138 1712 1296 5139 1710 1294 5140 1711 1295 5141 834 623 5142 836 625 5143 1710 1294 5144 355 300 5145 1710 1294 5146 1713 1297 5147 1714 1298 5148 1713 1297 5149 1710 1294 5150 1712 1296 5151 1714 1298 5152 1710 1294 5153 836 625 5154 1715 1299 5155 1711 1295 5156 1716 1300 5157 1717 1301 5158 1718 1302 5159 1719 1303 5160 1720 1304 5161 1717 1301 5162 1716 1300 5163 1719 1303 5164 1717 1301 5165 836 625 5166 1721 1305 5167 1715 1299 5168 1722 1306 5169 1718 1302 5170 1723 1307 5171 1722 1306 5172 1716 1300 5173 1718 1302 5174 1724 1308 5175 1725 1309 5176 1721 1305 5177 1726 1310 5178 1723 1307 5179 1727 1311 5180 836 625 5181 1724 1308 5182 1721 1305 5183 1726 1310 5184 1722 1306 5185 1723 1307 5186 1724 1308 5187 1728 1312 5188 1725 1309 5189 1729 1313 5190 1727 1311 5191 1730 1314 5192 1729 1313 5193 1726 1310 5194 1727 1311 5195 1540 1138 5196 1731 1315 5197 1539 1137 5198 1732 1316 5199 1731 1315 5200 1540 1138 5201 1733 1317 5202 1734 1318 5203 1735 1319 5204 1736 1320 5205 1729 1313 5206 1730 1314 5207 842 630 5208 1724 1308 5209 836 625 5210 1631 1216 5211 793 582 5212 792 581 5213 1737 1321 5214 1738 1322 5215 1739 1323 5216 786 575 5217 789 578 5218 1738 1322 5219 1737 1321 5220 786 575 5221 1738 1322 5222 1583 1324 5223 1740 1324 5224 1632 1324 5225 470 415 5226 1669 1254 5227 473 418 5228 474 419 5229 475 420 5230 1741 1325 5231 1742 1326 5232 1741 1325 5233 1743 1327 5234 1742 1326 5235 474 419 5236 1741 1325 5237 494 439 5238 1661 1246 5239 487 432 5240 1744 1328 5241 1745 1329 5242 496 441 5243 1744 1328 5244 1746 1330 5245 1745 1329 5246 495 440 5247 1744 1328 5248 496 441 5249 1747 1331 5250 1659 1244 5251 1746 1330 5252 1744 1328 5253 1747 1331 5254 1746 1330 5255 1675 1260 5256 1743 1327 5257 1676 1261 5258 1675 1260 5259 1742 1326 5260 1743 1327 5261 1747 1331 5262 1655 1240 5263 1659 1244 5264 355 300 5265 1713 1297 5266 358 303 5267 359 304 5268 360 305 5269 1748 1332 5270 1749 1333 5271 1748 1332 5272 1750 1334 5273 1749 1333 5274 359 304 5275 1748 1332 5276 379 324 5277 1705 1289 5278 372 317 5279 1751 1335 5280 1752 1336 5281 381 326 5282 1751 1335 5283 1753 1337 5284 1752 1336 5285 380 325 5286 1751 1335 5287 381 326 5288 1754 1338 5289 1703 1287 5290 1753 1337 5291 1751 1335 5292 1754 1338 5293 1753 1337 5294 1719 1303 5295 1750 1334 5296 1720 1304 5297 1719 1303 5298 1749 1333 5299 1750 1334 5300 1754 1338 5301 1699 1283 5302 1703 1287 5303 1755 1339 5304 1581 1179 5305 786 575 5306 1737 1321 5307 1755 1339 5308 786 575 5309 1756 1340 5310 1579 1177 5311 1581 1179 5312 1755 1339 5313 1756 1340 5314 1581 1179 5315 1757 1341 5316 1577 1175 5317 1579 1177 5318 1756 1340 5319 1757 1341 5320 1579 1177 5321 1758 1342 5322 1575 1173 5323 1577 1175 5324 1757 1341 5325 1758 1342 5326 1577 1175 5327 1759 1343 5328 1573 1171 5329 1575 1173 5330 1758 1342 5331 1759 1343 5332 1575 1173 5333 1760 1344 5334 1571 1169 5335 1573 1171 5336 1759 1343 5337 1760 1344 5338 1573 1171 5339 1761 1345 5340 1569 1167 5341 1571 1169 5342 1762 1346 5343 1761 1345 5344 1571 1169 5345 1760 1344 5346 1762 1346 5347 1571 1169 5348 1763 1347 5349 1567 1165 5350 1569 1167 5351 1764 1348 5352 1763 1347 5353 1569 1167 5354 1765 1349 5355 1764 1348 5356 1569 1167 5357 1766 1350 5358 1765 1349 5359 1569 1167 5360 1761 1345 5361 1766 1350 5362 1569 1167 5363 1767 1351 5364 1565 1163 5365 1567 1165 5366 1768 1352 5367 1767 1351 5368 1567 1165 5369 1769 1353 5370 1768 1352 5371 1567 1165 5372 1770 1354 5373 1769 1353 5374 1567 1165 5375 1763 1347 5376 1770 1354 5377 1567 1165 5378 1771 1355 5379 1563 1161 5380 1565 1163 5381 1767 1351 5382 1771 1355 5383 1565 1163 5384 1772 1356 5385 1561 1159 5386 1563 1161 5387 1771 1355 5388 1772 1356 5389 1563 1161 5390 1773 1357 5391 1559 1157 5392 1561 1159 5393 1772 1356 5394 1773 1357 5395 1561 1159 5396 1773 1357 5397 1557 1155 5398 1559 1157 5399 1774 1358 5400 1555 1153 5401 1557 1155 5402 1773 1357 5403 1774 1358 5404 1557 1155 5405 1775 1359 5406 1553 1151 5407 1555 1153 5408 1774 1358 5409 1775 1359 5410 1555 1153 5411 1776 1360 5412 1551 1149 5413 1553 1151 5414 1777 1361 5415 1776 1360 5416 1553 1151 5417 1778 1362 5418 1777 1361 5419 1553 1151 5420 1779 1363 5421 1778 1362 5422 1553 1151 5423 1780 1364 5424 1779 1363 5425 1553 1151 5426 1781 1365 5427 1780 1364 5428 1553 1151 5429 1775 1359 5430 1781 1365 5431 1553 1151 5432 1782 1366 5433 1549 1147 5434 1551 1149 5435 1783 1367 5436 1782 1366 5437 1551 1149 5438 1784 1368 5439 1783 1367 5440 1551 1149 5441 1776 1360 5442 1784 1368 5443 1551 1149 5444 1785 1369 5445 1547 1145 5446 1549 1147 5447 1782 1366 5448 1785 1369 5449 1549 1147 5450 1786 1370 5451 1545 1143 5452 1547 1145 5453 1785 1369 5454 1786 1370 5455 1547 1145 5456 1787 1371 5457 1543 1141 5458 1545 1143 5459 1786 1370 5460 1787 1371 5461 1545 1143 5462 1788 1372 5463 1541 1139 5464 1543 1141 5465 1787 1371 5466 1788 1372 5467 1543 1141 5468 1789 1373 5469 1537 1135 5470 1541 1139 5471 1788 1372 5472 1789 1373 5473 1541 1139 5474 1790 1374 5475 1540 1138 5476 1537 1135 5477 1789 1373 5478 1790 1374 5479 1537 1135 5480 1791 1375 5481 1732 1316 5482 1540 1138 5483 1792 1376 5484 1791 1375 5485 1540 1138 5486 1793 1377 5487 1792 1376 5488 1540 1138 5489 1790 1374 5490 1793 1377 5491 1540 1138 5492 1794 1378 5493 1735 1319 5494 1795 1379 5495 1796 1380 5496 1733 1317 5497 1735 1319 5498 1794 1378 5499 1796 1380 5500 1735 1319 5501 1797 1381 5502 1795 1379 5503 1798 1382 5504 1797 1381 5505 1794 1378 5506 1795 1379 5507 1799 1383 5508 1798 1382 5509 1800 1384 5510 1799 1383 5511 1797 1381 5512 1798 1382 5513 1801 1385 5514 1793 1377 5515 1790 1374 5516 1799 1383 5517 1800 1384 5518 1802 1386 5519 1242 1025 5520 1790 1374 5521 1789 1373 5522 1803 1387 5523 1790 1374 5524 1242 1025 5525 1804 1388 5526 1790 1374 5527 1803 1387 5528 1801 1385 5529 1790 1374 5530 1804 1388 5531 1237 1020 5532 1789 1373 5533 1788 1372 5534 1242 1025 5535 1789 1373 5536 1237 1020 5537 1232 1015 5538 1788 1372 5539 1787 1371 5540 1237 1020 5541 1788 1372 5542 1232 1015 5543 1219 1002 5544 1787 1371 5545 1786 1370 5546 1224 1007 5547 1787 1371 5548 1219 1002 5549 1232 1015 5550 1787 1371 5551 1224 1007 5552 1211 994 5553 1786 1370 5554 1785 1369 5555 1219 1002 5556 1786 1370 5557 1211 994 5558 1805 1389 5559 1785 1369 5560 1782 1366 5561 1211 994 5562 1785 1369 5563 1806 1390 5564 1807 1391 5565 1806 1390 5566 1785 1369 5567 1805 1389 5568 1807 1391 5569 1785 1369 5570 1808 1392 5571 1809 1393 5572 1810 1394 5573 1811 1395 5574 1812 1396 5575 1809 1393 5576 1808 1392 5577 1811 1395 5578 1809 1393 5579 1813 1397 5580 1810 1394 5581 1814 1398 5582 1813 1397 5583 1808 1392 5584 1810 1394 5585 1815 1399 5586 1814 1398 5587 1816 1400 5588 1815 1399 5589 1813 1397 5590 1814 1398 5591 1817 1401 5592 1816 1400 5593 1818 1402 5594 1817 1401 5595 1815 1399 5596 1816 1400 5597 1819 1403 5598 1820 1404 5599 1821 1405 5600 1822 1406 5601 1817 1401 5602 1818 1402 5603 1823 1407 5604 1821 1405 5605 1824 1408 5606 1825 1409 5607 1819 1403 5608 1821 1405 5609 1823 1407 5610 1825 1409 5611 1821 1405 5612 1826 1410 5613 1824 1408 5614 1827 1411 5615 1826 1410 5616 1823 1407 5617 1824 1408 5618 1828 1412 5619 1827 1411 5620 1829 1413 5621 1828 1412 5622 1826 1410 5623 1827 1411 5624 1830 1414 5625 1781 1365 5626 1775 1359 5627 1828 1412 5628 1829 1413 5629 1831 1415 5630 1053 834 5631 1775 1359 5632 1774 1358 5633 1832 1416 5634 1775 1359 5635 1053 834 5636 1833 1417 5637 1775 1359 5638 1832 1416 5639 1830 1414 5640 1775 1359 5641 1833 1417 5642 1048 829 5643 1774 1358 5644 1773 1357 5645 1053 834 5646 1774 1358 5647 1048 829 5648 1043 824 5649 1773 1357 5650 1772 1356 5651 1048 829 5652 1773 1357 5653 1043 824 5654 1030 811 5655 1772 1356 5656 1771 1355 5657 1035 816 5658 1772 1356 5659 1030 811 5660 1043 824 5661 1772 1356 5662 1035 816 5663 1022 803 5664 1771 1355 5665 1767 1351 5666 1030 811 5667 1771 1355 5668 1022 803 5669 1834 1418 5670 1767 1351 5671 1768 1352 5672 1022 803 5673 1767 1351 5674 1835 1419 5675 1836 1420 5676 1835 1419 5677 1767 1351 5678 1834 1418 5679 1836 1420 5680 1767 1351 5681 1837 1421 5682 1838 1422 5683 1839 1423 5684 1840 1424 5685 1841 1425 5686 1838 1422 5687 1837 1421 5688 1840 1424 5689 1838 1422 5690 1842 1426 5691 1839 1423 5692 1843 1427 5693 1842 1426 5694 1837 1421 5695 1839 1423 5696 1844 1428 5697 1843 1427 5698 1845 1429 5699 1844 1428 5700 1842 1426 5701 1843 1427 5702 1846 1430 5703 1845 1429 5704 1847 1431 5705 1846 1430 5706 1844 1428 5707 1845 1429 5708 1848 1432 5709 1849 1433 5710 1850 1434 5711 1851 370 5712 1846 1430 5713 1847 1431 5714 1852 1435 5715 1850 1434 5716 1853 1436 5717 1854 1437 5718 1848 1432 5719 1850 1434 5720 1852 1435 5721 1854 1437 5722 1850 1434 5723 1855 1438 5724 1853 1436 5725 1856 1439 5726 1855 1438 5727 1852 1435 5728 1853 1436 5729 1857 1440 5730 1856 1439 5731 1858 1441 5732 1857 1440 5733 1855 1438 5734 1856 1439 5735 1859 1442 5736 1762 1346 5737 1760 1344 5738 1857 1440 5739 1858 1441 5740 1860 1443 5741 863 642 5742 1760 1344 5743 1759 1343 5744 1861 1444 5745 1859 1442 5746 1760 1344 5747 1862 1445 5748 1861 1444 5749 1760 1344 5750 863 642 5751 1862 1445 5752 1760 1344 5753 1863 1446 5754 1759 1343 5755 1758 1342 5756 1863 1446 5757 863 642 5758 1759 1343 5759 1864 1447 5760 1758 1342 5761 1757 1341 5762 1864 1447 5763 1863 1446 5764 1758 1342 5765 1865 1448 5766 1757 1341 5767 1756 1340 5768 1866 1449 5769 1864 1447 5770 1757 1341 5771 1865 1448 5772 1866 1449 5773 1757 1341 5774 1867 1450 5775 1756 1340 5776 1755 1339 5777 1865 1448 5778 1756 1340 5779 1867 1450 5780 1583 1451 5781 1868 1451 5782 1740 1451 5783 1583 1452 5784 1869 1452 5785 1868 1452 5786 1583 1453 5787 1870 1453 5788 1869 1453 5789 1871 1454 5790 1860 1443 5791 1872 1455 5792 1871 1454 5793 1857 1440 5794 1860 1443 5795 1873 1456 5796 1872 1455 5797 1874 1457 5798 1873 1456 5799 1871 1454 5800 1872 1455 5801 873 652 5802 1862 1445 5803 863 642 5804 1873 1456 5805 1874 1457 5806 875 654 5807 869 648 5808 863 642 5809 1863 1446 5810 1875 1458 5811 1863 1446 5812 1864 1447 5813 1876 1459 5814 1863 1446 5815 1875 1458 5816 1876 1459 5817 869 648 5818 1863 1446 5819 1583 1460 5820 1877 1460 5821 1878 1460 5822 1583 1461 5823 1879 1461 5824 1877 1461 5825 1583 1462 5826 1878 1462 5827 1870 1462 5828 1880 1463 5829 1879 1463 5830 1583 1463 5831 874 653 5832 1873 1456 5833 875 654 5834 1211 994 5835 1806 1390 5836 1214 997 5837 1215 998 5838 1216 999 5839 1881 1464 5840 1882 1465 5841 1881 1464 5842 1883 1466 5843 1882 1465 5844 1215 998 5845 1881 1464 5846 1251 1034 5847 1803 1387 5848 1242 1025 5849 1884 1467 5850 1885 1468 5851 1253 1036 5852 1884 1467 5853 1886 1469 5854 1885 1468 5855 1252 1035 5856 1884 1467 5857 1253 1036 5858 1887 1470 5859 1802 1386 5860 1886 1469 5861 1884 1467 5862 1887 1470 5863 1886 1469 5864 1811 1395 5865 1883 1466 5866 1812 1396 5867 1811 1395 5868 1882 1465 5869 1883 1466 5870 1887 1470 5871 1799 1383 5872 1802 1386 5873 1022 803 5874 1835 1419 5875 1025 806 5876 1026 807 5877 1027 808 5878 1888 1471 5879 1889 1472 5880 1888 1471 5881 1890 1473 5882 1889 1472 5883 1026 807 5884 1888 1471 5885 1062 843 5886 1832 1416 5887 1053 834 5888 1891 1474 5889 1892 1475 5890 1064 845 5891 1891 1474 5892 1893 1476 5893 1892 1475 5894 1063 844 5895 1891 1474 5896 1064 845 5897 1894 1477 5898 1831 1415 5899 1893 1476 5900 1891 1474 5901 1894 1477 5902 1893 1476 5903 1840 1424 5904 1890 1473 5905 1841 1425 5906 1840 1424 5907 1889 1472 5908 1890 1473 5909 1894 1477 5910 1828 1412 5911 1831 1415 5912 1895 1478 5913 1896 1479 5914 1897 1480 5915 1898 1481 5916 1899 1482 5917 1900 1483 5918 1898 1481 5919 1900 1483 5920 1901 1484 5921 1895 1478 5922 1897 1480 5923 1902 1485 5924 1903 1486 5925 1902 1485 5926 1904 1487 5927 1895 1478 5928 1902 1485 5929 1903 1486 5930 1903 1486 5931 1904 1487 5932 1905 1488 5933 1906 1489 5934 1905 1488 5935 1907 1490 5936 1903 1486 5937 1905 1488 5938 1906 1489 5939 1906 1489 5940 1907 1490 5941 1908 1491 5942 1909 1492 5943 1908 1491 5944 1910 1493 5945 1906 1489 5946 1908 1491 5947 1909 1492 5948 1909 1492 5949 1910 1493 5950 1911 1494 5951 1912 1495 5952 1911 1494 5953 1913 1496 5954 1909 1492 5955 1911 1494 5956 1912 1495 5957 1912 1495 5958 1913 1496 5959 1914 1497 5960 1915 1498 5961 1914 1497 5962 1916 1499 5963 1912 1495 5964 1914 1497 5965 1915 1498 5966 1915 1498 5967 1916 1499 5968 1917 1500 5969 1918 1501 5970 1917 1500 5971 1919 1502 5972 1915 1498 5973 1917 1500 5974 1918 1501 5975 1918 1501 5976 1919 1502 5977 1920 1503 5978 1921 1504 5979 1920 1503 5980 1922 1505 5981 1918 1501 5982 1920 1503 5983 1921 1504 5984 1921 1504 5985 1922 1505 5986 1923 1506 5987 1924 1507 5988 1923 1506 5989 1925 1508 5990 1921 1504 5991 1923 1506 5992 1924 1507 5993 1924 1507 5994 1925 1508 5995 1926 1509 5996 1927 1510 5997 1926 1509 5998 1928 1511 5999 1924 1507 6000 1926 1509 6001 1927 1510 6002 1927 1510 6003 1928 1511 6004 1929 1512 6005 1930 1513 6006 1931 1514 6007 1932 1515 6008 1927 1510 6009 1929 1512 6010 1933 1516 6011 1930 1513 6012 1932 1515 6013 1934 1517 6014 1935 1518 6015 1934 1517 6016 1936 1519 6017 1935 1518 6018 1930 1513 6019 1934 1517 6020 1935 1518 6021 1936 1519 6022 1937 1520 6023 1938 1521 6024 1937 1520 6025 1939 1522 6026 1935 1518 6027 1937 1520 6028 1938 1521 6029 1938 1521 6030 1939 1522 6031 1940 1523 6032 1941 1524 6033 1940 1523 6034 1942 1525 6035 1938 1521 6036 1940 1523 6037 1941 1524 6038 1941 1524 6039 1942 1525 6040 1943 1526 6041 1944 1527 6042 1943 1526 6043 1945 1528 6044 1941 1524 6045 1943 1526 6046 1944 1527 6047 1944 1527 6048 1945 1528 6049 1946 1529 6050 1947 1530 6051 1946 1529 6052 1948 1531 6053 1944 1527 6054 1946 1529 6055 1947 1530 6056 1947 1530 6057 1948 1531 6058 1949 1532 6059 1950 1533 6060 1949 1532 6061 1951 1534 6062 1947 1530 6063 1949 1532 6064 1950 1533 6065 1950 1533 6066 1951 1534 6067 1952 1535 6068 1953 1536 6069 1952 1535 6070 1954 1537 6071 1950 1533 6072 1952 1535 6073 1953 1536 6074 1953 1536 6075 1954 1537 6076 1955 1538 6077 1956 1539 6078 1955 1538 6079 1957 1540 6080 1953 1536 6081 1955 1538 6082 1956 1539 6083 1956 1539 6084 1957 1540 6085 1958 1541 6086 1898 1481 6087 1958 1541 6088 1899 1482 6089 1956 1539 6090 1958 1541 6091 1898 1481 6092 1959 1542 6093 1960 1543 6094 1961 1544 6095 1962 1545 6096 1963 1546 6097 1964 1547 6098 1962 1545 6099 1964 1547 6100 1965 1548 6101 1959 1542 6102 1961 1544 6103 1966 1549 6104 1967 1550 6105 1966 1549 6106 1968 1551 6107 1959 1542 6108 1966 1549 6109 1967 1550 6110 1967 1550 6111 1968 1551 6112 1969 1552 6113 1970 1553 6114 1969 1552 6115 1971 1554 6116 1967 1550 6117 1969 1552 6118 1970 1553 6119 1970 1553 6120 1971 1554 6121 1972 1555 6122 1973 1556 6123 1972 1555 6124 1974 1557 6125 1970 1553 6126 1972 1555 6127 1973 1556 6128 1973 1556 6129 1974 1557 6130 1975 1558 6131 1976 1559 6132 1975 1558 6133 1977 1560 6134 1973 1556 6135 1975 1558 6136 1976 1559 6137 1976 1559 6138 1977 1560 6139 1978 1561 6140 1979 1562 6141 1978 1561 6142 1980 1563 6143 1976 1559 6144 1978 1561 6145 1979 1562 6146 1979 1562 6147 1980 1563 6148 1981 1564 6149 1982 1565 6150 1981 1564 6151 1983 1566 6152 1979 1562 6153 1981 1564 6154 1982 1565 6155 1982 1565 6156 1983 1566 6157 1984 1567 6158 1985 1568 6159 1984 1567 6160 1986 1569 6161 1982 1565 6162 1984 1567 6163 1985 1568 6164 1985 1568 6165 1986 1569 6166 1987 1570 6167 1988 1571 6168 1987 1570 6169 1989 1572 6170 1985 1568 6171 1987 1570 6172 1988 1571 6173 1988 1571 6174 1989 1572 6175 1990 1573 6176 1991 1574 6177 1990 1573 6178 1992 1575 6179 1988 1571 6180 1990 1573 6181 1991 1574 6182 1991 1574 6183 1992 1575 6184 1993 1576 6185 1994 1577 6186 1995 1578 6187 1996 1579 6188 1991 1574 6189 1993 1576 6190 1997 1580 6191 1994 1577 6192 1996 1579 6193 1998 1581 6194 1999 1582 6195 1998 1581 6196 2000 1583 6197 1999 1582 6198 1994 1577 6199 1998 1581 6200 1999 1582 6201 2000 1583 6202 2001 1584 6203 2002 1585 6204 2001 1584 6205 2003 1586 6206 1999 1582 6207 2001 1584 6208 2002 1585 6209 2002 1585 6210 2003 1586 6211 2004 1587 6212 2005 1588 6213 2004 1587 6214 2006 1589 6215 2002 1585 6216 2004 1587 6217 2005 1588 6218 2005 1588 6219 2006 1589 6220 2007 1590 6221 2008 1591 6222 2007 1590 6223 2009 1592 6224 2005 1588 6225 2007 1590 6226 2008 1591 6227 2008 1591 6228 2009 1592 6229 2010 1593 6230 2011 1594 6231 2010 1593 6232 2012 1595 6233 2008 1591 6234 2010 1593 6235 2011 1594 6236 2011 1594 6237 2012 1595 6238 2013 1596 6239 2014 1597 6240 2013 1596 6241 2015 1598 6242 2011 1594 6243 2013 1596 6244 2014 1597 6245 2014 1597 6246 2015 1598 6247 2016 1599 6248 2017 1600 6249 2016 1599 6250 2018 1601 6251 2014 1597 6252 2016 1599 6253 2017 1600 6254 2017 1600 6255 2018 1601 6256 2019 1602 6257 2020 1603 6258 2019 1602 6259 2021 1604 6260 2017 1600 6261 2019 1602 6262 2020 1603 6263 2020 1603 6264 2021 1604 6265 2022 1605 6266 1962 1545 6267 2022 1605 6268 1963 1546 6269 2020 1603 6270 2022 1605 6271 1962 1545 6272 2023 1606 6273 2024 1607 6274 2025 1608 6275 2026 1609 6276 2027 1610 6277 2028 1611 6278 2026 1609 6279 2028 1611 6280 2029 1612 6281 2023 1606 6282 2025 1608 6283 2030 1613 6284 2031 1614 6285 2030 1613 6286 2032 1615 6287 2023 1606 6288 2030 1613 6289 2031 1614 6290 2031 1614 6291 2032 1615 6292 2033 1616 6293 2034 1617 6294 2033 1616 6295 2035 1618 6296 2031 1614 6297 2033 1616 6298 2034 1617 6299 2034 1617 6300 2035 1618 6301 2036 1619 6302 2037 1620 6303 2036 1619 6304 2038 1621 6305 2034 1617 6306 2036 1619 6307 2037 1620 6308 2037 1620 6309 2038 1621 6310 2039 1622 6311 2040 1623 6312 2039 1622 6313 2041 1624 6314 2037 1620 6315 2039 1622 6316 2040 1623 6317 2040 1623 6318 2041 1624 6319 2042 1625 6320 2043 1626 6321 2042 1625 6322 2044 1627 6323 2040 1623 6324 2042 1625 6325 2043 1626 6326 2043 1626 6327 2044 1627 6328 2045 1628 6329 2046 1629 6330 2045 1628 6331 2047 1630 6332 2043 1626 6333 2045 1628 6334 2046 1629 6335 2046 1629 6336 2047 1630 6337 2048 1631 6338 2049 1632 6339 2048 1631 6340 2050 1633 6341 2046 1629 6342 2048 1631 6343 2049 1632 6344 2049 1632 6345 2050 1633 6346 2051 1634 6347 2052 1635 6348 2051 1634 6349 2053 1636 6350 2049 1632 6351 2051 1634 6352 2052 1635 6353 2052 1635 6354 2053 1636 6355 2054 1637 6356 2055 1638 6357 2054 1637 6358 2056 1639 6359 2052 1635 6360 2054 1637 6361 2055 1638 6362 2055 1638 6363 2056 1639 6364 2057 1640 6365 2058 1641 6366 2059 1642 6367 2060 1643 6368 2055 1638 6369 2057 1640 6370 2061 1644 6371 2058 1641 6372 2060 1643 6373 2062 1645 6374 2063 1646 6375 2062 1645 6376 2064 1647 6377 2063 1646 6378 2058 1641 6379 2062 1645 6380 2063 1646 6381 2064 1647 6382 2065 1648 6383 2066 1649 6384 2065 1648 6385 2067 1650 6386 2063 1646 6387 2065 1648 6388 2066 1649 6389 2066 1649 6390 2067 1650 6391 2068 1651 6392 2069 1652 6393 2068 1651 6394 2070 1653 6395 2066 1649 6396 2068 1651 6397 2069 1652 6398 2069 1652 6399 2070 1653 6400 2071 1654 6401 2072 1655 6402 2071 1654 6403 2073 1656 6404 2069 1652 6405 2071 1654 6406 2072 1655 6407 2072 1655 6408 2073 1656 6409 2074 1657 6410 2075 1658 6411 2074 1657 6412 2076 1659 6413 2072 1655 6414 2074 1657 6415 2075 1658 6416 2075 1658 6417 2076 1659 6418 2077 1660 6419 2078 1661 6420 2077 1660 6421 2079 1662 6422 2075 1658 6423 2077 1660 6424 2078 1661 6425 2078 1661 6426 2079 1662 6427 2080 1663 6428 2081 1664 6429 2080 1663 6430 2082 1665 6431 2078 1661 6432 2080 1663 6433 2081 1664 6434 2081 1664 6435 2082 1665 6436 2083 1666 6437 2084 1667 6438 2083 1666 6439 2085 1668 6440 2081 1664 6441 2083 1666 6442 2084 1667 6443 2084 1667 6444 2085 1668 6445 2086 1669 6446 2026 1609 6447 2086 1669 6448 2027 1610 6449 2084 1667 6450 2086 1669 6451 2026 1609 6452 2087 1577 6453 2088 1578 6454 2089 1579 6455 2090 1574 6456 2091 1575 6457 2092 1576 6458 2090 1574 6459 2092 1576 6460 2093 1670 6461 2087 1577 6462 2089 1579 6463 2094 1581 6464 2095 1582 6465 2094 1581 6466 2096 1583 6467 2087 1577 6468 2094 1581 6469 2095 1582 6470 2095 1582 6471 2096 1583 6472 2097 1584 6473 2098 1585 6474 2097 1584 6475 2099 1586 6476 2095 1582 6477 2097 1584 6478 2098 1585 6479 2098 1585 6480 2099 1586 6481 2100 1671 6482 2101 1588 6483 2100 1671 6484 2102 1672 6485 2098 1585 6486 2100 1671 6487 2101 1588 6488 2101 1588 6489 2102 1672 6490 2103 1590 6491 2104 1591 6492 2103 1590 6493 2105 1592 6494 2101 1588 6495 2103 1590 6496 2104 1591 6497 2104 1591 6498 2105 1592 6499 2106 1593 6500 2107 1594 6501 2106 1593 6502 2108 1595 6503 2104 1591 6504 2106 1593 6505 2107 1594 6506 2107 1594 6507 2108 1595 6508 2109 1596 6509 2110 1597 6510 2109 1596 6511 2111 1598 6512 2107 1594 6513 2109 1596 6514 2110 1597 6515 2110 1597 6516 2111 1598 6517 2112 1599 6518 2113 1600 6519 2112 1599 6520 2114 1601 6521 2110 1597 6522 2112 1599 6523 2113 1600 6524 2113 1600 6525 2114 1601 6526 2115 1602 6527 2116 1603 6528 2115 1602 6529 2117 1604 6530 2113 1600 6531 2115 1602 6532 2116 1603 6533 2116 1603 6534 2117 1604 6535 2118 1605 6536 2119 1545 6537 2118 1605 6538 2120 1546 6539 2116 1603 6540 2118 1605 6541 2119 1545 6542 2119 1545 6543 2120 1546 6544 2121 1547 6545 2122 1542 6546 2123 1543 6547 2124 1544 6548 2119 1545 6549 2121 1547 6550 2125 1673 6551 2122 1542 6552 2124 1544 6553 2126 1549 6554 2127 1550 6555 2126 1549 6556 2128 1551 6557 2127 1550 6558 2122 1542 6559 2126 1549 6560 2127 1550 6561 2128 1551 6562 2129 1552 6563 2130 1553 6564 2129 1552 6565 2131 1554 6566 2127 1550 6567 2129 1552 6568 2130 1553 6569 2130 1553 6570 2131 1554 6571 2132 1674 6572 2133 1556 6573 2132 1674 6574 2134 1675 6575 2130 1553 6576 2132 1674 6577 2133 1556 6578 2133 1556 6579 2134 1675 6580 2135 1558 6581 2136 1559 6582 2135 1558 6583 2137 1560 6584 2133 1556 6585 2135 1558 6586 2136 1559 6587 2136 1559 6588 2137 1560 6589 2138 1561 6590 2139 1562 6591 2138 1561 6592 2140 1563 6593 2136 1559 6594 2138 1561 6595 2139 1562 6596 2139 1562 6597 2140 1563 6598 2141 1564 6599 2142 1565 6600 2141 1564 6601 2143 1566 6602 2139 1562 6603 2141 1564 6604 2142 1565 6605 2142 1565 6606 2143 1566 6607 2144 1567 6608 2145 1568 6609 2144 1567 6610 2146 1569 6611 2142 1565 6612 2144 1567 6613 2145 1568 6614 2145 1568 6615 2146 1569 6616 2147 1570 6617 2148 1571 6618 2147 1570 6619 2149 1572 6620 2145 1568 6621 2147 1570 6622 2148 1571 6623 2148 1571 6624 2149 1572 6625 2150 1573 6626 2090 1574 6627 2150 1573 6628 2091 1575 6629 2148 1571 6630 2150 1573 6631 2090 1574 6632 2151 1641 6633 2152 1642 6634 2153 1643 6635 2154 1638 6636 2155 1639 6637 2156 1640 6638 2154 1638 6639 2156 1640 6640 2157 1644 6641 2151 1641 6642 2153 1643 6643 2158 1645 6644 2159 1646 6645 2158 1645 6646 2160 1647 6647 2151 1641 6648 2158 1645 6649 2159 1646 6650 2159 1646 6651 2160 1647 6652 2161 1648 6653 2162 1649 6654 2161 1648 6655 2163 1650 6656 2159 1646 6657 2161 1648 6658 2162 1649 6659 2162 1649 6660 2163 1650 6661 2164 1651 6662 2165 1652 6663 2164 1651 6664 2166 1653 6665 2162 1649 6666 2164 1651 6667 2165 1652 6668 2165 1652 6669 2166 1653 6670 2167 1654 6671 2168 1655 6672 2167 1654 6673 2169 1656 6674 2165 1652 6675 2167 1654 6676 2168 1655 6677 2168 1655 6678 2169 1656 6679 2170 1657 6680 2171 1658 6681 2170 1657 6682 2172 1659 6683 2168 1655 6684 2170 1657 6685 2171 1658 6686 2171 1658 6687 2172 1659 6688 2173 1660 6689 2174 1661 6690 2173 1660 6691 2175 1662 6692 2171 1658 6693 2173 1660 6694 2174 1661 6695 2174 1661 6696 2175 1662 6697 2176 1663 6698 2177 1664 6699 2176 1663 6700 2178 1665 6701 2174 1661 6702 2176 1663 6703 2177 1664 6704 2177 1664 6705 2178 1665 6706 2179 1666 6707 2180 1667 6708 2179 1666 6709 2181 1668 6710 2177 1664 6711 2179 1666 6712 2180 1667 6713 2180 1667 6714 2181 1668 6715 2182 1669 6716 2183 1609 6717 2182 1669 6718 2184 1610 6719 2180 1667 6720 2182 1669 6721 2183 1609 6722 2183 1609 6723 2184 1610 6724 2185 1611 6725 2186 1606 6726 2187 1607 6727 2188 1608 6728 2183 1609 6729 2185 1611 6730 2189 1612 6731 2186 1606 6732 2188 1608 6733 2190 1613 6734 2191 1614 6735 2190 1613 6736 2192 1615 6737 2191 1614 6738 2186 1606 6739 2190 1613 6740 2191 1614 6741 2192 1615 6742 2193 1616 6743 2194 1617 6744 2193 1616 6745 2195 1618 6746 2191 1614 6747 2193 1616 6748 2194 1617 6749 2194 1617 6750 2195 1618 6751 2196 1619 6752 2197 1620 6753 2196 1619 6754 2198 1621 6755 2194 1617 6756 2196 1619 6757 2197 1620 6758 2197 1620 6759 2198 1621 6760 2199 1622 6761 2200 1623 6762 2199 1622 6763 2201 1624 6764 2197 1620 6765 2199 1622 6766 2200 1623 6767 2200 1623 6768 2201 1624 6769 2202 1625 6770 2203 1626 6771 2202 1625 6772 2204 1627 6773 2200 1623 6774 2202 1625 6775 2203 1626 6776 2203 1626 6777 2204 1627 6778 2205 1628 6779 2206 1629 6780 2205 1628 6781 2207 1630 6782 2203 1626 6783 2205 1628 6784 2206 1629 6785 2206 1629 6786 2207 1630 6787 2208 1631 6788 2209 1632 6789 2208 1631 6790 2210 1633 6791 2206 1629 6792 2208 1631 6793 2209 1632 6794 2209 1632 6795 2210 1633 6796 2211 1634 6797 2212 1635 6798 2211 1634 6799 2213 1636 6800 2209 1632 6801 2211 1634 6802 2212 1635 6803 2212 1635 6804 2213 1636 6805 2214 1637 6806 2154 1638 6807 2214 1637 6808 2155 1639 6809 2212 1635 6810 2214 1637 6811 2154 1638 6812 2215 1676 6813 2216 1677 6814 2217 1678 6815 2218 1679 6816 2219 1680 6817 2220 1681 6818 2221 1682 6819 2218 1679 6820 2220 1681 6821 2222 1683 6822 2217 1678 6823 2223 1684 6824 2222 1683 6825 2215 1676 6826 2217 1678 6827 2224 1685 6828 2223 1684 6829 2225 1119 6830 2224 1685 6831 2222 1683 6832 2223 1684 6833 2226 1686 6834 2225 1119 6835 2227 1687 6836 2226 1686 6837 2224 1685 6838 2225 1119 6839 2228 1688 6840 2227 1687 6841 2229 1689 6842 2228 1688 6843 2226 1686 6844 2227 1687 6845 2230 1690 6846 2229 1689 6847 2231 1128 6848 2230 1690 6849 2228 1688 6850 2229 1689 6851 631 542 6852 2232 542 6853 630 542 6854 2233 1691 6855 2231 1128 6856 2234 1692 6857 2233 1691 6858 2230 1690 6859 2231 1128 6860 631 542 6861 2235 542 6862 2232 542 6863 2236 1693 6864 2234 1692 6865 2237 1694 6866 2236 1693 6867 2233 1691 6868 2234 1692 6869 2238 542 6870 1527 542 6871 2235 542 6872 2239 1695 6873 2237 1694 6874 2240 1696 6875 631 542 6876 2238 542 6877 2235 542 6878 2239 1695 6879 2236 1693 6880 2237 1694 6881 2241 1697 6882 2242 1698 6883 2243 1699 6884 2244 542 6885 1528 542 6886 1527 542 6887 2238 542 6888 2244 542 6889 1527 542 6890 2239 1695 6891 2240 1696 6892 2245 1700 6893 2246 1701 6894 2243 1699 6895 2247 1702 6896 2246 1701 6897 2241 1697 6898 2243 1699 6899 2248 1703 6900 2247 1702 6901 2249 551 6902 2248 1703 6903 2246 1701 6904 2247 1702 6905 2250 1704 6906 2249 551 6907 2251 1705 6908 2250 1704 6909 2248 1703 6910 2249 551 6911 2252 1706 6912 2251 1705 6913 2253 1707 6914 2252 1706 6915 2250 1704 6916 2251 1705 6917 2254 1708 6918 2253 1707 6919 2255 560 6920 2254 1708 6921 2252 1706 6922 2253 1707 6923 2256 1709 6924 2255 560 6925 2257 1710 6926 2256 1709 6927 2254 1708 6928 2255 560 6929 2258 1711 6930 2257 1710 6931 2219 1680 6932 2258 1711 6933 2256 1709 6934 2257 1710 6935 2218 1679 6936 2258 1711 6937 2219 1680 6938 2259 1712 6939 2260 1713 6940 2261 1714 6941 2262 1715 6942 2263 1707 6943 2264 1716 6944 2265 1717 6945 2262 1715 6946 2264 1716 6947 2266 1718 6948 2261 1714 6949 2267 1680 6950 2266 1718 6951 2259 1712 6952 2261 1714 6953 2268 1719 6954 2267 1680 6955 2269 11 6956 2268 1719 6957 2266 1718 6958 2267 1680 6959 1490 542 6960 2270 542 6961 1489 542 6962 2271 1720 6963 2269 11 6964 2272 1721 6965 2271 1720 6966 2268 1719 6967 2269 11 6968 1490 542 6969 2273 542 6970 2270 542 6971 2274 1722 6972 2272 1721 6973 2275 1723 6974 2274 1722 6975 2271 1720 6976 2272 1721 6977 2276 542 6978 2277 542 6979 2273 542 6980 2278 1724 6981 2275 1723 6982 2279 1119 6983 1490 542 6984 2276 542 6985 2273 542 6986 2278 1724 6987 2274 1722 6988 2275 1723 6989 2276 542 6990 2280 542 6991 2277 542 6992 2281 1725 6993 2279 1119 6994 2282 1687 6995 2281 1725 6996 2278 1724 6997 2279 1119 6998 2276 542 6999 2283 542 7000 2280 542 7001 2284 1726 7002 2282 1687 7003 2285 1689 7004 2284 1726 7005 2281 1725 7006 2282 1687 7007 2276 542 7008 2286 542 7009 2283 542 7010 2287 1727 7011 2285 1689 7012 2288 1728 7013 2287 1727 7014 2284 1726 7015 2285 1689 7016 1479 542 7017 2289 542 7018 2286 542 7019 2290 1729 7020 2291 1730 7021 2292 1731 7022 2276 542 7023 1479 542 7024 2286 542 7025 2287 1727 7026 2288 1728 7027 2293 1732 7028 1479 542 7029 2294 542 7030 2289 542 7031 2295 1733 7032 2292 1731 7033 2296 1694 7034 2295 1733 7035 2290 1729 7036 2292 1731 7037 1479 542 7038 1478 542 7039 2294 542 7040 2297 1734 7041 2296 1694 7042 2298 1735 7043 2297 1734 7044 2295 1733 7045 2296 1694 7046 2299 1736 7047 2298 1735 7048 2300 1737 7049 2299 1736 7050 2297 1734 7051 2298 1735 7052 2301 1738 7053 2300 1737 7054 2302 1739 7055 2301 1738 7056 2299 1736 7057 2300 1737 7058 2303 1740 7059 2302 1739 7060 2304 551 7061 2303 1740 7062 2301 1738 7063 2302 1739 7064 2305 1741 7065 2304 551 7066 2306 1705 7067 2305 1741 7068 2303 1740 7069 2304 551 7070 2307 1742 7071 2306 1705 7072 2263 1707 7073 2307 1742 7074 2305 1741 7075 2306 1705 7076 2262 1715 7077 2307 1742 7078 2263 1707 7079 2308 1743 7080 2309 1744 7081 2310 1745 7082 2311 1746 7083 2312 1702 7084 2313 1747 7085 2314 1748 7086 2311 1746 7087 2313 1747 7088 2315 1749 7089 2310 1745 7090 2316 1750 7091 2315 1749 7092 2308 1743 7093 2310 1745 7094 2317 1751 7095 2316 1750 7096 2318 1752 7097 2317 1751 7098 2315 1749 7099 2316 1750 7100 2319 1753 7101 2318 1752 7102 2320 1710 7103 2319 1753 7104 2317 1751 7105 2318 1752 7106 2321 1754 7107 2320 1710 7108 2322 1680 7109 2321 1754 7110 2319 1753 7111 2320 1710 7112 2323 1755 7113 2322 1680 7114 2324 11 7115 2323 1755 7116 2321 1754 7117 2322 1680 7118 1427 542 7119 2325 542 7120 1436 542 7121 2326 1756 7122 2324 11 7123 2327 1678 7124 2326 1756 7125 2323 1755 7126 2324 11 7127 1427 542 7128 2328 542 7129 2325 542 7130 2329 1757 7131 2327 1678 7132 2330 1684 7133 2329 1757 7134 2326 1756 7135 2327 1678 7136 2331 542 7137 2332 542 7138 2328 542 7139 2333 1758 7140 2330 1684 7141 2334 1759 7142 1427 542 7143 2331 542 7144 2328 542 7145 2333 1758 7146 2329 1757 7147 2330 1684 7148 2331 542 7149 2335 542 7150 2332 542 7151 2336 1760 7152 2337 1761 7153 2338 1762 7154 2333 1758 7155 2334 1759 7156 2339 1763 7157 2331 542 7158 2340 542 7159 2335 542 7160 2341 1764 7161 2338 1762 7162 2342 1765 7163 2341 1764 7164 2336 1760 7165 2338 1762 7166 2343 542 7167 2344 542 7168 2340 542 7169 2345 1766 7170 2342 1765 7171 2346 1767 7172 2331 542 7173 2343 542 7174 2340 542 7175 2345 1766 7176 2341 1764 7177 2342 1765 7178 2343 542 7179 2347 542 7180 2344 542 7181 2348 1768 7182 2346 1767 7183 2349 1731 7184 2348 1768 7185 2345 1766 7186 2346 1767 7187 2343 542 7188 2350 542 7189 2347 542 7190 2351 1769 7191 2349 1731 7192 2352 1770 7193 2351 1769 7194 2348 1768 7195 2349 1731 7196 2343 542 7197 1422 542 7198 2350 542 7199 2353 1770 7200 2352 1770 7201 2354 1735 7202 2353 1770 7203 2351 1769 7204 2352 1770 7205 2355 1771 7206 2354 1735 7207 2356 1699 7208 2343 542 7209 1423 542 7210 1422 542 7211 2355 1771 7212 2353 1770 7213 2354 1735 7214 2357 1772 7215 2356 1699 7216 2312 1702 7217 2357 1772 7218 2355 1771 7219 2356 1699 7220 2311 1746 7221 2357 1772 7222 2312 1702 7223 2358 1729 7224 2359 1730 7225 2360 1692 7226 2361 1727 7227 2362 1689 7228 2363 1728 7229 2364 1732 7230 2361 1727 7231 2363 1728 7232 2365 1733 7233 2360 1692 7234 2366 1694 7235 2365 1733 7236 2358 1729 7237 2360 1692 7238 2367 1734 7239 2366 1694 7240 2368 1735 7241 2367 1734 7242 2365 1733 7243 2366 1694 7244 728 542 7245 2369 542 7246 727 542 7247 2370 1736 7248 2368 1735 7249 2371 1737 7250 2370 1736 7251 2367 1734 7252 2368 1735 7253 728 542 7254 2372 542 7255 2369 542 7256 2373 1738 7257 2371 1737 7258 2374 1739 7259 2373 1738 7260 2370 1736 7261 2371 1737 7262 2375 542 7263 2376 542 7264 2372 542 7265 2377 1740 7266 2374 1739 7267 2378 551 7268 728 542 7269 2375 542 7270 2372 542 7271 2377 1740 7272 2373 1738 7273 2374 1739 7274 2375 542 7275 2379 542 7276 2376 542 7277 2380 1741 7278 2378 551 7279 2381 1705 7280 2380 1741 7281 2377 1740 7282 2378 551 7283 2375 542 7284 2382 542 7285 2379 542 7286 2383 1742 7287 2381 1705 7288 2384 1707 7289 2383 1742 7290 2380 1741 7291 2381 1705 7292 2375 542 7293 2385 542 7294 2382 542 7295 2386 1715 7296 2384 1707 7297 2387 1716 7298 2386 1715 7299 2383 1742 7300 2384 1707 7301 717 542 7302 2388 542 7303 2385 542 7304 2389 1712 7305 2390 1713 7306 2391 1710 7307 2375 542 7308 717 542 7309 2385 542 7310 2386 1715 7311 2387 1716 7312 2392 1717 7313 717 542 7314 2393 542 7315 2388 542 7316 2394 1718 7317 2391 1710 7318 2395 1680 7319 2394 1718 7320 2389 1712 7321 2391 1710 7322 717 542 7323 716 542 7324 2393 542 7325 2396 1719 7326 2395 1680 7327 2397 11 7328 2396 1719 7329 2394 1718 7330 2395 1680 7331 2398 1720 7332 2397 11 7333 2399 1721 7334 2398 1720 7335 2396 1719 7336 2397 11 7337 2400 1722 7338 2399 1721 7339 2401 1723 7340 2400 1722 7341 2398 1720 7342 2399 1721 7343 2402 1724 7344 2401 1723 7345 2403 1119 7346 2402 1724 7347 2400 1722 7348 2401 1723 7349 2404 1725 7350 2403 1119 7351 2405 1687 7352 2404 1725 7353 2402 1724 7354 2403 1119 7355 2406 1726 7356 2405 1687 7357 2362 1689 7358 2406 1726 7359 2404 1725 7360 2405 1687 7361 2361 1727 7362 2406 1726 7363 2362 1689 7364 2407 1760 7365 2408 1761 7366 2409 1762 7367 2410 1758 7368 2411 1684 7369 2412 1759 7370 2413 1763 7371 2410 1758 7372 2412 1759 7373 2414 1764 7374 2409 1762 7375 2415 1765 7376 2414 1764 7377 2407 1760 7378 2409 1762 7379 2416 1766 7380 2415 1765 7381 2417 1767 7382 2416 1766 7383 2414 1764 7384 2415 1765 7385 2418 1768 7386 2417 1767 7387 2419 1731 7388 2418 1768 7389 2416 1766 7390 2417 1767 7391 2420 1769 7392 2419 1731 7393 2421 1694 7394 2420 1769 7395 2418 1768 7396 2419 1731 7397 2422 1773 7398 2421 1694 7399 2423 1735 7400 2422 1773 7401 2420 1769 7402 2421 1694 7403 658 542 7404 2424 542 7405 667 542 7406 2425 1771 7407 2423 1735 7408 2426 1699 7409 2425 1771 7410 2422 1773 7411 2423 1735 7412 658 542 7413 2427 542 7414 2424 542 7415 2428 1772 7416 2426 1699 7417 2429 1702 7418 2428 1772 7419 2425 1771 7420 2426 1699 7421 2430 542 7422 2431 542 7423 2427 542 7424 2432 1746 7425 2429 1702 7426 2433 1747 7427 658 542 7428 2430 542 7429 2427 542 7430 2432 1746 7431 2428 1772 7432 2429 1702 7433 2430 542 7434 2434 542 7435 2431 542 7436 2435 1743 7437 2436 1744 7438 2437 1745 7439 2432 1746 7440 2433 1747 7441 2438 1748 7442 2430 542 7443 2439 542 7444 2434 542 7445 2440 1749 7446 2437 1745 7447 2441 1750 7448 2440 1749 7449 2435 1743 7450 2437 1745 7451 2442 542 7452 2443 542 7453 2439 542 7454 2444 1751 7455 2441 1750 7456 2445 1752 7457 2430 542 7458 2442 542 7459 2439 542 7460 2444 1751 7461 2440 1749 7462 2441 1750 7463 2442 542 7464 2446 542 7465 2443 542 7466 2447 1753 7467 2445 1752 7468 2448 1710 7469 2447 1753 7470 2444 1751 7471 2445 1752 7472 2442 542 7473 2449 542 7474 2446 542 7475 2450 1754 7476 2448 1710 7477 2451 1774 7478 2450 1754 7479 2447 1753 7480 2448 1710 7481 2442 542 7482 653 542 7483 2449 542 7484 2452 1774 7485 2451 1774 7486 2453 11 7487 2452 1774 7488 2450 1754 7489 2451 1774 7490 2454 1756 7491 2453 11 7492 2455 1678 7493 2442 542 7494 654 542 7495 653 542 7496 2454 1756 7497 2452 1774 7498 2453 11 7499 2456 1757 7500 2455 1678 7501 2411 1684 7502 2456 1757 7503 2454 1756 7504 2455 1678 7505 2410 1758 7506 2456 1757 7507 2411 1684 7508 2457 1698 7509 2458 1775 7510 2459 1699 7511 1509 542 7512 1508 542 7513 2460 542 7514 2461 1694 7515 2462 1770 7516 2463 1696 7517 2461 1694 7518 2463 1696 7519 2464 1776 7520 2465 1737 7521 2459 1699 7522 2466 1739 7523 2457 1698 7524 2459 1699 7525 2465 1737 7526 2467 1739 7527 2466 1739 7528 2468 551 7529 2465 1737 7530 2466 1739 7531 2467 1739 7532 2469 551 7533 2468 551 7534 2470 1705 7535 2467 1739 7536 2468 551 7537 2469 551 7538 2471 1745 7539 2470 1705 7540 2472 1707 7541 2469 551 7542 2470 1705 7543 2471 1745 7544 2473 1707 7545 2472 1707 7546 2474 560 7547 2471 1745 7548 2472 1707 7549 2473 1707 7550 2475 560 7551 2474 560 7552 2476 1710 7553 2473 1707 7554 2474 560 7555 2475 560 7556 2477 1710 7557 2476 1710 7558 2478 1774 7559 2475 560 7560 2476 1710 7561 2477 1710 7562 2479 1774 7563 2478 1774 7564 2480 1681 7565 2477 1710 7566 2478 1774 7567 2479 1774 7568 2481 542 7569 2482 542 7570 1528 542 7571 2483 1677 7572 2484 1777 7573 2485 1721 7574 2244 542 7575 2481 542 7576 1528 542 7577 2479 1774 7578 2480 1681 7579 2486 1778 7580 2487 542 7581 2488 542 7582 2482 542 7583 2489 1721 7584 2485 1721 7585 2490 1723 7586 2491 542 7587 2487 542 7588 2482 542 7589 2481 542 7590 2491 542 7591 2482 542 7592 2489 1721 7593 2483 1677 7594 2485 1721 7595 2492 542 7596 2493 542 7597 2488 542 7598 2494 1723 7599 2490 1723 7600 2495 1119 7601 2487 542 7602 2492 542 7603 2488 542 7604 2489 1721 7605 2490 1723 7606 2494 1723 7607 2496 542 7608 2497 542 7609 2493 542 7610 2498 1119 7611 2495 1119 7612 2499 1687 7613 2492 542 7614 2496 542 7615 2493 542 7616 2494 1723 7617 2495 1119 7618 2498 1119 7619 2500 542 7620 2501 542 7621 2497 542 7622 2502 1687 7623 2499 1687 7624 2503 1765 7625 2496 542 7626 2500 542 7627 2497 542 7628 2498 1119 7629 2499 1687 7630 2502 1687 7631 2504 542 7632 2505 542 7633 2501 542 7634 2506 1689 7635 2503 1765 7636 2507 1128 7637 2500 542 7638 2504 542 7639 2501 542 7640 2502 1687 7641 2503 1765 7642 2506 1689 7643 2504 542 7644 2508 542 7645 2505 542 7646 2509 1128 7647 2507 1128 7648 2510 1731 7649 2506 1689 7650 2507 1128 7651 2509 1128 7652 1509 542 7653 2460 542 7654 2508 542 7655 2511 1731 7656 2510 1731 7657 2462 1770 7658 2504 542 7659 1509 542 7660 2508 542 7661 2509 1128 7662 2510 1731 7663 2511 1731 7664 2511 1731 7665 2462 1770 7666 2461 1694 7667 2512 542 7668 2513 542 7669 2514 542 7670 2515 1713 7671 2516 1713 7672 2517 1710 7673 2512 542 7674 2514 542 7675 2518 542 7676 2519 1707 7677 2520 1707 7678 2521 1716 7679 2519 1707 7680 2521 1716 7681 2522 1716 7682 678 542 7683 2523 542 7684 2513 542 7685 2524 1710 7686 2517 1710 7687 2525 1680 7688 2512 542 7689 678 542 7690 2513 542 7691 2515 1713 7692 2517 1710 7693 2524 1710 7694 678 542 7695 2526 542 7696 2523 542 7697 2527 1680 7698 2525 1680 7699 2528 11 7700 2524 1710 7701 2525 1680 7702 2527 1680 7703 678 542 7704 694 542 7705 2526 542 7706 2529 11 7707 2528 11 7708 2530 1678 7709 2527 1680 7710 2528 11 7711 2529 11 7712 2531 1678 7713 2530 1678 7714 2532 1684 7715 2529 11 7716 2530 1678 7717 2531 1678 7718 2533 1684 7719 2532 1684 7720 2534 1119 7721 2531 1678 7722 2532 1684 7723 2533 1684 7724 2535 1119 7725 2534 1119 7726 2536 1687 7727 2533 1684 7728 2534 1119 7729 2535 1119 7730 2537 1687 7731 2536 1687 7732 2538 1689 7733 2535 1119 7734 2536 1687 7735 2537 1687 7736 2539 1689 7737 2538 1689 7738 2540 1728 7739 2537 1687 7740 2538 1689 7741 2539 1689 7742 2541 1730 7743 2542 1730 7744 2543 1692 7745 2539 1689 7746 2540 1728 7747 2544 1728 7748 2545 1692 7749 2543 1692 7750 2546 1694 7751 2545 1692 7752 2541 1730 7753 2543 1692 7754 2547 1694 7755 2546 1694 7756 2548 1735 7757 2545 1692 7758 2546 1694 7759 2547 1694 7760 2549 542 7761 2550 542 7762 704 542 7763 2551 1735 7764 2548 1735 7765 2552 1699 7766 705 542 7767 2549 542 7768 704 542 7769 2547 1694 7770 2548 1735 7771 2551 1735 7772 2549 542 7773 2553 542 7774 2550 542 7775 2554 1699 7776 2552 1699 7777 2555 1739 7778 2551 1735 7779 2552 1699 7780 2554 1699 7781 2549 542 7782 2556 542 7783 2553 542 7784 2557 1739 7785 2555 1739 7786 2558 551 7787 2554 1699 7788 2555 1739 7789 2557 1739 7790 2512 542 7791 2559 542 7792 2556 542 7793 2560 551 7794 2558 551 7795 2561 1705 7796 2549 542 7797 2512 542 7798 2556 542 7799 2557 1739 7800 2558 551 7801 2560 551 7802 2512 542 7803 2518 542 7804 2559 542 7805 2562 1705 7806 2561 1705 7807 2520 1707 7808 2560 551 7809 2561 1705 7810 2562 1705 7811 2562 1705 7812 2520 1707 7813 2519 1707 7814 1441 542 7815 1439 542 7816 2563 542 7817 2564 1779 7818 2565 1779 7819 2566 1780 7820 2567 1781 7821 2568 1781 7822 2569 1782 7823 2567 1781 7824 2569 1782 7825 2570 1782 7826 2571 1780 7827 2566 1780 7828 2572 1783 7829 2564 1779 7830 2566 1780 7831 2571 1780 7832 2573 1783 7833 2572 1783 7834 2574 1784 7835 2571 1780 7836 2572 1783 7837 2573 1783 7838 2575 1784 7839 2574 1784 7840 2576 1785 7841 2573 1783 7842 2574 1784 7843 2575 1784 7844 2577 1785 7845 2576 1785 7846 2578 1786 7847 2575 1784 7848 2576 1785 7849 2577 1785 7850 2579 1786 7851 2578 1786 7852 2580 1787 7853 2577 1785 7854 2578 1786 7855 2579 1786 7856 2581 1787 7857 2580 1787 7858 2582 1788 7859 2579 1786 7860 2580 1787 7861 2581 1787 7862 2583 1789 7863 2584 1789 7864 2585 1790 7865 2581 1787 7866 2582 1788 7867 2586 1788 7868 2587 1790 7869 2585 1790 7870 2588 1791 7871 2583 1789 7872 2585 1790 7873 2587 1790 7874 2589 1791 7875 2588 1791 7876 2590 1792 7877 2587 1790 7878 2588 1791 7879 2589 1791 7880 2591 1793 7881 2592 1793 7882 2593 1794 7883 2589 1791 7884 2590 1792 7885 2594 1792 7886 2595 1794 7887 2593 1794 7888 2596 1795 7889 2591 1793 7890 2593 1794 7891 2595 1794 7892 2597 1795 7893 2596 1795 7894 2598 1796 7895 2595 1794 7896 2596 1795 7897 2597 1795 7898 2599 1796 7899 2598 1796 7900 2600 1797 7901 2597 1795 7902 2598 1796 7903 2599 1796 7904 2601 1797 7905 2600 1797 7906 2602 1798 7907 2599 1796 7908 2600 1797 7909 2601 1797 7910 2603 1798 7911 2602 1798 7912 2604 558 7913 2601 1797 7914 2602 1798 7915 2603 1798 7916 2605 558 7917 2604 558 7918 2606 1799 7919 2603 1798 7920 2604 558 7921 2605 558 7922 2607 1799 7923 2606 1799 7924 2608 1800 7925 2605 558 7926 2606 1799 7927 2607 1799 7928 2609 1800 7929 2608 1800 7930 2610 1801 7931 2607 1799 7932 2608 1800 7933 2609 1800 7934 2611 1801 7935 2610 1801 7936 2612 1802 7937 2609 1800 7938 2610 1801 7939 2611 1801 7940 2613 1802 7941 2612 1802 7942 2614 1803 7943 2611 1801 7944 2612 1802 7945 2613 1802 7946 2615 1803 7947 2614 1803 7948 2616 1804 7949 2613 1802 7950 2614 1803 7951 2615 1803 7952 2617 1805 7953 2618 1805 7954 2619 1806 7955 2615 1803 7956 2616 1804 7957 2620 1804 7958 2621 1806 7959 2619 1806 7960 2622 1807 7961 2617 1805 7962 2619 1806 7963 2621 1806 7964 2623 1807 7965 2622 1807 7966 2624 1808 7967 2621 1806 7968 2622 1807 7969 2623 1807 7970 2625 1809 7971 2626 1809 7972 2627 1810 7973 2623 1807 7974 2624 1808 7975 2628 1808 7976 2629 1810 7977 2627 1810 7978 2630 1811 7979 2625 1809 7980 2627 1810 7981 2629 1810 7982 2631 1811 7983 2630 1811 7984 2632 1812 7985 2629 1810 7986 2630 1811 7987 2631 1811 7988 2633 1812 7989 2632 1812 7990 2634 1813 7991 2631 1811 7992 2632 1812 7993 2633 1812 7994 2635 1813 7995 2634 1813 7996 2636 1814 7997 2633 1812 7998 2634 1813 7999 2635 1813 8000 2637 1814 8001 2636 1814 8002 2638 1815 8003 2635 1813 8004 2636 1814 8005 2637 1814 8006 2639 542 8007 2640 542 8008 1510 542 8009 2641 1815 8010 2638 1815 8011 2642 1816 8012 1511 542 8013 2639 542 8014 1510 542 8015 2637 1814 8016 2638 1815 8017 2641 1815 8018 2643 542 8019 2644 542 8020 2640 542 8021 2645 1817 8022 2646 1817 8023 2647 1818 8024 2639 542 8025 2643 542 8026 2640 542 8027 2641 1815 8028 2642 1816 8029 2648 1816 8030 2649 1818 8031 2647 1818 8032 2650 1819 8033 2645 1817 8034 2647 1818 8035 2649 1818 8036 2651 1819 8037 2650 1819 8038 2652 1820 8039 2649 1818 8040 2650 1819 8041 2651 1819 8042 2653 1821 8043 2654 1821 8044 2655 1822 8045 2651 1819 8046 2652 1820 8047 2656 1820 8048 2657 1822 8049 2655 1822 8050 2658 1823 8051 2653 1821 8052 2655 1822 8053 2657 1822 8054 2659 1823 8055 2658 1823 8056 2660 1824 8057 2657 1822 8058 2658 1823 8059 2659 1823 8060 2661 1824 8061 2660 1824 8062 2662 1825 8063 2659 1823 8064 2660 1824 8065 2661 1824 8066 2663 1825 8067 2662 1825 8068 2664 1826 8069 2661 1824 8070 2662 1825 8071 2663 1825 8072 2665 1826 8073 2664 1826 8074 2666 566 8075 2663 1825 8076 2664 1826 8077 2665 1826 8078 2667 566 8079 2666 566 8080 2668 1827 8081 2665 1826 8082 2666 566 8083 2667 566 8084 2669 1827 8085 2668 1827 8086 2670 1828 8087 2667 566 8088 2668 1827 8089 2669 1827 8090 2671 1828 8091 2670 1828 8092 2672 1829 8093 2669 1827 8094 2670 1828 8095 2671 1828 8096 2673 1829 8097 2672 1829 8098 2674 1830 8099 2671 1828 8100 2672 1829 8101 2673 1829 8102 2675 542 8103 2676 542 8104 2481 542 8105 2677 1830 8106 2674 1830 8107 2678 1831 8108 2244 542 8109 2675 542 8110 2481 542 8111 2673 1829 8112 2674 1830 8113 2677 1830 8114 2679 542 8115 2680 542 8116 2676 542 8117 2681 1831 8118 2678 1831 8119 2682 1832 8120 2683 542 8121 2679 542 8122 2676 542 8123 2675 542 8124 2683 542 8125 2676 542 8126 2677 1830 8127 2678 1831 8128 2681 1831 8129 2684 1833 8130 2685 1833 8131 2686 1834 8132 2681 1831 8133 2682 1832 8134 2687 1832 8135 2688 1834 8136 2686 1834 8137 2689 1835 8138 2684 1833 8139 2686 1834 8140 2688 1834 8141 2690 1835 8142 2689 1835 8143 2691 1836 8144 2688 1834 8145 2689 1835 8146 2690 1835 8147 2692 1837 8148 2693 1837 8149 2694 1838 8150 2690 1835 8151 2691 1836 8152 2695 1836 8153 2696 1838 8154 2694 1838 8155 2697 1839 8156 2692 1837 8157 2694 1838 8158 2696 1838 8159 2698 1839 8160 2697 1839 8161 2699 1840 8162 2696 1838 8163 2697 1839 8164 2698 1839 8165 2700 1840 8166 2699 1840 8167 2701 1841 8168 2698 1839 8169 2699 1840 8170 2700 1840 8171 2702 1841 8172 2701 1841 8173 2703 1842 8174 2700 1840 8175 2701 1841 8176 2702 1841 8177 2704 1842 8178 2703 1842 8179 2705 1843 8180 2702 1841 8181 2703 1842 8182 2704 1842 8183 2706 1844 8184 2705 1843 8185 2707 1845 8186 2704 1842 8187 2705 1843 8188 2706 1844 8189 2708 1846 8190 2709 1846 8191 2710 1847 8192 2706 1844 8193 2707 1845 8194 2711 1845 8195 2712 1848 8196 2710 1847 8197 2713 1849 8198 2708 1846 8199 2710 1847 8200 2712 1848 8201 2714 1849 8202 2713 1849 8203 2715 1850 8204 2712 1848 8205 2713 1849 8206 2714 1849 8207 2716 1851 8208 2717 1851 8209 2718 1852 8210 2714 1849 8211 2715 1850 8212 2719 1850 8213 2720 1852 8214 2718 1852 8215 2721 1853 8216 2716 1851 8217 2718 1852 8218 2720 1852 8219 2722 1853 8220 2721 1853 8221 2723 1854 8222 2720 1852 8223 2721 1853 8224 2722 1853 8225 2724 1854 8226 2723 1854 8227 2725 1855 8228 2722 1853 8229 2723 1854 8230 2724 1854 8231 2726 1855 8232 2725 1855 8233 2727 1856 8234 2724 1854 8235 2725 1855 8236 2726 1855 8237 2728 1856 8238 2727 1856 8239 2729 1117 8240 2726 1855 8241 2727 1856 8242 2728 1856 8243 2730 1117 8244 2729 1117 8245 2731 1857 8246 2728 1856 8247 2729 1117 8248 2730 1117 8249 2732 1857 8250 2731 1857 8251 2733 1858 8252 2730 1117 8253 2731 1857 8254 2732 1857 8255 2734 1859 8256 2733 1858 8257 2735 1860 8258 2732 1857 8259 2733 1858 8260 2734 1859 8261 2736 1860 8262 2735 1860 8263 2737 1861 8264 2734 1859 8265 2735 1860 8266 2736 1860 8267 2738 1861 8268 2737 1861 8269 2739 1862 8270 2736 1860 8271 2737 1861 8272 2738 1861 8273 2740 1862 8274 2739 1862 8275 2741 1863 8276 2738 1861 8277 2739 1862 8278 2740 1862 8279 2742 1864 8280 2743 1864 8281 2744 1865 8282 2740 1862 8283 2741 1863 8284 2745 1863 8285 2746 1865 8286 2744 1865 8287 2747 1866 8288 2742 1864 8289 2744 1865 8290 2746 1865 8291 670 542 8292 2748 542 8293 675 542 8294 2749 1866 8295 2747 1866 8296 2750 1867 8297 2746 1865 8298 2747 1866 8299 2749 1866 8300 2751 1868 8301 2752 1868 8302 2753 1869 8303 2749 1866 8304 2750 1867 8305 2754 1867 8306 2755 1869 8307 2753 1869 8308 2756 1870 8309 2751 1868 8310 2753 1869 8311 2755 1869 8312 2757 1870 8313 2756 1870 8314 2758 1871 8315 2755 1869 8316 2756 1870 8317 2757 1870 8318 2759 1871 8319 2758 1871 8320 2760 1872 8321 2757 1870 8322 2758 1871 8323 2759 1871 8324 2761 1872 8325 2760 1872 8326 2762 1873 8327 2759 1871 8328 2760 1872 8329 2761 1872 8330 2763 1873 8331 2762 1873 8332 2764 1874 8333 2761 1872 8334 2762 1873 8335 2763 1873 8336 2765 1874 8337 2764 1874 8338 2766 1875 8339 2763 1873 8340 2764 1874 8341 2765 1874 8342 2767 1876 8343 2768 1876 8344 2769 1877 8345 2765 1874 8346 2766 1875 8347 2770 1875 8348 2771 1877 8349 2769 1877 8350 2772 1878 8351 2767 1876 8352 2769 1877 8353 2771 1877 8354 2773 1878 8355 2772 1878 8356 2774 1879 8357 2771 1877 8358 2772 1878 8359 2773 1878 8360 2775 1880 8361 2776 1880 8362 2777 1881 8363 2773 1878 8364 2774 1879 8365 2778 1879 8366 2779 1881 8367 2777 1881 8368 2780 1882 8369 2775 1880 8370 2777 1881 8371 2779 1881 8372 2781 1882 8373 2780 1882 8374 2782 1883 8375 2779 1881 8376 2780 1882 8377 2781 1882 8378 2783 1883 8379 2782 1883 8380 2784 1884 8381 2781 1882 8382 2782 1883 8383 2783 1883 8384 2785 1884 8385 2784 1884 8386 2786 1885 8387 2783 1883 8388 2784 1884 8389 2785 1884 8390 2787 1885 8391 2786 1885 8392 2788 1126 8393 2785 1884 8394 2786 1885 8395 2787 1885 8396 2789 1126 8397 2788 1126 8398 2790 1886 8399 2787 1885 8400 2788 1126 8401 2789 1126 8402 2791 1886 8403 2790 1886 8404 2792 1887 8405 2789 1126 8406 2790 1886 8407 2791 1886 8408 2793 1887 8409 2792 1887 8410 2794 1888 8411 2791 1886 8412 2792 1887 8413 2793 1887 8414 2795 1888 8415 2794 1888 8416 2796 1889 8417 2793 1887 8418 2794 1888 8419 2795 1888 8420 2797 1889 8421 2796 1889 8422 2798 1890 8423 2795 1888 8424 2796 1889 8425 2797 1889 8426 2799 1890 8427 2798 1890 8428 2800 1891 8429 2797 1889 8430 2798 1890 8431 2799 1890 8432 2801 1892 8433 2802 1892 8434 2803 1893 8435 2799 1890 8436 2800 1891 8437 2804 1891 8438 2805 1893 8439 2803 1893 8440 2806 1894 8441 2801 1892 8442 2803 1893 8443 2805 1893 8444 2807 1894 8445 2806 1894 8446 2808 1895 8447 2805 1893 8448 2806 1894 8449 2807 1894 8450 2809 1896 8451 2810 1896 8452 2811 1897 8453 2807 1894 8454 2808 1895 8455 2812 1895 8456 2813 1897 8457 2811 1897 8458 2814 1898 8459 2809 1896 8460 2811 1897 8461 2813 1897 8462 2815 1898 8463 2814 1898 8464 2816 1899 8465 2813 1897 8466 2814 1898 8467 2815 1898 8468 2817 1899 8469 2816 1899 8470 2818 1900 8471 2815 1898 8472 2816 1899 8473 2817 1899 8474 2819 1900 8475 2818 1900 8476 2820 1901 8477 2817 1899 8478 2818 1900 8479 2819 1900 8480 2821 1901 8481 2820 1901 8482 2822 1902 8483 2819 1900 8484 2820 1901 8485 2821 1901 8486 2823 542 8487 2824 542 8488 746 542 8489 2825 1902 8490 2822 1902 8491 2826 1903 8492 747 542 8493 2823 542 8494 746 542 8495 2821 1901 8496 2822 1902 8497 2825 1902 8498 2827 542 8499 2828 542 8500 2824 542 8501 2829 1904 8502 2830 1904 8503 2831 1905 8504 2823 542 8505 2827 542 8506 2824 542 8507 2825 1902 8508 2826 1903 8509 2832 1903 8510 2833 1905 8511 2831 1905 8512 2834 1906 8513 2829 1904 8514 2831 1905 8515 2833 1905 8516 2835 1906 8517 2834 1906 8518 2836 1907 8519 2833 1905 8520 2834 1906 8521 2835 1906 8522 2837 1908 8523 2838 1908 8524 2839 1909 8525 2835 1906 8526 2836 1907 8527 2840 1907 8528 2841 1909 8529 2839 1909 8530 2842 1910 8531 2837 1908 8532 2839 1909 8533 2841 1909 8534 2843 1910 8535 2842 1910 8536 2844 1911 8537 2841 1909 8538 2842 1910 8539 2843 1910 8540 2845 1911 8541 2844 1911 8542 2846 1912 8543 2843 1910 8544 2844 1911 8545 2845 1911 8546 2847 1912 8547 2846 1912 8548 2848 1913 8549 2845 1911 8550 2846 1912 8551 2847 1912 8552 2849 1914 8553 2848 1913 8554 2850 1134 8555 2847 1912 8556 2848 1913 8557 2849 1914 8558 2851 1134 8559 2850 1134 8560 2852 1915 8561 2849 1914 8562 2850 1134 8563 2851 1134 8564 2853 1916 8565 2852 1915 8566 2854 1917 8567 2851 1134 8568 2852 1915 8569 2853 1916 8570 2855 1917 8571 2854 1917 8572 2856 1918 8573 2853 1916 8574 2854 1917 8575 2855 1917 8576 2857 1918 8577 2856 1918 8578 2858 1919 8579 2855 1917 8580 2856 1918 8581 2857 1918 8582 2859 542 8583 2860 542 8584 764 542 8585 2861 1919 8586 2858 1919 8587 2862 1920 8588 765 542 8589 2859 542 8590 764 542 8591 2857 1918 8592 2858 1919 8593 2861 1919 8594 2863 542 8595 2864 542 8596 2860 542 8597 2865 1920 8598 2862 1920 8599 2866 1921 8600 2867 542 8601 2863 542 8602 2860 542 8603 2859 542 8604 2867 542 8605 2860 542 8606 2861 1919 8607 2862 1920 8608 2865 1920 8609 2868 1922 8610 2869 1922 8611 2870 1923 8612 2865 1920 8613 2866 1921 8614 2871 1921 8615 2872 1923 8616 2870 1923 8617 2873 1924 8618 2868 1922 8619 2870 1923 8620 2872 1923 8621 2874 1924 8622 2873 1924 8623 2875 1925 8624 2872 1923 8625 2873 1924 8626 2874 1924 8627 2876 1926 8628 2877 1926 8629 2878 1927 8630 2874 1924 8631 2875 1925 8632 2879 1925 8633 2880 1927 8634 2878 1927 8635 2881 1928 8636 2876 1926 8637 2878 1927 8638 2880 1927 8639 2882 1928 8640 2881 1928 8641 2883 1929 8642 2880 1927 8643 2881 1928 8644 2882 1928 8645 2884 1929 8646 2883 1929 8647 2885 1930 8648 2882 1928 8649 2883 1929 8650 2884 1929 8651 2886 1930 8652 2885 1930 8653 2887 1931 8654 2884 1929 8655 2885 1930 8656 2886 1930 8657 2888 1931 8658 2887 1931 8659 2889 1932 8660 2886 1930 8661 2887 1931 8662 2888 1931 8663 2890 1933 8664 2889 1932 8665 2891 1934 8666 2888 1931 8667 2889 1932 8668 2890 1933 8669 2892 1935 8670 2893 1935 8671 2894 1936 8672 2890 1933 8673 2891 1934 8674 2895 1934 8675 2896 1937 8676 2894 1936 8677 2897 1938 8678 2892 1935 8679 2894 1936 8680 2896 1937 8681 2898 1938 8682 2897 1938 8683 2899 1939 8684 2896 1937 8685 2897 1938 8686 2898 1938 8687 2900 1940 8688 2901 1940 8689 2902 1941 8690 2898 1938 8691 2899 1939 8692 2903 1939 8693 2904 1941 8694 2902 1941 8695 2905 1942 8696 2904 1941 8697 2900 1940 8698 2902 1941 8699 2906 1942 8700 2905 1942 8701 2907 1943 8702 2904 1941 8703 2905 1942 8704 2906 1942 8705 2908 1943 8706 2907 1943 8707 2909 1944 8708 2906 1942 8709 2907 1943 8710 2908 1943 8711 2910 1944 8712 2909 1944 8713 2911 1945 8714 2908 1943 8715 2909 1944 8716 2910 1944 8717 2912 1945 8718 2911 1945 8719 2913 549 8720 2910 1944 8721 2911 1945 8722 2912 1945 8723 2914 549 8724 2913 549 8725 2915 1946 8726 2912 1945 8727 2913 549 8728 2914 549 8729 2916 1946 8730 2915 1946 8731 2917 1947 8732 2914 549 8733 2915 1946 8734 2916 1946 8735 2918 1947 8736 2917 1947 8737 2919 1948 8738 2916 1946 8739 2917 1947 8740 2918 1947 8741 2920 1948 8742 2919 1948 8743 2921 1949 8744 2918 1947 8745 2919 1948 8746 2920 1948 8747 2922 1949 8748 2921 1949 8749 2923 1950 8750 2920 1948 8751 2921 1949 8752 2922 1949 8753 2924 1950 8754 2923 1950 8755 2925 1951 8756 2922 1949 8757 2923 1950 8758 2924 1950 8759 2926 1952 8760 2927 1952 8761 2928 1953 8762 2924 1950 8763 2925 1951 8764 2929 1951 8765 2930 1953 8766 2928 1953 8767 2568 1781 8768 2926 1952 8769 2928 1953 8770 2930 1953 8771 2930 1953 8772 2568 1781 8773 2567 1781 8774 2931 1479 8775 2932 1479 8776 2933 1954 8777 2934 1484 8778 2935 1484 8779 2936 1955 8780 2934 1484 8781 2936 1955 8782 2937 1955 8783 2938 1954 8784 2933 1954 8785 2939 1956 8786 2938 1954 8787 2931 1479 8788 2933 1954 8789 2940 1956 8790 2939 1956 8791 2941 1957 8792 2938 1954 8793 2939 1956 8794 2940 1956 8795 2942 1957 8796 2941 1957 8797 2943 1958 8798 2940 1956 8799 2941 1957 8800 2942 1957 8801 2944 1959 8802 2943 1958 8803 2945 1960 8804 2942 1957 8805 2943 1958 8806 2944 1959 8807 2946 1130 8808 2945 1960 8809 2947 1961 8810 2944 1959 8811 2945 1960 8812 2946 1130 8813 2948 1962 8814 2947 1961 8815 2949 1963 8816 2946 1130 8817 2947 1961 8818 2948 1962 8819 2950 1964 8820 2949 1963 8821 2951 1965 8822 2948 1962 8823 2949 1963 8824 2950 1964 8825 2952 1965 8826 2951 1965 8827 2953 1966 8828 2950 1964 8829 2951 1965 8830 2952 1965 8831 2954 1967 8832 2953 1966 8833 2955 1123 8834 2952 1965 8835 2953 1966 8836 2954 1967 8837 2956 1123 8838 2955 1123 8839 2957 1968 8840 2954 1967 8841 2955 1123 8842 2956 1123 8843 2958 1969 8844 2957 1968 8845 2959 1970 8846 2956 1123 8847 2957 1968 8848 2958 1969 8849 2960 1970 8850 2959 1970 8851 2961 1971 8852 2958 1969 8853 2959 1970 8854 2960 1970 8855 2962 1972 8856 2961 1971 8857 2963 1973 8858 2960 1970 8859 2961 1971 8860 2962 1972 8861 2964 1974 8862 2963 1973 8863 2965 1117 8864 2962 1972 8865 2963 1973 8866 2964 1974 8867 2966 1117 8868 2965 1117 8869 2967 1975 8870 2964 1974 8871 2965 1117 8872 2966 1117 8873 2968 1976 8874 2967 1975 8875 2969 1977 8876 2966 1117 8877 2967 1975 8878 2968 1976 8879 2970 1977 8880 2969 1977 8881 2971 1978 8882 2968 1976 8883 2969 1977 8884 2970 1977 8885 2972 1978 8886 2971 1978 8887 2973 1979 8888 2970 1977 8889 2971 1978 8890 2972 1978 8891 2974 1979 8892 2973 1979 8893 2975 1980 8894 2972 1978 8895 2973 1979 8896 2974 1979 8897 2976 1981 8898 2977 1981 8899 2978 1982 8900 2974 1979 8901 2975 1980 8902 2979 1980 8903 2980 1982 8904 2978 1982 8905 2981 1983 8906 2976 1981 8907 2978 1982 8908 2980 1982 8909 2982 1983 8910 2981 1983 8911 2983 1984 8912 2980 1982 8913 2981 1983 8914 2982 1983 8915 2984 1984 8916 2983 1984 8917 2985 1985 8918 2982 1983 8919 2983 1984 8920 2984 1984 8921 2986 1986 8922 2985 1985 8923 2987 1987 8924 2984 1984 8925 2985 1985 8926 2986 1986 8927 2988 562 8928 2987 1987 8929 2989 1988 8930 2986 1986 8931 2987 1987 8932 2988 562 8933 2990 1989 8934 2989 1988 8935 2991 1990 8936 2988 562 8937 2989 1988 8938 2990 1989 8939 2992 1991 8940 2991 1990 8941 2993 1992 8942 2990 1989 8943 2991 1990 8944 2992 1991 8945 2994 1992 8946 2993 1992 8947 2995 1993 8948 2992 1991 8949 2993 1992 8950 2994 1992 8951 2996 1994 8952 2995 1993 8953 2997 555 8954 2994 1992 8955 2995 1993 8956 2996 1994 8957 2998 555 8958 2997 555 8959 2999 1995 8960 2996 1994 8961 2997 555 8962 2998 555 8963 3000 1996 8964 2999 1995 8965 3001 1997 8966 2998 555 8967 2999 1995 8968 3000 1996 8969 3002 1997 8970 3001 1997 8971 3003 1998 8972 3000 1996 8973 3001 1997 8974 3002 1997 8975 3004 1999 8976 3003 1998 8977 3005 2000 8978 3002 1997 8979 3003 1998 8980 3004 1999 8981 3006 2001 8982 3005 2000 8983 3007 549 8984 3004 1999 8985 3005 2000 8986 3006 2001 8987 3008 549 8988 3007 549 8989 3009 2002 8990 3006 2001 8991 3007 549 8992 3008 549 8993 3010 2003 8994 3009 2002 8995 3011 2004 8996 3008 549 8997 3009 2002 8998 3010 2003 8999 3012 2004 9000 3011 2004 9001 3013 2005 9002 3010 2003 9003 3011 2004 9004 3012 2004 9005 3014 2005 9006 3013 2005 9007 2935 1484 9008 3012 2004 9009 3013 2005 9010 3014 2005 9011 3014 2005 9012 2935 1484 9013 2934 1484 9014 3015 31 9015 3016 31 9016 3017 31 9017 3018 2006 9018 3019 2006 9019 3020 2007 9020 3021 31 9021 3017 31 9022 3022 31 9023 3023 2008 9024 3024 2008 9025 3025 2009 9026 3021 31 9027 3015 31 9028 3017 31 9029 3023 2008 9030 3025 2009 9031 3026 2009 9032 3015 31 9033 3027 31 9034 3016 31 9035 3028 2007 9036 3020 2007 9037 3029 1698 9038 3018 2006 9039 3020 2007 9040 3028 2007 9041 3030 31 9042 3031 31 9043 3027 31 9044 3032 1698 9045 3029 1698 9046 3033 2010 9047 3015 31 9048 3030 31 9049 3027 31 9050 3028 2007 9051 3029 1698 9052 3032 1698 9053 3030 2011 9054 3034 2011 9055 3031 2011 9056 3035 2010 9057 3033 2010 9058 3036 1737 9059 3032 1698 9060 3033 2010 9061 3035 2010 9062 3037 31 9063 3038 31 9064 3034 31 9065 3039 1737 9066 3036 1737 9067 3040 2012 9068 3030 31 9069 3037 31 9070 3034 31 9071 3035 2010 9072 3036 1737 9073 3039 1737 9074 3037 31 9075 3041 31 9076 3038 31 9077 3042 2013 9078 3040 2012 9079 3043 547 9080 3039 1737 9081 3040 2012 9082 3042 2013 9083 3044 31 9084 3045 31 9085 3041 31 9086 3046 547 9087 3043 547 9088 3047 2014 9089 3037 31 9090 3044 31 9091 3041 31 9092 3042 2013 9093 3043 547 9094 3046 547 9095 3044 2015 9096 3048 2015 9097 3045 2015 9098 3049 2016 9099 3047 2014 9100 3050 1740 9101 3046 547 9102 3047 2014 9103 3049 2016 9104 3051 2017 9105 3052 2017 9106 3048 2017 9107 3053 1740 9108 3050 1740 9109 3054 2018 9110 3044 31 9111 3051 31 9112 3048 31 9113 3049 2016 9114 3050 1740 9115 3053 1740 9116 3055 2019 9117 3056 2019 9118 3052 2019 9119 3057 549 9120 3054 2018 9121 3058 1747 9122 3051 2020 9123 3055 2020 9124 3052 2020 9125 3053 1740 9126 3054 2018 9127 3057 549 9128 3055 31 9129 3059 31 9130 3056 31 9131 3060 2021 9132 3058 1747 9133 3061 2022 9134 3057 549 9135 3058 1747 9136 3060 2021 9137 3062 31 9138 3063 31 9139 3059 31 9140 3064 2023 9141 3061 2022 9142 3065 551 9143 3055 31 9144 3062 31 9145 3059 31 9146 3060 2021 9147 3061 2022 9148 3064 2023 9149 3066 31 9150 3067 31 9151 3063 31 9152 3068 2024 9153 3065 551 9154 3069 2025 9155 3062 31 9156 3066 31 9157 3063 31 9158 3064 2023 9159 3065 551 9160 3068 2024 9161 3070 31 9162 3071 31 9163 3067 31 9164 3072 2025 9165 3069 2025 9166 3073 2026 9167 3074 31 9168 3070 31 9169 3067 31 9170 3066 2027 9171 3074 2027 9172 3067 2027 9173 3068 2024 9174 3069 2025 9175 3072 2025 9176 3075 31 9177 3076 31 9178 3071 31 9179 3077 1744 9180 3073 2026 9181 3078 553 9182 3070 31 9183 3075 31 9184 3071 31 9185 3072 2025 9186 3073 2026 9187 3077 1744 9188 3079 31 9189 3080 31 9190 3076 31 9191 3081 2028 9192 3078 553 9193 3082 1705 9194 3075 31 9195 3079 31 9196 3076 31 9197 3077 1744 9198 3078 553 9199 3081 2028 9200 3083 31 9201 3084 31 9202 3080 31 9203 3085 1745 9204 3082 1705 9205 3086 2029 9206 3079 31 9207 3083 31 9208 3080 31 9209 3081 2028 9210 3082 1705 9211 3085 1745 9212 3083 31 9213 3087 31 9214 3084 31 9215 3088 2030 9216 3086 2029 9217 3089 555 9218 3085 1745 9219 3086 2029 9220 3088 2030 9221 3090 555 9222 3089 555 9223 3091 2031 9224 3088 2030 9225 3089 555 9226 3090 555 9227 3092 2032 9228 3091 2031 9229 3093 1707 9230 3090 555 9231 3091 2031 9232 3092 2032 9233 3094 1750 9234 3093 1707 9235 3095 558 9236 3092 2032 9237 3093 1707 9238 3094 1750 9239 3096 2033 9240 3095 558 9241 3097 2034 9242 3094 1750 9243 3095 558 9244 3096 2033 9245 3074 31 9246 3098 31 9247 3070 31 9248 3099 2035 9249 3097 2034 9250 3100 2036 9251 3096 2033 9252 3097 2034 9253 3099 2035 9254 3101 31 9255 3102 31 9256 3098 31 9257 3103 2036 9258 3100 2036 9259 3104 560 9260 3074 2037 9261 3101 2037 9262 3098 2037 9263 3099 2035 9264 3100 2036 9265 3103 2036 9266 3105 31 9267 3106 31 9268 3102 31 9269 3107 560 9270 3104 560 9271 3108 2038 9272 3101 2039 9273 3105 2039 9274 3102 2039 9275 3103 2036 9276 3104 560 9277 3107 560 9278 3109 31 9279 3110 31 9280 3106 31 9281 3111 2040 9282 3108 2038 9283 3112 1713 9284 3105 31 9285 3109 31 9286 3106 31 9287 3107 560 9288 3108 2038 9289 3111 2040 9290 3113 31 9291 3114 31 9292 3110 31 9293 3115 2041 9294 3112 1713 9295 3116 2042 9296 3109 31 9297 3113 31 9298 3110 31 9299 3111 2040 9300 3112 1713 9301 3115 2041 9302 3113 2043 9303 3117 2043 9304 3114 2043 9305 3118 562 9306 3116 2042 9307 3119 1754 9308 3115 2041 9309 3116 2042 9310 3118 562 9311 3120 2044 9312 3121 2044 9313 3117 2044 9314 3122 1754 9315 3119 1754 9316 3123 2045 9317 3113 31 9318 3120 31 9319 3117 31 9320 3118 562 9321 3119 1754 9322 3122 1754 9323 3124 31 9324 3125 31 9325 3121 31 9326 3126 2046 9327 3123 2045 9328 3127 564 9329 3120 31 9330 3124 31 9331 3121 31 9332 3122 1754 9333 3123 2045 9334 3126 2046 9335 3124 31 9336 3128 31 9337 3125 31 9338 3129 564 9339 3127 564 9340 3130 2047 9341 3126 2046 9342 3127 564 9343 3129 564 9344 3131 31 9345 3132 31 9346 3128 31 9347 3133 2048 9348 3130 2047 9349 3134 1774 9350 3124 31 9351 3131 31 9352 3128 31 9353 3129 564 9354 3130 2047 9355 3133 2048 9356 3131 2049 9357 3135 2049 9358 3132 2049 9359 3136 1774 9360 3134 1774 9361 3137 2050 9362 3133 2048 9363 3134 1774 9364 3136 1774 9365 3138 31 9366 3139 31 9367 3135 31 9368 3140 2050 9369 3137 2050 9370 3141 1681 9371 3131 31 9372 3138 31 9373 3135 31 9374 3136 1774 9375 3137 2050 9376 3140 2050 9377 3138 31 9378 3142 31 9379 3139 31 9380 3143 1681 9381 3141 1681 9382 3144 2051 9383 3140 2050 9384 3141 1681 9385 3143 1681 9386 3145 31 9387 3146 31 9388 3142 31 9389 3147 2051 9390 3144 2051 9391 3148 2052 9392 3138 31 9393 3145 31 9394 3142 31 9395 3143 1681 9396 3144 2051 9397 3147 2051 9398 3149 31 9399 3150 31 9400 3146 31 9401 3151 2053 9402 3152 2053 9403 3153 2054 9404 3149 31 9405 3146 31 9406 3145 31 9407 3147 2051 9408 3148 2052 9409 3154 2052 9410 3149 31 9411 3155 31 9412 3150 31 9413 3156 2054 9414 3153 2054 9415 3157 1677 9416 3156 2054 9417 3151 2053 9418 3153 2054 9419 3158 31 9420 3159 31 9421 3155 31 9422 3160 1677 9423 3157 1677 9424 3161 2055 9425 3149 31 9426 3158 31 9427 3155 31 9428 3156 2054 9429 3157 1677 9430 3160 1677 9431 3158 2049 9432 3162 2049 9433 3159 2049 9434 3163 2055 9435 3161 2055 9436 3164 1721 9437 3160 1677 9438 3161 2055 9439 3163 2055 9440 3165 31 9441 3166 31 9442 3162 31 9443 3167 1721 9444 3164 1721 9445 3168 2056 9446 3158 31 9447 3165 31 9448 3162 31 9449 3163 2055 9450 3164 1721 9451 3167 1721 9452 3165 31 9453 3169 31 9454 3166 31 9455 3170 2057 9456 3168 2056 9457 3171 1115 9458 3167 1721 9459 3168 2056 9460 3170 2057 9461 3172 31 9462 3173 31 9463 3169 31 9464 3174 1115 9465 3171 1115 9466 3175 2058 9467 3165 31 9468 3172 31 9469 3169 31 9470 3170 2057 9471 3171 1115 9472 3174 1115 9473 3172 2044 9474 3176 2044 9475 3173 2044 9476 3177 2059 9477 3175 2058 9478 3178 1724 9479 3174 1115 9480 3175 2058 9481 3177 2059 9482 3179 2043 9483 3180 2043 9484 3176 2043 9485 3181 1724 9486 3178 1724 9487 3182 2060 9488 3172 31 9489 3179 31 9490 3176 31 9491 3177 2059 9492 3178 1724 9493 3181 1724 9494 3183 2061 9495 3184 2061 9496 3180 2061 9497 3185 1117 9498 3182 2060 9499 3186 1759 9500 3179 2062 9501 3183 2062 9502 3180 2062 9503 3181 1724 9504 3182 2060 9505 3185 1117 9506 3183 31 9507 3187 31 9508 3184 31 9509 3188 2063 9510 3186 1759 9511 3189 2064 9512 3185 1117 9513 3186 1759 9514 3188 2063 9515 3190 31 9516 3191 31 9517 3187 31 9518 3192 2065 9519 3189 2064 9520 3193 1119 9521 3183 31 9522 3190 31 9523 3187 31 9524 3188 2063 9525 3189 2064 9526 3192 2065 9527 3194 31 9528 3195 31 9529 3191 31 9530 3196 2066 9531 3193 1119 9532 3197 2067 9533 3190 31 9534 3194 31 9535 3191 31 9536 3192 2065 9537 3193 1119 9538 3196 2066 9539 3198 31 9540 3199 31 9541 3195 31 9542 3200 2067 9543 3197 2067 9544 3201 2068 9545 3202 31 9546 3198 31 9547 3195 31 9548 3194 2069 9549 3202 2069 9550 3195 2069 9551 3196 2066 9552 3197 2067 9553 3200 2067 9554 3203 31 9555 3204 31 9556 3199 31 9557 3205 1761 9558 3201 2068 9559 3206 1121 9560 3198 31 9561 3203 31 9562 3199 31 9563 3200 2067 9564 3201 2068 9565 3205 1761 9566 3207 31 9567 3208 31 9568 3204 31 9569 3209 2070 9570 3206 1121 9571 3210 1687 9572 3203 31 9573 3207 31 9574 3204 31 9575 3205 1761 9576 3206 1121 9577 3209 2070 9578 3211 31 9579 3212 31 9580 3208 31 9581 3213 1762 9582 3210 1687 9583 3214 2071 9584 3207 31 9585 3211 31 9586 3208 31 9587 3209 2070 9588 3210 1687 9589 3213 1762 9590 3211 31 9591 3215 31 9592 3212 31 9593 3216 2072 9594 3214 2071 9595 3217 1123 9596 3213 1762 9597 3214 2071 9598 3216 2072 9599 3218 1123 9600 3217 1123 9601 3219 2073 9602 3216 2072 9603 3217 1123 9604 3218 1123 9605 3220 2074 9606 3219 2073 9607 3221 1689 9608 3218 1123 9609 3219 2073 9610 3220 2074 9611 3222 1765 9612 3221 1689 9613 3223 1126 9614 3220 2074 9615 3221 1689 9616 3222 1765 9617 3224 2075 9618 3223 1126 9619 3225 2076 9620 3222 1765 9621 3223 1126 9622 3224 2075 9623 3202 31 9624 3226 31 9625 3198 31 9626 3227 2077 9627 3225 2076 9628 3228 2078 9629 3224 2075 9630 3225 2076 9631 3227 2077 9632 3229 31 9633 3230 31 9634 3226 31 9635 3231 2078 9636 3228 2078 9637 3232 1128 9638 3202 2079 9639 3229 2079 9640 3226 2079 9641 3227 2077 9642 3228 2078 9643 3231 2078 9644 3233 31 9645 3234 31 9646 3230 31 9647 3235 1128 9648 3232 1128 9649 3236 2080 9650 3229 2081 9651 3233 2081 9652 3230 2081 9653 3231 2078 9654 3232 1128 9655 3235 1128 9656 3237 31 9657 3238 31 9658 3234 31 9659 3239 2082 9660 3236 2080 9661 3240 1730 9662 3233 31 9663 3237 31 9664 3234 31 9665 3235 1128 9666 3236 2080 9667 3239 2082 9668 3241 31 9669 3242 31 9670 3238 31 9671 3243 2083 9672 3240 1730 9673 3244 2084 9674 3237 31 9675 3241 31 9676 3238 31 9677 3239 2082 9678 3240 1730 9679 3243 2083 9680 3241 2017 9681 3245 2017 9682 3242 2017 9683 3246 1130 9684 3244 2084 9685 3247 1769 9686 3243 2083 9687 3244 2084 9688 3246 1130 9689 3248 2015 9690 3249 2015 9691 3245 2015 9692 3250 1769 9693 3247 1769 9694 3251 2085 9695 3241 31 9696 3248 31 9697 3245 31 9698 3246 1130 9699 3247 1769 9700 3250 1769 9701 3252 31 9702 3253 31 9703 3249 31 9704 3254 2086 9705 3251 2085 9706 3255 1132 9707 3248 31 9708 3252 31 9709 3249 31 9710 3250 1769 9711 3251 2085 9712 3254 2086 9713 3252 31 9714 3256 31 9715 3253 31 9716 3257 1132 9717 3255 1132 9718 3258 2087 9719 3254 2086 9720 3255 1132 9721 3257 1132 9722 3259 31 9723 3260 31 9724 3256 31 9725 3261 2088 9726 3258 2087 9727 3262 1770 9728 3252 31 9729 3259 31 9730 3256 31 9731 3257 1132 9732 3258 2087 9733 3261 2088 9734 3259 2011 9735 3263 2011 9736 3260 2011 9737 3264 1770 9738 3262 1770 9739 3265 2089 9740 3261 2088 9741 3262 1770 9742 3264 1770 9743 3266 31 9744 3267 31 9745 3263 31 9746 3268 2089 9747 3265 2089 9748 3269 1696 9749 3259 31 9750 3266 31 9751 3263 31 9752 3264 1770 9753 3265 2089 9754 3268 2089 9755 3266 31 9756 3022 31 9757 3267 31 9758 3270 1696 9759 3269 1696 9760 3024 2008 9761 3268 2089 9762 3269 1696 9763 3270 1696 9764 3266 31 9765 3021 31 9766 3022 31 9767 3270 1696 9768 3024 2008 9769 3023 2008 9770 3271 2008 9771 3272 2008 9772 3273 1696 9773 3274 1698 9774 3275 1698 9775 3276 2007 9776 3274 1698 9777 3276 2007 9778 3277 2007 9779 3278 1696 9780 3273 1696 9781 3279 1770 9782 3278 1696 9783 3271 2008 9784 3273 1696 9785 3280 1770 9786 3279 1770 9787 3281 1132 9788 3278 1696 9789 3279 1770 9790 3280 1770 9791 3282 1132 9792 3281 1132 9793 3283 1769 9794 3280 1770 9795 3281 1132 9796 3282 1132 9797 3284 1769 9798 3283 1769 9799 3285 1730 9800 3282 1132 9801 3283 1769 9802 3284 1769 9803 3286 2083 9804 3285 1730 9805 3287 1128 9806 3284 1769 9807 3285 1730 9808 3286 2083 9809 3288 1128 9810 3287 1128 9811 3289 2076 9812 3286 2083 9813 3287 1128 9814 3288 1128 9815 3290 2077 9816 3289 2076 9817 3291 1689 9818 3288 1128 9819 3289 2076 9820 3290 2077 9821 3292 1765 9822 3291 1689 9823 3293 1123 9824 3290 2077 9825 3291 1689 9826 3292 1765 9827 3294 1123 9828 3293 1123 9829 3295 1687 9830 3292 1765 9831 3293 1123 9832 3294 1123 9833 3296 1762 9834 3295 1687 9835 3297 2068 9836 3294 1123 9837 3295 1687 9838 3296 1762 9839 3298 1761 9840 3297 2068 9841 3299 1119 9842 3296 1762 9843 3297 2068 9844 3298 1761 9845 3300 1119 9846 3299 1119 9847 3301 1759 9848 3298 1761 9849 3299 1119 9850 3300 1119 9851 3302 2063 9852 3301 1759 9853 3303 1724 9854 3300 1119 9855 3301 1759 9856 3302 2063 9857 3304 1684 9858 3303 1724 9859 3305 1115 9860 3302 2063 9861 3303 1724 9862 3304 1684 9863 3306 1115 9864 3305 1115 9865 3307 1721 9866 3304 1684 9867 3305 1115 9868 3306 1115 9869 3308 1721 9870 3307 1721 9871 3309 1677 9872 3306 1115 9873 3307 1721 9874 3308 1721 9875 3310 1677 9876 3309 1677 9877 3311 2054 9878 3308 1721 9879 3309 1677 9880 3310 1677 9881 3312 2051 9882 3313 2051 9883 3314 1681 9884 3310 1677 9885 3311 2054 9886 3315 2054 9887 3316 1681 9888 3314 1681 9889 3317 1774 9890 3312 2051 9891 3314 1681 9892 3316 1681 9893 3318 1774 9894 3317 1774 9895 3319 564 9896 3316 1681 9897 3317 1774 9898 3318 1774 9899 3320 564 9900 3319 564 9901 3321 1754 9902 3318 1774 9903 3319 564 9904 3320 564 9905 3322 1754 9906 3321 1754 9907 3323 1713 9908 3320 564 9909 3321 1754 9910 3322 1754 9911 3324 2041 9912 3323 1713 9913 3325 560 9914 3322 1754 9915 3323 1713 9916 3324 2041 9917 3326 560 9918 3325 560 9919 3327 2034 9920 3324 2041 9921 3325 560 9922 3326 560 9923 3328 2035 9924 3327 2034 9925 3329 1707 9926 3326 560 9927 3327 2034 9928 3328 2035 9929 3330 1750 9930 3329 1707 9931 3331 555 9932 3328 2035 9933 3329 1707 9934 3330 1750 9935 3332 555 9936 3331 555 9937 3333 1705 9938 3330 1750 9939 3331 555 9940 3332 555 9941 3334 1745 9942 3333 1705 9943 3335 2026 9944 3332 555 9945 3333 1705 9946 3334 1745 9947 3336 1744 9948 3335 2026 9949 3337 551 9950 3334 1745 9951 3335 2026 9952 3336 1744 9953 3338 551 9954 3337 551 9955 3339 1747 9956 3336 1744 9957 3337 551 9958 3338 551 9959 3340 2021 9960 3339 1747 9961 3341 1740 9962 3338 551 9963 3339 1747 9964 3340 2021 9965 3342 1702 9966 3341 1740 9967 3343 547 9968 3340 2021 9969 3341 1740 9970 3342 1702 9971 3344 547 9972 3343 547 9973 3345 1737 9974 3342 1702 9975 3343 547 9976 3344 547 9977 3346 1737 9978 3345 1737 9979 3275 1698 9980 3344 547 9981 3345 1737 9982 3346 1737 9983 3346 1737 9984 3275 1698 9985 3274 1698 9986 3347 2090 9987 3348 2091 9988 3349 2092 9989 3350 2093 9990 3351 2094 9991 3352 2095 9992 3350 2093 9993 3352 2095 9994 3353 2096 9995 3354 2097 9996 3349 2092 9997 3355 2098 9998 3354 2097 9999 3347 2090 10000 3349 2092 10001 3356 2099 10002 3355 2098 10003 3357 2100 10004 3354 2097 10005 3355 2098 10006 3356 2099 10007 3358 2101 10008 3357 2100 10009 3359 2102 10010 3356 2099 10011 3357 2100 10012 3358 2101 10013 3360 2103 10014 3359 2102 10015 3361 2104 10016 3358 2101 10017 3359 2102 10018 3360 2103 10019 3362 2105 10020 3361 2104 10021 3363 2106 10022 3360 2103 10023 3361 2104 10024 3362 2105 10025 3364 2107 10026 3363 2106 10027 3365 2108 10028 3362 2105 10029 3363 2106 10030 3364 2107 10031 3366 2109 10032 3365 2108 10033 3367 2110 10034 3364 2107 10035 3365 2108 10036 3366 2109 10037 3368 2111 10038 3367 2110 10039 3369 2112 10040 3366 2109 10041 3367 2110 10042 3368 2111 10043 3370 2113 10044 3371 2113 10045 3372 2114 10046 3368 2111 10047 3369 2112 10048 3373 2112 10049 3374 2115 10050 3372 2114 10051 3375 2116 10052 3370 2113 10053 3372 2114 10054 3374 2115 10055 3376 2117 10056 3375 2116 10057 3377 2118 10058 3374 2115 10059 3375 2116 10060 3376 2117 10061 3378 2119 10062 3377 2118 10063 3379 2120 10064 3376 2117 10065 3377 2118 10066 3378 2119 10067 3380 2121 10068 3379 2120 10069 3381 2122 10070 3378 2119 10071 3379 2120 10072 3380 2121 10073 3382 2123 10074 3381 2122 10075 3383 2124 10076 3380 2121 10077 3381 2122 10078 3382 2123 10079 3384 2125 10080 3383 2124 10081 3385 2126 10082 3382 2123 10083 3383 2124 10084 3384 2125 10085 3386 2127 10086 3385 2126 10087 3351 2094 10088 3384 2125 10089 3385 2126 10090 3386 2127 10091 3386 2127 10092 3351 2094 10093 3350 2093 10094 3393 11 10095 3394 11 10096 3395 11 10097 3424 2128 10098 3425 2128 10099 3426 2128 10100 3427 2129 10101 3428 2130 10102 3429 2131 10103 3430 1735 10104 3424 1735 10105 3426 1735 10106 3431 2132 10107 3432 2132 10108 3433 2132 10109 3434 2133 10110 3431 2133 10111 3433 2133 10112 3434 2134 10113 3433 2134 10114 3435 2134 10115 3436 2135 10116 3429 2131 10117 3437 2136 10118 3438 2137 10119 3427 2129 10120 3429 2131 10121 3436 2135 10122 3438 2137 10123 3429 2131 10124 3430 2138 10125 3439 2138 10126 3424 2138 10127 3440 2139 10128 3441 2139 10129 3442 2139 10130 3443 2140 10131 3436 2135 10132 3437 2136 10133 3444 2141 10134 3443 2140 10135 3437 2136 10136 3445 2142 10137 3446 2142 10138 3439 2142 10139 3447 2143 10140 3448 2144 10141 3449 2145 10142 3430 1735 10143 3445 1735 10144 3439 1735 10145 3450 2146 10146 3442 2146 10147 3451 2146 10148 3450 2147 10149 3440 2147 10150 3442 2147 10151 3452 2148 10152 3453 2148 10153 3446 2148 10154 3454 2149 10155 3449 2145 10156 3455 2150 10157 3445 2151 10158 3452 2151 10159 3446 2151 10160 3454 2149 10161 3447 2143 10162 3449 2145 10163 3456 1735 10164 3457 1735 10165 3453 1735 10166 3458 542 10167 3459 542 10168 3460 542 10169 3452 1735 10170 3456 1735 10171 3453 1735 10172 3461 2152 10173 3454 2149 10174 3455 2150 10175 3462 2153 10176 3463 2153 10177 3457 2153 10178 3464 2154 10179 3465 2155 10180 3466 2156 10181 3456 1735 10182 3462 1735 10183 3457 1735 10184 3467 542 10185 3458 542 10186 3460 542 10187 3467 542 10188 3460 542 10189 3468 542 10190 3469 2157 10191 3470 2157 10192 3463 2157 10193 3471 2158 10194 3466 2156 10195 3472 2159 10196 3462 1735 10197 3469 1735 10198 3463 1735 10199 3471 2158 10200 3464 2154 10201 3466 2156 10202 3473 1735 10203 3474 1735 10204 3470 1735 10205 3475 2160 10206 3476 2160 10207 3477 2160 10208 3469 1735 10209 3473 1735 10210 3470 1735 10211 3478 2161 10212 3471 2158 10213 3472 2159 10214 3473 2162 10215 3479 2162 10216 3474 2162 10217 3480 2163 10218 3481 2164 10219 3482 2165 10220 3483 2166 10221 3475 2166 10222 3477 2166 10223 3483 2167 10224 3477 2167 10225 3484 2167 10226 3485 2168 10227 3482 2165 10228 3486 2169 10229 3487 2170 10230 3480 2163 10231 3482 2165 10232 3485 2168 10233 3487 2170 10234 3482 2165 10235 3488 2171 10236 3489 2171 10237 3490 2171 10238 3491 2172 10239 3485 2168 10240 3486 2169 10241 3492 2173 10242 3491 2172 10243 3486 2169 10244 3493 2174 10245 3494 2175 10246 3495 2176 10247 3496 2177 10248 3490 2177 10249 3497 2177 10250 3496 2178 10251 3488 2178 10252 3490 2178 10253 3498 2179 10254 3495 2176 10255 3499 2180 10256 3498 2179 10257 3493 2174 10258 3495 2176 10259 3500 31 10260 3501 31 10261 3502 31 10262 3503 2181 10263 3498 2179 10264 3499 2180 10265 3504 2182 10266 3505 2183 10267 3506 2184 10268 3507 31 10269 3502 31 10270 3508 31 10271 3507 31 10272 3500 31 10273 3502 31 10274 3509 2185 10275 3506 2184 10276 3510 2186 10277 3509 2185 10278 3504 2182 10279 3506 2184 10280 3511 2187 10281 3509 2185 10282 3510 2186 10283 3512 11 10284 3513 11 10285 3514 11 10286 3515 2188 10287 3516 2189 10288 3517 2190 10289 3518 11 10290 3514 11 10291 3519 11 10292 3520 2191 10293 3521 2191 10294 3522 2192 10295 3518 11 10296 3512 11 10297 3514 11 10298 3520 2191 10299 3522 2192 10300 3523 2192 10301 3524 11 10302 3525 11 10303 3513 11 10304 3526 2190 10305 3517 2190 10306 3527 2193 10307 3528 11 10308 3524 11 10309 3513 11 10310 3512 2194 10311 3528 2194 10312 3513 2194 10313 3526 2190 10314 3515 2188 10315 3517 2190 10316 3529 11 10317 3530 11 10318 3525 11 10319 3531 2195 10320 3527 2193 10321 3532 2196 10322 3524 2197 10323 3529 2197 10324 3525 2197 10325 3526 2190 10326 3527 2193 10327 3531 2195 10328 3529 11 10329 3533 11 10330 3530 11 10331 3534 2198 10332 3532 2196 10333 3535 2199 10334 3531 2195 10335 3532 2196 10336 3534 2198 10337 3536 11 10338 3537 11 10339 3533 11 10340 3538 2200 10341 3535 2199 10342 3539 2201 10343 3540 2202 10344 3536 2202 10345 3533 2202 10346 3529 11 10347 3540 11 10348 3533 11 10349 3534 2198 10350 3535 2199 10351 3538 2200 10352 3541 11 10353 3542 11 10354 3537 11 10355 3543 2203 10356 3539 2201 10357 3544 2204 10358 3536 11 10359 3541 11 10360 3537 11 10361 3538 2200 10362 3539 2201 10363 3543 2203 10364 3545 11 10365 3546 11 10366 3542 11 10367 3547 2204 10368 3544 2204 10369 3548 2205 10370 3549 11 10371 3545 11 10372 3542 11 10373 3541 2206 10374 3549 2206 10375 3542 2206 10376 3543 2203 10377 3544 2204 10378 3547 2204 10379 3550 11 10380 3551 11 10381 3546 11 10382 3552 2207 10383 3553 2207 10384 3554 2208 10385 3550 11 10386 3546 11 10387 3545 11 10388 3547 2204 10389 3548 2205 10390 3555 2205 10391 3556 2209 10392 3557 2209 10393 3551 2209 10394 3558 2208 10395 3554 2208 10396 3559 2210 10397 3560 11 10398 3556 11 10399 3551 11 10400 3550 11 10401 3560 11 10402 3551 11 10403 3552 2207 10404 3554 2208 10405 3558 2208 10406 3561 11 10407 3562 11 10408 3557 11 10409 3563 2211 10410 3559 2210 10411 3564 2212 10412 3556 11 10413 3561 11 10414 3557 11 10415 3558 2208 10416 3559 2210 10417 3563 2211 10418 3561 11 10419 3565 11 10420 3562 11 10421 3566 2213 10422 3564 2212 10423 3567 2214 10424 3563 2211 10425 3564 2212 10426 3566 2213 10427 3568 11 10428 3569 11 10429 3565 11 10430 3570 2215 10431 3567 2214 10432 3571 2216 10433 3572 11 10434 3568 11 10435 3565 11 10436 3561 11 10437 3572 11 10438 3565 11 10439 3566 2213 10440 3567 2214 10441 3570 2215 10442 3573 11 10443 3519 11 10444 3569 11 10445 3574 2217 10446 3571 2216 10447 3521 2191 10448 3568 11 10449 3573 11 10450 3569 11 10451 3570 2215 10452 3571 2216 10453 3574 2217 10454 3575 11 10455 3518 11 10456 3519 11 10457 3573 11 10458 3575 11 10459 3519 11 10460 3574 2217 10461 3521 2191 10462 3520 2191 10463 3576 2218 10464 3577 2219 10465 3578 2220 10466 3579 2221 10467 3580 2222 10468 3581 2223 10469 3582 2224 10470 3581 2223 10471 3583 2225 10472 3579 2221 10473 3581 2223 10474 3582 2224 10475 3584 2226 10476 3578 2220 10477 3585 2227 10478 3586 2228 10479 3578 2220 10480 3584 2226 10481 3576 2218 10482 3578 2220 10483 3586 2228 10484 3587 2229 10485 3585 2227 10486 3588 2230 10487 3587 2229 10488 3584 2226 10489 3585 2227 10490 3589 2231 10491 3588 2230 10492 3590 2232 10493 3587 2229 10494 3588 2230 10495 3589 2231 10496 3591 11 10497 3592 11 10498 3540 11 10499 3593 2233 10500 3590 2232 10501 3594 2234 10502 3529 11 10503 3591 11 10504 3540 11 10505 3589 2231 10506 3590 2232 10507 3593 2233 10508 3595 11 10509 3596 11 10510 3592 11 10511 3597 2235 10512 3594 2234 10513 3598 2236 10514 3591 11 10515 3595 11 10516 3592 11 10517 3593 2233 10518 3594 2234 10519 3597 2235 10520 3595 11 10521 3599 11 10522 3596 11 10523 3597 2235 10524 3598 2236 10525 3600 2237 10526 3601 2238 10527 3600 2237 10528 3602 2239 10529 3601 2238 10530 3597 2235 10531 3600 2237 10532 3603 2240 10533 3602 2239 10534 3604 2241 10535 3601 2238 10536 3602 2239 10537 3603 2240 10538 3605 2242 10539 3604 2241 10540 3606 2243 10541 3603 2240 10542 3604 2241 10543 3605 2242 10544 3607 2244 10545 3606 2243 10546 3608 2245 10547 3605 2242 10548 3606 2243 10549 3607 2244 10550 3609 2246 10551 3608 2245 10552 3610 2247 10553 3609 2246 10554 3607 2244 10555 3608 2245 10556 3609 2246 10557 3610 2247 10558 3611 2248 10559 3612 2249 10560 3611 2248 10561 3613 2250 10562 3609 2246 10563 3611 2248 10564 3612 2249 10565 3614 2251 10566 3615 2252 10567 3616 2253 10568 3617 2254 10569 3613 2250 10570 3618 2255 10571 3612 2249 10572 3613 2250 10573 3617 2254 10574 3619 2256 10575 3616 2253 10576 3620 2257 10577 3621 2258 10578 3616 2253 10579 3619 2256 10580 3614 2251 10581 3616 2253 10582 3621 2258 10583 3622 2259 10584 3620 2257 10585 3623 2260 10586 3622 2259 10587 3619 2256 10588 3620 2257 10589 3624 2261 10590 3623 2260 10591 3625 2262 10592 3622 2259 10593 3623 2260 10594 3624 2261 10595 3626 11 10596 3627 11 10597 3572 11 10598 3628 2263 10599 3625 2262 10600 3629 2264 10601 3561 2265 10602 3626 2265 10603 3572 2265 10604 3624 2261 10605 3625 2262 10606 3628 2263 10607 3630 11 10608 3631 11 10609 3627 11 10610 3632 2266 10611 3629 2264 10612 3633 2267 10613 3626 11 10614 3630 11 10615 3627 11 10616 3628 2263 10617 3629 2264 10618 3632 2266 10619 3630 11 10620 3634 11 10621 3631 11 10622 3632 2266 10623 3633 2267 10624 3635 2268 10625 3636 2269 10626 3635 2268 10627 3637 2270 10628 3636 2269 10629 3632 2266 10630 3635 2268 10631 3638 2271 10632 3637 2270 10633 3639 2272 10634 3636 2269 10635 3637 2270 10636 3638 2271 10637 3640 2273 10638 3639 2272 10639 3641 2274 10640 3638 2271 10641 3639 2272 10642 3640 2273 10643 3642 2275 10644 3641 2274 10645 3643 2276 10646 3640 2273 10647 3641 2274 10648 3642 2275 10649 3644 2277 10650 3643 2276 10651 3645 2278 10652 3644 2277 10653 3642 2275 10654 3643 2276 10655 3644 2277 10656 3645 2278 10657 3580 2222 10658 3644 2277 10659 3580 2222 10660 3579 2221 10661 3646 11 10662 3647 11 10663 3648 11 10664 3649 11 10665 3646 11 10666 3648 11 10667 3650 11 10668 3649 11 10669 3648 11 10670 3651 11 10671 3652 11 10672 3647 11 10673 3646 11 10674 3651 11 10675 3647 11 10676 3653 11 10677 3654 11 10678 3652 11 10679 3651 11 10680 3653 11 10681 3652 11 10682 3650 11 10683 3655 11 10684 3649 11 10685 3656 11 10686 3657 11 10687 3655 11 10688 3650 11 10689 3656 11 10690 3655 11 10691 3658 11 10692 3659 11 10693 3657 11 10694 3656 11 10695 3658 11 10696 3657 11 10697 3660 11 10698 3661 11 10699 3662 11 10700 3663 11 10701 3664 11 10702 3665 11 10703 3666 11 10704 3667 11 10705 3668 11 10706 3675 11 10707 3676 11 10708 3677 11 10709 3688 2279 10710 3689 2279 10711 3690 2279 10712 3691 31 10713 3690 31 10714 3692 31 10715 3693 31 10716 3690 31 10717 3691 31 10718 3693 31 10719 3688 31 10720 3690 31 10721 3694 31 10722 3695 31 10723 3689 31 10724 3696 31 10725 3694 31 10726 3689 31 10727 3688 2280 10728 3696 2280 10729 3689 2280 10730 3697 31 10731 3698 31 10732 3695 31 10733 3699 31 10734 3697 31 10735 3695 31 10736 3694 2281 10737 3699 2281 10738 3695 2281 10739 3700 31 10740 3701 31 10741 3698 31 10742 3702 31 10743 3700 31 10744 3698 31 10745 3697 31 10746 3702 31 10747 3698 31 10748 3703 2282 10749 3704 2282 10750 3701 2282 10751 3705 31 10752 3703 31 10753 3701 31 10754 3706 2283 10755 3705 2283 10756 3701 2283 10757 3700 2284 10758 3706 2284 10759 3701 2284 10760 3707 31 10761 3708 31 10762 3704 31 10763 3709 2285 10764 3707 2285 10765 3704 2285 10766 3710 31 10767 3709 31 10768 3704 31 10769 3703 2286 10770 3710 2286 10771 3704 2286 10772 3711 31 10773 3712 31 10774 3708 31 10775 3713 2287 10776 3711 2287 10777 3708 2287 10778 3714 2288 10779 3713 2288 10780 3708 2288 10781 3707 31 10782 3714 31 10783 3708 31 10784 3715 31 10785 3716 31 10786 3712 31 10787 3717 31 10788 3715 31 10789 3712 31 10790 3711 31 10791 3717 31 10792 3712 31 10793 3718 31 10794 3719 31 10795 3716 31 10796 3715 31 10797 3718 31 10798 3716 31 10799 3718 31 10800 3720 31 10801 3719 31 10802 3721 31 10803 3722 31 10804 3717 31 10805 3723 31 10806 3721 31 10807 3717 31 10808 3724 31 10809 3723 31 10810 3717 31 10811 3725 31 10812 3724 31 10813 3717 31 10814 3711 31 10815 3725 31 10816 3717 31 10817 3726 2289 10818 3727 2289 10819 3722 2289 10820 3728 2290 10821 3726 2290 10822 3722 2290 10823 3729 31 10824 3728 31 10825 3722 31 10826 3721 31 10827 3729 31 10828 3722 31 10829 3730 31 10830 3731 31 10831 3727 31 10832 3732 31 10833 3730 31 10834 3727 31 10835 3733 31 10836 3732 31 10837 3727 31 10838 3726 2291 10839 3733 2291 10840 3727 2291 10841 3734 2292 10842 3735 2292 10843 3731 2292 10844 3736 2293 10845 3734 2293 10846 3731 2293 10847 3730 31 10848 3736 31 10849 3731 31 10850 3737 31 10851 3738 31 10852 3735 31 10853 3739 2294 10854 3737 2294 10855 3735 2294 10856 3734 31 10857 3739 31 10858 3735 31 10859 3740 2295 10860 3741 2295 10861 3738 2295 10862 3742 2296 10863 3740 2296 10864 3738 2296 10865 3737 2297 10866 3742 2297 10867 3738 2297 10868 3743 31 10869 3744 31 10870 3741 31 10871 3745 31 10872 3743 31 10873 3741 31 10874 3746 2298 10875 3745 2298 10876 3741 2298 10877 3740 2299 10878 3746 2299 10879 3741 2299 10880 3747 2300 10881 3748 2300 10882 3744 2300 10883 3749 31 10884 3747 31 10885 3744 31 10886 3743 31 10887 3749 31 10888 3744 31 10889 3750 31 10890 3751 31 10891 3748 31 10892 3752 31 10893 3750 31 10894 3748 31 10895 3747 2301 10896 3752 2301 10897 3748 2301 10898 3753 31 10899 3754 31 10900 3751 31 10901 3755 31 10902 3753 31 10903 3751 31 10904 3750 2297 10905 3755 2297 10906 3751 2297 10907 3756 31 10908 3757 31 10909 3754 31 10910 3758 31 10911 3756 31 10912 3754 31 10913 3753 31 10914 3758 31 10915 3754 31 10916 3759 2302 10917 3760 2302 10918 3757 2302 10919 3761 31 10920 3759 31 10921 3757 31 10922 3762 2303 10923 3761 2303 10924 3757 2303 10925 3756 2304 10926 3762 2304 10927 3757 2304 10928 3763 31 10929 3764 31 10930 3760 31 10931 3765 2305 10932 3763 2305 10933 3760 2305 10934 3766 31 10935 3765 31 10936 3760 31 10937 3759 2306 10938 3766 2306 10939 3760 2306 10940 3767 31 10941 3768 31 10942 3764 31 10943 3769 2307 10944 3767 2307 10945 3764 2307 10946 3770 2308 10947 3769 2308 10948 3764 2308 10949 3763 31 10950 3770 31 10951 3764 31 10952 3771 31 10953 3772 31 10954 3768 31 10955 3773 31 10956 3771 31 10957 3768 31 10958 3767 31 10959 3773 31 10960 3768 31 10961 3774 31 10962 3775 31 10963 3772 31 10964 3771 31 10965 3774 31 10966 3772 31 10967 3774 31 10968 3776 31 10969 3775 31 10970 3777 31 10971 3778 31 10972 3773 31 10973 3779 31 10974 3777 31 10975 3773 31 10976 3780 31 10977 3779 31 10978 3773 31 10979 3781 31 10980 3780 31 10981 3773 31 10982 3767 31 10983 3781 31 10984 3773 31 10985 3782 2309 10986 3783 2309 10987 3778 2309 10988 3784 2310 10989 3782 2310 10990 3778 2310 10991 3785 31 10992 3784 31 10993 3778 31 10994 3777 31 10995 3785 31 10996 3778 31 10997 3786 31 10998 3787 31 10999 3783 31 11000 3788 31 11001 3786 31 11002 3783 31 11003 3789 31 11004 3788 31 11005 3783 31 11006 3782 2311 11007 3789 2311 11008 3783 2311 11009 3790 2312 11010 3791 2312 11011 3787 2312 11012 3792 2313 11013 3790 2313 11014 3787 2313 11015 3786 31 11016 3792 31 11017 3787 31 11018 3793 31 11019 3794 31 11020 3791 31 11021 3795 2314 11022 3793 2314 11023 3791 2314 11024 3790 31 11025 3795 31 11026 3791 31 11027 3796 2315 11028 3692 2315 11029 3794 2315 11030 3797 2316 11031 3796 2316 11032 3794 2316 11033 3793 2281 11034 3797 2281 11035 3794 2281 11036 3798 31 11037 3691 31 11038 3692 31 11039 3799 2317 11040 3798 2317 11041 3692 2317 11042 3796 2318 11043 3799 2318 11044 3692 2318 11045 3800 31 11046 3801 31 11047 3802 31 11048 3803 31 11049 3800 31 11050 3802 31 11051 3804 31 11052 3803 31 11053 3802 31 11054 3805 31 11055 3806 31 11056 3801 31 11057 3800 31 11058 3805 31 11059 3801 31 11060 3807 31 11061 3808 31 11062 3806 31 11063 3805 31 11064 3807 31 11065 3806 31 11066 3809 31 11067 3810 31 11068 3808 31 11069 3807 31 11070 3809 31 11071 3808 31 11072 3811 31 11073 3812 31 11074 3810 31 11075 3809 31 11076 3811 31 11077 3810 31 11078 3813 31 11079 3814 31 11080 3812 31 11081 3811 31 11082 3813 31 11083 3812 31 11084 3815 31 11085 3816 31 11086 3814 31 11087 3813 31 11088 3815 31 11089 3814 31 11090 3817 31 11091 3818 31 11092 3816 31 11093 3815 31 11094 3817 31 11095 3816 31 11096 3817 31 11097 3819 31 11098 3818 31 11099 3804 31 11100 3820 31 11101 3803 31 11102 3821 31 11103 3822 31 11104 3820 31 11105 3804 31 11106 3821 31 11107 3820 31 11108 3823 31 11109 3824 31 11110 3822 31 11111 3821 31 11112 3823 31 11113 3822 31 11114 3825 31 11115 3826 31 11116 3824 31 11117 3823 31 11118 3825 31 11119 3824 31 11120 3827 31 11121 3828 31 11122 3826 31 11123 3825 31 11124 3827 31 11125 3826 31 11126 3829 31 11127 3830 31 11128 3828 31 11129 3827 31 11130 3829 31 11131 3828 31 11132 3831 31 11133 3832 31 11134 3830 31 11135 3829 31 11136 3831 31 11137 3830 31 11138 3833 31 11139 3834 31 11140 3832 31 11141 3831 31 11142 3833 31 11143 3832 31 11144 3833 31 11145 3835 31 11146 3834 31 11147 3836 31 11148 3837 31 11149 3838 31 11150 3839 31 11151 3840 31 11152 3837 31 11153 3836 31 11154 3839 31 11155 3837 31 11156 3841 31 11157 3838 31 11158 3842 31 11159 3841 31 11160 3836 31 11161 3838 31 11162 3841 31 11163 3842 31 11164 3843 31 11165 3841 2319 11166 3843 2319 11167 3844 2319 11168 3845 31 11169 3844 31 11170 3846 31 11171 3847 31 11172 3841 31 11173 3844 31 11174 3845 31 11175 3847 31 11176 3844 31 11177 3845 31 11178 3846 31 11179 3848 31 11180 3845 2320 11181 3848 2320 11182 3849 2320 11183 3850 31 11184 3849 31 11185 3851 31 11186 3850 2321 11187 3845 2321 11188 3849 2321 11189 3850 31 11190 3851 31 11191 3852 31 11192 3853 31 11193 3852 31 11194 3854 31 11195 3850 31 11196 3852 31 11197 3853 31 11198 3855 31 11199 3854 31 11200 3856 31 11201 3855 31 11202 3853 31 11203 3854 31 11204 3855 31 11205 3856 31 11206 3857 31 11207 3855 2322 11208 3857 2322 11209 3858 2322 11210 3859 31 11211 3858 31 11212 3860 31 11213 3861 31 11214 3855 31 11215 3858 31 11216 3859 31 11217 3861 31 11218 3858 31 11219 3859 31 11220 3860 31 11221 3862 31 11222 3859 2323 11223 3862 2323 11224 3863 2323 11225 3839 31 11226 3863 31 11227 3840 31 11228 3839 2324 11229 3859 2324 11230 3863 2324 11231 3864 31 11232 3865 31 11233 3866 31 11234 3867 31 11235 3868 31 11236 3865 31 11237 3864 31 11238 3867 31 11239 3865 31 11240 3869 31 11241 3866 31 11242 3870 31 11243 3869 31 11244 3864 31 11245 3866 31 11246 3869 31 11247 3870 31 11248 3871 31 11249 3869 31 11250 3871 31 11251 3872 31 11252 3873 31 11253 3872 31 11254 3874 31 11255 3875 31 11256 3869 31 11257 3872 31 11258 3873 31 11259 3875 31 11260 3872 31 11261 3873 31 11262 3874 31 11263 3876 31 11264 3873 31 11265 3876 31 11266 3877 31 11267 3878 31 11268 3877 31 11269 3879 31 11270 3878 31 11271 3873 31 11272 3877 31 11273 3878 31 11274 3879 31 11275 3880 31 11276 3881 31 11277 3880 31 11278 3882 31 11279 3878 31 11280 3880 31 11281 3881 31 11282 3883 31 11283 3882 31 11284 3884 31 11285 3883 31 11286 3881 31 11287 3882 31 11288 3883 31 11289 3884 31 11290 3885 31 11291 3883 31 11292 3885 31 11293 3886 31 11294 3887 31 11295 3886 31 11296 3888 31 11297 3889 31 11298 3883 31 11299 3886 31 11300 3887 31 11301 3889 31 11302 3886 31 11303 3887 31 11304 3888 31 11305 3890 31 11306 3887 31 11307 3890 31 11308 3891 31 11309 3867 31 11310 3891 31 11311 3868 31 11312 3867 31 11313 3887 31 11314 3891 31 11315 3892 31 11316 3893 31 11317 3894 31 11318 3895 31 11319 3896 31 11320 3893 31 11321 3892 31 11322 3895 31 11323 3893 31 11324 3897 31 11325 3894 31 11326 3898 31 11327 3897 31 11328 3892 31 11329 3894 31 11330 3897 31 11331 3898 31 11332 3899 31 11333 3897 31 11334 3899 31 11335 3900 31 11336 3901 31 11337 3900 31 11338 3902 31 11339 3903 31 11340 3897 31 11341 3900 31 11342 3901 31 11343 3903 31 11344 3900 31 11345 3901 31 11346 3902 31 11347 3904 31 11348 3901 31 11349 3904 31 11350 3905 31 11351 3906 31 11352 3905 31 11353 3907 31 11354 3906 31 11355 3901 31 11356 3905 31 11357 3906 31 11358 3907 31 11359 3908 31 11360 3909 31 11361 3908 31 11362 3910 31 11363 3906 31 11364 3908 31 11365 3909 31 11366 3911 31 11367 3910 31 11368 3912 31 11369 3911 31 11370 3909 31 11371 3910 31 11372 3911 31 11373 3912 31 11374 3913 31 11375 3911 31 11376 3913 31 11377 3914 31 11378 3915 31 11379 3914 31 11380 3916 31 11381 3917 31 11382 3911 31 11383 3914 31 11384 3915 31 11385 3917 31 11386 3914 31 11387 3915 31 11388 3916 31 11389 3918 31 11390 3915 31 11391 3918 31 11392 3919 31 11393 3895 31 11394 3919 31 11395 3896 31 11396 3895 31 11397 3915 31 11398 3919 31 11399 3920 31 11400 3921 31 11401 3922 31 11402 3923 31 11403 3924 31 11404 3921 31 11405 3920 31 11406 3923 31 11407 3921 31 11408 3925 31 11409 3922 31 11410 3926 31 11411 3925 31 11412 3920 31 11413 3922 31 11414 3925 31 11415 3926 31 11416 3927 31 11417 3925 31 11418 3927 31 11419 3928 31 11420 3929 31 11421 3928 31 11422 3930 31 11423 3931 31 11424 3925 31 11425 3928 31 11426 3929 31 11427 3931 31 11428 3928 31 11429 3929 31 11430 3930 31 11431 3932 31 11432 3929 31 11433 3932 31 11434 3933 31 11435 3934 31 11436 3933 31 11437 3935 31 11438 3934 31 11439 3929 31 11440 3933 31 11441 3934 31 11442 3935 31 11443 3936 31 11444 3937 31 11445 3936 31 11446 3938 31 11447 3934 31 11448 3936 31 11449 3937 31 11450 3939 31 11451 3938 31 11452 3940 31 11453 3939 31 11454 3937 31 11455 3938 31 11456 3939 31 11457 3940 31 11458 3941 31 11459 3939 31 11460 3941 31 11461 3942 31 11462 3943 31 11463 3942 31 11464 3944 31 11465 3945 31 11466 3939 31 11467 3942 31 11468 3943 31 11469 3945 31 11470 3942 31 11471 3943 31 11472 3944 31 11473 3946 31 11474 3943 31 11475 3946 31 11476 3947 31 11477 3923 31 11478 3947 31 11479 3924 31 11480 3923 31 11481 3943 31 11482 3947 31 11483 3948 31 11484 3949 31 11485 3950 31 11486 3951 31 11487 3952 31 11488 3949 31 11489 3948 31 11490 3951 31 11491 3949 31 11492 3953 31 11493 3950 31 11494 3954 31 11495 3953 31 11496 3948 31 11497 3950 31 11498 3953 31 11499 3954 31 11500 3955 31 11501 3953 31 11502 3955 31 11503 3956 31 11504 3957 31 11505 3956 31 11506 3958 31 11507 3959 31 11508 3953 31 11509 3956 31 11510 3957 31 11511 3959 31 11512 3956 31 11513 3957 31 11514 3958 31 11515 3960 31 11516 3957 31 11517 3960 31 11518 3961 31 11519 3962 31 11520 3961 31 11521 3963 31 11522 3962 31 11523 3957 31 11524 3961 31 11525 3962 31 11526 3963 31 11527 3964 31 11528 3965 31 11529 3964 31 11530 3966 31 11531 3962 31 11532 3964 31 11533 3965 31 11534 3967 31 11535 3966 31 11536 3968 31 11537 3967 31 11538 3965 31 11539 3966 31 11540 3967 31 11541 3968 31 11542 3969 31 11543 3967 31 11544 3969 31 11545 3970 31 11546 3971 31 11547 3970 31 11548 3972 31 11549 3973 31 11550 3967 31 11551 3970 31 11552 3971 31 11553 3973 31 11554 3970 31 11555 3971 31 11556 3972 31 11557 3974 31 11558 3971 31 11559 3974 31 11560 3975 31 11561 3951 31 11562 3975 31 11563 3952 31 11564 3951 31 11565 3971 31 11566 3975 31 11567 3976 31 11568 3977 31 11569 3861 31 11570 3859 31 11571 3976 31 11572 3861 31 11573 3978 31 11574 3979 31 11575 3977 31 11576 3976 31 11577 3978 31 11578 3977 31 11579 3978 31 11580 3980 31 11581 3979 31 11582 3981 31 11583 3982 31 11584 3847 31 11585 3845 31 11586 3981 31 11587 3847 31 11588 3983 31 11589 3984 31 11590 3982 31 11591 3981 31 11592 3983 31 11593 3982 31 11594 3983 31 11595 3985 31 11596 3984 31 11597 3986 31 11598 3987 31 11599 3889 31 11600 3887 31 11601 3986 31 11602 3889 31 11603 3988 31 11604 3989 31 11605 3987 31 11606 3986 31 11607 3988 31 11608 3987 31 11609 3988 31 11610 3990 31 11611 3989 31 11612 3991 31 11613 3992 31 11614 3875 31 11615 3873 31 11616 3991 31 11617 3875 31 11618 3993 31 11619 3994 31 11620 3992 31 11621 3991 31 11622 3993 31 11623 3992 31 11624 3993 31 11625 3995 31 11626 3994 31 11627 3996 31 11628 3997 31 11629 3917 31 11630 3915 31 11631 3996 31 11632 3917 31 11633 3998 31 11634 3999 31 11635 3997 31 11636 3996 31 11637 3998 31 11638 3997 31 11639 3998 31 11640 4000 31 11641 3999 31 11642 4001 31 11643 4002 31 11644 3903 31 11645 3901 31 11646 4001 31 11647 3903 31 11648 4003 31 11649 4004 31 11650 4002 31 11651 4001 31 11652 4003 31 11653 4002 31 11654 4003 31 11655 4005 31 11656 4004 31 11657 4006 31 11658 4007 31 11659 3945 31 11660 3943 31 11661 4006 31 11662 3945 31 11663 4008 31 11664 4009 31 11665 4007 31 11666 4006 31 11667 4008 31 11668 4007 31 11669 4008 31 11670 4010 31 11671 4009 31 11672 4011 31 11673 4012 31 11674 3931 31 11675 3929 31 11676 4011 31 11677 3931 31 11678 4013 31 11679 4014 31 11680 4012 31 11681 4011 31 11682 4013 31 11683 4012 31 11684 4013 31 11685 4015 31 11686 4014 31 11687 4016 31 11688 4017 31 11689 3973 31 11690 3971 31 11691 4016 31 11692 3973 31 11693 4018 31 11694 4019 31 11695 4017 31 11696 4016 31 11697 4018 31 11698 4017 31 11699 4018 31 11700 4020 31 11701 4019 31 11702 4021 31 11703 4022 31 11704 3959 31 11705 3957 31 11706 4021 31 11707 3959 31 11708 4023 31 11709 4024 31 11710 4022 31 11711 4021 31 11712 4023 31 11713 4022 31 11714 4023 31 11715 4025 31 11716 4024 31 11717 4026 2325 11718 4027 2326 11719 4028 2327 11720 4029 2328 11721 4030 2329 11722 4031 2330 11723 4032 2331 11724 4026 2325 11725 4028 2327 11726 4033 2332 11727 4032 2331 11728 4028 2327 11729 4034 2333 11730 4033 2332 11731 4028 2327 11732 4035 2334 11733 4034 2333 11734 4028 2327 11735 4036 2335 11736 4035 2334 11737 4028 2327 11738 4037 2336 11739 4036 2335 11740 4028 2327 11741 4038 2337 11742 4037 2336 11743 4028 2327 11744 4039 2338 11745 4038 2337 11746 4028 2327 11747 4040 2339 11748 4041 2340 11749 4030 2329 11750 4042 2341 11751 4040 2339 11752 4030 2329 11753 4043 2342 11754 4042 2341 11755 4030 2329 11756 4044 2343 11757 4043 2342 11758 4030 2329 11759 4045 2344 11760 4044 2343 11761 4030 2329 11762 4046 2345 11763 4045 2344 11764 4030 2329 11765 4047 2346 11766 4046 2345 11767 4030 2329 11768 4029 2328 11769 4047 2346 11770 4030 2329 11771 4048 2343 11772 4049 2347 11773 4050 2348 11774 4051 2341 11775 4052 2349 11776 4053 2350 11777 4054 2344 11778 4048 2343 11779 4050 2348 11780 4055 2345 11781 4054 2344 11782 4050 2348 11783 4056 2346 11784 4055 2345 11785 4050 2348 11786 4057 2351 11787 4056 2346 11788 4050 2348 11789 4058 2352 11790 4057 2351 11791 4050 2348 11792 4059 2325 11793 4058 2352 11794 4050 2348 11795 4060 2331 11796 4059 2325 11797 4050 2348 11798 4061 2353 11799 4060 2331 11800 4050 2348 11801 4062 2333 11802 4063 2354 11803 4052 2349 11804 4064 2334 11805 4062 2333 11806 4052 2349 11807 4065 2335 11808 4064 2334 11809 4052 2349 11810 4066 2336 11811 4065 2335 11812 4052 2349 11813 4067 2355 11814 4066 2336 11815 4052 2349 11816 4068 2356 11817 4067 2355 11818 4052 2349 11819 4069 2339 11820 4068 2356 11821 4052 2349 11822 4051 2341 11823 4069 2339 11824 4052 2349 11825 4070 2357 11826 4071 2357 11827 4072 2357 11828 4073 542 11829 4070 542 11830 4072 542 11831 4074 2358 11832 4073 2358 11833 4072 2358 11834 4075 2359 11835 4076 2359 11836 4071 2359 11837 4070 2360 11838 4075 2360 11839 4071 2360 11840 4075 2361 11841 4077 2361 11842 4076 2361 11843 4078 2362 11844 4079 2362 11845 4077 2362 11846 4080 542 11847 4078 542 11848 4077 542 11849 4081 2363 11850 4080 2363 11851 4077 2363 11852 4075 542 11853 4081 542 11854 4077 542 11855 4082 542 11856 4083 542 11857 4079 542 11858 4084 542 11859 4082 542 11860 4079 542 11861 4078 542 11862 4084 542 11863 4079 542 11864 4085 2364 11865 4086 2364 11866 4083 2364 11867 4082 542 11868 4085 542 11869 4083 542 11870 4087 542 11871 4088 542 11872 4086 542 11873 4085 2365 11874 4087 2365 11875 4086 2365 11876 4089 542 11877 4090 542 11878 4080 542 11879 4081 542 11880 4089 542 11881 4080 542 11882 4091 2366 11883 4092 2366 11884 4090 2366 11885 4089 2367 11886 4091 2367 11887 4090 2367 11888 4074 2368 11889 4093 2368 11890 4073 2368 11891 4094 2369 11892 4095 2369 11893 4093 2369 11894 4074 542 11895 4094 542 11896 4093 542 11897 4096 2370 11898 4097 2370 11899 4095 2370 11900 4094 542 11901 4096 542 11902 4095 542 11903 4098 2371 11904 4099 2371 11905 4097 2371 11906 4096 2372 11907 4098 2372 11908 4097 2372 11909 4100 2373 11910 4101 2373 11911 4099 2373 11912 4098 2374 11913 4100 2374 11914 4099 2374 11915 4100 2375 11916 4102 2375 11917 4101 2375 11918 4103 542 11919 4104 542 11920 4102 542 11921 4105 542 11922 4103 542 11923 4102 542 11924 4106 542 11925 4105 542 11926 4102 542 11927 4100 542 11928 4106 542 11929 4102 542 11930 4107 542 11931 4108 542 11932 4104 542 11933 4103 542 11934 4107 542 11935 4104 542 11936 4106 2376 11937 4109 2376 11938 4105 2376 11939 4106 2377 11940 4110 2377 11941 4109 2377 11942 4111 542 11943 4112 542 11944 4110 542 11945 4106 542 11946 4111 542 11947 4110 542 11948 4111 2378 11949 4113 2378 11950 4112 2378 11951 4111 2379 11952 4114 2379 11953 4113 2379 11954 4111 2380 11955 4115 2380 11956 4114 2380 11957 4116 2381 11958 4117 2381 11959 4115 2381 11960 4111 542 11961 4116 542 11962 4115 542 11963 4118 2382 11964 4119 2382 11965 4117 2382 11966 4116 542 11967 4118 542 11968 4117 542 11969 4120 2383 11970 4121 2383 11971 4119 2383 11972 4118 542 11973 4120 542 11974 4119 542 11975 4122 2384 11976 4123 2384 11977 4121 2384 11978 4120 2385 11979 4122 2385 11980 4121 2385 11981 4124 2386 11982 4125 2386 11983 4123 2386 11984 4122 2387 11985 4124 2387 11986 4123 2387 11987 4126 2388 11988 4127 2388 11989 4125 2388 11990 4128 542 11991 4126 542 11992 4125 542 11993 4129 2389 11994 4128 2389 11995 4125 2389 11996 4130 542 11997 4129 542 11998 4125 542 11999 4131 542 12000 4130 542 12001 4125 542 12002 4132 2390 12003 4131 2390 12004 4125 2390 12005 4133 2391 12006 4132 2391 12007 4125 2391 12008 4124 542 12009 4133 542 12010 4125 542 12011 4134 2392 12012 4135 2392 12013 4127 2392 12014 4136 542 12015 4134 542 12016 4127 542 12017 4137 542 12018 4136 542 12019 4127 542 12020 4138 2393 12021 4137 2393 12022 4127 2393 12023 4139 542 12024 4138 542 12025 4127 542 12026 4126 542 12027 4139 542 12028 4127 542 12029 4140 2394 12030 4141 2394 12031 4135 2394 12032 4134 2395 12033 4140 2395 12034 4135 2395 12035 4142 542 12036 4143 542 12037 4141 542 12038 4140 542 12039 4142 542 12040 4141 542 12041 4144 2396 12042 4145 2396 12043 4143 2396 12044 4142 2397 12045 4144 2397 12046 4143 2397 12047 4146 2398 12048 4147 2398 12049 4145 2398 12050 4144 542 12051 4146 542 12052 4145 542 12053 4148 2399 12054 4149 2399 12055 4147 2399 12056 4146 2400 12057 4148 2400 12058 4147 2400 12059 4150 2401 12060 4151 2401 12061 4149 2401 12062 4148 2402 12063 4150 2402 12064 4149 2402 12065 4152 2403 12066 4153 2403 12067 4151 2403 12068 4150 2404 12069 4152 2404 12070 4151 2404 12071 4152 542 12072 4154 542 12073 4153 542 12074 4152 2405 12075 4155 2405 12076 4154 2405 12077 4152 2406 12078 4156 2406 12079 4155 2406 12080 4152 2407 12081 4157 2407 12082 4156 2407 12083 4158 2408 12084 4159 2408 12085 4157 2408 12086 4152 2409 12087 4158 2409 12088 4157 2409 12089 4158 2410 12090 4160 2410 12091 4159 2410 12092 4158 2411 12093 4161 2411 12094 4160 2411 12095 4158 2412 12096 4162 2412 12097 4161 2412 12098 4158 2413 12099 4163 2413 12100 4162 2413 12101 4158 2414 12102 4164 2414 12103 4163 2414 12104 4158 2415 12105 4165 2415 12106 4164 2415 12107 4166 2416 12108 4167 2416 12109 4165 2416 12110 4158 542 12111 4166 542 12112 4165 542 12113 4168 2417 12114 4169 2417 12115 4167 2417 12116 4166 2418 12117 4168 2418 12118 4167 2418 12119 4170 2419 12120 4171 2419 12121 4169 2419 12122 4168 2420 12123 4170 2420 12124 4169 2420 12125 4172 2421 12126 4173 2421 12127 4171 2421 12128 4170 2422 12129 4172 2422 12130 4171 2422 12131 4174 2423 12132 4175 2423 12133 4173 2423 12134 4172 542 12135 4174 542 12136 4173 542 12137 4176 2424 12138 4177 2424 12139 4175 2424 12140 4178 542 12141 4176 542 12142 4175 542 12143 4179 542 12144 4178 542 12145 4175 542 12146 4180 542 12147 4179 542 12148 4175 542 12149 4174 542 12150 4180 542 12151 4175 542 12152 4181 2425 12153 4182 2425 12154 4177 2425 12155 4183 542 12156 4181 542 12157 4177 542 12158 4184 2426 12159 4183 2426 12160 4177 2426 12161 4176 2427 12162 4184 2427 12163 4177 2427 12164 4185 2428 12165 4186 2428 12166 4182 2428 12167 4187 542 12168 4185 542 12169 4182 542 12170 4181 2429 12171 4187 2429 12172 4182 2429 12173 4188 2430 12174 4189 2430 12175 4186 2430 12176 4185 542 12177 4188 542 12178 4186 542 12179 4190 2431 12180 4191 2431 12181 4189 2431 12182 4188 2432 12183 4190 2432 12184 4189 2432 12185 4192 2433 12186 4193 2433 12187 4191 2433 12188 4190 2434 12189 4192 2434 12190 4191 2434 12191 4194 2435 12192 4195 2435 12193 4193 2435 12194 4192 542 12195 4194 542 12196 4193 542 12197 4196 2436 12198 4197 2436 12199 4195 2436 12200 4194 542 12201 4196 542 12202 4195 542 12203 4198 2437 12204 4199 2437 12205 4197 2437 12206 4196 542 12207 4198 542 12208 4197 542 12209 4198 2438 12210 4200 2438 12211 4199 2438 12212 4201 2439 12213 4202 2439 12214 4200 2439 12215 4203 542 12216 4201 542 12217 4200 542 12218 4204 2440 12219 4203 2440 12220 4200 2440 12221 4198 2441 12222 4204 2441 12223 4200 2441 12224 4205 542 12225 4206 542 12226 4202 542 12227 4207 542 12228 4205 542 12229 4202 542 12230 4201 542 12231 4207 542 12232 4202 542 12233 4208 2442 12234 4209 2442 12235 4206 2442 12236 4205 542 12237 4208 542 12238 4206 542 12239 4210 542 12240 4211 542 12241 4209 542 12242 4208 2443 12243 4210 2443 12244 4209 2443 12245 4212 2444 12246 4213 2444 12247 4203 2444 12248 4204 542 12249 4212 542 12250 4203 542 12251 4214 542 12252 4215 542 12253 4213 542 12254 4212 2445 12255 4214 2445 12256 4213 2445 12257 4216 542 12258 4217 542 12259 4181 542 12260 4183 542 12261 4216 542 12262 4181 542 12263 4218 542 12264 4219 542 12265 4217 542 12266 4216 542 12267 4218 542 12268 4217 542 12269 4220 2446 12270 4221 2447 12271 4222 2448 12272 4223 2449 12273 4224 2450 12274 4225 2451 12275 4226 2452 12276 4227 2452 12277 4228 2453 12278 4226 2452 12279 4228 2453 12280 4229 2453 12281 4230 2454 12282 4231 2455 12283 4232 2455 12284 4233 2456 12285 4234 2457 12286 4221 2447 12287 4235 2458 12288 4225 2451 12289 4236 2459 12290 4237 2460 12291 4233 2456 12292 4221 2447 12293 4238 2461 12294 4237 2460 12295 4221 2447 12296 4239 2462 12297 4238 2461 12298 4221 2447 12299 4240 2463 12300 4239 2462 12301 4221 2447 12302 4220 2446 12303 4240 2463 12304 4221 2447 12305 4241 2464 12306 4223 2449 12307 4225 2451 12308 4242 2465 12309 4241 2464 12310 4225 2451 12311 4243 2466 12312 4242 2465 12313 4225 2451 12314 4244 2467 12315 4243 2466 12316 4225 2451 12317 4235 2458 12318 4244 2467 12319 4225 2451 12320 4245 2468 12321 4246 2468 12322 4247 2469 12323 4248 2470 12324 4249 2471 12325 4250 2471 12326 4248 2470 12327 4251 2470 12328 4249 2471 12329 4252 2469 12330 4247 2469 12331 4253 2472 12332 4252 2469 12333 4245 2468 12334 4247 2469 12335 4254 2472 12336 4253 2472 12337 4255 2473 12338 4254 2472 12339 4252 2469 12340 4253 2472 12341 4256 2473 12342 4255 2473 12343 4257 2474 12344 4256 2473 12345 4254 2472 12346 4255 2473 12347 4258 2474 12348 4257 2474 12349 4259 2475 12350 4258 2474 12351 4256 2473 12352 4257 2474 12353 4260 2475 12354 4259 2475 12355 4227 2452 12356 4260 2475 12357 4258 2474 12358 4259 2475 12359 4226 2452 12360 4260 2475 12361 4227 2452 12362 4261 2476 12363 4262 2476 12364 4263 2476 12365 4264 2454 12366 4231 2455 12367 4230 2454 12368 4265 2477 12369 4263 2477 12370 4266 2477 12371 4265 11 12372 4261 11 12373 4263 11 12374 4267 11 12375 4268 11 12376 4269 11 12377 4270 11 12378 4271 11 12379 4268 11 12380 4267 11 12381 4270 11 12382 4268 11 12383 4267 2478 12384 4269 2478 12385 4272 2478 12386 4267 2479 12387 4272 2479 12388 4273 2479 12389 4274 11 12390 4273 11 12391 4275 11 12392 4274 11 12393 4267 11 12394 4273 11 12395 4274 11 12396 4275 11 12397 4276 11 12398 4274 11 12399 4276 11 12400 4262 11 12401 4261 11 12402 4274 11 12403 4262 11 12404 4264 2454 12405 4230 2454 12406 4277 2480 12407 4278 2480 12408 4277 2480 12409 4279 2481 12410 4278 2480 12411 4264 2454 12412 4277 2480 12413 4280 2481 12414 4279 2481 12415 4281 2482 12416 4280 2481 12417 4278 2480 12418 4279 2481 12419 4282 2482 12420 4281 2482 12421 4283 2483 12422 4282 2482 12423 4280 2481 12424 4281 2482 12425 4284 2483 12426 4283 2483 12427 4251 2470 12428 4284 2483 12429 4282 2482 12430 4283 2483 12431 4248 2470 12432 4284 2483 12433 4251 2470 12434 4265 11 12435 4266 11 12436 4285 11 12437 4265 2484 12438 4285 2484 12439 4286 2484 12440 4287 11 12441 4286 11 12442 4288 11 12443 4265 2485 12444 4286 2485 12445 4287 2485 12446 4287 11 12447 4288 11 12448 4289 11 12449 4287 11 12450 4289 11 12451 4271 11 12452 4270 11 12453 4287 11 12454 4271 11 12455 4290 11 12456 4291 11 12457 4270 11 12458 4267 11 12459 4290 11 12460 4270 11 12461 4292 11 12462 4293 11 12463 4291 11 12464 4290 11 12465 4292 11 12466 4291 11 12467 4294 11 12468 4295 11 12469 4293 11 12470 4292 11 12471 4294 11 12472 4293 11 12473 4296 11 12474 4297 11 12475 4261 11 12476 4265 11 12477 4296 11 12478 4261 11 12479 4298 11 12480 4299 11 12481 4297 11 12482 4296 11 12483 4298 11 12484 4297 11 12485 4300 11 12486 4301 11 12487 4299 11 12488 4298 11 12489 4300 11 12490 4299 11 12491 4305 11 12492 4306 11 12493 4307 11 12494 4352 11 12495 4353 11 12496 4354 11 12497 4355 11 12498 4356 11 12499 4357 11 12500 4358 11 12501 4359 11 12502 4360 11 12503 4364 11 12504 4365 11 12505 4366 11 12506 4367 11 12507 4368 11 12508 4369 11 12509 4370 2486 12510 4371 2486 12511 4372 2486 12512 4390 11 12513 4391 11 12514 4392 11 12515 4393 11 12516 4394 11 12517 4395 11 12518 4396 11 12519 4397 11 12520 4398 11 12521 4399 11 12522 4396 11 12523 4398 11 12524 4400 11 12525 4401 11 12526 4402 11 12527 4413 2487 12528 4414 2487 12529 4415 2487 12530 4416 2129 12531 4417 2130 12532 4418 2131 12533 4419 1735 12534 4413 1735 12535 4415 1735 12536 4420 2488 12537 4421 2488 12538 4422 2488 12539 4423 2489 12540 4420 2489 12541 4422 2489 12542 4423 2490 12543 4422 2490 12544 4424 2490 12545 4425 2135 12546 4418 2131 12547 4426 2136 12548 4427 2137 12549 4416 2129 12550 4418 2131 12551 4425 2135 12552 4427 2137 12553 4418 2131 12554 4419 2491 12555 4428 2491 12556 4413 2491 12557 4429 2492 12558 4430 2492 12559 4431 2492 12560 4432 2140 12561 4425 2135 12562 4426 2136 12563 4433 2141 12564 4432 2140 12565 4426 2136 12566 4434 2142 12567 4435 2142 12568 4428 2142 12569 4436 2493 12570 4437 2144 12571 4438 2494 12572 4419 1735 12573 4434 1735 12574 4428 1735 12575 4439 2495 12576 4431 2495 12577 4440 2495 12578 4439 2496 12579 4429 2496 12580 4431 2496 12581 4441 2148 12582 4442 2148 12583 4435 2148 12584 4443 2149 12585 4438 2494 12586 4444 2150 12587 4434 2151 12588 4441 2151 12589 4435 2151 12590 4443 2149 12591 4436 2493 12592 4438 2494 12593 4445 1735 12594 4446 1735 12595 4442 1735 12596 4447 542 12597 4448 542 12598 4449 542 12599 4441 1735 12600 4445 1735 12601 4442 1735 12602 4450 2152 12603 4443 2149 12604 4444 2150 12605 4451 2153 12606 4452 2153 12607 4446 2153 12608 4453 2154 12609 4454 2155 12610 4455 2156 12611 4445 1735 12612 4451 1735 12613 4446 1735 12614 4456 542 12615 4447 542 12616 4449 542 12617 4456 542 12618 4449 542 12619 4457 542 12620 4458 2157 12621 4459 2157 12622 4452 2157 12623 4460 2497 12624 4455 2156 12625 4461 2159 12626 4451 1735 12627 4458 1735 12628 4452 1735 12629 4460 2497 12630 4453 2154 12631 4455 2156 12632 4462 1735 12633 4463 1735 12634 4459 1735 12635 4464 2498 12636 4465 2498 12637 4466 2498 12638 4458 1735 12639 4462 1735 12640 4459 1735 12641 4467 2161 12642 4460 2497 12643 4461 2159 12644 4462 2499 12645 4468 2499 12646 4463 2499 12647 4469 2163 12648 4470 2164 12649 4471 2165 12650 4472 2500 12651 4464 2500 12652 4466 2500 12653 4472 2501 12654 4466 2501 12655 4473 2501 12656 4474 2168 12657 4471 2165 12658 4475 2169 12659 4476 2170 12660 4469 2163 12661 4471 2165 12662 4474 2168 12663 4476 2170 12664 4471 2165 12665 4477 2502 12666 4478 2502 12667 4479 2502 12668 4480 2172 12669 4474 2168 12670 4475 2169 12671 4481 2173 12672 4480 2172 12673 4475 2169 12674 4482 2503 12675 4483 2175 12676 4484 2176 12677 4485 2504 12678 4479 2504 12679 4486 2504 12680 4485 2505 12681 4477 2505 12682 4479 2505 12683 4487 2179 12684 4484 2176 12685 4488 2180 12686 4487 2179 12687 4482 2503 12688 4484 2176 12689 4489 31 12690 4490 31 12691 4491 31 12692 4492 2181 12693 4487 2179 12694 4488 2180 12695 4493 2182 12696 4494 2183 12697 4495 2184 12698 4496 31 12699 4491 31 12700 4497 31 12701 4496 2506 12702 4489 2506 12703 4491 2506 12704 4498 2185 12705 4495 2184 12706 4499 2186 12707 4498 2185 12708 4493 2182 12709 4495 2184 12710 4500 2187 12711 4498 2185 12712 4499 2186 12713 4501 11 12714 4502 11 12715 4503 11 12716 4504 2188 12717 4505 2189 12718 4506 2190 12719 4507 11 12720 4503 11 12721 4508 11 12722 4509 2191 12723 4510 2191 12724 4511 2192 12725 4507 11 12726 4501 11 12727 4503 11 12728 4509 2191 12729 4511 2192 12730 4512 2192 12731 4513 11 12732 4514 11 12733 4502 11 12734 4515 2190 12735 4506 2190 12736 4516 2193 12737 4517 11 12738 4513 11 12739 4502 11 12740 4501 2194 12741 4517 2194 12742 4502 2194 12743 4515 2190 12744 4504 2188 12745 4506 2190 12746 4518 11 12747 4519 11 12748 4514 11 12749 4520 2195 12750 4516 2193 12751 4521 2196 12752 4513 2197 12753 4518 2197 12754 4514 2197 12755 4515 2190 12756 4516 2193 12757 4520 2195 12758 4518 11 12759 4522 11 12760 4519 11 12761 4523 2198 12762 4521 2196 12763 4524 2199 12764 4520 2195 12765 4521 2196 12766 4523 2198 12767 4525 11 12768 4526 11 12769 4522 11 12770 4527 2200 12771 4524 2199 12772 4528 2201 12773 4529 2202 12774 4525 2202 12775 4522 2202 12776 4518 11 12777 4529 11 12778 4522 11 12779 4523 2198 12780 4524 2199 12781 4527 2200 12782 4530 11 12783 4531 11 12784 4526 11 12785 4532 2203 12786 4528 2201 12787 4533 2204 12788 4525 11 12789 4530 11 12790 4526 11 12791 4527 2200 12792 4528 2201 12793 4532 2203 12794 4534 11 12795 4535 11 12796 4531 11 12797 4536 2204 12798 4533 2204 12799 4537 2205 12800 4538 11 12801 4534 11 12802 4531 11 12803 4530 2206 12804 4538 2206 12805 4531 2206 12806 4532 2203 12807 4533 2204 12808 4536 2204 12809 4539 11 12810 4540 11 12811 4535 11 12812 4541 2207 12813 4542 2207 12814 4543 2208 12815 4539 11 12816 4535 11 12817 4534 11 12818 4536 2204 12819 4537 2205 12820 4544 2205 12821 4545 2507 12822 4546 2507 12823 4540 2507 12824 4547 2208 12825 4543 2208 12826 4548 2210 12827 4549 11 12828 4545 11 12829 4540 11 12830 4539 11 12831 4549 11 12832 4540 11 12833 4541 2207 12834 4543 2208 12835 4547 2208 12836 4550 11 12837 4551 11 12838 4546 11 12839 4552 2211 12840 4548 2210 12841 4553 2212 12842 4545 11 12843 4550 11 12844 4546 11 12845 4547 2208 12846 4548 2210 12847 4552 2211 12848 4550 11 12849 4554 11 12850 4551 11 12851 4555 2213 12852 4553 2212 12853 4556 2214 12854 4552 2211 12855 4553 2212 12856 4555 2213 12857 4557 11 12858 4558 11 12859 4554 11 12860 4559 2215 12861 4556 2214 12862 4560 2216 12863 4561 11 12864 4557 11 12865 4554 11 12866 4550 11 12867 4561 11 12868 4554 11 12869 4555 2213 12870 4556 2214 12871 4559 2215 12872 4562 11 12873 4508 11 12874 4558 11 12875 4563 2217 12876 4560 2216 12877 4510 2191 12878 4557 11 12879 4562 11 12880 4558 11 12881 4559 2215 12882 4560 2216 12883 4563 2217 12884 4564 11 12885 4507 11 12886 4508 11 12887 4562 11 12888 4564 11 12889 4508 11 12890 4563 2217 12891 4510 2191 12892 4509 2191 12893 4565 2218 12894 4566 2219 12895 4567 2220 12896 4568 2221 12897 4569 2222 12898 4570 2223 12899 4571 2224 12900 4570 2223 12901 4572 2225 12902 4568 2221 12903 4570 2223 12904 4571 2224 12905 4573 2226 12906 4567 2220 12907 4574 2227 12908 4575 2228 12909 4567 2220 12910 4573 2226 12911 4565 2218 12912 4567 2220 12913 4575 2228 12914 4576 2229 12915 4574 2227 12916 4577 2230 12917 4576 2229 12918 4573 2226 12919 4574 2227 12920 4578 2231 12921 4577 2230 12922 4579 2232 12923 4576 2229 12924 4577 2230 12925 4578 2231 12926 4580 11 12927 4581 11 12928 4529 11 12929 4582 2233 12930 4579 2232 12931 4583 2234 12932 4518 11 12933 4580 11 12934 4529 11 12935 4578 2231 12936 4579 2232 12937 4582 2233 12938 4584 11 12939 4585 11 12940 4581 11 12941 4586 2235 12942 4583 2234 12943 4587 2236 12944 4580 11 12945 4584 11 12946 4581 11 12947 4582 2233 12948 4583 2234 12949 4586 2235 12950 4584 11 12951 4588 11 12952 4585 11 12953 4586 2235 12954 4587 2236 12955 4589 2237 12956 4590 2238 12957 4589 2237 12958 4591 2239 12959 4590 2238 12960 4586 2235 12961 4589 2237 12962 4592 2240 12963 4591 2239 12964 4593 2241 12965 4590 2238 12966 4591 2239 12967 4592 2240 12968 4594 2508 12969 4593 2241 12970 4595 2243 12971 4592 2240 12972 4593 2241 12973 4594 2508 12974 4596 2244 12975 4595 2243 12976 4597 2509 12977 4594 2508 12978 4595 2243 12979 4596 2244 12980 4598 2246 12981 4597 2509 12982 4599 2510 12983 4598 2246 12984 4596 2244 12985 4597 2509 12986 4598 2246 12987 4599 2510 12988 4600 2248 12989 4601 2249 12990 4600 2248 12991 4602 2250 12992 4598 2246 12993 4600 2248 12994 4601 2249 12995 4603 2251 12996 4604 2252 12997 4605 2253 12998 4606 2254 12999 4602 2250 13000 4607 2255 13001 4601 2249 13002 4602 2250 13003 4606 2254 13004 4608 2256 13005 4605 2253 13006 4609 2257 13007 4610 2258 13008 4605 2253 13009 4608 2256 13010 4603 2251 13011 4605 2253 13012 4610 2258 13013 4611 2259 13014 4609 2257 13015 4612 2260 13016 4611 2259 13017 4608 2256 13018 4609 2257 13019 4613 2261 13020 4612 2260 13021 4614 2262 13022 4611 2259 13023 4612 2260 13024 4613 2261 13025 4615 11 13026 4616 11 13027 4561 11 13028 4617 2263 13029 4614 2262 13030 4618 2264 13031 4550 2265 13032 4615 2265 13033 4561 2265 13034 4613 2261 13035 4614 2262 13036 4617 2263 13037 4619 11 13038 4620 11 13039 4616 11 13040 4621 2266 13041 4618 2264 13042 4622 2267 13043 4615 11 13044 4619 11 13045 4616 11 13046 4617 2263 13047 4618 2264 13048 4621 2266 13049 4619 11 13050 4623 11 13051 4620 11 13052 4621 2266 13053 4622 2267 13054 4624 2268 13055 4625 2269 13056 4624 2268 13057 4626 2270 13058 4625 2269 13059 4621 2266 13060 4624 2268 13061 4627 2271 13062 4626 2270 13063 4628 2272 13064 4625 2269 13065 4626 2270 13066 4627 2271 13067 4629 2273 13068 4628 2272 13069 4630 2274 13070 4627 2271 13071 4628 2272 13072 4629 2273 13073 4631 2275 13074 4630 2274 13075 4632 2511 13076 4629 2273 13077 4630 2274 13078 4631 2275 13079 4633 2277 13080 4632 2511 13081 4634 2512 13082 4633 2277 13083 4631 2275 13084 4632 2511 13085 4633 2277 13086 4634 2512 13087 4569 2222 13088 4633 2277 13089 4569 2222 13090 4568 2221 13091 4635 11 13092 4636 11 13093 4637 11 13094 4638 11 13095 4635 11 13096 4637 11 13097 4639 11 13098 4638 11 13099 4637 11 13100 4640 11 13101 4641 11 13102 4636 11 13103 4635 11 13104 4640 11 13105 4636 11 13106 4642 11 13107 4643 11 13108 4641 11 13109 4640 11 13110 4642 11 13111 4641 11 13112 4639 11 13113 4644 11 13114 4638 11 13115 4645 11 13116 4646 11 13117 4644 11 13118 4639 11 13119 4645 11 13120 4644 11 13121 4647 11 13122 4648 11 13123 4646 11 13124 4645 11 13125 4647 11 13126 4646 11 13127 4681 11 13128 4682 11 13129 4683 11 13130 4706 11 13131 4707 11 13132 4708 11 13133 4709 11 13134 4710 11 13135 4711 11 13136 4712 11 13137 4709 11 13138 4711 11 13139 4713 11 13140 4714 11 13141 4715 11 13142 4716 11 13143 4717 11 13144 4718 11 13145 4728 11 13146 4729 11 13147 4730 11 13148 4745 11 13149 4746 11 13150 4747 11 13151 4767 1735 13152 4768 1735 13153 4769 1735 13154 4770 2129 13155 4771 2130 13156 4772 2131 13157 4773 2513 13158 4767 2513 13159 4769 2513 13160 4774 2514 13161 4775 2514 13162 4776 2514 13163 4777 2515 13164 4774 2515 13165 4776 2515 13166 4777 2516 13167 4776 2516 13168 4778 2516 13169 4779 2135 13170 4772 2131 13171 4780 2136 13172 4781 2137 13173 4770 2129 13174 4772 2131 13175 4779 2135 13176 4781 2137 13177 4772 2131 13178 4773 1735 13179 4782 1735 13180 4767 1735 13181 4783 2517 13182 4784 2517 13183 4785 2517 13184 4786 2140 13185 4779 2135 13186 4780 2136 13187 4787 2141 13188 4786 2140 13189 4780 2136 13190 4788 2518 13191 4789 2518 13192 4782 2518 13193 4790 2143 13194 4791 2519 13195 4792 2494 13196 4773 2520 13197 4788 2520 13198 4782 2520 13199 4793 2521 13200 4785 2521 13201 4794 2521 13202 4793 2522 13203 4783 2522 13204 4785 2522 13205 4795 2523 13206 4796 2523 13207 4789 2523 13208 4797 2149 13209 4792 2494 13210 4798 2150 13211 4788 2524 13212 4795 2524 13213 4789 2524 13214 4797 2149 13215 4790 2143 13216 4792 2494 13217 4799 1735 13218 4800 1735 13219 4796 1735 13220 4801 542 13221 4802 542 13222 4803 542 13223 4795 1735 13224 4799 1735 13225 4796 1735 13226 4804 2152 13227 4797 2149 13228 4798 2150 13229 4805 2525 13230 4806 2525 13231 4800 2525 13232 4807 2154 13233 4808 2526 13234 4809 2156 13235 4799 1735 13236 4805 1735 13237 4800 1735 13238 4810 542 13239 4801 542 13240 4803 542 13241 4810 542 13242 4803 542 13243 4811 542 13244 4812 2527 13245 4813 2527 13246 4806 2527 13247 4814 2158 13248 4809 2156 13249 4815 2159 13250 4805 2528 13251 4812 2528 13252 4806 2528 13253 4814 2158 13254 4807 2154 13255 4809 2156 13256 4816 1735 13257 4817 1735 13258 4813 1735 13259 4818 2529 13260 4819 2529 13261 4820 2529 13262 4812 1735 13263 4816 1735 13264 4813 1735 13265 4821 2161 13266 4814 2158 13267 4815 2159 13268 4816 1735 13269 4822 1735 13270 4817 1735 13271 4823 2163 13272 4824 2164 13273 4825 2165 13274 4826 2530 13275 4818 2530 13276 4820 2530 13277 4826 2531 13278 4820 2531 13279 4827 2531 13280 4828 2168 13281 4825 2165 13282 4829 2169 13283 4830 2170 13284 4823 2163 13285 4825 2165 13286 4828 2168 13287 4830 2170 13288 4825 2165 13289 4831 2532 13290 4832 2532 13291 4833 2532 13292 4834 2172 13293 4828 2168 13294 4829 2169 13295 4835 2173 13296 4834 2172 13297 4829 2169 13298 4836 2503 13299 4837 2533 13300 4838 2534 13301 4839 2535 13302 4833 2535 13303 4840 2535 13304 4839 2536 13305 4831 2536 13306 4833 2536 13307 4841 2179 13308 4838 2534 13309 4842 2180 13310 4841 2179 13311 4836 2503 13312 4838 2534 13313 4843 31 13314 4844 31 13315 4845 31 13316 4846 2181 13317 4841 2179 13318 4842 2180 13319 4847 2182 13320 4848 2183 13321 4849 2184 13322 4850 31 13323 4845 31 13324 4851 31 13325 4850 31 13326 4843 31 13327 4845 31 13328 4852 2537 13329 4849 2184 13330 4853 2186 13331 4852 2537 13332 4847 2182 13333 4849 2184 13334 4854 2187 13335 4852 2537 13336 4853 2186 13337 4855 11 13338 4856 11 13339 4857 11 13340 4858 2188 13341 4859 2188 13342 4860 2190 13343 4861 11 13344 4857 11 13345 4862 11 13346 4863 2191 13347 4864 2191 13348 4865 2192 13349 4861 11 13350 4855 11 13351 4857 11 13352 4863 2191 13353 4865 2192 13354 4866 2192 13355 4867 11 13356 4868 11 13357 4856 11 13358 4869 2190 13359 4860 2190 13360 4870 2193 13361 4871 11 13362 4867 11 13363 4856 11 13364 4855 2538 13365 4871 2538 13366 4856 2538 13367 4869 2190 13368 4858 2188 13369 4860 2190 13370 4872 11 13371 4873 11 13372 4868 11 13373 4874 2195 13374 4870 2193 13375 4875 2196 13376 4867 2539 13377 4872 2539 13378 4868 2539 13379 4869 2190 13380 4870 2193 13381 4874 2195 13382 4872 11 13383 4876 11 13384 4873 11 13385 4877 2198 13386 4875 2196 13387 4878 2199 13388 4874 2195 13389 4875 2196 13390 4877 2198 13391 4879 11 13392 4880 11 13393 4876 11 13394 4881 2200 13395 4878 2199 13396 4882 2201 13397 4883 11 13398 4879 11 13399 4876 11 13400 4872 11 13401 4883 11 13402 4876 11 13403 4877 2198 13404 4878 2199 13405 4881 2200 13406 4884 11 13407 4885 11 13408 4880 11 13409 4886 2203 13410 4882 2201 13411 4887 2204 13412 4879 11 13413 4884 11 13414 4880 11 13415 4881 2200 13416 4882 2201 13417 4886 2203 13418 4888 11 13419 4889 11 13420 4885 11 13421 4890 2204 13422 4887 2204 13423 4891 2205 13424 4892 11 13425 4888 11 13426 4885 11 13427 4884 2540 13428 4892 2540 13429 4885 2540 13430 4886 2203 13431 4887 2204 13432 4890 2204 13433 4893 11 13434 4894 11 13435 4889 11 13436 4895 2207 13437 4896 2207 13438 4897 2208 13439 4893 11 13440 4889 11 13441 4888 11 13442 4890 2204 13443 4891 2205 13444 4898 2205 13445 4899 2541 13446 4900 2541 13447 4894 2541 13448 4901 2208 13449 4897 2208 13450 4902 2210 13451 4903 11 13452 4899 11 13453 4894 11 13454 4893 11 13455 4903 11 13456 4894 11 13457 4895 2207 13458 4897 2208 13459 4901 2208 13460 4904 11 13461 4905 11 13462 4900 11 13463 4906 2211 13464 4902 2210 13465 4907 2212 13466 4899 2542 13467 4904 2542 13468 4900 2542 13469 4901 2208 13470 4902 2210 13471 4906 2211 13472 4904 11 13473 4908 11 13474 4905 11 13475 4909 2213 13476 4907 2212 13477 4910 2214 13478 4906 2211 13479 4907 2212 13480 4909 2213 13481 4911 2543 13482 4912 2543 13483 4908 2543 13484 4913 2215 13485 4910 2214 13486 4914 2216 13487 4915 11 13488 4911 11 13489 4908 11 13490 4904 11 13491 4915 11 13492 4908 11 13493 4909 2213 13494 4910 2214 13495 4913 2215 13496 4916 11 13497 4862 11 13498 4912 11 13499 4917 2217 13500 4914 2216 13501 4864 2191 13502 4911 11 13503 4916 11 13504 4912 11 13505 4913 2215 13506 4914 2216 13507 4917 2217 13508 4918 11 13509 4861 11 13510 4862 11 13511 4916 11 13512 4918 11 13513 4862 11 13514 4917 2217 13515 4864 2191 13516 4863 2191 13517 4919 2218 13518 4920 2219 13519 4921 2220 13520 4922 2221 13521 4923 2222 13522 4924 2223 13523 4925 2544 13524 4924 2223 13525 4926 2225 13526 4922 2221 13527 4924 2223 13528 4925 2544 13529 4927 2226 13530 4921 2220 13531 4928 2227 13532 4929 2228 13533 4921 2220 13534 4927 2226 13535 4919 2218 13536 4921 2220 13537 4929 2228 13538 4930 2229 13539 4928 2227 13540 4931 2230 13541 4930 2229 13542 4927 2226 13543 4928 2227 13544 4932 2231 13545 4931 2230 13546 4933 2232 13547 4930 2229 13548 4931 2230 13549 4932 2231 13550 4934 11 13551 4935 11 13552 4883 11 13553 4936 2233 13554 4933 2232 13555 4937 2545 13556 4872 11 13557 4934 11 13558 4883 11 13559 4932 2231 13560 4933 2232 13561 4936 2233 13562 4938 11 13563 4939 11 13564 4935 11 13565 4940 2546 13566 4937 2545 13567 4941 2547 13568 4934 11 13569 4938 11 13570 4935 11 13571 4936 2233 13572 4937 2545 13573 4940 2546 13574 4938 11 13575 4942 11 13576 4939 11 13577 4940 2546 13578 4941 2547 13579 4943 2237 13580 4944 2238 13581 4943 2237 13582 4945 2239 13583 4944 2238 13584 4940 2546 13585 4943 2237 13586 4946 2240 13587 4945 2239 13588 4947 2548 13589 4944 2238 13590 4945 2239 13591 4946 2240 13592 4948 2242 13593 4947 2548 13594 4949 2243 13595 4946 2240 13596 4947 2548 13597 4948 2242 13598 4950 2549 13599 4949 2243 13600 4951 2509 13601 4948 2242 13602 4949 2243 13603 4950 2549 13604 4952 2246 13605 4951 2509 13606 4953 2247 13607 4952 2246 13608 4950 2549 13609 4951 2509 13610 4952 2246 13611 4953 2247 13612 4954 2248 13613 4955 2249 13614 4954 2248 13615 4956 2250 13616 4952 2246 13617 4954 2248 13618 4955 2249 13619 4957 2251 13620 4958 2252 13621 4959 2253 13622 4960 2254 13623 4956 2250 13624 4961 2255 13625 4955 2249 13626 4956 2250 13627 4960 2254 13628 4962 2256 13629 4959 2253 13630 4963 2257 13631 4964 2550 13632 4959 2253 13633 4962 2256 13634 4957 2251 13635 4959 2253 13636 4964 2550 13637 4965 2259 13638 4963 2257 13639 4966 2260 13640 4965 2259 13641 4962 2256 13642 4963 2257 13643 4967 2261 13644 4966 2260 13645 4968 2262 13646 4965 2259 13647 4966 2260 13648 4967 2261 13649 4969 11 13650 4970 11 13651 4915 11 13652 4971 2551 13653 4968 2262 13654 4972 2552 13655 4904 11 13656 4969 11 13657 4915 11 13658 4967 2261 13659 4968 2262 13660 4971 2551 13661 4973 11 13662 4974 11 13663 4970 11 13664 4975 2553 13665 4972 2552 13666 4976 2267 13667 4969 11 13668 4973 11 13669 4970 11 13670 4971 2551 13671 4972 2552 13672 4975 2553 13673 4973 11 13674 4977 11 13675 4974 11 13676 4975 2553 13677 4976 2267 13678 4978 2268 13679 4979 2269 13680 4978 2268 13681 4980 2270 13682 4979 2269 13683 4975 2553 13684 4978 2268 13685 4981 2271 13686 4980 2270 13687 4982 2554 13688 4979 2269 13689 4980 2270 13690 4981 2271 13691 4983 2555 13692 4982 2554 13693 4984 2274 13694 4981 2271 13695 4982 2554 13696 4983 2555 13697 4985 2556 13698 4984 2274 13699 4986 2511 13700 4983 2555 13701 4984 2274 13702 4985 2556 13703 4987 2277 13704 4986 2511 13705 4988 2278 13706 4987 2277 13707 4985 2556 13708 4986 2511 13709 4987 2277 13710 4988 2278 13711 4923 2222 13712 4987 2277 13713 4923 2222 13714 4922 2221 13715 4989 11 13716 4990 11 13717 4991 11 13718 4992 11 13719 4989 11 13720 4991 11 13721 4993 11 13722 4992 11 13723 4991 11 13724 4994 11 13725 4995 11 13726 4990 11 13727 4989 11 13728 4994 11 13729 4990 11 13730 4996 11 13731 4997 11 13732 4995 11 13733 4994 11 13734 4996 11 13735 4995 11 13736 4993 11 13737 4998 11 13738 4992 11 13739 4999 11 13740 5000 11 13741 4998 11 13742 4993 11 13743 4999 11 13744 4998 11 13745 5001 11 13746 5002 11 13747 5000 11 13748 4999 11 13749 5001 11 13750 5000 11 13751 5003 11 13752 5004 11 13753 5005 11 13754

-
- - - - -

3387 542 13755 3388 542 13756 3389 542 13757 3390 555 13758 3391 555 13759 3392 555 13760 3396 555 13761 3397 555 13762 3398 555 13763 3399 2557 13764 3400 2557 13765 3401 2557 13766 3402 31 13767 3403 31 13768 3404 31 13769 3405 555 13770 3406 555 13771 3407 555 13772 3399 2557 13773 3401 2557 13774 3408 2557 13775 3405 555 13776 3407 555 13777 3409 555 13778 3410 542 13779 3411 542 13780 3412 542 13781 3413 2558 13782 3414 2559 13783 3415 2560 13784 3416 2561 13785 3414 2559 13786 3413 2558 13787 3417 2562 13788 3415 2560 13789 3418 2563 13790 3413 2558 13791 3415 2560 13792 3417 2562 13793 3419 31 13794 3420 31 13795 3421 31 13796 3417 2562 13797 3418 2563 13798 3422 2564 13799 3419 31 13800 3421 31 13801 3423 31 13802 3669 2453 13803 3670 2453 13804 3671 2453 13805 3672 542 13806 3673 542 13807 3674 542 13808 3678 2565 13809 3679 2565 13810 3680 2565 13811 3681 2566 13812 3682 2566 13813 3683 2566 13814 3684 2567 13815 3685 2568 13816 3686 2569 13817 3687 2570 13818 3685 2568 13819 3684 2567 13820 4302 31 13821 4303 31 13822 4304 31 13823 4308 2569 13824 4309 2569 13825 4310 2569 13826 4311 11 13827 4312 11 13828 4313 11 13829 4314 11 13830 4315 11 13831 4312 11 13832 4311 11 13833 4316 11 13834 4312 11 13835 4317 2571 13836 4312 2571 13837 4316 2571 13838 4318 11 13839 4312 11 13840 4317 11 13841 4318 11 13842 4314 11 13843 4312 11 13844 4319 11 13845 4320 11 13846 4315 11 13847 4321 11 13848 4319 11 13849 4315 11 13850 4314 11 13851 4321 11 13852 4315 11 13853 4322 2572 13854 4323 2572 13855 4320 2572 13856 4324 11 13857 4322 11 13858 4320 11 13859 4325 11 13860 4324 11 13861 4320 11 13862 4319 11 13863 4325 11 13864 4320 11 13865 4326 11 13866 4327 11 13867 4323 11 13868 4322 11 13869 4326 11 13870 4323 11 13871 4328 11 13872 4329 11 13873 4324 11 13874 4330 11 13875 4328 11 13876 4324 11 13877 4331 11 13878 4330 11 13879 4324 11 13880 4325 11 13881 4331 11 13882 4324 11 13883 4317 11 13884 4316 11 13885 4329 11 13886 4328 11 13887 4317 11 13888 4329 11 13889 4332 11 13890 4333 11 13891 4334 11 13892 4335 11 13893 4332 11 13894 4334 11 13895 4336 11 13896 4337 11 13897 4338 11 13898 4339 11 13899 4336 11 13900 4338 11 13901 4340 11 13902 4341 11 13903 4336 11 13904 4339 11 13905 4340 11 13906 4336 11 13907 4342 11 13908 4343 11 13909 4344 11 13910 4345 11 13911 4342 11 13912 4344 11 13913 4346 11 13914 4345 11 13915 4344 11 13916 4345 11 13917 4347 11 13918 4342 11 13919 4348 11 13920 4349 11 13921 4347 11 13922 4350 11 13923 4348 11 13924 4347 11 13925 4345 11 13926 4350 11 13927 4347 11 13928 4350 11 13929 4351 11 13930 4348 11 13931 4361 2573 13932 4362 2573 13933 4363 2573 13934 4373 542 13935 4374 542 13936 4375 542 13937 4376 555 13938 4377 555 13939 4378 555 13940 4379 542 13941 4380 542 13942 4381 542 13943 4382 1123 13944 4383 1123 13945 4384 1123 13946 4382 1123 13947 4384 1123 13948 4385 1123 13949 4386 555 13950 4387 555 13951 4388 555 13952 4389 542 13953 4379 542 13954 4381 542 13955 4403 555 13956 4404 555 13957 4405 555 13958 4406 31 13959 4407 31 13960 4408 31 13961 4406 31 13962 4408 31 13963 4409 31 13964 4410 2574 13965 4411 2574 13966 4412 2574 13967 4649 2575 13968 4650 2576 13969 4651 2577 13970 4652 2578 13971 4650 2576 13972 4649 2575 13973 4653 2579 13974 4654 2580 13975 4655 2581 13976 4656 2582 13977 4654 2580 13978 4653 2579 13979 4657 2583 13980 4655 2581 13981 4658 2584 13982 4653 2579 13983 4655 2581 13984 4657 2583 13985 4659 2585 13986 4658 2584 13987 4660 2586 13988 4657 2583 13989 4658 2584 13990 4659 2585 13991 4661 2587 13992 4660 2586 13993 4662 2588 13994 4659 2585 13995 4660 2586 13996 4661 2587 13997 4661 2587 13998 4662 2588 13999 4663 2589 14000 4664 1123 14001 4665 1123 14002 4666 1123 14003 4667 31 14004 4668 31 14005 4669 31 14006 4667 31 14007 4669 31 14008 4670 31 14009 4671 542 14010 4672 542 14011 4673 542 14012 4674 1123 14013 4664 1123 14014 4666 1123 14015 4675 555 14016 4676 555 14017 4677 555 14018 4678 542 14019 4679 542 14020 4680 542 14021 4684 542 14022 4685 542 14023 4686 542 14024 4687 1123 14025 4688 1123 14026 4689 1123 14027 4690 2590 14028 4691 2590 14029 4692 2590 14030 4684 542 14031 4686 542 14032 4693 542 14033 4694 1123 14034 4695 1123 14035 4696 1123 14036 4690 2591 14037 4692 2591 14038 4697 2591 14039 4698 542 14040 4699 542 14041 4700 542 14042 4694 1123 14043 4696 1123 14044 4701 1123 14045 4702 555 14046 4703 555 14047 4704 555 14048 4698 542 14049 4700 542 14050 4705 542 14051 4719 31 14052 4720 31 14053 4721 31 14054 4722 555 14055 4723 555 14056 4724 555 14057 4725 542 14058 4726 542 14059 4727 542 14060 4731 555 14061 4732 555 14062 4733 555 14063 4734 1123 14064 4735 1123 14065 4736 1123 14066 4737 31 14067 4738 31 14068 4739 31 14069 4737 31 14070 4739 31 14071 4740 31 14072 4741 542 14073 4742 542 14074 4743 542 14075 4744 1123 14076 4734 1123 14077 4736 1123 14078 4748 555 14079 4749 555 14080 4750 555 14081 4751 1123 14082 4752 1123 14083 4753 1123 14084 4754 31 14085 4755 31 14086 4756 31 14087 4754 31 14088 4756 31 14089 4757 31 14090 4758 555 14091 4759 555 14092 4760 555 14093 4761 555 14094 4762 555 14095 4763 555 14096 4764 31 14097 4765 31 14098 4766 31 14099 5006 2592 14100 5007 2593 14101 5008 2594 14102 5009 2595 14103 5007 2593 14104 5006 2592 14105

-
-
-
-
- - - - - 7.54969e-11 4.01334e-10 9.99987e-4 0 9.99987e-4 -2.38416e-10 -7.54968e-11 0 2.38415e-10 9.99987e-4 -4.01334e-10 0 0 0 0 1 - - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl deleted file mode 100644 index bae34a09c013db51315380b61f84d8c063869b94..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6284 zcmb7|d2Cfx5QoQ5rIY}&77i?9zJtQ@#HBbef#GOejvNo-1$Y>_w}~_^>2}^f8JFSshGGR z*5%BkXt&(!{q~+Z9C1!Iy|V27XKh8~^2W6255va{Sv+Z(_qSQks+!0O5jTsV^3}Qx zLte}{=+X3KHtXD)=+)Zd*sUUHMf$UxlS7^W>X8ZVm&Vnjirg8 z73p6Jhem$a&#jwTv52lB+KZraw9l%D`?-~-C$k>1c5!YJK`YW#${|g;Bx77YT@l?h zqd1mTS{9{p@tZ4=y~@SKpeM6W#y%WtJ-RMhdgpghT9Gc*UL4h)Bx5+@>ZrQtN)c2# zwrb(6wu?beW)D3-E_UeJ(&&~+^-)@pE>}%8sJ4j*B`d)?_$uC*>n;4Gj_y# ziJ%o}*Bd8>kJ+D$F;zs~%pGy}R8;mVkJIZm>~}Hf$?QR8e(>7T>i3j6tw_7x*q3wC zkCB&LtLmL1sC3ePJi4Vz+{K_Lvl{JSx6yUgW!gbnk#_sv*dsHZ%;R$r4WsI+7mJ|c z@3R+!p3FLL84#N@t7D?Wp)XQ(2nf4_8aN-M@sSQ)uS2D z>`C=Tw@X74otpZ?v!Y+ukCnZP{1|=@CR`6valN5F_h`mb9y%Egb)Vo7v?5)j-gvs8 z)Q^!V;(&;5ib3TuomY8hs=OHVq`FF;iC!MGB3-NAD4Vp*k1;{SpS8t_wu(XJc=Fu! zV$hS>#^l-V#h?}GyoKv4OKpW8<4Y0CCoV{IRtzfdFG<_E=hR^@20fV#s;Y@E6X8~u zR;2$>Z#)y^(OSfFB5oH!r9r*%LdHQa20iH%J-4P>?~jCgf6$6_t$JgAupi|j^!`Y6 z6+z_*^~NxNKj_J<_vrfSYJbmZMY?rXW_){4S9geTd+sWc%Ey)C<7s|f(UaMX!mLE5 zYS*n5tw{f=-Z&rhhiW&`MMS0uDyRCaiXYL>^*KG6-7D)cqI!y;73sao;n$$gvqcn% zaCuN^qa3y?7Z-z`%#JJT^P}pk-ONBM(q-C%41+|>OJUsW045g=TufJk9O;m z??J{hYf$EuIvrYzpcUy7*Bin6{8tgBB3va>iE2M)>&$X_(39DI?O={hIrmhwBE3y@ zl^M(>yF@%9;uaB98sFR;ul45=dNOOTN}Q+j-BmlSNPnx|XgM}DUpZpF2=`P}4yZTI z`12J#nLVaT&(VyPA%a$WvQmoJdb*_3Djdnk?N@(Ten1 z^+rW7?>a(V<;}ZP`l~nc{dt$3%(muV80dD%tUSgUmoqhIc(XO5W)4abR7%uAOa1Ad zvCTRZTnGp%%!BJ@HW>sJ?jS41>{5PH3@WT$_KMl~f(yG-c~D{3@{~y0rU)uLuXsM1 zoy~7rD=Ivx`DO^mpu%?)--%&@3g6D02Eqgt&Ly0K%=-HK(b!lPqr!=d6JR(770#lZ zeZvG5?ME=(bLtNhRNPagzH8jmHho8pENI#fDlYTX7ahAG9D@ogpEYf^Hup+Zk}Ho< zVI8wV&EC$v67(PyRwe7r?DgEaK}S(xjj?*dc~D`+uoldY<<1TIg9`VbI~$Hcg}cdp z^705Wr^3DAs+;|OHa#GyaHYA1O;6=&mkQU7D`HlM7*x0l%+Ktnv+2Q}Q(;bg+NP)a z=ef%#WNfpvnxb7vt~^GC@xn0%Yl>;q?MEBEKlla+trbpfvzUnMBGN_hJYTK3XRUuH zLr-S!Y3^C6TO3EQCwOy1+AJ=@-4wYQjtb+^Q)sOcBp4%ni_^rEC#diqCVXF#B2*;_ z-g59ZB7AE=f-&fqo>KPi|MCP^kvY**nBZ){cQ`$T2~I_vUg#-Ia318`Mo(dalQ1V% zdI}T#2H>ntPho;zKm1Cer!c|qK7OCkQ<&fvFTYIbDNOKNpWo#46ef7f!P^LW3KP8F z;XMpJg$dRuZ=mQYOt5}fea+V{6~=2m1{FSg^O;lOiZ;I=RJhMKt`gVhR9Jn@*De+I tMDra*g)7Z94DSaOt{Ye6hQz;aJeXgYpu(K^v|)k@pYXpu730y9+21WY#bE#d diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae deleted file mode 100644 index c5e6720a80..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae +++ /dev/null @@ -1,109 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T14:19:13 - 2019-01-15T14:19:13 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 66.62159 199.1908 -7.838266 73 200.4 0 67.04737 198.805 0 73 201.1355 9.366105 67.04737 198.805 0 73 200.4 0 62.35687 147.4 -4.909072 66.62159 199.1908 -7.838266 67.04737 198.805 0 62.55 147.4 0 66.65715 199.1585 7.50474 62.55 147.4 0 67.04737 198.805 0 66.65715 199.1585 7.50474 73 200.5892 -4.744023 73 201.1355 9.366105 73 200.4 0 73 200.5892 -4.744023 73 201.145 -9.425759 73 201.145 -9.425759 65.23722 200.4394 -16.08258 73 203.3566 -18.60236 73 203.3307 18.52296 73 203.3566 -18.60236 62.89741 202.5284 -24.14646 73 206.9651 -27.28928 73 205.5958 -4.636376 73 206.9651 -27.28928 73 205.5785 4.426485 59.50509 205.5042 -32.14698 73 211.8458 -35.24898 73 207.099 -13.56462 73 211.8458 -35.24898 54.97298 212.6055 -43.80249 73 217.9537 -42.40642 73 214.3578 -30.08507 73 217.9537 -42.40642 54.97298 209.3612 -39.97518 73 210.0452 -22.12212 54.97298 219.9317 -50.6487 73 225.1053 -48.5209 73 219.9292 -37.24397 73 225.1053 -48.5209 54.97298 216.1361 -47.36745 54.97298 228.2261 -56.28329 73 233.1109 -53.43502 73 226.6157 -43.40071 73 233.1109 -53.43502 54.97298 223.9698 -53.62659 54.97298 237.29 -60.57145 73 241.7791 -57.03734 73 234.1582 -48.33597 73 241.7791 -57.03734 54.97298 232.675 -58.60287 54.97298 246.9069 -63.41062 73 250.9048 -59.24386 73 242.4686 -51.99485 73 250.9048 -59.24386 54.97298 242.0435 -62.17724 54.97298 256.8465 -64.73287 73 260.2702 -59.99981 73 251.3035 -54.24254 73 260.2702 -59.99981 54.97298 251.8511 -64.2642 54.97298 266.8711 -64.50656 73 269.6504 -59.28258 73 260.4 -55 73 269.6504 -59.28258 54.97298 261.8632 -64.81381 73 255.819 -54.80755 54.97298 276.7409 -62.73711 73 278.8189 -57.10287 73 278.2565 -52.02062 73 278.8189 -57.10287 54.97298 271.8403 -63.81294 73 269.4408 -54.25185 54.97298 286.2198 -59.46686 73 287.5507 -53.50549 73 286.5788 -48.37014 73 287.5507 -53.50549 54.97298 281.5437 -61.28552 54.97298 290.7413 -57.29203 73 291.6828 -51.19839 73 291.6828 -51.19839 54.97298 295.0811 -54.77404 73 295.6245 -48.57189 73 294.1535 -43.42462 73 295.6245 -48.57189 54.97298 299.2131 -51.92798 73 299.3497 -45.63732 73 297.6402 -40.47071 73 299.3497 -45.63732 54.97298 303.1127 -48.7709 73 302.8335 -42.41926 73 300.8807 -37.23322 73 302.8335 -42.41926 54.97298 306.7564 -45.3217 73 306.05 -38.93364 73 303.833 -33.74082 73 306.05 -38.93364 54.97298 310.1225 -41.60105 73 308.9768 -35.21779 73 306.4852 -30.01914 73 308.9768 -35.21779 54.97298 315.9428 -33.43601 73 313.8686 -27.22327 73 310.8111 -21.99357 73 313.8686 -27.22327 54.97298 313.1907 -37.63123 54.97298 320.4345 -24.47112 73 317.4692 -18.52296 73 315.2215 -4.426485 73 317.4692 -18.52296 54.97298 318.3622 -29.04054 73 313.7468 -13.38335 54.97298 323.4899 -14.92082 73 319.6645 -9.366105 73 319.655 9.425759 73 319.6645 -9.366105 54.97298 322.1471 -19.75514 73 317.4434 18.60236 54.97298 325.2303 0 73 320.4 0 73 320.2108 4.744023 73 320.4 0 54.97298 325.0362 -5.013586 54.97298 324.4549 -9.997143 54.97298 325.0362 5.013586 73 320.4 0 54.97298 325.2303 0 73 320.2108 4.744023 45.97885 331.8909 0 54.97298 325.2303 0 54.97298 325.0362 -5.013586 45.97885 331.2736 9.374498 54.97298 325.2303 0 45.97885 331.8909 0 54.97298 325.0362 5.013586 45.97885 331.2736 -9.374498 54.97298 324.4549 -9.997143 54.97298 323.4899 -14.92082 45.97885 329.4324 -18.5871 54.97298 322.1471 -19.75514 54.97298 320.4345 -24.47112 45.97885 326.399 -27.47872 54.97298 318.3622 -29.04054 45.97885 322.2259 -35.8958 54.97298 315.9428 -33.43601 54.97298 313.1907 -37.63123 45.97885 316.9851 -43.69299 54.97298 310.1225 -41.60105 54.97298 306.7564 -45.3217 45.97885 310.7671 -50.73564 54.97298 303.1127 -48.7709 45.97885 303.6793 -56.90211 54.97298 299.2131 -51.92798 54.97298 295.0811 -54.77404 45.97885 295.8441 -62.08593 54.97298 290.7413 -57.29203 54.97298 286.2198 -59.46686 45.97885 287.3968 -66.19757 54.97298 281.5437 -61.28552 45.97885 278.4833 -69.16603 54.97298 276.7409 -62.73711 54.97298 271.8403 -63.81294 45.97885 269.2575 -70.94004 54.97298 266.8711 -64.50656 54.97298 261.8632 -64.81381 45.97885 259.8788 -71.48899 54.97298 256.8465 -64.73287 54.97298 251.8511 -64.2642 45.97885 250.509 -70.80335 54.97298 246.9069 -63.41062 45.97885 241.3101 -68.89499 54.97298 242.0435 -62.17724 54.97298 237.29 -60.57145 45.97885 232.4408 -65.79689 54.97298 232.675 -58.60287 54.97298 228.2261 -56.28329 45.97885 224.0544 -61.56249 54.97298 223.9698 -53.62659 45.97885 216.2956 -56.26497 54.97298 219.9317 -50.6487 54.97298 216.1361 -47.36745 46.01564 209.3612 -50.02604 54.97298 212.6055 -43.80249 50.25096 209.3612 -45.76991 54.97298 209.3612 -39.97518 50.64026 147.4 -36.716 54.97298 209.3612 -39.97518 59.50509 205.5042 -32.14698 47.58631 147.4 -40.59246 50.25096 209.3612 -45.76991 55.74084 147.4 -28.38063 62.89741 202.5284 -24.14646 53.35656 147.4 -32.64563 59.49447 147.4 -19.31087 65.23722 200.4394 -16.08258 57.79339 147.4 -23.92148 60.82553 147.4 -14.58077 61.78324 147.4 -9.763909 44.23035 147.4 -44.22867 46.01564 209.3612 -50.02604 40.59742 147.4 -47.58352 44.79955 209.3612 -51.11795 44.79955 209.3612 -51.11795 36.71356 147.4 -50.642 38.64964 209.3612 -55.91287 38.64964 209.3612 -55.91287 32.60395 147.4 -53.37942 36.0613 209.3612 -57.6162 36.0613 209.3612 -57.6162 31.84824 209.3612 -60.04776 25.46692 211.3358 -64.56887 31.84824 209.3612 -60.04776 36.0229 217.5118 -63.93712 23.81617 147.4 -57.83746 22.67369 210.4263 -64.17652 25.46692 211.3358 -64.56887 31.84824 209.3612 -60.04776 22.67369 210.4263 -64.17652 28.29614 147.4 -55.78374 14.45719 147.4 -60.85541 12.98032 211.5135 -66.9118 23.252 212.0202 -65.90705 12.98032 211.5135 -66.9118 19.19369 147.4 -59.53233 4.760062 147.4 -62.36774 2.967647 212.5878 -68.18865 14.37408 214.7581 -70.25098 2.967647 212.5878 -68.18865 9.636244 147.4 -61.80323 -5.039426 147.4 -62.3458 -7.104365 213.6084 -67.97223 4.121392 217.9103 -73.50268 -7.104365 213.6084 -67.97223 -0.141712 147.4 -62.54979 13.94689 214.8896 -70.42224 -14.70538 147.4 -60.79596 -17.00805 214.5402 -66.27647 -6.025453 221.0206 -75.08634 -17.00805 214.5402 -66.27647 -9.903903 147.4 -61.7609 3.064081 218.2349 -73.74087 -19.41596 147.4 -59.46022 -21.83266 214.9631 -64.88639 -16.28796 224.1575 -75.14109 -21.83266 214.9631 -64.88639 -8.299376 221.7165 -75.23102 -24.00643 147.4 -57.75894 -26.53528 215.3532 -63.14635 -19.51969 225.1436 -74.83963 -26.53528 215.3532 -63.14635 -28.45097 147.4 -55.70494 -31.08435 215.7065 -61.0703 -26.45742 227.2577 -73.66539 -31.08435 215.7065 -61.0703 -35.46889 216.0225 -58.66487 -36.32621 230.2588 -70.68886 -35.46889 216.0225 -58.66487 -30.39257 228.4552 -72.66928 -32.722 147.4 -53.30737 -39.67829 216.2996 -55.93358 -40.72129 231.5931 -68.82544 -39.67829 216.2996 -55.93358 -36.79549 147.4 -50.58251 -43.67799 216.5373 -52.8963 -45.69338 233.101 -66.27128 -43.67799 216.5373 -52.8963 -40.64623 147.4 -47.54211 -47.43993 216.7337 -49.57416 -50.32191 234.5033 -63.41976 -47.43993 216.7337 -49.57416 -44.2502 147.4 -44.2088 -50.94563 216.8917 -45.9846 -54.36434 235.7268 -60.50415 -50.94563 216.8917 -45.9846 -47.58338 147.4 -40.59617 -54.17495 217.0117 -42.14921 -59.0212 237.135 -56.57065 -54.17495 217.0117 -42.14921 -50.62059 147.4 -36.74311 -57.11404 217.0984 -38.08555 -62.17095 238.0867 -53.49663 -57.11404 217.0984 -38.08555 -53.32715 147.4 -32.69383 -59.7494 217.1547 -33.81137 -66.72772 239.4625 -48.31177 -59.7494 217.1547 -33.81137 -55.70747 147.4 -28.44606 -62.06512 217.1866 -29.35139 -68.79174 240.0853 -45.60712 -62.06512 217.1866 -29.35139 -57.76154 147.4 -23.99858 -64.04738 217.1991 -24.73189 -73.15702 241.4016 -38.88586 -64.04738 217.1991 -24.73189 -59.46792 147.4 -19.39247 -65.68744 217.1983 -19.97206 -76.69876 242.4687 -31.94951 -65.68744 217.1983 -19.97206 -73.581 241.5294 -38.14108 -60.80711 147.4 -14.65774 -66.97674 217.1904 -15.09123 -78.77391 243.0937 -26.83584 -66.97674 217.1904 -15.09123 -78.28528 242.9466 -28.13884 -61.77333 147.4 -9.826401 -67.90534 217.1798 -10.11759 -81.33267 243.8639 -18.34547 -67.90534 217.1798 -10.11759 -80.23657 243.534 -22.41946 -62.35276 147.4 -4.945741 -68.4663 217.1733 -5.078178 -82.53995 244.2272 -12.27183 -68.4663 217.1733 -5.078178 -82.18522 244.1205 -14.33761 -81.98159 244.0592 -15.39472 -62.55 147.4 0 -68.65397 217.1687 0 -83.31884 244.4615 -5.379289 -68.65397 217.1687 0 -83.11232 244.3994 -7.830876 -82.84999 244.3205 -10.1158 -62.35687 147.4 4.909072 -68.65397 217.1687 0 -62.55 147.4 0 -83.48104 244.5103 -1.852624 -83.50286 244.5169 0 -68.46621 217.1733 5.079516 -83.41838 244.4915 -3.64613 -68.46621 217.1733 5.079516 -62.35687 147.4 4.909072 -62.55 147.4 0 -62.35276 147.4 -4.945741 -61.78324 147.4 9.763909 -61.77333 147.4 -9.826401 -60.82553 147.4 14.58077 -60.80711 147.4 -14.65774 -59.49447 147.4 19.31087 -59.46792 147.4 -19.39247 -57.79339 147.4 23.92148 -57.76154 147.4 -23.99858 -55.74084 147.4 28.38063 -55.70747 147.4 -28.44606 -55 147.4 0 -53.32715 147.4 -32.69383 -52.02062 147.4 -17.8565 -50.62059 147.4 -36.74311 -54.25185 147.4 -9.040809 -48.37014 147.4 -26.17878 -47.58338 147.4 -40.59617 -44.2502 147.4 -44.2088 -43.42462 147.4 -33.75352 -40.64623 147.4 -47.54211 -40.47071 147.4 -37.24022 -36.79549 147.4 -50.58251 -33.74082 147.4 -43.43301 -32.722 147.4 -53.30737 -37.23322 147.4 -40.48065 -30.01914 147.4 -46.0852 -28.45097 147.4 -55.70494 -24.00643 147.4 -57.75894 -21.99357 147.4 -50.41108 -19.41596 147.4 -59.46022 -14.70538 147.4 -60.79596 -13.38335 147.4 -53.34679 -9.903903 147.4 -61.7609 -5.039426 147.4 -62.3458 -4.426485 147.4 -54.82153 -0.141712 147.4 -62.54979 4.636376 147.4 -54.80418 4.760062 147.4 -62.36774 9.636244 147.4 -61.80323 13.56462 147.4 -53.30099 14.45719 147.4 -60.85541 19.19369 147.4 -59.53233 22.12212 147.4 -50.35481 23.81617 147.4 -57.83746 28.29614 147.4 -55.78374 30.08507 147.4 -46.0422 32.60395 147.4 -53.37942 36.71356 147.4 -50.642 37.24397 147.4 -40.47077 40.59742 147.4 -47.58352 43.40071 147.4 -33.78425 44.23035 147.4 -44.22867 47.58631 147.4 -40.59246 48.33597 147.4 -26.24179 50.64026 147.4 -36.716 51.99485 147.4 -17.9314 53.35656 147.4 -32.64563 54.24254 147.4 -9.096512 55.74084 147.4 -28.38063 57.76154 147.4 23.99858 57.79339 147.4 -23.92148 55.70747 147.4 28.44606 55 147.4 0 54.80755 147.4 -4.580959 59.46792 147.4 19.39247 59.49447 147.4 -19.31087 60.80711 147.4 14.65774 60.82553 147.4 -14.58077 61.77333 147.4 9.826401 61.78324 147.4 -9.763909 62.35276 147.4 4.945741 62.35687 147.4 -4.909072 62.55 147.4 0 62.35276 147.4 4.945741 45.83531 331.983 0 36.0229 336.6877 10.36986 45.83531 331.983 0 36.0229 336.6877 -10.36986 36.0229 337.3893 0 36.0229 334.5958 -20.55073 36.0229 331.1517 -30.35706 36.0229 326.4181 -39.61013 36.0229 320.4813 -48.14131 36.0229 313.4496 -55.7951 36.0229 305.451 -62.43204 36.0229 296.6314 -67.93115 36.0229 287.1514 -72.1922 36.0229 277.1839 -75.13755 36.0229 266.9105 -76.71352 36.0229 256.5185 -76.89138 36.0229 246.1972 -75.6679 36.0229 236.1347 -73.06536 36.0229 226.5145 -69.13121 -84.24063 249.0634 0 -84.6249 252.4232 0 -85 260.4 0 -84.24063 249.1604 1.479726 -85 260.4 0 -84.6249 252.4232 0 -84.24063 249.1604 -1.479726 -84.24063 249.4497 -2.934133 -84.24063 249.9263 -4.338336 -84.24063 250.5822 -5.668309 -84.24063 251.406 -6.901296 -84.24063 252.3838 -8.016201 -84.24063 253.4987 -8.993946 -84.24063 254.7317 -9.8178 -84.24063 256.0617 -10.47367 -84.24063 257.4659 -10.95033 -84.24063 258.9203 -11.23963 -84.24063 260.4 -11.33662 -84.24063 261.8797 -11.23963 -84.24063 263.3341 -10.95033 -84.24063 264.7384 -10.47367 -84.24063 266.0683 -9.8178 -84.24063 267.3013 -8.993946 -84.24063 268.4162 -8.016201 -84.24063 269.394 -6.901296 -84.24063 270.2178 -5.668309 -84.24063 270.8737 -4.338336 -84.24063 271.3504 -2.934133 -84.24063 271.6396 -1.479726 -84.24063 271.7366 0 -84.24063 271.6396 1.479726 -84.24063 271.7366 0 -84.24063 249.4497 2.934133 -84.24063 249.9263 4.338336 -84.24063 250.5822 5.668309 -84.24063 251.406 6.901296 -84.24063 252.3838 8.016201 -84.24063 253.4987 8.993946 -84.24063 254.7317 9.8178 -84.24063 256.0617 10.47367 -84.24063 257.4659 10.95033 -84.24063 258.9203 11.23963 -84.24063 260.4 11.33662 -84.24063 261.8797 11.23963 -84.24063 263.3341 10.95033 -84.24063 264.7384 10.47367 -84.24063 266.0683 9.8178 -84.24063 267.3013 8.993946 -84.24063 268.4162 8.016201 -84.24063 269.394 6.901296 -84.24063 270.2178 5.668309 -84.24063 270.8737 4.338336 -84.24063 271.3504 2.934133 -84.24063 249.0634 0 -83.50286 244.5169 0 -83.47967 244.5099 1.909943 -83.50286 244.5169 0 -83.41838 244.4915 -3.64613 -83.48104 244.5103 -1.852624 -83.31884 244.4615 -5.379289 -83.11232 244.3994 -7.830876 -82.84999 244.3205 -10.1158 -82.18522 244.1205 -14.33761 -82.53995 244.2272 -12.27183 -81.97303 246.1615 -17.398 -81.98159 244.0592 -15.39472 -81.97303 248.5895 -19.12947 -81.97303 251.2253 -20.52435 -81.97303 254.0225 -21.5581 -81.97303 256.932 -22.21254 -81.97303 259.9024 -22.47613 -81.97303 262.8816 -22.34426 -81.97303 265.8171 -21.81924 -81.97303 268.6574 -20.9103 -81.97303 271.3523 -19.63344 -81.97303 273.8545 -18.01112 -81.97303 276.12 -16.07189 -81.97303 278.1089 -13.84988 -81.97303 279.7862 -11.38418 -81.97303 281.1224 -8.718166 -81.97303 282.094 -5.898755 -81.97303 282.6839 -2.975555 -81.97303 282.8817 0 -81.97303 282.8817 0 -78.23781 293.3311 -4.403518 -78.23781 293.6242 0 -81.97303 282.6904 2.925848 -78.23781 293.6242 0 -83.47967 244.5099 1.909943 -81.33267 243.8639 -18.34547 -80.23657 243.534 -22.41946 -78.23781 246.7565 -30.29358 -78.77391 243.0937 -26.83584 -78.28528 242.9466 -28.13884 -78.23781 250.892 -31.83462 -78.23781 255.1952 -32.81395 -78.23781 259.5903 -33.21429 -78.23781 263.9997 -33.02858 -78.23781 268.3455 -32.2601 -78.23781 272.5512 -30.9224 -78.23781 276.5424 -29.03908 -78.23781 280.2488 -26.64339 -78.23781 283.605 -23.77758 -78.23781 286.5518 -20.49222 -78.23781 289.0371 -16.84529 -78.23781 291.0171 -12.90113 -78.23781 292.4569 -8.729338 -73.10187 303.3769 -5.839935 -73.10187 303.7719 0 -78.23781 293.3636 4.152732 -73.10187 303.7719 0 -76.69876 242.4687 -31.94951 -73.10187 246.7559 -41.16983 -73.581 241.5294 -38.14108 -73.15702 241.4016 -38.88586 -73.10187 252.4235 -42.63208 -73.10187 258.2365 -43.31786 -73.10187 264.0889 -43.21469 -73.10187 269.8741 -42.32445 -73.10187 275.4867 -40.66336 -73.10187 280.8246 -38.26166 -73.10187 285.7904 -35.16311 -73.10187 290.2939 -31.42413 -73.10187 294.2528 -27.11282 -73.10187 297.5952 -22.3077 -73.10187 300.2602 -17.09629 -73.10187 302.1992 -11.57351 -66.65713 312.6834 -6.947996 -66.65713 313.143 0 -73.10187 303.4634 5.163478 -66.65713 313.143 0 -68.79174 240.0853 -45.60712 -66.65713 245.8829 -50.70582 -66.72772 239.4625 -48.31177 -66.65713 252.689 -52.17631 -66.65713 259.6296 -52.7374 -66.65713 266.5836 -52.37929 -66.65713 273.4298 -51.10824 -66.65713 280.0488 -48.9464 -66.65713 286.3255 -45.93144 -66.65713 292.1502 -42.11593 -66.65713 297.4216 -37.56635 -66.65713 302.0477 -32.36201 -66.65713 305.9479 -26.59361 -66.65713 309.0542 -20.3617 -66.65713 311.3125 -13.77489 -59.01899 321.0471 -7.980749 -59.01899 321.5699 0 -66.65713 312.6834 6.947765 -59.01899 321.5699 0 -62.17095 238.0867 -53.49663 -59.01899 244.6162 -59.09847 -59.0212 237.135 -56.57065 -59.01899 252.4616 -60.65261 -59.01899 260.4427 -61.1699 -59.01899 268.4231 -60.64147 -59.01899 276.2663 -59.07638 -59.01899 283.8383 -56.50137 -59.01899 291.0096 -52.96046 -59.01899 297.6576 -48.51419 -59.01899 303.6688 -43.23857 -59.01899 308.9402 -37.22377 -59.01899 313.3818 -30.57263 -59.01899 316.9177 -23.39885 -59.01899 319.4874 -15.82507 -50.32421 328.3179 -8.924008 -50.32421 328.9017 0 -59.01899 321.0471 7.980781 -50.32421 328.9017 0 -54.36434 235.7268 -60.50415 -50.32421 242.9059 -66.23014 -50.32191 234.5033 -63.41976 -50.32421 251.6831 -67.94475 -50.32421 260.6088 -68.50132 -50.32421 269.531 -67.89035 -50.32421 278.2976 -66.12226 -50.32421 286.7591 -63.22716 -50.32421 294.7713 -59.25444 -50.32421 302.1977 -54.27177 -50.32421 308.9118 -48.36409 -50.32421 314.7989 -41.6321 -50.32421 319.759 -34.19052 -50.32421 323.7072 -26.16621 -50.32421 326.5765 -17.69591 -40.72843 334.3656 -9.761198 -40.72843 335.0069 0 -50.32421 328.4846 7.54775 -40.72843 335.0069 0 -40.72843 240.7763 -71.97989 -45.69338 233.101 -66.27128 -40.72843 250.3624 -73.92863 -40.72843 260.1212 -74.60643 -40.72843 269.8847 -74.00159 -40.72843 279.4852 -72.12456 -40.72843 288.7575 -69.00759 -40.72843 297.5424 -64.70425 -40.72843 305.6887 -59.28853 -40.72843 313.0564 -52.85356 -40.72843 319.5189 -45.50994 -40.72843 324.965 -37.38393 -40.72843 329.3011 -28.61523 -40.72843 332.4527 -19.35458 -30.40347 339.082 -10.47772 -30.40347 339.7765 0 -40.72843 334.3656 9.761198 -30.40347 339.7765 0 -40.72129 231.5931 -68.82544 -30.40347 238.2644 -76.22757 -36.32621 230.2588 -70.68886 -30.40347 248.5201 -78.48246 -30.40347 258.9838 -79.36387 -30.40347 269.4722 -78.85636 -30.40347 279.8019 -76.96881 -30.40347 289.792 -73.73426 -30.40347 299.2678 -69.2093 -30.40347 308.0633 -63.47314 -30.40347 316.0247 -56.62616 -30.40347 323.0126 -48.78819 -30.40347 328.9048 -40.0964 -30.40347 333.5981 -30.70289 -30.40347 337.0104 -20.77207 -19.53418 342.382 -11.06179 -19.53418 343.125 0 -30.40347 339.082 10.47773 -19.53418 343.125 0 -30.39257 228.4552 -72.66928 -19.53418 235.4103 -78.86019 -26.45742 227.2577 -73.66539 -19.53418 246.1797 -81.49356 -19.53418 257.2046 -82.6632 -19.53418 268.2868 -82.34813 -19.53418 279.2274 -80.554 -19.53418 289.8298 -77.31303 -19.53418 299.9036 -72.68344 -19.53418 309.2679 -66.74836 -19.53418 317.7545 -59.61442 -19.53418 325.2109 -51.40974 -19.53418 331.5033 -42.28169 -19.53418 336.5185 -32.39421 -19.53418 340.1666 -21.9249 -8.31516 344.2063 -11.50464 -8.428314 344.9811 0 -19.53418 342.7814 7.531389 -8.428314 344.9811 0 -19.51969 225.1436 -74.83963 -8.31516 232.2584 -79.7741 -16.28796 224.1575 -75.14109 -8.31516 243.3692 -82.86019 -8.31516 254.7965 -84.40651 -8.31516 266.328 -84.38436 -8.31516 277.7492 -82.79409 -8.31516 288.8481 -79.66532 -8.31516 299.4184 -75.05615 -8.31516 309.2636 -69.05224 -8.31516 318.2007 -61.76516 -8.31516 326.0638 -53.33032 -8.31516 332.7067 -43.90446 -8.31516 338.0059 -33.66275 -8.31516 341.863 -22.7955 -8.31516 344.9923 0 -8.31516 344.9923 0 -8.299376 221.7165 -75.23102 3.052735 228.1721 -78.59418 -6.025453 221.0206 -75.08634 3.052735 238.687 -82.12324 3.052735 249.572 -84.25222 3.052735 260.6416 -84.94482 3.052735 271.7071 -84.18925 3.052735 282.5799 -81.99839 3.052735 293.0745 -78.40957 3.052735 303.012 -73.484 3.052735 312.2231 -67.30564 3.052735 320.5507 -59.97982 3.052735 327.8528 -51.63143 3.052735 334.0049 -42.40281 3.052735 338.9022 -32.45129 3.052735 342.4612 -21.94653 3.052735 344.6211 -11.06761 2.927736 345.3496 0 -8.31516 344.3271 10.58751 2.927736 345.3496 0 3.052735 345.3452 0 3.052735 345.3452 0 3.064081 218.2349 -73.74087 14.36597 224.5501 -75.71923 4.121392 217.9103 -73.50268 14.36597 235.0034 -79.83503 14.36597 245.9134 -82.5152 14.36597 257.0839 -83.71154 14.36597 268.3141 -83.40256 14.36597 279.4019 -81.59381 14.36597 290.148 -78.31779 14.36597 300.3592 -73.63343 14.36597 309.8518 -67.62498 14.36597 318.4552 -60.40046 14.36597 326.0146 -52.0898 14.36597 332.3941 -42.84244 14.36597 337.4789 -32.82468 14.36597 341.1777 -22.21665 14.36597 343.424 -11.20911 14.23147 344.2002 0 3.052735 344.5789 11.38407 14.23147 344.2002 0 14.36597 344.1772 0 14.36597 344.1772 0 13.94689 214.8896 -70.42224 14.37408 214.7581 -70.25098 25.42201 220.0784 -70.37677 23.252 212.0202 -65.90705 25.42201 229.5938 -75.03133 25.42201 239.6347 -78.40615 25.42201 250.0297 -80.44364 25.42201 260.6016 -81.10907 25.42201 271.1701 -80.39109 25.42201 281.5549 -78.30194 25.42201 291.5789 -74.87725 25.42201 301.071 -70.17543 25.42201 309.8695 -64.27668 25.42201 317.8242 -57.28162 25.42201 324.7995 -49.30954 25.42201 330.6763 -40.49644 25.42201 335.3545 -30.99262 25.42201 338.7543 -20.96018 25.42201 340.8176 -10.57023 25.28092 341.5534 0 14.36597 343.424 11.20903 25.28092 341.5534 0 25.42201 341.5093 0 25.42201 341.5093 0 35.87865 337.4566 0 25.42201 341.1587 7.533926 35.87865 337.4566 0 36.0229 337.3893 0 54.97298 324.4549 9.997143 54.97298 324.4549 9.997143 45.97885 329.4324 18.5871 54.97298 323.4899 14.92082 73 319.655 9.425759 54.97298 323.4899 14.92082 54.97298 322.1471 19.75514 58.74761 322.4311 15 54.97298 322.1471 19.75514 45.97885 326.399 27.47872 54.97298 320.4345 24.47112 58.10222 320.0225 23.24046 54.97298 320.4345 24.47112 58.45947 321.3558 19.16064 54.97298 318.3622 29.04054 58.00047 319.1929 25.33454 54.97298 318.3622 29.04054 45.97885 322.2259 35.8958 54.97298 315.9428 33.43601 58.82065 317.1844 29.08427 54.97298 315.9428 33.43601 58.11343 318.4289 26.96714 58.39733 317.754 28.2022 45.97885 316.9851 43.69299 54.97298 313.1907 37.63123 73 313.835 27.28928 54.97298 313.1907 37.63123 60.50268 316.2875 29.82695 59.34957 316.7408 29.63127 59.91502 316.4491 29.85868 54.97298 310.1225 41.60105 73 308.9542 35.24898 54.97298 310.1225 41.60105 45.97885 310.7671 50.73564 54.97298 306.7564 45.3217 54.97298 306.7564 45.3217 54.97298 303.1127 48.7709 73 302.8464 42.40642 54.97298 303.1127 48.7709 45.97885 303.6793 56.90211 54.97298 299.2131 51.92798 54.97298 299.2131 51.92798 45.97885 295.8441 62.08593 54.97298 295.0811 54.77404 73 295.6947 48.5209 54.97298 295.0811 54.77404 54.97298 290.7413 57.29203 54.97298 290.7413 57.29203 45.97885 287.3968 66.19757 54.97298 286.2198 59.46686 73 287.6891 53.43502 54.97298 286.2198 59.46686 54.97298 281.5437 61.28552 54.97298 281.5437 61.28552 45.97885 278.4833 69.16603 54.97298 276.7409 62.73711 73 279.0209 57.03734 54.97298 276.7409 62.73711 45.97885 269.2575 70.94004 54.97298 271.8403 63.81294 54.97298 271.8403 63.81294 54.97298 266.8711 64.50656 73 269.8952 59.24386 54.97298 266.8711 64.50656 45.97885 259.8788 71.48899 54.97298 261.8632 64.81381 54.97298 261.8632 64.81381 54.97298 256.8465 64.73287 73 260.5299 59.99981 54.97298 256.8465 64.73287 45.97885 250.509 70.80335 54.97298 251.8511 64.2642 54.97298 251.8511 64.2642 54.97298 246.9069 63.41062 73 251.1496 59.28258 54.97298 246.9069 63.41062 45.97885 241.3101 68.89499 54.97298 242.0435 62.17724 54.97298 242.0435 62.17724 45.97885 232.4408 65.79689 54.97298 237.29 60.57145 73 241.9811 57.10287 54.97298 237.29 60.57145 54.97298 232.675 58.60287 54.97298 232.675 58.60287 45.97885 224.0544 61.56249 54.97298 228.2261 56.28329 73 233.2493 53.50549 54.97298 228.2261 56.28329 54.97298 223.9698 53.62659 73 229.1172 51.19839 54.97298 223.9698 53.62659 45.97885 216.2956 56.26497 54.97298 219.9317 50.6487 73 225.1755 48.57189 54.97298 219.9317 50.6487 46.01564 209.3612 50.02604 54.97298 216.1361 47.36745 73 221.4503 45.63732 54.97298 216.1361 47.36745 54.97298 212.6055 43.80249 73 217.9665 42.41926 54.97298 212.6055 43.80249 50.25096 209.3612 45.76991 54.97298 209.3612 39.97518 73 214.75 38.93364 54.97298 209.3612 39.97518 47.58338 147.4 40.59617 54.97298 209.3612 39.97518 50.25096 209.3612 45.76991 73 211.8232 35.21779 58.96675 205.9713 33.20747 53.32715 147.4 32.69383 58.96675 205.9713 33.20747 50.62059 147.4 36.74311 44.2502 147.4 44.2088 46.01564 209.3612 50.02604 44.79955 209.3612 51.11795 44.79955 209.3612 51.11795 36.0229 217.5118 63.93712 38.64964 209.3612 55.91287 36.0613 209.3612 57.6162 36.0229 226.5145 69.13121 36.0229 236.1347 73.06536 36.0229 246.1972 75.6679 36.0229 256.5185 76.89138 36.0229 266.9105 76.71352 36.0229 277.1839 75.13755 36.0229 287.1514 72.1922 36.0229 296.6314 67.93115 36.0229 305.451 62.43204 36.0229 313.4496 55.7951 36.0229 320.4813 48.14131 36.0229 326.4181 39.61013 36.0229 331.1517 30.35706 36.0229 334.5958 20.55073 40.64623 147.4 47.54211 38.64964 209.3612 55.91287 36.79549 147.4 50.58251 36.0613 209.3612 57.6162 31.84824 209.3612 60.04776 32.722 147.4 53.30737 31.84824 209.3612 60.04776 25.42201 220.4664 70.59769 25.46656 211.3359 64.5691 25.42201 230.4212 75.36573 25.42201 240.9311 78.73809 25.42201 251.8016 80.65227 25.42201 262.8313 81.07287 25.42201 273.816 79.99208 25.42201 284.5522 77.42992 25.42201 294.8412 73.43383 25.42201 304.4923 68.07783 25.42201 313.3269 61.46109 25.42201 321.1813 53.70615 25.42201 327.9102 44.95663 25.57312 333.3515 35.34251 25.41586 333.3784 35.40033 28.474 334.6242 30.08337 26.19396 333.3273 34.93535 26.82431 333.4365 34.2218 27.42864 333.683 33.2005 27.98837 334.0746 31.8388 29.92763 338.5303 15 28.83818 335.349 27.85681 29.4645 337.1779 21.49406 27.10688 339.5531 15 25.42221 340.1102 15 22.65575 210.4284 64.18304 31.84824 209.3612 60.04776 25.46656 211.3359 64.5691 28.45097 147.4 55.70494 22.65575 210.4284 64.18304 23.26391 212.0165 65.90013 23.26391 212.0165 65.90013 14.36597 224.5512 75.71976 14.37355 214.7582 70.25119 14.36597 235.0045 79.83538 14.36597 245.9144 82.51538 14.36597 257.0849 83.71158 14.36597 268.315 83.40248 14.36597 279.4027 81.59362 14.36597 290.1487 78.31752 14.36597 300.3598 73.63312 14.36597 309.8523 67.62464 14.36597 318.4555 60.40012 14.36597 326.0148 52.08948 14.36597 332.3942 42.84217 24.88469 333.5363 15 25.41586 333.3784 35.40033 25.57312 333.3515 35.34251 25.01062 333.4888 35.46117 25.01062 333.4888 35.46117 26 333.321 15 26.19396 333.3273 34.93535 26.82431 333.4365 34.2218 26.92034 333.4657 15 27.42864 333.683 33.2005 27.74413 333.8801 15 27.98837 334.0746 31.8388 28.40313 334.5252 15 28.474 334.6242 30.08337 28.83818 335.349 27.85681 29.92763 338.5303 15 28.83818 335.349 27.85681 29.4645 337.1779 21.49406 28.83818 335.349 15 28.83818 335.349 15 23.16182 337.293 15 29.92763 338.5303 15 27.10688 339.5531 15 23.00412 336.168 15 28.83818 335.349 15 25.42221 340.1102 15 24.25127 340.4742 15 24.25127 340.4742 15 12.97491 211.5141 66.91291 14.37355 214.7582 70.25119 13.9719 214.8819 70.4123 13.9719 214.8819 70.4123 3.052735 227.9267 78.49311 4.160076 217.8985 73.49363 3.064656 218.2347 73.74074 3.052735 238.1753 81.98625 3.052735 248.785 84.14733 3.052735 259.5834 84.94124 7.289701 272.8429 83.76763 3.072762 270.3597 84.35865 5.208437 271.2829 84.13998 10.49642 280.1259 82.01036 8.963376 274.9312 83.26812 10.05761 277.3843 82.67627 3.052735 300.7836 74.73183 10.19036 282.9311 81.32331 9.149246 285.5518 80.67596 7.458848 287.7902 80.11924 5.250816 289.4928 79.69322 3.067632 290.4419 79.45475 3.052735 310.4346 68.6456 3.052735 319.1829 61.32088 3.052735 326.8706 52.88983 3.052735 333.3591 43.50454 23.24802 335.1266 33.17328 14.36597 337.479 32.82445 3.052735 338.5313 33.33435 23.56841 334.5639 34.19424 23.99023 334.0937 34.90988 24.48425 333.7321 35.32608 23.16182 337.293 27.85681 14.36597 341.1778 22.21649 3.052735 342.2939 22.56274 23.00553 336.503 30.0679 23.05001 335.7755 31.81557 23.7881 339.1217 21.49443 23.16182 337.293 15 24.25127 340.4742 15 23.7881 339.1217 21.49443 23.16182 337.293 27.85681 23.16182 337.293 15 23.16182 337.293 27.85681 23.00553 336.503 30.0679 23.00412 336.168 15 23.05001 335.7755 31.81557 23.24802 335.1266 33.17328 23.27465 335.0685 15 23.56841 334.5639 34.19424 23.93215 334.1484 15 23.99023 334.0937 34.90988 24.48425 333.7321 35.32608 2.991063 212.5854 68.18741 4.160076 217.8985 73.49363 3.064656 218.2347 73.74074 -5.97312 221.0046 75.08213 -7.022048 213.6004 67.98007 -5.97312 221.0046 75.08213 -8.31516 231.5675 79.52701 -8.298602 221.7162 75.23098 -8.31516 241.9352 82.55247 -8.31516 252.604 84.2323 -8.31516 263.3998 84.5391 2.976411 270.3312 66 3.072762 270.3597 84.35865 5.208437 271.2829 84.13998 2.725606 270.2599 84.38233 2.725606 270.2599 84.38233 5.718314 271.5951 66 7.289701 272.8429 83.76763 7.976566 273.5722 66 8.963376 274.9312 83.26812 9.574053 276.0903 66 10.05761 277.3843 82.67627 10.39938 278.9509 66 10.49642 280.1259 82.01036 10.38881 281.9227 66 10.19036 282.9311 81.32331 9.541881 284.7805 66 9.149246 285.5518 80.67596 7.932786 287.279 66 7.458848 287.7902 80.11924 5.684371 289.2271 66 5.250816 289.4928 79.69322 3.067632 290.4419 79.45475 2.711331 290.5439 79.4291 2.964506 290.4726 66 2.711331 290.5439 79.4291 -8.31516 305.827 71.36 -8.31516 296.5384 76.48448 0 290.9 79.33946 -8.31516 314.4011 65.11328 -8.31516 322.126 57.84251 -8.31516 328.8802 49.66209 -8.31516 334.5574 40.70066 -8.31516 339.0683 31.09913 -8.31516 342.3421 21.00852 -8.298602 221.7162 75.23098 -16.22254 224.1375 75.1456 -16.91499 214.5318 66.29953 -16.22254 224.1375 75.1456 -19.53418 235.0348 78.74023 -19.51857 225.1432 74.83975 -19.53418 245.4043 81.35445 -19.53418 256.0245 82.60914 -7.449712 273.0006 83.73033 -8.393984 274.092 83.46841 -19.53418 266.7177 82.48336 -5.227266 271.2937 84.13688 -2.676414 270.2468 84.38526 0 269.9 84.46746 -7.932786 273.521 66 -8.393984 274.092 83.46841 -7.449712 273.0006 83.73033 -9.142182 275.2357 83.19493 -9.541881 276.0195 66 -9.142182 275.2357 83.19493 -5.684371 271.5729 66 -5.227266 271.2937 84.13688 -2.964506 270.3274 66 -2.676414 270.2468 84.38526 0 269.9 84.46746 0 269.9 66 0 269.9 84.46746 0 269.9 66 -19.51857 225.1432 74.83975 -26.38088 227.2343 73.68235 -21.74006 214.9552 64.91675 -26.38088 227.2343 73.68235 -30.40347 238.2641 76.2275 -30.39124 228.4548 72.66967 -30.40347 248.5199 78.48243 -30.40347 258.9836 79.36386 -19.53418 277.3053 80.97917 -30.40347 269.472 78.85637 -8.37976 286.7269 80.38486 -19.53418 287.6105 78.12174 -30.40347 279.8017 76.96884 -8.970254 285.8575 80.60015 -10.06673 283.3851 81.21176 -10.49715 280.6447 81.88391 -10.18462 277.8459 82.56465 -19.53418 297.4609 73.95881 -30.40347 289.7919 73.73431 -19.53418 306.692 68.55995 -30.40347 299.2677 69.20938 -19.53418 315.1495 62.01538 -30.40347 308.0632 63.47321 -19.53418 322.6921 54.43446 -30.40347 316.0246 56.62623 -19.53418 329.1937 45.94388 -30.40347 323.0126 48.78826 -19.53418 334.5457 36.68554 -30.40347 328.9048 40.09646 -18.93985 338.4953 27.7022 -19.53418 338.6587 26.81414 -30.40347 333.5981 30.70294 -18.67436 337.7337 29.92946 -18.26704 337.1282 31.68762 -17.7672 336.6687 33.05159 -17.20581 336.346 34.0759 -16.60405 336.1545 34.79317 -15.99508 336.093 35.20982 -15.41759 336.1501 35.34444 -14.86158 336.3174 35.22336 -19.31847 340.3575 21.41501 -19.54294 341.4615 16.49574 -30.40347 337.0104 20.7721 -18.93985 338.4953 15 -19.54294 341.4615 16.49574 -19.31847 340.3575 21.41501 -19.59917 341.738 15 -19.59917 341.738 15 -18.93985 338.4953 27.7022 -18.93985 338.4953 15 -18.93985 338.4953 27.7022 -18.67436 337.7337 29.92946 -18.56493 337.5371 15 -18.26704 337.1282 31.68762 -17.89824 336.77 15 -17.7672 336.6687 33.05159 -17.20581 336.346 34.0759 -17.01372 336.2695 15 -16.60405 336.1545 34.79317 -16 336.093 15 -15.99508 336.093 35.20982 -15.41759 336.1501 35.34444 -14.95741 336.2802 15 -14.86158 336.3174 35.22336 -14.31213 336.6129 34.81024 -14.31213 336.6129 34.81024 -13.82404 337.0278 34.08932 -14.04724 336.8162 15 -13.82404 337.0278 34.08932 -13.42886 337.5473 33.06001 -13.42886 337.5473 33.06001 -13.14613 338.1681 31.69074 -13.37965 337.6332 15 -13.14613 338.1681 31.69074 -13.00714 338.8861 29.92901 -13.03582 338.6318 15 -13.00714 338.8861 29.92901 -13.06015 339.6907 27.7022 -13.06015 339.6907 27.7022 -13.71947 342.9335 15 -13.06015 339.6907 27.7022 -13.43876 341.5529 21.4152 -13.43876 341.5529 21.4152 -13.06015 339.6907 15 -13.06015 339.6907 15 -13.71947 342.9335 15 -19.53418 341.7536 15 -13.71947 342.9335 15 -16.67004 342.3885 15 -16.67004 342.3885 15 -19.59917 341.738 15 -13.06015 339.6907 15 -19.53418 341.7536 15 -7.309887 287.9376 80.08237 -2.67668 290.5531 79.42676 -5.165318 289.5416 79.68093 -7.976566 287.2278 66 -8.37976 286.7269 80.38486 -8.970254 285.8575 80.60015 -7.309887 287.9376 80.08237 -9.574053 284.7098 66 -10.06673 283.3851 81.21176 -10.39938 281.8491 66 -10.49715 280.6447 81.88391 -10.38881 278.8774 66 -10.18462 277.8459 82.56465 -26.44347 215.3458 63.18416 -30.39124 228.4548 72.66967 -36.2395 230.2324 70.72212 -30.98949 215.6994 61.1178 -36.2395 230.2324 70.72212 -40.72843 240.7762 71.97988 -40.71991 231.5927 68.82608 -40.72843 250.3624 73.92863 -40.72843 260.1212 74.60643 -40.72843 269.8847 74.0016 -40.72843 279.4851 72.12456 -40.72843 288.7575 69.00759 -40.72843 297.5424 64.70426 -40.72843 305.6887 59.28854 -40.72843 313.0564 52.85356 -40.72843 319.5189 45.50995 -40.72843 324.965 37.38394 -40.72843 329.3011 28.61523 -40.72843 332.4527 19.35458 -18.93985 338.4953 15 -35.37036 216.0157 58.72362 -40.71991 231.5927 68.82608 -45.60571 233.0745 66.3207 -39.57728 216.2932 56.00443 -45.60571 233.0745 66.3207 -50.32421 242.9856 66.25113 -50.32326 234.5037 63.41885 -50.32421 251.8456 67.96541 -50.32421 260.8541 68.50013 -50.32421 269.8547 67.84603 -50.32421 278.6913 66.01443 -50.32421 287.2103 63.03713 -50.32421 295.2641 58.96582 -50.32421 302.7128 53.87113 -50.32421 309.4272 47.84151 -50.32421 315.2907 40.98158 -47.37823 321.7118 34.9451 -48.64122 320.4954 35.32114 -48.15489 320.8045 35.45994 -47.73599 321.2017 35.34735 -48.85761 326.5509 21.49412 -47.12776 322.3038 34.23291 -47.00813 322.9493 33.20876 -47.03627 323.6351 31.8421 -47.23842 324.3421 30.08234 -47.65346 325.0392 27.85547 -49.74824 327.669 15 -50.32455 327.2389 15 -43.57526 216.5315 52.98031 -50.32326 234.5037 63.41885 -54.25997 235.6952 60.58491 -47.33538 216.7287 49.67338 -54.25997 235.6952 60.58491 -59.01899 252.4612 60.65256 -59.01899 244.6157 59.09835 -59.01899 260.4423 61.1699 -59.01899 268.4227 60.64152 -59.01899 276.266 59.07646 -59.01899 283.838 56.50148 -59.01899 291.0094 52.96059 -59.01899 297.6575 48.51433 -59.01899 303.6686 43.2387 -59.01899 308.9401 37.2239 -49.82639 320.175 34.19471 -50.32241 320.1874 33.43838 -59.01899 313.3818 30.57275 -49.20775 320.2765 34.90557 -50 320.17 15 -50.32241 320.1874 33.43838 -49.82639 320.175 34.19471 -50.46897 320.2069 33.18165 -50.88472 320.3034 15 -50.46897 320.2069 33.18165 -49.20775 320.2765 34.90557 -48.89626 320.3805 15 -48.64122 320.4954 35.32114 -48.15489 320.8045 35.45994 -47.95515 320.9755 15 -47.73599 321.2017 35.34735 -47.37823 321.7118 34.9451 -47.29803 321.8679 15 -47.12776 322.3038 34.23291 -47.00945 322.9378 15 -47.00813 322.9493 33.20876 -47.03627 323.6351 31.8421 -47.13042 324.0447 15 -47.23842 324.3421 30.08234 -47.65346 325.0392 27.85547 -49.74824 327.669 15 -47.65346 325.0392 27.85547 -48.85761 326.5509 21.49412 -47.65346 325.0392 15 -47.65346 325.0392 15 -47.65346 325.0392 15 -49.74824 327.669 15 -50.32455 327.2389 15 -52.12831 325.8419 15 -52.12831 325.8419 15 -59.01144 237.1321 56.57963 -50.84238 216.8874 46.09818 -59.01144 237.1321 56.57963 -66.65713 245.886 50.70672 -62.11941 238.0711 53.54995 -54.07727 217.0084 42.27401 -62.11941 238.0711 53.54995 -66.65713 252.692 52.17676 -66.65713 259.6324 52.73744 -66.65713 266.5861 52.37899 -66.65713 273.432 51.10767 -66.65713 280.0508 48.94562 -66.65713 286.3271 45.93053 -66.65713 292.1515 42.11494 -66.65713 297.4226 37.56537 -66.65713 302.0484 32.36109 -66.65713 305.9483 26.5928 -52.34654 321.3009 27.85547 -59.01899 316.9177 23.39894 -66.65713 309.0545 20.36105 -51.75972 320.7403 30.08286 -51.1209 320.3873 31.83053 -53.5509 322.8128 21.49283 -59.01899 319.4874 15.82513 -66.65713 311.3126 13.77444 -54.44132 323.9306 15 -54.44132 323.9306 15 -52.34654 321.3009 15 -54.44132 323.9306 15 -53.5509 322.8128 21.49283 -47.13042 324.0447 15 -47.00945 322.9378 15 -52.34654 321.3009 15 -52.34654 321.3009 27.85547 -52.34654 321.3009 15 -52.34654 321.3009 27.85547 -51.75972 320.7403 30.08286 -51.69094 320.692 15 -51.1209 320.3873 31.83053 -66.74029 239.4663 48.29607 -57.0279 217.0962 38.21406 -66.74029 239.4663 48.29607 -73.10187 246.7829 41.17878 -68.7149 240.0621 45.7125 -68.7149 240.0621 45.7125 -73.10187 252.4646 42.63973 -73.10187 258.2914 43.32056 -73.10187 264.1568 43.20884 -73.10187 269.9535 42.30659 -73.10187 275.5754 40.63033 -73.10187 280.9197 38.21073 -73.10187 285.8886 35.09205 -73.10187 290.3911 31.33135 -68.61811 296.01 35.33395 -69.55603 294.5506 34.9384 -69.13723 294.9883 35.337 -68.8292 295.4726 35.46077 -70.14102 299.506 27.85601 -68.51029 296.6239 34.91642 -68.53386 297.2622 34.19489 -68.69622 297.8923 33.1687 -69.00685 298.4971 31.80676 -69.48138 299.0495 30.05915 -71.87532 300.3897 21.44201 -73.10494 301.0162 15.19895 -72.56456 300.7409 18.22215 -73.10187 302.5424 10.25351 -73.14265 241.3973 38.91081 -59.68402 217.1535 33.92643 -73.14265 241.3973 38.91081 -78.23781 246.4476 30.15256 -73.44529 241.4885 38.38162 -65.49497 225.2262 33.05176 -73.44529 241.4885 38.38162 -63.52895 223.9257 35.26662 -63.88613 224.3694 35.14942 -64.34738 224.756 34.75216 -64.89223 225.0492 34.05331 -78.23781 250.2254 31.62788 -78.23593 258.1766 33.15414 -78.23781 254.1548 32.63193 -77.484 259.2384 34.92664 9.541881 284.7805 66 9.574053 276.0903 66 10.38881 281.9227 66 -77.79296 258.6787 34.20954 -78.23781 266.7493 32.61183 -77.30403 259.8332 35.3379 -77.25003 260.4114 35.46038 -77.30847 260.9894 35.32788 -77.48976 261.5752 34.9135 -77.79761 262.1279 34.19865 -78.22615 262.6145 33.17785 7.932786 287.279 66 7.976566 273.5722 66 -78.23781 270.7757 31.56249 -78.23781 274.6394 30.0181 -78.23781 278.2797 28.0029 -78.23781 281.6396 25.5485 -72.86499 294.16 27.85601 -73.1229 294.2914 27.00598 -78.23781 284.6664 22.69338 -72.08062 293.8891 30.13078 -71.34262 293.8373 31.8933 -70.67078 293.9508 33.24143 -70.07318 294.1957 34.24331 -72.86499 294.16 15 -73.1229 294.2914 27.00598 -72.86499 294.16 27.85601 -78.23781 287.3125 19.48233 -74.60461 295.0464 21.41913 -74.60461 295.0464 21.41913 -72.86499 294.16 15 -72.86499 294.16 27.85601 -72.08062 293.8891 30.13078 -71.503 293.833 15 -71.34262 293.8373 31.8933 -72.20333 293.9159 15 -70.67078 293.9508 33.24143 -70.38233 294.0503 15 -70.07318 294.1957 34.24331 -69.55603 294.5506 34.9384 -69.42726 294.6678 15 -69.13723 294.9883 35.337 -68.8292 295.4726 35.46077 -68.77169 295.5941 15 -68.61811 296.01 35.33395 -68.51029 296.6239 34.91642 -68.50691 296.6967 15 -68.53386 297.2622 34.19489 -68.67044 297.8197 15 -68.69622 297.8923 33.1687 -69.00685 298.4971 31.80676 -69.24109 298.8035 15 -69.48138 299.0495 30.05915 -70.14102 299.506 27.85601 -72.56456 300.7409 18.22215 -70.14102 299.506 27.85601 -71.87532 300.3897 21.44201 -73.10494 301.0162 15.19895 -73.13687 301.0325 15 -70.14102 299.506 15 -70.14102 299.506 15 -73.13687 301.0325 15 -78.23781 292.5861 8.240331 -76.54758 242.4232 32.28474 -66.1454 225.2729 31.72018 -76.54758 242.4232 32.28474 -78.27421 242.9432 28.16753 -67.53401 224.8731 27.85184 -78.27421 242.9432 28.16753 -66.83155 225.167 30.01048 -81.97303 248.7533 19.22962 -81.97303 246.2453 17.46622 -78.6286 243.0499 27.23086 -78.6286 243.0499 27.23086 -81.97303 251.4779 20.6354 -81.97303 254.3684 21.65742 -78.77436 257.788 31.82419 -81.9843 257.4 22.24155 -80.25 257.4 27.85566 -79.44992 257.5087 30.07241 10.39938 278.9509 66 -79.08889 257.6344 15 -78.77436 257.788 31.82419 -78.23593 258.1766 33.15414 -78.11267 258.2955 15 -77.79296 258.6787 34.20954 -77.484 259.2384 34.92664 -77.47212 259.2678 15 -77.30403 259.8332 35.3379 -77.25003 260.4114 35.46038 -77.25006 260.4119 15 -77.30847 260.9894 35.32788 -77.48125 261.5544 15 -77.48976 261.5752 34.9135 -77.79761 262.1279 34.19865 -78.12545 262.5177 15 -78.22615 262.6145 33.17785 -78.77622 263.013 31.81953 -78.77622 263.013 31.81953 -81.97303 266.3024 21.693 -81.9843 263.4 22.24155 -80.25 263.4 27.85566 -79.45053 263.2915 30.07079 -81.97303 269.0754 20.74035 -81.97303 271.7008 19.43491 -81.97303 274.134 17.79888 -81.97303 276.3337 15.8601 -81.97303 278.2622 13.65154 -78.23781 289.5366 15.96571 -81.97303 279.887 11.21078 -75.86083 295.6865 15 -78.23781 291.3037 12.19869 -81.97303 281.1803 8.57932 -75.29203 295.3966 18.20484 -81.97303 282.1201 5.801929 -74.54679 298.3839 15 -72.86499 294.16 15 -73.13687 301.0325 15 -74.54679 298.3839 15 -72.20333 293.9159 15 -71.503 293.833 15 -70.38233 294.0503 15 -70.14102 299.506 15 -75.86083 295.6865 15 -75.86083 295.6865 15 -75.29203 295.3966 18.20484 -80.11442 243.4972 22.82492 -69.17012 223.9284 21.48612 -80.11442 243.4972 22.82492 -81.24094 243.8363 18.72312 -70.40156 223.2175 15 -81.24094 243.8363 18.72312 -81.97932 244.0585 15.40611 -81.97932 244.0585 15.40611 -82.12406 244.1021 14.66349 -82.12406 244.1021 14.66349 -80.25 257.4 15 -81.9843 257.4 22.24155 -80.25 257.4 27.85566 -83.6122 257.4 15 -82.25606 257.4 21.21201 -82.25606 257.4 21.21201 -80.25 257.4 15 -80.25 257.4 27.85566 -79.44992 257.5087 30.07241 -82.49318 244.2131 12.5643 -67.90335 217.1798 10.13094 -82.49318 244.2131 12.5643 -82.81657 244.3104 10.37024 -82.81657 244.3104 10.37024 -83.0912 244.3931 8.03926 -83.0912 244.3931 8.03926 -83.3083 244.4584 5.530963 -83.3083 244.4584 5.530963 -83.41331 244.49 3.754015 -83.41331 244.49 3.754015 -83.666 260.4 15 -83.65255 258.8998 15 -83.65255 261.9002 15 -83.6122 263.4 15 -82.25606 263.4 21.21201 -83.6122 263.4 15 -81.9843 263.4 22.24155 -82.25606 263.4 21.21201 -80.25 263.4 27.85566 -83.6122 257.4 15 -83.6122 263.4 15 -83.65255 261.9002 15 -80.25 257.4 15 -80.25 263.4 15 -80.25 263.4 15 -83.65255 258.8998 15 -83.666 260.4 15 -83.6122 257.4 15 -79.09465 263.1682 15 -79.45053 263.2915 30.07079 -80.25 263.4 27.85566 -80.25 263.4 15 0 290.9 79.33946 0 290.9 66 0 290.9 79.33946 -2.67668 290.5531 79.42676 0 290.9 66 -2.976411 290.4688 66 -5.165318 289.5416 79.68093 -5.718314 289.2049 66 66.77414 200.5839 15 65.47537 200.2252 15 64.513 202.9981 15 65.47537 200.2252 15 66.77414 200.5839 15 61.77333 147.4 9.826401 65.47537 200.2252 15 65.27436 197.9858 15 65.27436 197.9858 15 68.07296 200.9427 15 68.07296 200.9427 15 73 203.3307 18.52296 66.52468 201.8366 19.53368 64.513 202.9981 15 68.07296 200.9427 15 66.52468 201.8366 19.53368 73 206.9314 27.22327 64.513 202.9981 24.14707 64.513 202.9981 24.14707 63.78588 203.2987 25.334 64.513 202.9981 15 64.513 202.9981 24.14707 63.78588 203.2987 25.334 63.013 203.4 26.06299 63.78944 203.2977 15 63.013 203.4 26.06299 62.52994 203.3609 26.28821 63.013 203.4 15 62.52994 203.3609 26.28821 62.08028 203.2513 26.33821 62.08028 203.2513 26.33821 61.40267 202.9312 27.81363 62.08028 203.2513 26.33821 61.91339 203.1911 15 61.40267 202.9312 27.81363 55.825 159.3945 30.47047 60.84769 202.4764 28.9151 60.42607 201.9191 29.67563 60.15242 201.3039 30.10651 60.02756 200.6952 30.23656 56.89847 161.6997 28.86414 56.41777 161.1903 29.69723 56.07861 160.6072 30.22544 55.88602 160.002 30.46962 64.24816 319.7772 19.00672 73 317.4434 18.60236 61.63955 321.6336 15 64.53171 320.8354 15 62.46699 316.6292 28.01657 73 315.2042 4.636376 73 313.835 27.28928 63.06182 317.0668 26.74917 63.55799 317.6786 25.08306 63.89778 318.4696 22.94665 73 313.701 13.56462 73 308.9542 35.24898 61.14128 316.2493 29.53398 61.8148 316.3588 28.93522 73 306.4422 30.08507 73 302.8464 42.40642 73 310.7548 22.12212 73 300.8708 37.24397 73 295.6947 48.5209 73 294.1843 43.40071 73 287.6891 53.43502 73 286.6418 48.33597 73 279.0209 57.03734 73 278.3314 51.99485 73 269.8952 59.24386 73 269.4965 54.24254 73 260.5299 59.99981 73 260.4 55 73 251.1496 59.28258 73 264.981 54.80755 73 242.5435 52.02062 73 241.9811 57.10287 73 251.3592 54.25185 73 234.2212 48.37014 73 233.2493 53.50549 73 229.1172 51.19839 73 226.6465 43.42462 73 225.1755 48.57189 73 223.1598 40.47071 73 221.4503 45.63732 73 219.9193 37.23322 73 217.9665 42.41926 73 216.967 33.74082 73 214.75 38.93364 73 214.3148 30.01914 73 211.8232 35.21779 73 209.9889 21.99357 73 206.9314 27.22327 73 207.0532 13.38335 63.89778 318.4696 15 64.53171 320.8354 15 61.63955 321.6336 15 64.24816 319.7772 19.00672 64.53171 320.8354 15 63.89778 318.4696 22.94665 63.89778 318.4696 15 61 316.246 15 58.74761 322.4311 15 63.49127 317.5747 15 62.82626 316.866 15 61.96962 316.4071 15 58.10222 320.0225 15 58.74761 322.4311 15 58.45947 321.3558 19.16064 59.92296 316.4462 15 58.99216 317.0177 15 58.32799 317.8832 15 58.10222 320.0225 15 58.10222 320.0225 23.24046 58.10222 320.0225 15 58.10222 320.0225 23.24046 58.00047 319.1929 25.33454 58.01685 318.9302 15 58.11343 318.4289 26.96714 58.32799 317.8832 15 58.39733 317.754 28.2022 58.82065 317.1844 29.08427 58.99216 317.0177 15 59.34957 316.7408 29.63127 59.91502 316.4491 29.85868 59.92296 316.4462 15 60.50268 316.2875 29.82695 61 316.246 15 61.14128 316.2493 29.53398 61.8148 316.3588 28.93522 61.96962 316.4071 15 62.46699 316.6292 28.01657 62.82626 316.866 15 63.06182 317.0668 26.74917 63.49127 317.5747 15 63.55799 317.6786 25.08306 63.89778 318.4696 22.94665 63.89778 318.4696 15 61.91339 203.1911 15 61.513 197.8019 15 65.07332 195.7464 15 61.513 197.8019 26.45257 65.07332 195.7464 15 61.513 197.8019 15 63.013 203.4 15 63.78944 203.2977 15 65.07332 195.7464 15 60.80711 147.4 14.65774 62.05136 162.1292 15 63.53199 196.6363 20.82528 63.53199 196.6363 20.82528 60.97 202.5962 15 60.66511 198.5327 15 61.513 197.8019 26.45257 61.513 197.8019 15 60.66511 198.5327 15 60.31014 201.7 15 60.14557 199.5197 15 60.46973 198.8088 28.96215 60.14557 199.5197 15 60.91719 198.2535 27.89223 60.02226 200.6258 15 60.0303 200.0783 30.11092 60.02226 200.6258 15 60.17288 199.4337 29.69762 60.02756 200.6952 30.23656 60.31014 201.7 15 60.42607 201.9191 29.67563 60.97 202.5962 15 60.15242 201.3039 30.10651 60.84769 202.4764 28.9151 60.21032 156.2673 19.61899 59.46792 147.4 19.39247 61.78239 159.1413 15 61.51335 156.1533 15 58.56353 156.4114 24.12603 57.76154 147.4 23.99858 57.02877 156.9972 27.67609 55.70747 147.4 28.44606 57.72047 156.6107 26.12105 53.32715 147.4 32.69383 55.89368 158.7617 30.22811 56.11378 158.1157 29.69692 56.49275 157.513 28.85377 52.02062 147.4 17.8565 50.62059 147.4 36.74311 54.25185 147.4 9.040809 48.37014 147.4 26.17878 47.58338 147.4 40.59617 44.2502 147.4 44.2088 43.42462 147.4 33.75352 40.64623 147.4 47.54211 40.47071 147.4 37.24022 36.79549 147.4 50.58251 33.74082 147.4 43.43301 32.722 147.4 53.30737 37.23322 147.4 40.48065 30.01914 147.4 46.0852 28.45097 147.4 55.70494 24.00643 147.4 57.75894 24.00643 147.4 57.75894 19.41596 147.4 59.46022 21.99357 147.4 50.41108 19.41596 147.4 59.46022 12.97491 211.5141 66.91291 14.70538 147.4 60.79596 14.70538 147.4 60.79596 9.903903 147.4 61.7609 13.38335 147.4 53.34679 9.903903 147.4 61.7609 2.991063 212.5854 68.18741 5.039426 147.4 62.3458 5.039426 147.4 62.3458 0.141712 147.4 62.54979 4.426485 147.4 54.82153 0.141712 147.4 62.54979 -7.022048 213.6004 67.98007 -4.760062 147.4 62.36774 -4.636376 147.4 54.80418 -4.760062 147.4 62.36774 -9.636244 147.4 61.80323 -9.636244 147.4 61.80323 -16.91499 214.5318 66.29953 -14.45719 147.4 60.85541 -13.56462 147.4 53.30099 -14.45719 147.4 60.85541 -19.19369 147.4 59.53233 -19.19369 147.4 59.53233 -21.74006 214.9552 64.91675 -23.81617 147.4 57.83746 -22.12212 147.4 50.35481 -23.81617 147.4 57.83746 -30.98949 215.6994 61.1178 -28.29614 147.4 55.78374 -28.29614 147.4 55.78374 -26.44347 215.3458 63.18416 -35.37036 216.0157 58.72362 -32.60395 147.4 53.37942 -30.08507 147.4 46.0422 -32.60395 147.4 53.37942 -39.57728 216.2932 56.00443 -36.71356 147.4 50.642 -36.71356 147.4 50.642 -43.57526 216.5315 52.98031 -40.59742 147.4 47.58352 -37.24397 147.4 40.47077 -40.59742 147.4 47.58352 -47.33538 216.7287 49.67338 -44.23035 147.4 44.22867 -43.40071 147.4 33.78425 -44.23035 147.4 44.22867 -50.84238 216.8874 46.09818 -47.58631 147.4 40.59246 -47.58631 147.4 40.59246 -54.07727 217.0084 42.27401 -50.64026 147.4 36.716 -48.33597 147.4 26.24179 -50.64026 147.4 36.716 -57.0279 217.0962 38.21406 -53.35656 147.4 32.64563 -51.99485 147.4 17.9314 -53.35656 147.4 32.64563 -56.50516 157.4978 28.82653 -55.74084 147.4 28.38063 -54.24254 147.4 9.096512 -59.68402 217.1535 33.92643 -55.82515 159.3696 30.46566 -56.12449 158.0934 29.67248 -55.89961 158.7351 30.21225 -57.72749 156.608 26.10494 -57.79339 147.4 23.92148 -57.03991 156.9889 27.65146 -54.80755 147.4 4.580959 -60.21032 156.2673 19.61899 -59.49447 147.4 19.31087 -58.56353 156.4114 24.12603 -61.51335 156.1533 15 -60.82553 147.4 14.58077 -66.96784 217.1905 15.13074 -61.78324 147.4 9.763909 -64.91617 193.9962 15 -61.78239 159.1413 15 -62.05136 162.1292 15 -64.37945 188.0202 15 -64.64785 191.0083 15 -67.90335 217.1798 10.13094 -67.45172 217.9924 15 -66.96784 217.1905 15.13074 -68.9284 220.6046 15 -63.80868 194.0931 19.2013 -65.66699 217.1984 20.03924 -65.66699 217.1984 20.03924 -62.43146 194.2136 23.32286 -64.01552 217.1991 24.81422 -66.19934 218.7154 21.19382 -64.01552 217.1991 24.81422 -60.23333 193.5161 28.38066 -62.01995 217.1862 29.44663 -64.534 219.6769 27.33045 -62.01995 217.1862 29.44663 -60.84842 193.9182 27.12327 -61.58626 194.1677 25.4606 -59.22356 191.7893 30.09981 -63.39606 220.8463 31.51821 -59.41082 192.4027 29.848 -59.75036 192.9985 29.28105 -63.85037 220.2179 29.6858 -55.88095 159.9767 30.4743 -63.13394 221.5071 32.92467 -63.03585 222.1698 33.97367 -63.08317 222.8159 34.70653 -63.25925 223.4155 35.13185 57.5103 162.0966 27.7051 60.0303 200.0783 30.11092 60.17288 199.4337 29.69762 60.46973 198.8088 28.96215 58.24418 162.3432 26.17974 60.91719 198.2535 27.89223 61.513 197.8019 26.45257 59.08647 162.3886 24.2293 60.7432 162.2436 19.67009 -56.7467 161.5628 15 -62.05136 162.1292 15 -61.78239 159.1413 15 -60.7432 162.2436 19.67009 -62.05136 162.1292 15 -59.08647 162.3886 24.2293 -59.08647 162.3886 15 -63.27686 188.1167 19.15429 -60.7432 162.2436 19.67009 -57.70272 162.182 15 -59.08647 162.3886 15 -55.9944 158.4085 15 -61.51335 156.1533 15 -56.09166 160.6346 15 -55.82877 159.5309 15 -58.56353 156.4114 15 -61.51335 156.1533 15 -60.21032 156.2673 19.61899 -56.56599 157.4267 15 -57.46443 156.7264 15 -58.56353 156.4114 15 -58.56353 156.4114 24.12603 -58.56353 156.4114 15 -58.56353 156.4114 24.12603 -57.72749 156.608 26.10494 -57.46443 156.7264 15 -57.03991 156.9889 27.65146 -56.56599 157.4267 15 -56.50516 157.4978 28.82653 -56.12449 158.0934 29.67248 -55.9944 158.4085 15 -55.89961 158.7351 30.21225 -55.82515 159.3696 30.46566 -55.82877 159.5309 15 -55.88095 159.9767 30.4743 -56.06707 160.5806 30.24195 -56.06707 160.5806 30.24195 -56.40243 161.1695 29.72246 -56.09166 160.6346 15 -56.40243 161.1695 29.72246 -59.17039 191.1763 30.08591 -56.88293 161.6865 28.89224 -56.7467 161.5628 15 -56.88293 161.6865 28.89224 -59.48099 189.8949 29.21359 -57.49756 162.0903 27.73027 -57.49756 162.0903 27.73027 -59.25 190.5368 29.8045 -59.86483 189.305 28.29827 -58.2367 162.3417 26.19606 -57.70272 162.182 15 -58.2367 162.3417 26.19606 -61.08219 188.4292 25.36558 -59.08647 162.3886 24.2293 -58.825 162.4 15 -59.08647 162.3886 24.2293 -60.39896 188.8035 27.03231 -61.90853 188.2364 23.22817 -58.95586 162.3971 15 -59.08647 162.3886 15 58.56353 156.4114 15 61.51335 156.1533 15 61.78239 159.1413 15 60.21032 156.2673 19.61899 61.51335 156.1533 15 58.56353 156.4114 24.12603 58.56353 156.4114 15 55.82876 159.5307 15 62.05136 162.1292 15 57.46452 156.7263 15 56.5661 157.4265 15 55.99446 158.4084 15 59.08647 162.3886 15 62.05136 162.1292 15 60.7432 162.2436 19.67009 56.09157 160.6344 15 56.74657 161.5627 15 57.70262 162.182 15 59.08647 162.3886 15 59.08647 162.3886 24.2293 59.08647 162.3886 15 59.08647 162.3886 24.2293 58.24418 162.3432 26.17974 57.70262 162.182 15 57.5103 162.0966 27.7051 58.825 162.4 15 58.95586 162.3971 15 56.89847 161.6997 28.86414 56.74657 161.5627 15 56.41777 161.1903 29.69723 56.09157 160.6344 15 56.07861 160.6072 30.22544 55.88602 160.002 30.46962 55.82876 159.5307 15 55.825 159.3945 30.47047 55.89368 158.7617 30.22811 55.99446 158.4084 15 56.11378 158.1157 29.69692 56.49275 157.513 28.85377 56.5661 157.4265 15 57.02877 156.9972 27.67609 57.46452 156.7263 15 57.72047 156.6107 26.12105 58.56353 156.4114 24.12603 58.56353 156.4114 15 -60.09169 193.3878 15 -64.91617 193.9962 15 -64.64785 191.0083 15 -63.80868 194.0931 19.2013 -64.91617 193.9962 15 -62.43146 194.2136 23.32286 -62.43146 194.2136 15 -61.04772 194.007 15 -62.43146 194.2136 15 -59.3394 190.2335 15 -64.37945 188.0202 15 -59.43666 192.4596 15 -59.17377 191.3559 15 -61.90853 188.2364 15 -64.37945 188.0202 15 -63.27686 188.1167 19.15429 -59.91099 189.2517 15 -60.80943 188.5514 15 -61.90853 188.2364 15 -61.90853 188.2364 23.22817 -61.90853 188.2364 15 -61.90853 188.2364 23.22817 -61.08219 188.4292 25.36558 -60.80943 188.5514 15 -60.39896 188.8035 27.03231 -59.91099 189.2517 15 -59.86483 189.305 28.29827 -59.48099 189.8949 29.21359 -59.3394 190.2335 15 -59.25 190.5368 29.8045 -59.17039 191.1763 30.08591 -59.17377 191.3559 15 -59.22356 191.7893 30.09981 -59.41082 192.4027 29.848 -59.43666 192.4596 15 -59.75036 192.9985 29.28105 -60.09169 193.3878 15 -60.23333 193.5161 28.38066 -60.84842 193.9182 27.12327 -61.04772 194.007 15 -61.58626 194.1677 25.4606 -62.17 194.225 15 -62.43146 194.2136 23.32286 -62.30086 194.2221 15 -62.43146 194.2136 15 -55 146.4 0 -55 147.4 0 -54.25185 147.4 -9.040809 -54.25185 146.4 9.040809 -54.80755 147.4 4.580959 -55 147.4 0 -55 146.4 0 -54.24254 146.4 -9.096512 -52.02062 147.4 -17.8565 -54.80755 146.4 -4.580959 -51.99485 146.4 -17.9314 -48.37014 147.4 -26.17878 -48.33597 146.4 -26.24179 -43.42462 147.4 -33.75352 -43.40071 146.4 -33.78425 -40.47071 147.4 -37.24022 -37.24397 146.4 -40.47077 -37.23322 147.4 -40.48065 -33.74082 147.4 -43.43301 -30.08507 146.4 -46.0422 -30.01914 147.4 -46.0852 -22.12212 146.4 -50.35481 -21.99357 147.4 -50.41108 -13.56462 146.4 -53.30099 -13.38335 147.4 -53.34679 -4.636376 146.4 -54.80418 -4.426485 147.4 -54.82153 4.426485 146.4 -54.82153 4.636376 147.4 -54.80418 13.38335 146.4 -53.34679 13.56462 147.4 -53.30099 21.99357 146.4 -50.41108 22.12212 147.4 -50.35481 30.01914 146.4 -46.0852 30.08507 147.4 -46.0422 33.74082 146.4 -43.43301 37.24397 147.4 -40.47077 40.47071 146.4 -37.24022 43.40071 147.4 -33.78425 37.23322 146.4 -40.48065 43.42462 146.4 -33.75352 48.33597 147.4 -26.24179 48.37014 146.4 -26.17878 51.99485 147.4 -17.9314 52.02062 146.4 -17.8565 54.24254 147.4 -9.096512 54.25185 146.4 -9.040809 54.80755 147.4 -4.580959 55 147.4 0 55 146.4 0 55 147.4 0 54.25185 147.4 9.040809 55 146.4 0 54.24254 146.4 9.096512 52.02062 147.4 17.8565 54.80755 146.4 4.580959 51.99485 146.4 17.9314 48.37014 147.4 26.17878 48.33597 146.4 26.24179 43.42462 147.4 33.75352 43.40071 146.4 33.78425 40.47071 147.4 37.24022 37.24397 146.4 40.47077 37.23322 147.4 40.48065 33.74082 147.4 43.43301 30.08507 146.4 46.0422 30.01914 147.4 46.0852 22.12212 146.4 50.35481 21.99357 147.4 50.41108 13.56462 146.4 53.30099 13.38335 147.4 53.34679 4.636376 146.4 54.80418 4.426485 147.4 54.82153 -4.426485 146.4 54.82153 -4.636376 147.4 54.80418 -13.38335 146.4 53.34679 -13.56462 147.4 53.30099 -21.99357 146.4 50.41108 -22.12212 147.4 50.35481 -30.01914 146.4 46.0852 -30.08507 147.4 46.0422 -33.74082 146.4 43.43301 -37.24397 147.4 40.47077 -40.47071 146.4 37.24022 -43.40071 147.4 33.78425 -37.23322 146.4 40.48065 -43.42462 146.4 33.75352 -48.33597 147.4 26.24179 -48.37014 146.4 26.17878 -51.99485 147.4 17.9314 -52.02062 146.4 17.8565 -54.24254 147.4 9.096512 -55.85556 146.4 -28.4391 -55 146.4 0 -54.80755 146.4 -4.580959 -55.82222 146.4 28.50449 -54.25185 146.4 9.040809 -54.24254 146.4 -9.096512 -51.99485 146.4 -17.9314 -50.74445 146.4 -36.79166 -48.33597 146.4 -26.24179 -47.68409 146.4 -40.67623 -43.40071 146.4 -33.78425 -40.68064 146.4 -47.68179 -37.24397 146.4 -40.47077 -44.32109 146.4 -44.32004 -36.78876 146.4 -50.74653 -30.08507 146.4 -46.0422 -28.35401 146.4 -55.89877 -22.12212 146.4 -50.35481 -32.67069 146.4 -53.48954 -19.23284 146.4 -59.65501 -13.56462 146.4 -53.30099 -9.655741 146.4 -61.93051 -4.636376 146.4 -54.80418 0.142315 146.4 -62.67855 4.426485 146.4 -54.82153 9.924565 146.4 -61.888 13.38335 146.4 -53.34679 19.45614 146.4 -59.58256 21.99357 146.4 -50.41108 28.50967 146.4 -55.81954 30.01914 146.4 -46.0852 33.74082 146.4 -43.43301 36.87129 146.4 -50.68659 37.23322 146.4 -40.48065 40.47071 146.4 -37.24022 43.42462 146.4 -33.75352 44.3413 146.4 -44.29981 48.37014 146.4 -26.17878 50.72493 146.4 -36.81856 52.02062 146.4 -17.8565 54.25185 146.4 -9.040809 55.82222 146.4 -28.50449 55 146.4 0 55.85556 146.4 28.4391 54.80755 146.4 4.580959 54.24254 146.4 9.096512 51.99485 146.4 17.9314 50.74445 146.4 36.79166 48.33597 146.4 26.24179 47.68409 146.4 40.67623 43.40071 146.4 33.78425 40.68064 146.4 47.68179 37.24397 146.4 40.47077 44.32109 146.4 44.32004 36.78876 146.4 50.74653 30.08507 146.4 46.0422 28.35401 146.4 55.89877 22.12212 146.4 50.35481 32.67069 146.4 53.48954 19.23284 146.4 59.65501 13.56462 146.4 53.30099 9.655741 146.4 61.93051 4.636376 146.4 54.80418 -0.142315 146.4 62.67855 -4.426485 146.4 54.82153 -9.924565 146.4 61.888 -13.38335 146.4 53.34679 -19.45614 146.4 59.58256 -21.99357 146.4 50.41108 -28.50967 146.4 55.81954 -30.01914 146.4 46.0852 -33.74082 146.4 43.43301 -36.87129 146.4 50.68659 -37.23322 146.4 40.48065 -40.47071 146.4 37.24022 -43.42462 146.4 33.75352 -44.3413 146.4 44.29981 -48.37014 146.4 26.17878 -50.72493 146.4 36.81856 -52.02062 146.4 17.8565 -62.48111 146.4 4.955946 -61.91042 146.4 -9.784027 -62.67877 146.4 0 -65.5 130.4 0 -62.67877 146.4 0 -61.91042 146.4 -9.784027 -64.7713 130.4 9.743709 -62.48111 146.4 4.955946 -62.67877 146.4 0 -65.5 130.4 0 -61.90049 146.4 9.846662 -59.61693 146.4 -19.35069 -62.56806 130.4 -19.37624 -59.61693 146.4 -19.35069 -64.76152 130.4 -9.807445 -59.59034 146.4 19.43241 -58.98452 130.4 -28.47751 -55.85556 146.4 -28.4391 -54.13003 130.4 -36.88257 -50.74445 146.4 -36.79166 -47.68409 146.4 -40.67623 -48.03369 130.4 -44.5292 -44.32109 146.4 -44.32004 -40.68064 146.4 -47.68179 -40.86348 130.4 -51.18907 -36.78876 146.4 -50.74653 -32.67069 146.4 -53.48954 -32.79672 130.4 -56.69684 -28.35401 146.4 -55.89877 -24.00988 130.4 -60.93996 -19.23284 146.4 -59.65501 -14.69078 130.4 -63.83041 -9.655741 146.4 -61.93051 -5.040033 130.4 -65.30491 0.142315 146.4 -62.67855 4.732599 130.4 -65.32788 9.924565 146.4 -61.888 14.41347 130.4 -63.89348 19.45614 146.4 -59.58256 23.78907 130.4 -61.02622 28.50967 146.4 -55.81954 32.64857 130.4 -56.78203 36.87129 146.4 -50.68659 40.78843 130.4 -51.24872 44.3413 146.4 -44.29981 48.01821 130.4 -44.5459 50.72493 146.4 -36.81856 54.15135 130.4 -36.8515 55.82222 146.4 -28.50449 59.59034 146.4 -19.43241 59.01793 130.4 -28.40861 59.59034 146.4 -19.43241 59.61693 146.4 19.35069 61.90049 146.4 -9.846662 62.59423 130.4 -19.29223 61.90049 146.4 -9.846662 61.91042 146.4 9.784027 62.48111 146.4 -4.955946 64.7713 130.4 -9.743709 62.48111 146.4 -4.955946 62.67877 146.4 0 62.67877 146.4 0 65.5 130.4 0 62.67877 146.4 0 61.91042 146.4 9.784027 65.5 130.4 0 62.56806 130.4 19.37624 59.61693 146.4 19.35069 64.76152 130.4 9.807445 58.98452 130.4 28.47751 55.85556 146.4 28.4391 54.13003 130.4 36.88257 50.74445 146.4 36.79166 47.68409 146.4 40.67623 48.03369 130.4 44.5292 44.32109 146.4 44.32004 40.68064 146.4 47.68179 40.86348 130.4 51.18907 36.78876 146.4 50.74653 32.67069 146.4 53.48954 32.79672 130.4 56.69684 28.35401 146.4 55.89877 24.00988 130.4 60.93996 19.23284 146.4 59.65501 14.69078 130.4 63.83041 9.655741 146.4 61.93051 5.040033 130.4 65.30491 -0.142315 146.4 62.67855 -4.732599 130.4 65.32788 -9.924565 146.4 61.888 -14.41347 130.4 63.89348 -19.45614 146.4 59.58256 -23.78907 130.4 61.02622 -28.50967 146.4 55.81954 -32.64857 130.4 56.78203 -36.87129 146.4 50.68659 -40.78843 130.4 51.24872 -44.3413 146.4 44.29981 -48.01821 130.4 44.5459 -50.72493 146.4 36.81856 -54.15135 130.4 36.8515 -55.82222 146.4 28.50449 -59.01793 130.4 28.40861 -59.59034 146.4 19.43241 -62.59423 130.4 19.29223 -61.90049 146.4 9.846662 -64.7713 130.4 9.743709 -65.5 130.4 0 -64.76152 130.4 -9.807445 -62.59423 130.4 19.29223 -62.56806 130.4 -19.37624 -59.01793 130.4 28.40861 -58.98452 130.4 -28.47751 -54.15135 130.4 36.8515 -54.13003 130.4 -36.88257 -48.03369 130.4 -44.5292 -45 130.4 0 -40.86348 130.4 -51.18907 -48.01821 130.4 44.5459 -38.25572 130.4 -23.6968 -32.79672 130.4 -56.69684 -44.23486 130.4 -8.262195 -41.95843 130.4 -16.26262 -30.2992 130.4 -33.2694 -24.00988 130.4 -60.93996 -33.26306 130.4 -30.30535 -19.99404 130.4 -40.31335 -14.69078 130.4 -63.83041 -27.08792 130.4 -35.93297 -12.23404 130.4 -43.30418 -5.040033 130.4 -65.30491 -4.077956 130.4 -44.81395 4.732599 130.4 -65.32788 12.33043 130.4 -43.27685 14.41347 130.4 -63.89348 4.200896 130.4 -44.80258 20.04465 130.4 -40.28836 23.78907 130.4 -61.02622 27.09093 130.4 -35.93096 32.64857 130.4 -56.78203 33.23467 130.4 -30.33682 40.78843 130.4 -51.24872 41.93266 130.4 -16.3294 48.01821 130.4 -44.5459 38.21961 130.4 -23.75533 48.03369 130.4 44.5292 54.15135 130.4 -36.8515 45 130.4 0 43.26216 130.4 -12.37978 44.22597 130.4 -8.310162 44.80353 130.4 -4.189214 58.98452 130.4 28.47751 59.01793 130.4 -28.40861 54.13003 130.4 36.88257 62.56806 130.4 19.37624 62.59423 130.4 -19.29223 64.76152 130.4 9.807445 64.7713 130.4 -9.743709 65.5 130.4 0 40.86348 130.4 51.18907 38.25572 130.4 23.6968 32.79672 130.4 56.69684 44.23486 130.4 8.262195 41.95843 130.4 16.26262 30.2992 130.4 33.2694 24.00988 130.4 60.93996 33.26306 130.4 30.30535 19.99404 130.4 40.31335 14.69078 130.4 63.83041 27.08792 130.4 35.93297 12.23404 130.4 43.30418 5.040033 130.4 65.30491 4.077956 130.4 44.81395 -4.732599 130.4 65.32788 -12.33043 130.4 43.27685 -14.41347 130.4 63.89348 -4.200896 130.4 44.80258 -20.04465 130.4 40.28836 -23.78907 130.4 61.02622 -27.09093 130.4 35.93096 -32.64857 130.4 56.78203 -33.23467 130.4 30.33682 -40.78843 130.4 51.24872 -41.93266 130.4 16.3294 -38.21961 130.4 23.75533 -44.80353 130.4 4.189214 -43.26216 130.4 12.37978 -44.22597 130.4 8.310162 -45 110.4 0 -45 130.4 0 -44.23486 130.4 -8.262195 -44.23486 110.4 8.262195 -44.80353 130.4 4.189214 -45 130.4 0 -45 110.4 0 -44.22597 110.4 -8.310162 -41.95843 130.4 -16.26262 -44.80353 110.4 -4.189214 -41.93266 110.4 -16.3294 -38.25572 130.4 -23.6968 -43.26216 110.4 -12.37978 -38.21961 110.4 -23.75533 -33.26306 130.4 -30.30535 -33.23467 110.4 -30.33682 -30.2992 130.4 -33.2694 -27.09093 110.4 -35.93096 -27.08792 130.4 -35.93297 -20.04465 110.4 -40.28836 -19.99404 130.4 -40.31335 -12.33043 110.4 -43.27685 -12.23404 130.4 -43.30418 -4.200896 110.4 -44.80258 -4.077956 130.4 -44.81395 4.077956 110.4 -44.81395 4.200896 130.4 -44.80258 12.23404 110.4 -43.30418 12.33043 130.4 -43.27685 19.99404 110.4 -40.31335 20.04465 130.4 -40.28836 27.08792 110.4 -35.93297 27.09093 130.4 -35.93096 30.2992 110.4 -33.2694 33.23467 130.4 -30.33682 33.26306 110.4 -30.30535 38.21961 130.4 -23.75533 38.25572 110.4 -23.6968 41.93266 130.4 -16.3294 41.95843 110.4 -16.26262 43.26216 130.4 -12.37978 44.22597 130.4 -8.310162 44.23486 110.4 -8.262195 44.80353 130.4 -4.189214 45 130.4 0 45 110.4 0 45 130.4 0 44.23486 130.4 8.262195 45 110.4 0 44.22597 110.4 8.310162 41.95843 130.4 16.26262 44.80353 110.4 4.189214 41.93266 110.4 16.3294 38.25572 130.4 23.6968 43.26216 110.4 12.37978 38.21961 110.4 23.75533 33.26306 130.4 30.30535 33.23467 110.4 30.33682 30.2992 130.4 33.2694 27.09093 110.4 35.93096 27.08792 130.4 35.93297 20.04465 110.4 40.28836 19.99404 130.4 40.31335 12.33043 110.4 43.27685 12.23404 130.4 43.30418 4.200896 110.4 44.80258 4.077956 130.4 44.81395 -4.077956 110.4 44.81395 -4.200896 130.4 44.80258 -12.23404 110.4 43.30418 -12.33043 130.4 43.27685 -19.99404 110.4 40.31335 -20.04465 130.4 40.28836 -27.08792 110.4 35.93297 -27.09093 130.4 35.93096 -30.2992 110.4 33.2694 -33.23467 130.4 30.33682 -33.26306 110.4 30.30535 -38.21961 130.4 23.75533 -38.25572 110.4 23.6968 -41.93266 130.4 16.3294 -41.95843 110.4 16.26262 -43.26216 130.4 12.37978 -44.22597 130.4 8.310162 -44.23486 110.4 8.262195 -45 110.4 0 -44.80353 110.4 -4.189214 -44.22597 110.4 -8.310162 -43.26216 110.4 -12.37978 -41.95843 110.4 16.26262 -41.93266 110.4 -16.3294 -38.25572 110.4 23.6968 -38.21961 110.4 -23.75533 -33.26306 110.4 30.30535 -33.23467 110.4 -30.33682 -30.2992 110.4 33.2694 -27.09093 110.4 -35.93096 -27.08792 110.4 35.93297 -20.04465 110.4 -40.28836 -19.99404 110.4 40.31335 -12.33043 110.4 -43.27685 -12.23404 110.4 43.30418 -4.200896 110.4 -44.80258 -4.077956 110.4 44.81395 4.077956 110.4 -44.81395 4.200896 110.4 44.80258 12.23404 110.4 -43.30418 12.33043 110.4 43.27685 19.99404 110.4 -40.31335 20.04465 110.4 40.28836 27.08792 110.4 -35.93297 27.09093 110.4 35.93096 30.2992 110.4 -33.2694 33.23467 110.4 30.33682 33.26306 110.4 -30.30535 38.21961 110.4 23.75533 38.25572 110.4 -23.6968 41.93266 110.4 16.3294 41.95843 110.4 -16.26262 43.26216 110.4 12.37978 44.23486 110.4 -8.262195 44.80353 110.4 4.189214 45 110.4 0 44.22597 110.4 8.310162 -67.53401 224.8731 15 -70.40156 223.2175 15 -68.9284 220.6046 15 -69.17012 223.9284 21.48612 -70.40156 223.2175 15 -67.53401 224.8731 27.85184 -67.53401 224.8731 15 -67.45172 217.9924 15 -64.534 219.6769 15 -67.45172 217.9924 15 -66.19934 218.7154 21.19382 -66.81045 225.1727 15 -64.534 219.6769 15 -64.534 219.6769 27.33045 -64.534 219.6769 15 -64.534 219.6769 27.33045 -63.85037 220.2179 29.6858 -63.68617 220.4077 15 -63.39606 220.8463 31.51821 -63.16662 221.3945 15 -63.13394 221.5071 32.92467 -63.03585 222.1698 33.97367 -63.04324 222.5006 15 -63.08317 222.8159 34.70653 -63.25925 223.4155 35.13185 -63.33105 223.5748 15 -63.52895 223.9257 35.26662 -63.88613 224.3694 35.14942 -63.99087 224.4711 15 -64.34738 224.756 34.75216 -64.89223 225.0492 34.05331 -64.93429 225.066 15 -65.49497 225.2262 33.05176 -66.034 225.275 15 -66.1454 225.2729 31.72018 -66.81045 225.1727 15 -66.83155 225.167 30.01048 -67.53401 224.8731 27.85184 -67.53401 224.8731 15 -66.034 225.275 15 -64.93429 225.066 15 -63.99087 224.4711 15 -63.68617 220.4077 15 -63.33105 223.5748 15 -63.16662 221.3945 15 -63.04324 222.5006 15 -58.825 162.4 15 -58.95586 162.3971 15 58.95586 162.3971 15 58.825 162.4 15 -62.17 194.225 15 -62.30086 194.2221 15 110 260.4 -55 73 260.4 -55 73 269.4408 -54.25185 110 251.3592 -54.25185 73 255.819 -54.80755 73 260.4 -55 110 260.4 -55 110 269.4965 -54.24254 73 278.2565 -52.02062 110 264.981 -54.80755 110 278.3314 -51.99485 73 286.5788 -48.37014 110 286.6418 -48.33597 73 294.1535 -43.42462 110 294.1843 -43.40071 73 297.6402 -40.47071 110 300.8708 -37.24397 73 300.8807 -37.23322 73 303.833 -33.74082 110 306.4422 -30.08507 73 306.4852 -30.01914 110 310.7548 -22.12212 73 310.8111 -21.99357 110 313.701 -13.56462 73 313.7468 -13.38335 110 315.2042 -4.636376 73 315.2215 -4.426485 110 315.2215 4.426485 73 315.2042 4.636376 110 313.7468 13.38335 73 313.701 13.56462 110 310.8111 21.99357 73 310.7548 22.12212 110 306.4852 30.01914 73 306.4422 30.08507 110 303.833 33.74082 73 300.8708 37.24397 110 297.6402 40.47071 73 294.1843 43.40071 110 300.8807 37.23322 110 294.1535 43.42462 73 286.6418 48.33597 110 286.5788 48.37014 73 278.3314 51.99485 110 278.2565 52.02062 73 269.4965 54.24254 110 269.4408 54.25185 73 264.981 54.80755 73 260.4 55 110 260.4 55 73 260.4 55 73 251.3592 54.25185 110 260.4 55 110 251.3035 54.24254 73 242.5435 52.02062 110 255.819 54.80755 110 242.4686 51.99485 73 234.2212 48.37014 110 234.1582 48.33597 73 226.6465 43.42462 110 226.6157 43.40071 73 223.1598 40.47071 110 219.9292 37.24397 73 219.9193 37.23322 73 216.967 33.74082 110 214.3578 30.08507 73 214.3148 30.01914 110 210.0452 22.12212 73 209.9889 21.99357 110 207.099 13.56462 73 207.0532 13.38335 110 205.5958 4.636376 73 205.5785 4.426485 110 205.5785 -4.426485 73 205.5958 -4.636376 110 207.0532 -13.38335 73 207.099 -13.56462 110 209.9889 -21.99357 73 210.0452 -22.12212 110 214.3148 -30.01914 73 214.3578 -30.08507 110 216.967 -33.74082 73 219.9292 -37.24397 110 223.1598 -40.47071 73 226.6157 -43.40071 110 219.9193 -37.23322 110 226.6465 -43.42462 73 234.1582 -48.33597 110 234.2212 -48.37014 73 242.4686 -51.99485 110 242.5435 -52.02062 73 251.3035 -54.24254 110 260.4 55 110 260.4 -55 110 264.981 -54.80755 110 255.819 54.80755 110 251.3592 -54.25185 110 269.4408 54.25185 110 269.4965 -54.24254 110 278.2565 52.02062 110 278.3314 -51.99485 110 286.5788 48.37014 110 286.6418 -48.33597 110 294.1535 43.42462 110 294.1843 -43.40071 110 297.6402 40.47071 110 300.8708 -37.24397 110 300.8807 37.23322 110 306.4422 -30.08507 110 306.4852 30.01914 110 310.7548 -22.12212 110 303.833 33.74082 110 310.8111 21.99357 110 313.701 -13.56462 110 313.7468 13.38335 110 315.2042 -4.636376 110 315.2215 4.426485 110 251.3035 54.24254 110 242.5435 -52.02062 110 242.4686 51.99485 110 234.2212 -48.37014 110 234.1582 48.33597 110 226.6465 -43.42462 110 226.6157 43.40071 110 223.1598 -40.47071 110 219.9292 37.24397 110 219.9193 -37.23322 110 214.3578 30.08507 110 214.3148 -30.01914 110 210.0452 22.12212 110 216.967 -33.74082 110 209.9889 -21.99357 110 207.099 13.56462 110 207.0532 -13.38335 110 205.5958 4.636376 110 205.5785 -4.426485 58.01685 318.9302 15 23.27465 335.0685 15 28.40313 334.5252 15 23.93215 334.1484 15 27.74413 333.8801 15 24.88469 333.5363 15 26.92034 333.4657 15 26 333.321 15 -13.03582 338.6318 15 -13.37965 337.6332 15 -18.56493 337.5371 15 -14.04724 336.8162 15 -17.89824 336.77 15 -14.95741 336.2802 15 -17.01372 336.2695 15 -16 336.093 15 -79.08889 257.6344 15 -78.12545 262.5177 15 -78.11267 258.2955 15 -79.09465 263.1682 15 -77.48125 261.5544 15 -77.47212 259.2678 15 -77.25006 260.4119 15 -69.42726 294.6678 15 -69.24109 298.8035 15 -68.77169 295.5941 15 -68.67044 297.8197 15 -68.50691 296.6967 15 -47.29803 321.8679 15 -47.95515 320.9755 15 -51.69094 320.692 15 -48.89626 320.3805 15 -50.88472 320.3034 15 -50 320.17 15 0 269.9 66 0 290.9 66 -2.976411 290.4688 66 2.976411 270.3312 66 2.964506 290.4726 66 -5.684371 271.5729 66 -5.718314 289.2049 66 -2.964506 270.3274 66 -7.932786 273.521 66 -7.976566 287.2278 66 -9.541881 276.0195 66 -9.574053 284.7098 66 -10.38881 278.8774 66 -10.39938 281.8491 66 5.684371 289.2271 66 5.718314 271.5951 66 -7.408469 279.2319 66 -7.408469 281.5682 66 -4.715887 286.2319 66 -4.715887 286.2319 70.15 -4.715887 286.2319 66 -7.408469 281.5682 66 -4.715887 274.5682 66 -3.749989 286.8952 66 -3.749989 286.8952 70.15 -3.749989 286.8952 66 -4.715887 286.2319 66 -4.715887 286.2319 70.15 -7.477081 279.8141 66 -7.477081 280.9859 66 -7.408469 281.5682 70.15 -7.408469 281.5682 66 -7.477081 280.9859 66 -7.408469 281.5682 70.15 -7.5 280.4 66 -7.477081 280.9859 70.15 -7.5 280.4 66 -7.5 280.4 70.15 -7.477081 279.8141 66 -7.477081 279.8141 70.15 -7.408469 279.2319 66 -7.408469 279.2319 70.15 -7.408469 279.2319 66 -4.715887 274.5682 66 -7.408469 279.2319 70.15 -3.749989 273.9048 66 -4.715887 274.5682 70.15 -4.715887 274.5682 66 -3.749989 273.9048 66 -4.715887 274.5682 70.15 -2.692582 287.4 66 -2.692582 273.4 66 -3.749989 273.9048 70.15 -2.692582 273.4 66 2.692582 287.4 66 2.692582 273.4 66 -2.692582 273.4 70.15 -2.692582 273.4 66 2.692582 273.4 66 -2.692582 273.4 70.15 3.749989 286.8952 66 3.749989 273.9048 66 2.692582 273.4 70.15 2.692582 273.4 66 3.749989 273.9048 66 2.692582 273.4 70.15 4.715887 286.2319 66 4.715887 274.5682 66 3.749989 273.9048 70.15 4.715887 274.5682 66 7.408469 281.5682 66 7.408469 279.2319 66 4.715887 274.5682 70.15 4.715887 274.5682 66 7.408469 279.2319 66 4.715887 274.5682 70.15 7.477081 280.9859 66 7.477081 279.8141 66 7.408469 279.2319 70.15 7.408469 279.2319 66 7.477081 279.8141 66 7.408469 279.2319 70.15 7.5 280.4 66 7.477081 279.8141 70.15 7.5 280.4 66 7.5 280.4 70.15 7.477081 280.9859 66 7.477081 280.9859 70.15 7.408469 281.5682 66 7.408469 281.5682 70.15 7.408469 281.5682 66 4.715887 286.2319 66 7.408469 281.5682 70.15 4.715887 286.2319 70.15 4.715887 286.2319 66 3.749989 286.8952 66 4.715887 286.2319 70.15 3.749989 286.8952 70.15 2.692582 287.4 66 2.692582 287.4 70.15 2.692582 287.4 66 -2.692582 287.4 66 2.692582 287.4 70.15 -2.692582 287.4 70.15 -2.692582 287.4 66 -2.692582 287.4 70.15 -5.40263 283.01 70.15 -4.715887 286.2319 70.15 -7.408469 281.5682 70.15 -3.737038 285.0941 70.15 -3.749989 286.8952 70.15 -7.408469 279.2319 70.15 -4.715887 274.5682 70.15 -6 280.4 70.15 -7.477081 280.9859 70.15 -5.848591 281.7391 70.15 -2.692582 287.4 70.15 1.33716 286.249 70.15 2.692582 287.4 70.15 -1.332669 286.2501 70.15 3.740951 285.091 70.15 3.749989 286.8952 70.15 5.405448 283.0041 70.15 4.715887 286.2319 70.15 7.408469 279.2319 70.15 7.408469 281.5682 70.15 6 280.4 70.15 7.477081 279.8141 70.15 7.477081 280.9859 70.15 5.40263 277.7901 70.15 4.715887 274.5682 70.15 5.848591 279.061 70.15 7.5 280.4 70.15 3.737038 275.706 70.15 3.749989 273.9048 70.15 2.692582 273.4 70.15 -1.33716 274.551 70.15 -2.692582 273.4 70.15 1.332669 274.5499 70.15 -3.740951 275.7091 70.15 -3.749989 273.9048 70.15 -5.405448 277.7959 70.15 -7.477081 279.8141 70.15 -7.5 280.4 70.15 6 280.4 73.5 6 280.4 70.15 5.405448 283.0041 70.15 5.405448 277.7959 73.5 5.848591 279.061 70.15 6 280.4 70.15 6 280.4 73.5 5.40263 283.01 73.5 3.740951 285.091 70.15 5.848591 281.7391 73.5 3.737038 285.0941 73.5 1.33716 286.249 70.15 1.332669 286.2501 73.5 -1.332669 286.2501 70.15 -1.33716 286.249 73.5 -3.737038 285.0941 70.15 -3.740951 285.091 73.5 -5.40263 283.01 70.15 -5.405448 283.0041 73.5 -5.848591 281.7391 70.15 -6 280.4 70.15 -6 280.4 73.5 -6 280.4 70.15 -5.405448 277.7959 70.15 -6 280.4 73.5 -5.40263 277.7901 73.5 -3.740951 275.7091 70.15 -5.848591 279.061 73.5 -3.737038 275.706 73.5 -1.33716 274.551 70.15 -1.332669 274.5499 73.5 1.332669 274.5499 70.15 1.33716 274.551 73.5 3.737038 275.706 70.15 3.740951 275.7091 73.5 5.40263 277.7901 70.15 5.405448 277.7959 73.5 6 280.4 73.5 5.848591 281.7391 73.5 5.40263 283.01 73.5 4.85 280.4 73.5 3.737038 285.0941 73.5 3.428239 283.8307 73.5 1.332669 286.2501 73.5 4.201514 282.8229 73.5 1.24319 285.0879 73.5 -1.33716 286.249 73.5 2.416737 284.6049 73.5 -2.429053 284.5978 73.5 -3.740951 285.091 73.5 -0.01238989 285.25 73.5 -4.199618 282.8263 73.5 -5.405448 283.0041 73.5 -5.848591 279.061 73.5 -6 280.4 73.5 -5.40263 277.7901 73.5 -4.85 280.4 73.5 -3.737038 275.706 73.5 -3.428239 276.9693 73.5 -1.332669 274.5499 73.5 -4.201514 277.9771 73.5 -1.24319 275.7121 73.5 1.33716 274.551 73.5 -2.416737 276.1951 73.5 2.429053 276.2022 73.5 3.740951 275.7091 73.5 0.01238989 275.55 73.5 4.199618 277.9738 73.5 4.85 280.4 77 4.85 280.4 73.5 4.201514 282.8229 73.5 4.201514 277.9771 77 4.199618 277.9738 73.5 4.85 280.4 73.5 4.85 280.4 77 4.199618 282.8263 77 3.428239 283.8307 73.5 2.429053 284.5978 77 2.416737 284.6049 73.5 1.24319 285.0879 73.5 0.01238989 285.25 77 -0.01238989 285.25 73.5 -1.24319 285.0879 77 -2.429053 284.5978 73.5 -3.428239 283.8307 77 -4.199618 282.8263 73.5 -2.416737 284.6049 77 -4.201514 282.8229 77 -4.85 280.4 73.5 -4.85 280.4 77 -4.85 280.4 73.5 -4.201514 277.9771 73.5 -4.85 280.4 77 -4.199618 277.9738 77 -3.428239 276.9693 73.5 -2.429053 276.2022 77 -2.416737 276.1951 73.5 -1.24319 275.7121 73.5 -0.01238989 275.55 77 0.01238989 275.55 73.5 1.24319 275.7121 77 2.429053 276.2022 73.5 3.428239 276.9693 77 2.416737 276.1951 77 4.201514 277.9771 77 4.85 280.4 77 4.199618 282.8263 77 3.428239 276.9693 77 2.429053 284.5978 77 2.416737 276.1951 77 0.01238989 285.25 77 -0.01238989 275.55 77 -1.24319 285.0879 77 1.24319 275.7121 77 -2.416737 284.6049 77 -2.429053 276.2022 77 -3.428239 283.8307 77 -4.199618 277.9738 77 -4.201514 282.8229 77 -4.85 280.4 77 - - - - - - - - - - 0.2507784 -0.9598676 -0.125557 0.2466572 -0.9677374 -0.05142503 0.258315 -0.9641034 -0.06146574 0.2683825 -0.9523704 0.1447812 0.267103 -0.9611681 0.06936985 0.2580719 -0.9631612 0.07562702 0.9931222 -0.08752876 -0.07776266 0.9887596 -0.08606398 -0.1222597 0.9947177 -0.08530157 -0.05710172 0.9954324 -0.08707016 -0.0391556 0.9897111 -0.08615601 0.1142338 0.9955331 -0.08496516 0.04117023 0.9946442 -0.0870096 0.05578869 0.2661256 -0.9576251 0.110143 0.2442142 -0.9674572 -0.06622654 1 2.32011e-5 0 0.2631071 -0.9501275 -0.167429 1 -5.86874e-6 0 0.2560229 -0.932535 -0.2546191 0.2688121 -0.9154505 -0.2994838 1 -1.49105e-6 0 1 -5.90581e-6 0 0.2548357 -0.8882628 -0.382162 0.2677744 -0.8575861 -0.439139 1 0 0 0.2551705 -0.826214 -0.5022534 0.2656996 -0.7793671 -0.5674422 1 1.11856e-5 0 0.2613697 -0.7134561 -0.650128 0.2658523 -0.6820116 -0.6813097 1 2.46506e-6 0 0.2607275 -0.7604223 -0.5947933 1 -2.88767e-6 0 0.2612432 -0.6045521 -0.7525084 0.2659756 -0.5671399 -0.7794932 0.2608498 -0.6572365 -0.7071053 1 -2.84517e-6 0 0.2611222 -0.4811656 -0.8368363 0.2660983 -0.4384717 -0.8584488 0.2606034 -0.540495 -0.7999693 0.2610283 -0.3462371 -0.9011017 0.2662211 -0.2991516 -0.9163158 0.2603916 -0.4108217 -0.8737401 1 -2.79796e-6 0 0.260937 -0.2030121 -0.943768 0.2663106 -0.152535 -0.9517415 1 -1.28393e-6 0 0.2602056 -0.2713146 -0.9266507 1 2.74761e-6 0 0.2608737 -0.05490309 -0.9638106 0.2664595 -0.002044737 -0.9638441 0.2600567 -0.1253131 -0.9574275 0.2608193 0.0944882 -0.9607525 0.2665843 0.1485975 -0.9522876 1 -1.63e-7 0 0.2598712 0.02365237 -0.9653536 0.2607593 0.2416845 -0.9346622 0.2667383 0.2958842 -0.9172258 0.2596863 0.1720662 -0.9502401 0.2606944 0.3831066 -0.8861534 0.2635976 0.4216889 -0.8675799 1 1.2627e-6 0 0.2595074 0.3163957 -0.9124417 1 -1.37625e-6 0 0.2575496 0.4522606 -0.8538903 0.2602391 0.5034485 -0.8239024 0.2576418 0.5169011 -0.816354 0.2601492 0.5669324 -0.7816073 0.2577634 0.578518 -0.7738701 0.2600547 0.6268658 -0.7344462 0.2578606 0.6365789 -0.7268255 0.2599303 0.6830154 -0.6825881 1 -1.25322e-6 0 1 2.73983e-6 0 0.2579791 0.6908946 -0.6753603 0.2598152 0.7347035 -0.6266634 1 2.49835e-6 0 1 -2.75795e-6 0 0.2581258 0.7409902 -0.6199231 0.2633203 0.7902355 -0.5533449 1 -2.49388e-6 0 1 2.7714e-6 0 0.2603631 0.8268991 -0.4984467 0.267075 0.8588458 -0.4370985 0.2589269 0.7868828 -0.5601539 0.2603935 0.8939201 -0.3648317 0.2671356 0.9165866 -0.2975023 1 -1.73613e-6 0 0.2588963 0.8637914 -0.4322467 1 1.46443e-6 0 1 5.67752e-6 0 0.26039 0.9395343 -0.2224241 0.2644535 0.9530091 -0.1477765 1 2.95281e-6 0 0.2588315 0.9200862 -0.2940198 1 2.98206e-6 0 0.2715299 0.9612044 -0.04855614 0.2580719 0.9631612 -0.07562702 1 -2.32011e-5 0 0.269633 0.9605162 -0.06860607 0.2588033 0.9543982 -0.1488119 0.2587687 0.9630506 0.07464891 0.2588599 0.9651553 0.03830099 0.2586185 0.965257 0.0373553 0.2590763 0.9628459 0.07620608 0.5636213 0.824435 -0.05136311 0.5948505 0.8032358 -0.03106856 0.5939663 0.8021688 -0.06106907 0.5374981 0.8361252 0.1095016 0.5863862 0.8089895 0.04107815 0.5507431 0.8315165 0.07254326 0.5871087 0.8075834 0.05579012 0.5366798 0.8364697 -0.1108762 0.5936374 0.7946397 -0.1270532 0.593295 0.7841016 -0.1821696 0.537626 0.8141299 -0.219433 0.5891708 0.7677683 -0.2518129 0.5917427 0.7482467 -0.2999457 0.5379842 0.778777 -0.3226135 0.594031 0.719405 -0.3599772 0.5372928 0.7294731 -0.4233031 0.5944572 0.6878772 -0.416468 0.5936 0.6568054 -0.4650223 0.5380517 0.6671171 -0.5152235 0.5909401 0.6155079 -0.5214787 0.592377 0.5790707 -0.5601488 0.538275 0.5946753 -0.5971779 0.5940492 0.5297459 -0.6053717 0.5378125 0.5106503 -0.670816 0.5949441 0.4803439 -0.6444464 0.5938117 0.4320295 -0.6787771 0.5383591 0.4178082 -0.731851 0.5923768 0.3734629 -0.7138735 0.5928645 0.3242046 -0.7371588 0.5384839 0.3191411 -0.7798616 0.5939875 0.2613631 -0.7608339 0.5382124 0.2135758 -0.8152993 0.5951238 0.2024336 -0.77772 0.5939562 0.1431635 -0.7916567 0.5385407 0.1044365 -0.8361023 0.5935155 0.07721465 -0.80111 0.5932596 0.02142435 -0.8047261 0.5393625 -0.006317377 -0.84205 0.5889271 -0.05029547 -0.8066198 0.5916705 -0.101628 -0.7997486 0.5395492 -0.1150269 -0.8340597 0.5940239 -0.1669395 -0.7869352 0.5386641 -0.2249571 -0.8119331 0.5943622 -0.2297793 -0.7706719 0.593576 -0.2843818 -0.7528578 0.5392755 -0.3296082 -0.7749454 0.5907384 -0.3496637 -0.7271613 0.5922937 -0.3960833 -0.7016454 0.539345 -0.4272154 -0.725668 0.5940485 -0.4522276 -0.6652793 0.5410904 -0.5154841 -0.6644526 0.5948833 -0.5026843 -0.6272338 0.5939762 -0.5477387 -0.5892152 0.5802332 -0.5466925 -0.6037026 0.610422 -0.5774303 -0.5421802 0.6110334 -0.5361688 -0.5823755 0.621589 -0.5975397 -0.5065308 0.8071141 -0.08530151 -0.5842009 0.8041126 -0.08642953 -0.5881606 0.8686337 -0.08649098 -0.4878473 0.7580117 -0.08752977 -0.646341 0.7401229 -0.08609485 -0.6669377 0.8882952 -0.08670532 -0.4510144 0.9257644 -0.0855143 -0.3683037 0.8490619 -0.08536088 -0.5213516 0.9475458 -0.08758878 -0.3073847 0.9657109 -0.08578872 -0.2450366 0.9202075 -0.08673483 -0.3817005 0.9691027 -0.08591115 -0.2312125 0.9838479 -0.08606415 -0.1569603 0.704475 -0.08792585 -0.7042614 0.6858261 -0.0867964 -0.7225711 0.6462125 -0.0872237 -0.7581567 0.6398062 -0.0867663 -0.7636228 0.5357011 -0.5601164 -0.6318972 0.5851143 -0.08713233 -0.8062564 0.58017 -0.08679658 -0.8098576 0.4790979 -0.5414801 -0.6908435 0.5192264 -0.08777374 -0.8501176 0.5231986 -0.08713364 -0.8477447 0.4383427 -0.5375596 -0.7203372 0.449065 -0.08579051 -0.8893709 0.3495391 -0.5281387 -0.7738812 0.4691709 -0.3450495 -0.8129081 0.423177 -0.5045407 -0.7525689 0.379846 -0.0869196 -0.9209572 0.3272901 -0.084966 -0.9410963 0.1685249 -0.7784435 -0.6046694 0.1739004 -0.7885645 -0.5898516 0.133612 -0.7587931 -0.6374802 0.4502258 -0.08695048 -0.8886711 0.2310308 -0.08667469 -0.9690781 0.1848264 -0.08524113 -0.9790675 0.1227785 -0.7479631 -0.6522856 0.05459916 -0.7284671 -0.6829016 0.3050118 -0.08670586 -0.9483934 0.07678544 -0.08639883 -0.9932972 0.03854519 -0.08560514 -0.9955832 0.05447655 -0.7361204 -0.6746549 -0.04077321 -0.7035217 -0.7095034 0.1525045 -0.08639985 -0.984519 -0.07910501 -0.0860328 -0.9931469 -0.1080086 -0.08603459 -0.9904204 -0.04144471 -0.7077952 -0.705201 -0.1428906 -0.6773116 -0.7216864 -0.003418087 -0.08600223 -0.9962891 0.02182096 -0.7479566 -0.6633889 -0.2329248 -0.08560717 -0.9687196 -0.2330119 -0.08661264 -0.9686093 -0.1417009 -0.6796334 -0.7197357 -0.2316116 -0.6526877 -0.7213563 -0.1591279 -0.0855152 -0.9835473 -0.07605355 -0.7081041 -0.7020003 -0.3092501 -0.08749824 -0.9469469 -0.3194755 -0.08697986 -0.9435942 -0.2381429 -0.6485679 -0.7229437 -0.2949349 -0.632871 -0.7158825 -0.1803987 -0.6744429 -0.715949 -0.3823707 -0.08737546 -0.9198686 -0.3875029 -0.08710193 -0.9177444 -0.2875839 -0.6357182 -0.7163504 -0.3439503 -0.6200566 -0.7051439 -0.4530813 -0.08734464 -0.8871799 -0.4532356 -0.08713132 -0.8871222 -0.3397961 -0.6217285 -0.7056857 -0.3958343 -0.6068748 -0.6892157 -0.5165991 -0.08704084 -0.8517919 -0.4370722 -0.5950114 -0.6744846 -0.4456664 -0.5938965 -0.6698273 -0.387777 -0.6087055 -0.6921755 -0.5211074 -0.08743613 -0.8490006 -0.5773326 -0.08688825 -0.811873 -0.483124 -0.5827092 -0.653484 -0.4952386 -0.5808761 -0.6460046 -0.5860037 -0.08759075 -0.8055604 -0.6350417 -0.08679634 -0.7675862 -0.5282921 -0.570348 -0.6289759 -0.5433064 -0.5681188 -0.6181095 -0.6473191 -0.0876826 -0.757159 -0.6893309 -0.08670425 -0.7192394 -0.5712385 -0.558878 -0.6011174 -0.5896652 -0.5558803 -0.5859113 -0.7047896 -0.08777439 -0.7039655 -0.7399446 -0.08664476 -0.6670642 -0.6119088 -0.5478491 -0.5704638 -0.6340676 -0.5439442 -0.5496209 -0.7577809 -0.08783298 -0.6465706 -0.7865732 -0.08661365 -0.6113926 -0.6507325 -0.5375974 -0.5362241 -0.6761894 -0.5324733 -0.5091564 -0.8058664 -0.08783501 -0.5855464 -0.8290524 -0.08658277 -0.5524269 -0.6865316 -0.5280143 -0.4998756 -0.7150483 -0.5218885 -0.4651217 -0.8492332 -0.08783483 -0.5206612 -0.867164 -0.08658212 -0.4904387 -0.7201334 -0.519469 -0.4599564 -0.752064 -0.5109592 -0.4163179 -0.8873462 -0.08783429 -0.452661 -0.9006589 -0.08661413 -0.4258071 -0.7496727 -0.5118063 -0.4195774 -0.7834342 -0.5024111 -0.3658061 -0.9199294 -0.0878027 -0.3821264 -0.9293856 -0.08667588 -0.3587895 -0.775774 -0.505982 -0.3770373 -0.811081 -0.4959082 -0.3101982 -0.9470732 -0.0877428 -0.3087937 -0.9531739 -0.08673536 -0.2897182 -0.8141974 -0.4943537 -0.3044618 -0.8349173 -0.4894995 -0.2516013 -0.7931343 -0.5013703 -0.3457831 -0.9684275 -0.08765041 -0.2333784 -0.9718674 -0.0868256 -0.218941 -0.8379301 -0.4885484 -0.2432976 -0.8533914 -0.4847441 -0.1916941 -0.8286007 -0.4908124 -0.2693029 -0.983797 -0.08752727 -0.1564688 -0.9853423 -0.08694911 -0.1467667 -0.8583506 -0.4827822 -0.1736539 -0.8670312 -0.4813856 -0.1285485 -0.8483214 -0.4856576 -0.2109206 -0.993068 -0.08740729 -0.07858723 -0.9934789 -0.08707016 -0.07361137 -0.8697406 -0.4802221 -0.1137456 -0.875397 -0.4790513 -0.06473004 -0.8671795 -0.4802845 -0.1316304 -0.8638114 -0.4814687 -0.1483836 -0.9954007 -0.08725321 -0.03955233 -0.9955199 -0.0870698 -0.03686654 -0.8766078 -0.4784827 -0.05111992 -0.8784967 -0.4777483 4.27269e-4 -0.8752343 -0.4781774 -0.0728802 -0.8723049 -0.4797341 -0.094549 -0.9931269 -0.08728504 0.07797664 -0.995503 -0.08722358 0.03695863 -0.9954324 -0.08707016 0.0391556 -0.87844 -0.4775371 -0.01736551 -0.8779799 -0.4786956 0.001342833 -0.8757561 -0.4784231 0.06451815 -0.8773308 -0.4786607 -0.03427284 -0.9934705 -0.08716362 0.07361298 0 -1 1.98318e-6 0 -1 1.34999e-6 0 -1 0 0 -1 1.08366e-6 0 -1 -2.08568e-7 0 -1 5.32651e-7 0 -1 -1.34993e-6 0 -1 2.1061e-6 0 -1 -1.96617e-6 0 -1 4.48956e-7 0 -1 1.79267e-6 0 -1 1.80369e-6 0 -1 3.11534e-6 0 -1 3.2954e-6 0 -1 -3.13845e-6 0 -1 3.57465e-6 0 -1 -1.74101e-6 0 -1 -1.74374e-6 0 -1 1.74613e-6 0 -1 -3.29909e-6 0 -1 1.74744e-6 0 -1 -1.74737e-6 0 -1 1.49157e-6 0 -1 1.06197e-6 0 -1 1.16548e-6 0 -1 -6.76612e-7 0 -1 2.08568e-7 0 -1 -1.72795e-6 0 -1 -1.08367e-6 0 -1 -1.34999e-6 0 -1 -1.98318e-6 0.993233 -0.08642911 0.07757866 0.5097994 0.8583942 -0.05713266 0.4306564 0.8950061 0.1161866 0.522923 0.8450574 0.1114881 0.4226933 0.898063 -0.1217112 0.4514384 0.8902724 -0.06015312 0.4229948 0.8732737 -0.2418028 0.4230842 0.8326485 -0.3573464 0.4231497 0.7768376 -0.4663345 0.4232137 0.7068618 -0.5667774 0.4232712 0.6240267 -0.6568349 0.4232736 0.5298169 -0.7349379 0.4232984 0.425984 -0.7995975 0.423301 0.3144086 -0.8496845 0.4232977 0.1971218 -0.8842863 0.4232704 0.07626736 -0.9027876 0.423247 -0.04596263 -0.9048477 0.4232138 -0.1673689 -0.8904368 0.4231823 -0.2856923 -0.8598237 0.4231227 -0.3988596 -0.813559 -0.9930505 -0.1155136 -0.0225228 0 0 -1 -0.9987967 0 -0.04904407 -0.9921168 -0.1231753 0.02307248 -0.9987978 8.24015e-4 0.04901361 -0.9893726 -0.05554497 0.1343762 -0.9932499 -0.1149661 -0.01541221 -0.9931061 -0.113102 -0.03079324 -0.9928202 -0.1101133 -0.04672485 -0.9923942 -0.1059628 -0.06265598 -0.9916169 -0.100773 -0.0808748 -0.9908885 -0.09460866 -0.09585994 -0.9907274 -0.08270555 -0.1077919 -0.9907252 -0.06793439 -0.1176797 -0.990724 -0.05197465 -0.1255572 -0.9907239 -0.03515845 -0.1312643 -0.9907218 -0.01773178 -0.1347433 -0.9907181 0 -0.135933 -0.9907178 0.01773166 -0.1347733 -0.9907147 0.03518861 -0.1313242 -0.9907134 0.05203515 -0.1256169 -0.9907099 0.06799644 -0.1177731 -0.9907096 0.08279818 -0.1078848 -0.9907062 0.09619569 -0.09616518 -0.9907063 0.107915 -0.08279788 -0.9907007 0.117833 -0.06802636 -0.9907004 0.1257068 -0.05206501 -0.9906949 0.1314741 -0.0351879 -0.9906929 0.1349571 -0.01773178 -0.9906485 0.1361455 -0.008942067 -0.9906923 0.134957 0.0177623 -0.9906529 0.1361156 0.00891155 -0.9930902 -0.1132257 0.03085476 -0.9927974 -0.1102667 0.04684734 -0.9923567 -0.1062062 0.06283867 -0.9914649 -0.1012309 0.08215665 -0.9907329 -0.09601223 0.09607326 -0.9907235 -0.08270776 0.1078253 -0.9907155 -0.06796634 0.1177432 -0.9907111 -0.05200451 0.1256471 -0.9917491 -0.04025471 0.1217102 -0.9935972 -0.01483207 0.1120036 -0.9936284 -6.10374e-5 0.1127056 -0.9936064 0.01489323 0.1119131 -0.9919708 0.04010242 0.1199411 -0.9906966 0.05206477 0.1257368 -0.9906972 0.06802612 0.1178631 -0.9906973 0.08282768 0.1079751 -0.9906974 0.09622538 0.09622538 -0.9906948 0.1079748 0.08285796 -0.9906972 0.1178631 0.06802612 -0.9906966 0.1257368 0.05206477 -0.9906933 0.131478 0.03521949 -0.9903845 -0.1380391 0.009155809 -0.9870103 -0.160285 -0.01092571 -0.98697 -0.1592202 0.0232253 -0.9870246 -0.1601653 0.01138365 -0.9865896 -0.1570816 -0.04434418 -0.9869563 -0.1594011 -0.02255356 -0.9858418 -0.1531775 -0.06821113 -0.98461 -0.1454849 -0.09683734 -0.9828342 -0.1352908 -0.1254331 -0.9786331 -0.1071534 -0.1754862 -0.9810231 -0.1163103 -0.1551313 -0.9694608 -0.1520142 -0.1924517 -0.975041 -0.142278 -0.1704468 -0.9655054 -0.1317514 -0.2245908 -0.9636509 -0.1090154 -0.2439112 -0.9636539 -0.07577997 -0.2561808 -0.9636525 -0.04120129 -0.2639629 -0.9636494 -0.00589019 -0.2671056 -0.9636545 0.02948182 -0.26552 -0.9636515 0.0643655 -0.2592933 -0.9636523 0.09812009 -0.2484895 -0.9636615 0.1301321 -0.2332857 -0.9636539 0.1598867 -0.2140266 -0.9636595 0.1868051 -0.1909557 -0.9636605 0.2104269 -0.1645572 -0.9636604 0.2303556 -0.1352591 -0.9636617 0.2462257 -0.1035808 -0.9636642 0.2577624 -0.07007133 -0.9636687 0.2647525 -0.03534102 -0.9635136 0.2670713 -0.01773148 -0.9635341 0.2670159 0.01745718 -0.9194195 0.3898209 -0.05203509 -0.9190761 0.3932052 -0.02624619 -0.9637101 0.2646945 0.03463947 -0.9192348 0.3929331 0.02472043 -0.8772169 -0.4797943 0.01696872 -0.9580782 -0.1727672 -0.2285556 -0.9484505 -0.1403891 -0.2841353 -0.9223316 -0.1517127 -0.3553698 -0.9385048 -0.07303309 -0.337454 -0.933336 -0.1553424 -0.3236553 -0.9197699 -0.1122512 -0.3760628 -0.9197571 -0.06140458 -0.3876549 -0.9197261 -0.009491443 -0.3924462 -0.9197139 0.04257369 -0.3902742 -0.9196899 0.09393745 -0.3812432 -0.9196673 0.1436846 -0.3654681 -0.9196447 0.190869 -0.343253 -0.9196249 0.2347205 -0.3149546 -0.9196011 0.2744276 -0.2811113 -0.9195606 0.3093381 -0.2423189 -0.9195431 0.3387629 -0.1991987 -0.9195062 0.3622602 -0.1525643 -0.9194747 0.3793504 -0.1032456 -0.8588618 0.5075591 -0.06885051 -0.8583407 0.5119221 -0.03445565 -0.9195793 0.3898545 0.0488615 -0.8586038 0.5117197 0.03070253 -0.8994517 -0.1668466 -0.403917 -0.8604663 -0.1572974 -0.4846189 -0.8746832 -0.05658274 -0.4813809 -0.8679129 -0.1726182 -0.4657577 -0.8592286 -0.0941202 -0.5028596 -0.8592101 -0.02554464 -0.5109848 -0.859201 0.04345899 -0.5097892 -0.8591664 0.1117295 -0.4993492 -0.8591454 0.1779573 -0.479792 -0.8591139 0.2409791 -0.4515002 -0.8590888 0.2996083 -0.4149714 -0.8590597 0.3528041 -0.3708716 -0.8590205 0.3995863 -0.3200231 -0.8589828 0.4391048 -0.2633164 -0.8589392 0.4706404 -0.2017945 -0.8588885 0.4936098 -0.1366018 -0.7828807 0.6167643 -0.08185267 -0.7822293 0.621639 -0.04101735 -0.8590562 0.5082983 0.06045866 -0.7818346 0.6221594 0.0406512 -0.8110727 -0.1475288 -0.5660357 -0.7838499 -0.1677324 -0.5978671 -0.7912462 -0.1957514 -0.5793194 -0.7827607 -0.0909782 -0.6156367 -0.7827595 -0.009064197 -0.6222584 -0.7827521 0.07297098 -0.6180409 -0.7827595 0.1537563 -0.6030312 -0.7827613 0.2318558 -0.5775185 -0.7827624 0.3059267 -0.5419335 -0.7827698 0.3746601 -0.4968916 -0.7827788 0.4368472 -0.4431952 -0.7827895 0.4914218 -0.3817659 -0.7828143 0.5374104 -0.313675 -0.7828371 0.5740277 -0.2401217 -0.782862 0.6006286 -0.1623955 -0.6929344 0.7148471 -0.09399855 -0.6922042 0.7201598 -0.04715204 -0.7823859 0.6174 0.08179098 -0.6922324 0.7201268 0.04724341 -0.7267262 -0.1809491 -0.6626662 -0.6934282 -0.183085 -0.6968768 -0.6998541 -0.219063 -0.6798644 -0.6924842 -0.0935418 -0.7153431 -0.6925082 5.49343e-4 -0.7214097 -0.6925482 0.09467142 -0.7151325 -0.6925812 0.1871461 -0.6966403 -0.6926231 0.2764388 -0.6662244 -0.6926658 0.3609821 -0.6244246 -0.6927049 0.4393306 -0.5719691 -0.6927292 0.5101927 -0.5097349 -0.6927614 0.572301 -0.4388089 -0.6928185 0.6246079 -0.3603718 -0.6928486 0.6662663 -0.2757722 -0.6929016 0.6965028 -0.1864706 -0.5907327 0.800004 -0.1050171 -0.589841 0.8057936 -0.05276733 -0.6959007 0.7126253 0.08881109 -0.5916129 0.804911 0.04596173 -0.6283879 -0.2106121 -0.7488467 -0.5911265 -0.2055468 -0.7799488 -0.589058 -0.2395175 -0.7717786 -0.5911012 -0.1024233 -0.800068 -0.5910639 0.00262463 -0.8066205 -0.5910385 0.1076724 -0.7994249 -0.5910083 0.2108891 -0.7786111 -0.5909983 0.3105297 -0.7445083 -0.5909753 0.4048687 -0.6977317 -0.590937 0.4923304 -0.6390652 -0.5909113 0.5714095 -0.5694868 -0.5908854 0.6407235 -0.4902325 -0.5908426 0.6991536 -0.4026031 -0.5908147 0.7456675 -0.308088 -0.5907697 0.779473 -0.2083579 -0.4779342 0.8708719 -0.1147225 -0.4770743 0.876966 -0.0577116 -0.5917118 0.8015028 0.08643114 -0.4756647 0.8778402 0.05603235 -0.4774395 -0.2284043 -0.8484593 -0.5409625 -0.2478203 -0.8037069 -0.4785948 -0.1178634 -0.8700892 -0.4785377 -0.002990841 -0.8780619 -0.4785098 0.1118832 -0.8709251 -0.4784515 0.2248664 -0.8488341 -0.4784181 0.333971 -0.812145 -0.4783632 0.4373754 -0.7614929 -0.4783293 0.5332641 -0.6977326 -0.4782673 0.6199681 -0.6220129 -0.4782118 0.6960303 -0.5355888 -0.4781492 0.7601495 -0.4399388 -0.4780859 0.8112049 -0.3367202 -0.478022 0.8483114 -0.2277342 -0.3566129 0.9261253 -0.1229605 -0.3558532 0.932482 -0.06201487 -0.4754518 0.8723179 0.1140486 -0.3559406 0.932471 0.06167846 -0.4664908 -0.2809932 -0.8387069 -0.3560363 -0.2580088 -0.8981479 -0.4229702 -0.2826719 -0.8609256 -0.3572019 -0.1394748 -0.9235548 -0.3571698 -0.01632791 -0.9338968 -0.3571593 0.1070592 -0.9278877 -0.3571332 0.2285872 -0.905651 -0.3570751 0.3461492 -0.8675704 -0.35705 0.4576429 -0.8142962 -0.3570149 0.561128 -0.746777 -0.356954 0.6547922 -0.6662064 -0.3569245 0.7370133 -0.5739481 -0.3568569 0.8063385 -0.4716688 -0.3567992 0.8615552 -0.3611329 -0.3567357 0.9017122 -0.244243 -0.2289533 0.9647656 -0.1296446 -0.2285601 0.9713119 -0.06567782 -0.3599476 0.9250476 0.1213457 -0.2340214 0.9709998 0.0489223 -0.3440195 -0.3147205 -0.8846478 -0.2282561 -0.2917369 -0.9288643 -0.2980501 -0.3199323 -0.8993384 -0.2294445 -0.1670019 -0.9588877 -0.2294415 -0.03726363 -0.9726089 -0.2294134 0.09311431 -0.968865 -0.2294123 0.2218436 -0.9477107 -0.2293844 0.3465792 -0.9095415 -0.2293516 0.4651123 -0.8550254 -0.2293217 0.5752575 -0.785169 -0.2292947 0.6750965 -0.7011908 -0.2292583 0.7627906 -0.6046414 -0.2291988 0.8368048 -0.4972181 -0.2291409 0.89578 -0.3808842 -0.2290764 0.9386763 -0.2577034 -0.09827184 0.9859538 -0.1350475 -0.1314451 0.9889972 -0.06787413 -0.2331628 0.9688463 0.08349913 -0.1101742 0.9858916 0.1260136 -0.215619 -0.351308 -0.9110935 -0.09729415 -0.3294206 -0.9391571 -0.1687399 -0.3589348 -0.917983 -0.09863889 -0.2005739 -0.9747002 -0.09881991 -0.06622582 -0.9928992 -0.0989741 0.06933987 -0.9926712 -0.09906572 0.2036249 -0.9740241 -0.09915804 0.3341587 -0.9372864 -0.09918713 0.4585193 -0.8831319 -0.09918653 0.5743666 -0.8125671 -0.09915697 0.6795721 -0.7268769 -0.09909743 0.7721481 -0.6276679 -0.09894168 0.8504042 -0.516743 -0.09875929 0.9128521 -0.3961664 -0.09848451 0.9583246 -0.2681697 -0.06543356 0.9955728 -0.06747835 -0.08188331 0.9935868 0.07797682 -0.0840494 -0.3902775 -0.9168529 0.03671443 -0.3777346 -0.9251857 -0.03903353 -0.3996438 -0.9158391 0.03573805 -0.2553852 -0.9661787 0.03589075 -0.1271132 -0.9912388 0.03601241 0.003296017 -0.9993459 0.03610378 0.1336726 -0.9903677 0.03619551 0.2617311 -0.9644619 0.03628724 0.3853045 -0.9220758 0.03631788 0.5022857 -0.8639388 0.0363484 0.6106595 -0.7910587 0.03637856 0.7085588 -0.7047134 0.03634792 0.7943447 -0.606379 0.03628748 0.8665668 -0.4977403 0.03622597 0.9239916 -0.3806933 0.03607368 0.9656887 -0.2571853 0.03613454 0.9909537 -0.1292482 0.001434326 0.997842 -0.06564587 -0.08893358 0.9890428 0.1178355 0.0187999 0.9930994 0.1157599 0.06894338 0.9954523 -0.06573885 0.05212658 0.9951971 0.08285933 0.04934942 -0.4330053 -0.9000395 0.1695061 -0.420805 -0.8911739 0.09058231 -0.4382927 -0.8942564 0.1686487 -0.2992095 -0.9391652 0.1686477 -0.1709061 -0.9707466 0.1686486 -0.03955274 -0.9848824 0.168651 0.09250473 -0.9813255 0.1686488 0.2229424 -0.9601325 0.1686468 0.3494096 -0.9216676 0.168649 0.4695986 -0.8666226 0.1686497 0.5813624 -0.7959743 0.1686503 0.6826888 -0.7109803 0.1686171 0.7717323 -0.6131864 0.1686183 0.8469066 -0.5042986 0.1686177 0.9068126 -0.3863407 0.1685888 0.9504026 -0.2613676 0.1683717 0.976904 -0.1315661 0.1345904 0.9886447 -0.06683743 0.0372945 0.9903193 0.1337049 0.1506413 0.9818847 0.1149342 0.200388 0.9775251 -0.06549388 0.1839722 0.9794661 0.08246397 0.1686466 -0.4795107 -0.8611782 0.2168071 -0.488457 -0.8452246 0.299883 -0.471249 -0.8294544 0.2845601 -0.5224565 -0.8037816 0.2983521 -0.3621975 -0.8830623 0.2983259 -0.2438795 -0.9227808 0.2982627 -0.1214047 -0.9467314 0.2982336 0.003112912 -0.9544879 0.2982021 0.1275698 -0.9459394 0.2982023 0.24986 -0.9212196 0.2981727 0.367848 -0.8807843 0.2981457 0.479554 -0.8253103 0.2981456 0.5830457 -0.7557559 0.2981479 0.6765629 -0.6733279 0.2981706 0.7585191 -0.5794336 0.2981721 0.827527 -0.4757021 0.2982 0.8824232 -0.3638767 0.2982298 0.9222782 -0.24589 0.298536 0.9463609 -0.1236016 0.2649653 0.9621703 -0.06341832 0.1631872 0.9781165 0.1290665 0.2801626 0.9531938 0.113713 0.3296411 0.9420453 -0.06235128 0.3084262 0.9489614 0.06592124 0.3907056 0.9183809 -0.06265568 0.2953637 0.9518905 0.08163857 0.408042 0.9047729 0.1220158 0.4359363 0.8967764 0.07584023 0.5929211 0.7950477 0.1278436 0.2586225 0.9544374 0.1488743 0.5370857 0.8147234 0.2185515 0.5925395 0.7848135 0.1815615 0.2635601 0.9499272 0.1678532 0.2575802 0.9405034 0.2215983 0.5938447 0.76576 0.2469012 0.2592908 0.9409666 0.2176015 0.2562988 0.9209117 0.2936541 0.5369899 0.7789787 0.323781 0.5949677 0.7446632 0.3024737 0.2571842 0.9038223 0.3419967 0.2517549 0.896417 0.3647684 0.2582254 0.9226958 0.2862728 0.594031 0.719405 0.3599772 0.252027 0.8870694 0.3867691 0.2524869 0.864187 0.435237 0.5378413 0.728892 0.4236076 0.5924394 0.6880256 0.4190901 0.2510492 0.8553556 0.4531459 0.2657039 0.8225651 0.5027804 0.2486093 0.8799294 0.4048676 0.2582832 0.867109 0.4259247 0.5380172 0.6677835 0.5143956 0.5911274 0.6596126 0.4641978 0.2628349 0.8592492 0.438872 0.2641472 0.7882606 0.5557622 0.2609067 0.8387224 0.4779881 0.2469295 0.8514811 0.4626076 0.2550515 0.844078 0.471679 0.5936276 0.6156013 0.5183063 0.2618584 0.7810584 0.5669021 0.2669495 0.7358431 0.6223126 0.5376959 0.5945236 0.5978503 0.5945203 0.5763001 0.5607352 0.264051 0.6931493 0.6706872 0.5940492 0.5297459 0.6053717 0.2621924 0.6829335 0.6818042 0.2664619 0.6312867 0.7283374 0.5387615 0.5095238 0.6709111 0.591831 0.4788483 0.6484138 0.2638122 0.5813391 0.7697066 0.5388128 0.418568 0.7310824 0.589411 0.4370302 0.6794111 0.2624991 0.5679088 0.7801115 0.2659763 0.5116268 0.8170036 0.5933537 0.3739514 0.7128057 0.2635949 0.4555917 0.8502669 0.5382904 0.3189824 0.7800602 0.5937557 0.3231093 0.7369224 0.2627706 0.4391108 0.859147 0.2655469 0.3796884 0.8861837 0.5939875 0.2613631 0.7608339 0.2633807 0.3189256 0.9104488 0.5396078 0.212077 0.8147679 0.5911033 0.1984993 0.7817896 0.2630147 0.2996684 0.9170726 0.2651838 0.2386319 0.9342015 0.5395135 0.1053208 0.8353639 0.5873809 0.1493936 0.7954027 0.2631974 0.1746002 0.9488108 0.5929853 0.07669436 0.8015525 0.263259 0.1528708 0.9525362 0.2648134 0.0918622 0.9599142 0.5387741 -0.005310177 0.8424335 0.5926868 0.02200448 0.8051324 0.2630433 0.02609372 0.9644312 0.5938667 -0.0458393 0.8032566 0.2635325 0.00225836 0.9646479 0.2644153 -0.05710071 0.9627171 0.5385113 -0.1161255 0.834578 0.5949985 -0.105138 0.7968206 0.2628604 -0.1230527 0.9569548 0.5940239 -0.1669395 0.7869352 0.2638404 -0.1485381 0.9530608 0.2640237 -0.204755 0.9425321 0.5391494 -0.2253526 0.8115013 0.5925073 -0.2320709 0.7714132 0.2626828 -0.2692751 0.9265466 0.5391818 -0.3286912 0.7753999 0.5913185 -0.2830088 0.7551481 0.2641438 -0.2959448 0.9179568 0.263566 -0.3475251 0.8998663 0.5936548 -0.3463291 0.7263817 0.2624664 -0.4091119 0.8739216 0.5387241 -0.4279701 0.7256845 0.594582 -0.3974562 0.6989284 0.2623705 -0.4206107 0.8684748 0.2570912 -0.479574 0.8389952 0.5940485 -0.4522276 0.6652793 0.2608178 -0.5033547 0.8237767 0.2570632 -0.5429976 0.7994199 0.5419299 -0.5158054 0.6635185 0.5920698 -0.5064943 0.6268309 0.2608509 -0.5667793 0.7814846 0.2570309 -0.6032382 0.7550091 0.5813531 -0.5450052 0.6041507 0.590056 -0.5471462 0.5936878 0.2609103 -0.6266853 0.7342966 0.2570037 -0.6597985 0.7061269 0.610422 -0.5774303 0.5421802 0.2609397 -0.6827771 0.6824413 0.2570049 -0.7124782 0.6529346 0.6110334 -0.5361688 0.5823755 0.621589 -0.5975397 0.5065308 0.260967 -0.7344676 0.6264612 0.2561797 -0.7612756 0.5956774 0.7579689 -0.08752834 0.6463916 0.8017459 -0.08585119 0.5914669 0.7401229 -0.08609485 0.6669377 0.2641151 -0.7899039 0.5534393 0.2566379 -0.817707 0.5152595 0.8485808 -0.08856612 0.5216003 0.8590729 -0.0793488 0.5056656 0.8059229 -0.08713257 0.5855736 0.7047153 -0.0877422 0.7040438 0.6855401 -0.0873748 0.7227728 0.5357011 -0.5601164 0.6318972 0.6399269 -0.08749854 0.7634381 0.4246493 -0.5013145 0.7538945 0.4791214 -0.5414721 0.6908333 0.4484778 -0.5437279 0.7093854 0.4228089 -0.3987905 0.8137561 0.4228474 -0.2855402 0.8600389 0.4229022 -0.1670917 0.8906369 0.4229702 -0.04559618 0.9049957 0.4230579 0.07669484 0.902851 0.4231545 0.1976145 0.8842449 0.4232767 0.3149015 0.8495139 0.4233942 0.4264461 0.7993003 0.4235429 0.5302069 0.7345013 0.4237267 0.6242675 0.6563125 0.4239161 0.7069541 0.5661371 0.424221 0.7765991 0.465758 0.4318811 0.8279325 0.3577799 0.4381638 0.8656765 0.2421086 0.646952 -0.08670586 0.7575852 0.580141 -0.08725458 0.8098291 0.5865222 -0.08664458 0.8052854 0.5233153 -0.08740741 0.8476445 0.3896088 -0.5515134 0.7375893 0.5211733 -0.08755904 0.8489476 0.4485383 -0.08649092 0.8895689 0.2998548 -0.467041 0.8318414 0.3431243 -0.5268483 0.7776224 0.2985385 -0.3528015 0.8867954 0.2985656 -0.2291963 0.9264597 0.2985692 -0.1013237 0.9489942 0.2985684 0.02838271 0.9539661 0.2986006 0.1576015 0.9412754 0.2985989 0.2838887 0.9111783 0.2986011 0.4049304 0.8642157 0.2986002 0.5184913 0.801252 0.2985958 0.6224306 0.7234783 0.2985973 0.7148757 0.6322914 0.2985689 0.7940472 0.5294767 0.3436129 0.7986199 0.4941018 0.3042472 0.8150187 0.4931313 0.3915973 0.8529016 0.3452686 0.4294041 0.6729162 0.6023254 0.3908836 0.7981252 0.4584825 0.3807907 0.8259774 0.4156439 0.3774034 0.8418179 0.3858879 0.3686102 0.9202438 0.131446 0.4239352 0.8434453 0.3299682 0.3857597 0.886637 0.2550775 0.3177919 0.9478213 0.02536106 0.3209095 0.9398084 0.1173768 0.13334 -0.7586251 0.637737 0.1736563 -0.7887781 0.5896379 0.1683766 -0.7786771 0.6044101 0.451933 -0.08560723 0.8879348 0.3272287 -0.08588153 0.9410344 0.2861211 -0.5203589 0.8045878 0.1230529 -0.7478395 0.6523758 0.1699002 -0.4206762 0.8911597 0.2172367 -0.4884621 0.8451113 0.1688919 -0.2989941 0.9391902 0.1686506 -0.1706343 0.970794 0.1683446 -0.03915625 0.9849503 0.1738698 0.08722484 0.9808982 0.1923338 0.223128 0.9556263 0.1764923 0.3586307 0.9166431 0.1655987 0.4706105 0.8666619 0.1655973 0.5823678 0.7958803 0.1655973 0.6836308 0.7107928 0.1656276 0.7725933 0.6129169 0.1649547 0.8473578 0.5047523 0.3717525 0.9283284 0.002533078 0.2234948 0.9747037 0.001709043 0.126562 0.991957 0.001892149 0.2851983 0.798708 0.5298372 0.339706 0.9405317 9.15567e-5 0.01678532 0.9998579 0.001617491 -0.01492369 0.9998887 -1.52594e-4 -0.2092976 0.9778515 9.766e-4 -0.3056513 0.9521427 0.001281797 -0.4096552 0.9122404 -5.18821e-4 -0.5813613 0.8136434 0.001861631 -0.5996187 0.8002852 -0.001007139 -0.8018892 0.5974723 9.46092e-4 -0.769493 0.6386551 -5.49354e-4 -0.8918359 0.4523575 0.001190245 -0.9460512 0.3240173 0 -0.9460631 0.3239825 0 -0.8842692 0.4669774 0 0 0 1 0.247446 0.9556031 0.1599792 0.05542278 -0.7298657 0.6813402 0.07315415 -0.7303822 0.6791101 0.168954 -0.4795473 0.8610976 0.02636861 -0.720895 0.6925426 0.03735566 -0.3803321 0.9240953 0.09085494 -0.4385882 0.8940838 0.04962426 -0.4341059 0.8994941 0.03631812 -0.2612158 0.964597 0.03656125 -0.1362961 0.9899932 0.0368362 -0.009277701 0.9992783 0.1351077 0.112249 0.9844523 0.06024545 0.03164869 0.9976817 0.0950663 0.04623609 0.9943967 0.1610177 0.2486374 0.9551193 0.297138 -0.001464903 0.9548335 0.1626979 0.1736543 0.9712743 0.04059058 0.4768637 0.8780397 0.2160118 0.2662152 0.939398 0.149575 0.311663 0.9383462 0.119176 0.3582912 0.9259722 0.1034891 0.436357 0.8938024 0.08264708 0.4195532 0.9039605 0.03958326 0.5885307 0.8075054 0.03955352 0.6913937 0.7213946 0.03940063 0.7818173 0.6222615 0.03912568 0.8581718 0.5118695 0.2099403 0.8835868 0.4185684 0.1565033 0.9080429 0.3885421 0.03869867 0.9190632 0.3922057 0.2007237 0.8783074 0.4339197 0.2229107 0.8620396 0.4551908 0.2474477 0.8401259 0.4826573 0.2129341 0.9238234 0.3181346 0.1581526 0.9523948 0.2606374 0.03811824 0.9633948 0.2653631 0.2156787 0.9101113 0.3538084 0.2204371 0.8972519 0.3825528 0.2246546 0.9419562 0.2494975 0.9460603 -0.3239909 -1.39745e-6 0.9460577 -0.3239985 0 0.990049 -0.1406943 0.002868771 0.9809883 -0.1940674 0 0.9995799 0.02896225 -0.00112915 0.9986611 0.05169856 0.001831114 0.9623469 0.2717997 0.003692746 0.8854268 0.4647789 3.35713e-4 0.9088973 0.4170166 0.001739561 0.7709435 0.6369035 -2.44153e-4 0.6894004 0.7243756 0.002685666 0.6313014 0.7755377 2.74678e-4 0.48205 0.8761438 -6.10383e-5 -0.03940063 -0.7052748 0.7078384 -0.02911543 -0.7031352 0.7104599 -0.0778225 -0.6936885 0.7160587 -0.03912496 -0.4001309 0.9156225 -0.140694 -0.6799703 0.7196149 -0.1336444 -0.6760963 0.7245916 -0.09668552 -0.3373617 0.9363969 -0.08350014 -0.3933907 0.9155718 -0.09793525 -0.2173253 0.9711738 -0.09790503 -0.09180122 0.9909527 -0.1012926 0.02908462 0.9944314 -0.2833349 0.9590172 0.002746641 -0.3343346 0.9424545 2.7467e-4 -0.4930132 0.8700214 -8.54548e-4 0.1027591 -0.1429839 0.984376 -0.2019112 0.9794039 6.10373e-5 -0.5438585 0.8391659 0.004303216 -0.6860139 0.7275812 -0.003265559 -0.75919 0.6508477 0.005279779 -0.8454402 0.5340538 -0.004181087 -0.9117668 0.4106689 0.005707085 -0.953213 0.3022643 -0.004608392 -0.9903889 0.1381924 0.005737662 -0.9990206 0.04397839 -0.00488305 -0.9893711 -0.1453018 0.005676567 -0.9748126 -0.222973 -0.004852533 -0.9088566 -0.417073 0.005462884 -0.8795747 -0.4757394 -0.004516899 -0.7553188 -0.6553381 0.005066156 -0.7200878 -0.6938722 -0.003875851 -0.5399482 -0.8416931 0.002960324 -0.514397 -0.8575522 3.35709e-4 -0.3427637 -0.9394186 0.002411007 0.04049849 0.4154836 0.9086987 -0.2820572 -0.9593974 7.32458e-4 -0.2047827 -0.9788067 0.001312315 -0.09817928 0.533867 0.8398494 -0.1037943 0.4301011 0.8967942 -0.002533078 0.4215905 0.9067828 -0.09796571 0.6350073 0.7662692 -0.0977236 0.7261215 0.6805863 -0.09738683 0.8057686 0.5841685 -0.09302318 0.8707495 0.4828477 -0.07410109 0.9278811 0.3654392 -0.07455825 0.9661139 0.2471134 -0.1833879 -0.665342 0.7236636 -0.1695649 -0.3604018 0.9172559 -0.2315812 -0.6532373 0.7208684 -0.2378356 -0.6486538 0.7229679 -0.2286464 -0.2964286 0.9272815 -0.2154961 -0.3534429 0.9102964 -0.2298409 -0.1765236 0.9570854 -0.2297771 -0.05157697 0.9718757 -0.1449967 0.09601336 0.9847627 -0.1613836 0.1098983 0.9807537 -0.2300209 0.07385575 0.9703792 -0.08948284 0.08554583 0.9923078 -0.04022443 0.05554509 0.9976456 0.02160763 -0.01660245 0.9996287 0.755378 0.6552753 0.004303157 0.7945647 0.6071774 0.001678526 0.67912 0.7340246 -0.001983761 -0.1731979 0.1395959 0.9749439 0.9087347 0.4173477 0.004699885 0.8792455 0.4763673 0.00125122 0.5408375 0.8411197 0.003570735 0.4898934 0.8717796 -0.002197325 0.2813529 0.9596031 0.001617491 0.2500109 0.968243 3.05189e-4 0.1299182 0.9915226 0.002075254 -0.1421902 0.989838 0.001678526 -0.1308942 0.9913964 0 0.1426774 0.9897693 0 -0.2868812 -0.635625 0.7167148 -0.2981424 -0.3211234 0.8988831 -0.2931718 -0.6340153 0.7155942 -0.3394649 -0.6213095 0.7062139 -0.3565828 -0.2581288 0.8978965 -0.3439203 -0.3151408 0.8845366 -0.3579871 -0.1396241 0.9232282 -0.3582061 -0.01651096 0.9334966 -0.2350862 0.1985247 0.9514843 -0.358385 0.1068166 0.9274429 -0.1754857 0.3466377 0.9214375 -0.2287435 0.3200579 0.9193691 -0.3585671 0.2282817 0.9051614 -0.2998824 0.4086531 0.862017 -0.2235519 0.3127896 0.9231399 -0.1851012 0.2429662 0.9522106 -0.1747222 0.1863805 0.9668167 -0.2288054 0.4360334 0.8703579 -0.3587526 0.3457209 0.8670489 -0.2289537 0.5447036 0.8067704 -0.3589093 0.457121 0.8137719 -0.2291076 0.6442604 0.7296837 -0.3590915 0.5604891 0.7462608 -0.2292318 0.733017 0.6404209 -0.359211 0.654057 0.6657153 -0.229354 0.8094993 0.5404699 -0.3593598 0.7361459 0.5735414 -0.2453156 0.8623892 0.4428377 -0.3594834 0.8053661 0.4713355 -0.2922803 0.8889874 0.3525248 -0.2488256 0.9184849 0.3073621 -0.3596077 0.8604889 0.3608896 -0.4256259 0.8380674 0.3413003 -0.3010129 0.8761817 0.3764263 -0.249155 0.8840975 0.3953398 -0.2244089 0.8841766 0.4097225 -0.2099431 0.8810043 0.4239758 -0.1958101 0.873333 0.4460358 -0.1100518 0.7882472 0.6054378 -0.1399301 0.8702524 0.4723138 -0.7002316 0.6885428 0.1886389 -0.3081191 0.9280805 0.2091156 -0.3596747 0.9005755 0.2441271 0.9799497 0.1992454 0 -0.2661253 0.961561 0.06766051 0.979949 0.1992487 -1.07902e-5 0.9799506 0.1992409 0 0.931718 0.3631774 0.001953184 0.9442763 0.3291538 0 0.8469676 0.5316436 -0.001037597 0.8556352 0.5175744 0.002288937 0.6996824 0.7144536 -7.62979e-4 0.6324784 0.7745755 0.002014219 0.5253022 0.8509152 9.46106e-4 0.342238 0.9396133 -3.66226e-4 0.3371438 0.9414515 0.001800596 0.1517109 0.988425 -1.52596e-4 -0.002594113 0.9999943 0.002197384 -0.02868783 0.9995885 0 -0.1948658 0.9808299 -1.22077e-4 -0.3476117 0.9376361 0.002166807 -0.3562822 0.9343785 0 0.1092898 0.7388433 0.6649559 -0.5191916 0.8546579 2.74672e-4 -0.08707153 0.8902782 0.447016 -0.6513158 0.7588054 0.00149542 -0.6790428 0.7340987 -1.83113e-4 -0.1136848 0.9064874 0.4066405 -0.8134017 0.5816988 0.002044796 -0.1243646 0.9168192 0.3794419 -0.8732692 0.487235 0.001831114 -0.922508 0.385978 -5.18829e-4 -0.1092265 0.9347884 0.3379948 -0.9882551 0.1528069 0.001434326 -0.9873313 0.1586701 -7.93503e-4 -0.0606113 0.9419778 0.3301576 -0.9983872 -0.05670362 0.002807676 -0.9799547 -0.1992206 0 -0.1276299 0.9589943 0.2530624 -0.9799504 -0.1992418 0 -0.9997367 -0.02295017 0 -0.1475578 0.9792529 0.1388905 -0.211067 0.9770242 0.02957254 -0.2298067 0.9679349 0.1014446 -0.1397751 0.3681762 0.9191894 -0.03982782 0.4103335 0.9110655 -0.08731633 0.3811583 0.9203772 0.7592273 -0.6507924 0.006592154 0.7958863 -0.605445 0.001220762 0.8783657 -0.4779877 -0.001220703 0.6857643 -0.7278197 -0.002441525 0.9118304 -0.4105175 0.006378531 0.9640837 -0.265551 -0.005035698 0.9904085 -0.1380382 0.006042778 0.999983 -0.003204464 -0.004882991 0.9893492 0.1454557 0.005554497 0.9652296 0.2613661 -0.004425227 -0.3430949 -0.6208791 0.7048369 -0.3875938 -0.6086139 0.6923585 -0.4223515 -0.2832767 0.8610306 -0.3948559 -0.6072383 0.6894567 -0.4366092 -0.5951874 0.6746292 -0.4774127 -0.2284366 0.8484657 -0.4661165 -0.281202 0.8388449 -0.4784846 -0.1179273 0.8701412 -0.478358 -0.003082394 0.8781595 -0.4782394 0.1117926 0.8710854 -0.4781124 0.2248038 0.8490418 -0.4779868 0.3339377 0.8124127 -0.4778454 0.437407 0.7617999 -0.4777206 0.533327 0.6981014 -0.477595 0.6201197 0.6223782 -0.4774402 0.696262 0.5359758 -0.4712177 0.761975 0.4442387 -0.4671877 0.81709 0.3377863 -0.4716486 0.8519522 0.2274314 -0.4445497 -0.5941267 0.6703649 -0.4827521 -0.5828549 0.6536289 -0.5403178 -0.248551 0.8039149 -0.4940142 -0.5811769 0.6466711 -0.527857 -0.570492 0.6292106 -0.5887485 -0.2018854 0.7826989 -0.5803868 -0.2506861 0.7747952 -0.5911317 -0.1005616 0.8002817 -0.591106 0.005493521 0.8065752 -0.5910887 0.1115158 0.7988608 -0.5910769 0.2155613 0.7772782 -0.5910626 0.3159028 0.742193 -0.5910464 0.4107354 0.6942338 -0.5910353 0.4984399 0.63422 -0.591013 0.5775232 0.563179 -0.5919751 0.6440098 0.484579 -0.5073819 0.7416473 0.4387747 -0.5515252 0.6813874 0.4811769 -0.1331541 -0.2096346 0.968671 -0.5185256 0.6986209 0.4930113 -0.5274911 0.8111656 0.2525146 -0.4153985 0.7694533 0.4851658 -0.471646 0.7730551 0.4241884 -0.4971303 0.7753146 0.3895495 -0.5131848 0.7797723 0.3586037 -0.5223452 0.7927501 0.3141701 -0.5728202 0.8158164 0.07950323 -0.5975589 0.795382 0.1014446 -0.5420745 -0.5684122 0.6189208 -0.5708075 -0.559027 0.6013882 -0.6404457 -0.2360966 0.7308132 -0.5883604 -0.5561925 0.5869259 -0.6113647 -0.5480065 0.570896 -0.6926042 -0.09360253 0.7152189 -0.6948304 -0.1818333 0.695807 -0.6926951 4.57788e-4 0.7212305 -0.6927909 0.09451866 0.7149175 -0.6928973 0.1869577 0.6963765 -0.6929929 0.2761656 0.6659532 -0.6930906 0.3606452 0.6241478 -0.6931883 0.4389308 0.5716904 -0.6933001 0.5096673 0.5094842 -0.6933985 0.5717181 0.4385623 -0.6223876 0.6562339 0.4266039 -0.6384086 0.64613 0.4182708 -0.6961484 0.620094 0.3617469 -0.5995204 0.6692264 0.4389891 -0.01919662 0.9998139 0.001922667 0.04400801 0.9990313 0 -0.1275984 0.9918255 8.85041e-4 -0.6422241 0.6480534 0.4093595 0.2949346 0.9555161 0.001617491 0.1481686 0.9889604 0.001861631 -0.3113894 0.9502824 -2.13636e-4 -0.3673875 0.9300659 0.002014219 -0.4779878 0.8783659 0.00100708 -0.6157855 0.7879136 6.40903e-4 -0.6817006 0.7316295 0.001617491 -0.7391095 0.6735852 4.57785e-4 -0.8473089 0.5310978 0.001617491 -0.9006714 0.4344964 0.002014219 -0.9365935 0.3504176 -4.57783e-4 -0.9970037 0.07730531 0.002746701 -0.9889256 0.1484121 0 -0.9974685 -0.07111036 0 -0.9560896 -0.293071 0.001495361 -0.9520546 -0.3059271 -7.62987e-4 -0.8650876 -0.501608 0.003601193 -0.782182 -0.62305 -1.76526e-5 -0.7821798 -0.6230528 0 -0.8850586 -0.4654798 0 -0.6163682 0.7844075 0.06924831 -0.6994328 -0.2190648 0.6802974 -0.6327512 -0.5442765 0.5508076 -0.6503615 -0.537685 0.5365864 -0.7838239 -0.1677333 0.5979011 -0.7262775 -0.1803714 0.6633153 -0.6748707 -0.5328649 0.5104944 -0.6862866 -0.5280442 0.5001801 -0.782763 -0.09094792 0.6156384 -0.7827597 -0.009033679 0.6222586 -0.7827769 0.07300096 0.6180058 -0.782782 0.1537852 0.6029946 -0.7828008 0.2318584 0.577464 -0.7828119 0.3059223 0.5418645 -0.7828381 0.3746184 0.4968158 -0.7744046 0.4385973 0.4559935 -0.7685402 0.5068361 0.3904656 -0.7758944 0.546175 0.315723 -0.6575443 0.6811054 0.3220731 -0.7024101 0.6569052 0.2740361 -0.7802209 0.5778183 0.2395445 -0.6530282 0.6679828 0.3568658 -0.6456115 0.6583687 0.3869579 -0.6615558 0.7058079 0.2533364 -0.7057827 0.6840837 0.1841211 -0.782229 0.6014047 0.1625739 -0.6523523 0.7441242 0.1439295 0.7821695 0.6230658 0 0.7821699 0.6230652 0 0.6808794 0.7323954 7.01937e-4 0.6907777 0.7230673 0 0.5099421 0.8602086 -4.88304e-4 0.563878 0.8258573 0.001159727 0.2975623 0.954702 -9.15576e-4 -0.7911424 -0.1955653 0.5795241 -0.7141545 -0.5219737 0.4663978 -0.7199487 -0.5198341 0.4598332 -0.860619 -0.1569312 0.4844663 -0.8105592 -0.1465836 0.567016 -0.749004 -0.5120829 0.4204335 -0.8593845 -0.09366279 0.5026785 -0.8578106 -0.02661293 0.5132764 -0.8578435 0.04605394 0.5118434 -0.8590221 0.1126766 0.4993846 -0.8588783 0.1791492 0.4798268 -0.8587763 0.242352 0.4514077 -0.8586919 0.3011648 0.4146662 -0.8651295 0.3381839 0.3703818 -0.7896842 0.4357836 0.4318466 -0.3195718 -0.4506234 0.8335542 -0.1602259 -0.5729375 0.803785 -0.7971305 0.3960474 0.4557735 -0.8076868 0.4971248 0.3170319 -0.6963785 0.48647 0.5276399 -0.7706679 0.4679185 0.4325774 -0.7886503 0.4650843 0.4021534 -0.7982023 0.469143 0.3778597 -0.8010188 0.4852014 0.3506402 -0.8177061 0.5156556 0.2558441 -0.821708 0.5405315 0.1806146 -0.8216072 0.5294165 0.2113759 -0.8590198 0.4976131 0.1202756 -0.8679325 -0.171792 0.4660266 -0.7486687 -0.5139449 0.4187552 -0.7755643 -0.5043365 0.379664 -0.9224017 -0.1551883 0.3536829 -0.8726019 -0.03500539 0.4871762 -0.7800135 -0.5034778 0.3716036 -0.7934397 -0.499936 0.3471565 -0.5175781 -0.4382582 0.734876 -0.7617412 -0.5040023 0.4071022 -0.7676223 -0.5044846 0.3952865 -0.7731457 -0.5044232 0.3844518 -0.9193817 -0.120275 0.3745279 -0.9018464 -0.06711202 0.4268129 -0.9163424 -0.08234107 0.3918374 -0.8837105 -0.07397824 0.4621504 -0.8818886 -0.1476223 0.4477501 -0.916669 0.08307272 0.390918 -0.8623346 -0.073794 0.5009328 -0.8805445 -0.005188286 0.4739351 -0.8871846 0.033113 0.4602251 -0.8905867 0.06918746 0.4495203 -0.8912692 0.1169783 0.438127 -0.9030936 0.06756949 0.4240948 -0.9196547 0.1225331 0.3731233 -0.9197198 0.16819 0.354722 -0.9197558 0.2111926 0.3308277 -0.9197838 0.2508973 0.3017421 -0.8756768 0.3559411 0.3263378 -0.8894561 0.343648 0.3012871 -0.9198013 0.28661 0.267993 -0.8587437 0.371752 0.352647 -0.8471469 0.3703177 0.3810604 -0.8408795 0.3550971 0.4084455 -0.833352 0.3166041 0.4530852 0.4539869 0.8910084 0 -0.9215039 0.3127632 0.2302386 -0.8972421 0.355735 0.2615519 0.4539911 0.8910062 5.65593e-6 0.3454477 0.9384374 -0.001098692 0.3264638 0.9452099 0 0.1015974 0.9948253 -8.24011e-4 -0.03634786 0.999338 0.001525938 -0.139135 0.9902729 0.001068115 0.2340527 0.9722239 -1.52597e-4 -0.3460815 0.9382044 -5.18817e-4 -0.3737094 0.927544 0.001892149 -0.5349019 0.8449113 0.002197325 -0.6849486 0.7285914 2.74675e-4 -0.6921805 0.7217233 0.001281797 -0.805212 0.5929833 0.00213629 -0.8908579 0.4542796 0.001525938 -0.9107796 0.4128921 9.4609e-4 -0.9545495 0.2980507 0.001098632 -0.9922747 0.1240305 0.002746701 -0.9989303 0.04620635 0.001770079 -0.9969671 -0.07782363 -2.44153e-4 -0.9443805 -0.3288424 0.002838253 -0.9592366 -0.2826042 -2.13632e-4 -0.8759922 -0.4823252 3.6623e-4 -0.7533109 -0.657663 0.001525938 -0.737244 -0.6756264 -7.01934e-4 -0.5794886 -0.8149707 0.003967404 -0.4540067 -0.8909983 0 -0.4541832 -0.8909084 1.02562e-4 -0.452395 -0.8918175 -5.86336e-4 -0.4539973 -0.8910031 0 -0.6153384 -0.7882631 0 -0.8405455 0.5202519 0.1510674 -0.9197123 0.3803854 0.09714108 -0.8976382 -0.159281 0.4109444 -0.7910594 -0.4983491 0.3547865 -0.8129274 -0.4954105 0.3061333 -0.9346052 -0.1553708 0.3199582 -0.8146623 -0.4942055 0.3034574 -0.8262416 -0.4957511 0.2674993 -0.7998337 -0.4950625 0.3393808 -0.9637731 -0.1381919 0.2281327 -0.9678853 -0.1508257 0.2011213 -0.921043 0.1429831 0.3622645 -0.8346465 -0.4915466 0.2484895 -0.9638005 -0.1058716 0.244704 -0.9637882 -0.07159739 0.2568779 -0.9247837 -0.05276715 0.3768168 -0.9612902 -0.08261513 0.2628609 -0.9430144 -0.141182 0.3013166 -0.9341716 -0.07068318 0.3497535 -0.3874036 0.9219069 0.002533018 -0.5671361 0.8236185 0.003082394 -0.7262061 0.6874772 -9.15578e-5 -0.7118817 0.7022988 0.00100708 -0.8580375 0.5135713 0.004028439 -0.9403077 0.3403236 0.001068174 -0.9260387 0.3774287 1.83114e-4 -0.9869393 0.1610513 0.003662288 -0.9999948 -0.001709043 0.002746701 -0.9999944 -0.003051877 0.001403868 -0.9854298 -0.1700826 0 -0.9231789 -0.3843603 0.002838253 -0.9385982 -0.3450123 -3.05186e-5 -0.8533535 -0.5213328 3.05194e-5 -0.7076988 -0.7065086 0.002868711 -0.7270512 -0.6865832 -3.66227e-4 -0.9246661 0.05328625 0.3770323 -0.5638641 -0.8258673 7.93487e-4 -0.9619041 0.07733565 0.2622209 -0.9549551 0.06729549 0.2890196 -0.9433261 0.1382837 0.3016849 -0.9341319 0.07046884 0.3499027 -0.9638891 0.1027582 0.2456799 -0.9638741 0.1338858 0.2302641 -0.9638584 0.162759 0.2109184 -0.9638487 0.1888511 0.187966 -0.9638302 0.2117735 0.1618133 -0.9249165 0.332202 0.1848551 -0.9638121 0.2310878 0.1329091 -0.9021406 0.4123112 0.1270504 -0.9232698 0.3595173 0.135353 -0.9637895 0.2465018 0.1017197 -0.9029036 0.3707138 0.2175697 -0.9637564 0.2577626 0.0687896 -0.8844418 0.466453 -0.01358097 0.453998 0.8910027 1.41603e-5 0.453975 0.8910145 -1.0872e-5 -0.9500567 -0.03863704 0.3096764 -0.8366599 -0.4899896 0.2447659 -0.847597 -0.4855226 0.2141194 -0.9574235 -0.1687417 0.2342362 -0.8578867 -0.4839995 0.1725539 -0.8577056 -0.4828103 0.1767354 -0.9753176 -0.1409965 0.1699283 -0.8631764 -0.482418 0.1489951 -0.9791796 -0.09079474 0.181559 -0.8661325 -0.481378 0.1344977 0 1 0 -0.2644155 -0.9640607 0.02591049 -0.1957218 0.980654 0.003296077 -0.1346201 0.9908973 0 -0.35219 0.935928 -0.001098632 -0.9807662 -0.1128601 0.1592494 -0.8667746 -0.4821721 0.1273259 -0.8695433 -0.4798175 0.1169177 -0.9826585 -0.133369 0.1288217 -0.8719447 -0.4801342 0.09583151 -0.9845244 -0.144204 0.09958469 -0.874526 -0.4790894 0.07535171 -0.9858025 -0.1525047 0.07025527 -0.8768424 -0.4778365 0.05310308 -0.9865806 -0.1567444 0.04571712 -0.8774432 -0.4784417 0.03445559 -0.9879521 -1.52594e-4 0.1547604 -0.9878539 -0.0177623 0.1543674 -0.9878225 0.01791489 0.1545504 -0.9784133 0.136329 0.1553119 -0.9712004 0.05630719 0.2315157 0 1 -2.9223e-6 -0.3835398 -0.9235231 0.001525938 -0.3517922 -0.936078 -6.40898e-4 -0.1486583 -0.9888787 0.004455745 -0.1966971 -0.9804644 0 -0.1319934 -0.9912477 0.002410948 0.1414849 -0.989937 0.002624571 0.1285145 -0.9917076 0 0.258652 -0.96597 -0.001098692 -0.1426774 -0.9897693 0 0.2832134 -0.9590497 0.003753781 0.4993247 -0.8664097 -0.003021359 0.5439339 -0.8391103 0.005462825 0.2610598 -0.9452356 0.1959016 0.2527612 -0.9498535 0.1840927 0.9837459 -0.0877723 0.1566534 0.9819105 -0.08536094 0.1690129 0.9766315 -0.08764994 0.1962357 0.2690249 -0.9370552 0.2226055 0.2703105 -0.9133547 0.3044922 0.2688408 -0.9058309 0.3274065 -0.5000086 -0.8660205 -6.55002e-6 0.2685093 -0.8586315 0.4366404 0.2773255 -0.8870633 0.3690654 -0.5000159 -0.8660162 0 0.2653617 -0.8790659 0.396013 -0.3825297 -0.9239432 -3.05194e-5 -0.3820633 -0.9241362 0 -0.1816214 -0.9833685 3.05195e-5 0.2620955 -0.8750047 0.4070293 -0.2588022 -0.9659304 0 0.01968479 -0.9998063 0 0.2591412 -0.869867 0.4197348 0.02755862 -0.9996195 0.00125122 0.177103 -0.9841837 0.004150569 0.2523332 -0.8568586 0.4495791 0.3581401 -0.9336668 0.001403868 0.9072033 -0.01873856 0.420275 0.909443 -0.008911609 0.4157332 0.3659309 -0.9306364 0.003235042 0.6027746 -0.7979111 -0.00100708 0.864378 -0.08795768 0.49509 0.8973189 -0.05496466 0.4379473 0.8901291 -0.07165956 0.4500392 0.8847388 -0.08026432 0.4591242 0.8806394 -0.08603435 0.4659103 0.8878693 -0.08661395 0.4518697 0.8810244 -0.0865826 0.46508 0.8764893 -0.08691948 0.4735099 0.8738045 -0.08704167 0.4784241 0.2686303 0.919911 0.2856601 0.2647207 0.9173973 0.2971622 0.2607231 0.945354 0.1957788 0.2795535 0.9328728 0.2271525 0.2698483 0.8646315 0.4237858 0.32558 0.8390368 0.4359073 0.294268 0.8692841 0.3971795 0.270707 0.8944622 0.3558865 0.2594105 0.8527281 0.4533885 0.2589246 0.8573141 0.444939 1 -1.11851e-5 0 1 -2.4651e-6 0 1 2.88769e-6 0 1 2.8451e-6 0 1 2.79798e-6 0 1 1.28393e-6 0 1 -2.7476e-6 0 1 1.62998e-7 0 1 -1.26269e-6 0 1 1.37625e-6 0 1 1.25322e-6 0 1 -2.73983e-6 0 1 -2.49834e-6 0 1 2.75795e-6 0 1 2.49389e-6 0 1 -2.77139e-6 0 1 1.73608e-6 0 1 -1.46442e-6 0 1 -5.67748e-6 0 -0.9659261 0.2588183 0 -0.965924 0.2588257 0 0.9659257 -0.2588197 1.47075e-6 0.965927 -0.258815 0 0.9967777 -0.08014261 0.003357052 0.9925621 -0.1217394 0 0.9940187 0.1091986 -0.001648008 0.9944634 0.1050161 0.003784358 0.9358462 0.3524073 -0.001037657 0.890544 0.4548855 0.0032655 0.8261151 0.5635002 0.001159667 0.6839725 0.7295076 -5.18832e-4 0.6688916 0.7433588 0.001342833 0.5171516 0.8558866 0.003540217 0.3545383 0.9350386 0.002349913 0.3599702 0.9329623 0.001709043 0.1813744 0.9834141 -2.44152e-4 0.008972585 0.9999569 0.002441465 -0.00665307 0.999978 -1.52594e-4 -0.2095436 0.977799 7.93495e-4 -0.3219162 0.9467656 0.00225836 -0.42278 0.9062318 -0.001068115 -0.6087654 0.7933451 0.002899289 -0.6242066 0.7812577 -0.001617491 -0.8314668 0.5555726 0.001464903 -0.7993804 0.6008247 -8.85047e-4 -0.9166021 0.3997964 0.001861631 -0.9104752 0.4135638 0 0.4999901 0.8660311 0 0.9712988 -0.08722335 0.2212935 0.9684058 -0.08755964 0.2335026 0.9666157 -0.08707231 0.2409825 0.4998713 0.8660997 -6.84799e-5 0.9453617 -0.08624714 0.3144085 0.6134618 0.7897088 0.004974544 0.6528751 0.7574657 0 0.7819623 0.6233236 0.001648008 0.8829782 0.4694141 4.27267e-4 0.9559612 0.2934752 0.003265559 0.752329 0.6587876 -4.27269e-4 0.9966446 0.08185076 -3.05186e-4 0.9970922 -0.07617586 0.00213629 0.9618607 0.2735399 -1.83113e-4 0.9949901 -0.09995067 0.002197384 0.9014356 -0.43291 0.001709043 0.8877065 -0.4604098 -3.35709e-4 0.6815554 -0.7317595 0.003234982 0.9617351 -0.2739662 0.002838194 0.770557 -0.6373698 0.001281797 0.9470419 -0.08743757 0.3089765 0.9471654 -0.08749872 0.3085803 0.9688355 -0.08723163 0.231837 0.9653716 -0.08749747 0.2457681 0.9689716 -0.08722835 0.2312693 0.9246181 -0.08719414 0.3707811 0.920152 -0.08942103 0.3812145 0.8963751 -0.08966493 0.4341335 0.8870891 -0.09057968 0.4526239 0.9062415 -0.09106969 0.4128352 0.8728051 -0.08954191 0.4797849 0.8793503 -0.08795636 0.4679817 0.8866994 -0.08713179 0.4540619 0 -1 -5.32651e-7 0 -1 1.34993e-6 0 -1 -2.1061e-6 0 -1 1.96617e-6 0 -1 -4.48956e-7 0 -1 -1.79267e-6 0.3837449 -0.08548349 0.9194741 0.308125 -0.08603447 0.9474477 0 -1 -1.80369e-6 0.185004 -0.08554375 0.9790076 0.2353917 -0.08600205 0.968088 0 -1 -3.11534e-6 0.1567767 -0.08643013 0.9838451 0 -1 -3.2954e-6 0.03927761 -0.08526945 0.9955835 0.08118128 -0.0864306 0.9929448 0 -1 3.13845e-6 0.001525938 -0.08676517 0.9962277 0 -1 -3.57465e-6 -0.1066344 -0.08502674 0.9906562 -0.07513761 -0.08676528 0.9933912 0 -1 1.74101e-6 -0.1539385 -0.08701002 0.984242 -0.2320974 -0.08594161 0.9688885 -0.2298714 -0.0870105 0.9693237 0 -1 1.74374e-6 -0.3057408 -0.08758991 0.9480774 -0.3181331 -0.08691895 0.9440532 -0.3794138 -0.0873152 0.9210978 0 -1 -1.74613e-6 -0.4518325 -0.08725357 0.8878256 -0.4505913 -0.08725547 0.888456 0 -1 3.29909e-6 -0.3862257 -0.0871945 0.918274 -0.5151708 -0.08704185 0.8526564 -0.5192281 -0.08743834 0.850151 0 -1 -1.74744e-6 -0.5758686 -0.08688843 0.8129119 -0.5846946 -0.08759123 0.8065111 -0.633553 -0.08679729 0.7688153 -0.646527 -0.0877133 0.7578319 0 -1 1.74737e-6 -0.6878334 -0.08670395 0.7206717 -0.704452 -0.08780467 0.7042995 -0.7384666 -0.08664321 0.6687003 -0.7578218 -0.08786469 0.6465184 -0.7851963 -0.08661329 0.6131599 -0.8061583 -0.08786404 0.58514 0 -1 -1.49157e-6 -0.8278441 -0.08658409 0.5542359 -0.8496909 -0.08810949 0.5198676 0 -1 -1.06197e-6 -0.8828518 -0.0928691 0.4603782 -0.8870289 -0.08948111 0.45296 0 -1 -1.16548e-6 -0.8660898 -0.08609318 0.492419 -0.8645433 -0.08810842 0.4947746 -0.8765332 -0.09570723 0.4717305 -0.8714262 -0.09204709 0.4818129 0 -1 6.76612e-7 -0.9071751 -0.08923733 0.4111815 -0.9208555 -0.0895738 0.3794756 -0.8963526 -0.08838397 0.4344426 0 -1 1.72795e-6 -0.9468868 -0.08728474 0.3094946 -0.9474069 -0.08768159 0.3077859 -0.9246701 -0.08743745 0.3705944 -0.965447 -0.08725458 0.2455582 -0.9687395 -0.08792573 0.2319762 -0.9717353 -0.08682745 0.2195255 -0.9839301 -0.08749771 0.1556465 -0.9728074 -0.08725506 0.2145517 -0.9689489 -0.08722275 0.2313664 -0.9687546 -0.08703929 0.2322472 -0.9663448 -0.0875582 0.2418913 -0.9688315 -0.08723658 0.2318521 -0.9721481 -0.08728396 0.217508 -0.985306 -0.08694863 0.14701 -0.8559495 -0.4843747 0.1809195 -0.853114 -0.482362 0.1988046 -0.8596729 -0.4850767 0.1601968 -0.954176 -0.08707064 0.2862986 -0.952955 -0.08649075 0.2905101 -0.8404035 -0.48272 0.2463804 -0.9358717 -0.08740699 0.3413269 -0.9288498 -0.08636909 0.3602478 -0.8296678 -0.488889 0.2695161 -0.8151836 -0.4899038 0.3089824 -0.9014673 -0.08542239 0.4243348 -0.9002048 -0.0862177 0.4268465 -0.799394 -0.5007314 0.3320203 -0.7790634 -0.508175 0.3671764 -0.9093673 -0.08325511 0.4075779 -0.920802 -0.08643102 0.3803333 -0.8800171 -0.08664357 0.4669721 -0.7695784 -0.5109261 0.383019 -0.8893347 -0.08633929 0.4490316 -0.8940154 -0.08688676 0.4395306 -0.7869369 -0.5032612 0.3570133 -0.8731159 -0.08694839 0.4796965 -0.7630955 -0.5147934 0.3907339 -0.7604821 -0.5119017 0.3995293 -0.7580908 -0.5109179 0.4052917 -0.7437899 -0.5081796 0.4342005 0.8974561 -0.08719414 0.4324001 0.8897982 -0.087408 0.4479053 0.8929086 -0.08722466 0.4417085 0.8980182 -0.08719241 0.4312319 0.9089749 -0.08728402 0.4076104 0.9054104 -0.08719307 0.4154871 0.9199129 -0.08661377 0.3824374 0.9257157 -0.08731609 0.3680034 0.9479997 -0.0871334 0.3061115 0.08736592 -0.9961764 -6.85883e-5 0.08715736 -0.9961946 0 -0.9534345 -0.08642894 0.288951 -0.9478502 -0.08856528 0.3061637 -0.08716464 0.996194 4.46253e-6 -0.08717268 0.9961933 0 -0.2732035 0.9619498 0.003540158 -0.2288964 0.9734508 0 -0.4488481 0.8936066 -0.001617491 -0.453267 0.8913661 0.003936886 -0.6597632 0.7514733 -7.3246e-4 -0.7533785 0.6575772 0.00363183 -0.8183391 0.5747356 6.40901e-4 -0.9237804 0.3829222 -6.40899e-4 -0.943946 0.3300911 0.002441465 -0.9831513 0.1827805 0.002197384 -0.9999987 -0.001190245 0.001129209 -0.999033 -0.04394704 0.001312255 -0.9831354 -0.1828691 0.001953184 -0.875802 -0.08639913 0.4748747 -0.9336729 -0.3581119 0.003296017 -0.8807224 -0.08685755 0.4656006 -0.9117566 -0.4107254 0.002197325 -0.8400929 -0.5424424 -3.96745e-4 -0.8839316 -0.08707165 0.4594381 -0.8878613 -0.08719301 0.4517741 -0.6926605 -0.7212568 0.003173947 -0.7000216 -0.7141216 -4.88309e-4 -0.8936867 -0.08716213 0.4401444 -0.8972592 -0.08728438 0.4327902 -0.5190971 -0.8547142 0.001464903 -0.8896886 -0.08716213 0.4481709 -0.8889956 -0.08715337 0.4495455 -0.9002528 -0.08710151 0.4265657 -0.9089 -0.08731615 0.4077705 -0.3746219 -0.9271702 0.003723323 -0.2845857 -0.9586494 -0.001556396 -0.9201842 -0.08710175 0.381673 -0.92544 -0.08804845 0.3685218 -0.08298218 -0.996549 0.002014219 -0.0480681 -0.9988407 -0.002594113 -0.9091377 -0.08713245 0.4072793 -0.9349796 -0.08667391 0.3439489 0.04333657 -0.9990605 -3.05187e-4 0.06491464 -0.9978908 0 0.08723795 0.9961876 3.50721e-5 0.08716458 0.996194 0 -0.08715736 -0.9961946 -8.78254e-6 -0.08718186 -0.9961925 0 -0.05923688 -0.998208 -0.008484184 0.05380499 -0.9985516 0 0.281482 -0.9595657 -0.00125128 0.3747483 -0.9271198 0.003570735 0.5154414 -0.8569225 0.002014219 0.08118128 -0.996699 -8.24021e-4 -0.0444054 -0.9989845 -0.007629752 0.6949179 -0.7190889 -4.27266e-4 0.6926299 -0.7212873 0.002960324 0.8356992 -0.5491877 -2.7467e-4 0.9114218 -0.4114582 0.00350964 0.9295985 -0.3685739 1.22075e-4 0.9819062 -0.189368 -1.22074e-4 0.99905 -0.04345947 0.003265559 0.9999582 -0.00915569 1.52595e-4 0.9842798 0.1766155 4.5779e-4 0.9436016 0.3310754 0.002319455 0.9267089 0.3757802 -3.0519e-5 0.8242284 0.5662508 0.002746701 0.7537202 0.6571896 0.002807676 0.6634596 0.7482118 -8.54541e-4 0.4521376 0.8919456 0.002197325 0.4517123 0.892163 -0.001098632 0.2418655 0.9703002 0.004333734 0.2754345 0.9613198 0 0.08717745 -0.9961928 0 0.08715879 -0.9961945 0 -0.08716565 0.9961939 -2.96169e-6 -0.08714985 0.9961952 0 -0.2729975 0.9620071 0.003845453 -0.2271813 0.9738525 0 -0.4468955 0.8945846 -0.001739561 -0.4533031 0.8913466 0.004181087 -0.6571097 0.7537947 -5.79866e-4 -0.7533629 0.6575941 0.003814876 -0.8153839 0.5789204 4.88309e-4 -0.9217776 0.3877185 -7.32466e-4 -0.9439455 0.330091 0.002655088 -0.9823536 0.1870219 0.002075254 -0.9999954 0.002899289 9.76618e-4 -0.9990315 -0.04397749 0.001434326 -0.9839872 -0.1782298 0.001861631 -0.9352068 -0.3540864 0.003326594 -0.9117678 -0.4106999 0.002258419 -0.8413261 -0.5405277 -4.2727e-4 -0.6926603 -0.7212566 0.0032655 -0.7004838 -0.7136682 -5.49351e-4 -0.5200092 -0.8541592 0.001648008 -0.3747109 -0.9271333 0.003936886 -0.2852609 -0.9584487 -0.001586973 -0.08285838 -0.9965592 0.00213629 -0.04599165 -0.9989379 -0.002807676 0.04339748 -0.9990579 -3.35705e-4 0.06503617 -0.997883 0 -0.9964963 0.02569669 -0.0795927 -0.9965943 0 -0.08246201 -0.9838114 0.01400822 -0.1786584 -0.9838114 -0.01400822 0.1786584 -0.9455084 -0.3224024 0.04550379 -0.9964963 -0.02569669 0.0795927 -0.9965943 0 0.08246201 -0.9822971 8.85062e-4 -0.187328 -0.9469853 3.05194e-5 -0.3212773 -0.9455084 0.3224024 -0.04550379 -0.9442763 -9.15588e-5 -0.3291538 -0.8810096 1.22074e-4 -0.4730986 -0.8774181 -6.10378e-5 -0.4797264 -0.8023449 -5.18823e-4 -0.5968604 -0.7987114 -0.01367247 -0.6015591 -0.7265132 -0.1573578 -0.6688926 -0.6771942 -0.02545315 -0.7353641 -0.6768198 0 -0.7361487 -0.6063224 -0.1578446 -0.7793961 -0.5343004 -0.01455765 -0.8451694 -0.5266065 -0.001190185 -0.8501085 -0.4079839 4.27272e-4 -0.912989 -0.3946154 0 -0.9188465 -0.2544662 8.54528e-4 -0.9670814 -0.2358227 -5.79867e-4 -0.971796 -0.09317421 0.001098632 -0.9956493 -0.07168942 -0.00100708 -0.9974265 0.07168942 0.00100708 -0.9974265 0.09317421 -0.001098632 -0.9956493 0.2358227 5.79867e-4 -0.971796 0.2544662 -8.54528e-4 -0.9670814 0.3946154 0 -0.9188465 0.4079839 -4.27272e-4 -0.912989 0.5266065 0.001190185 -0.8501085 0.5343222 0.01455742 -0.8451555 0.6063561 0.1578454 -0.7793697 0.6771942 0.02545315 -0.7353641 0.7265424 0.1573575 -0.6688609 0.7987114 0.01367247 -0.6015591 0.6768198 0 -0.7361487 0.8023449 5.18823e-4 -0.5968604 0.877431 6.10387e-5 -0.479703 0.8810223 -1.22076e-4 -0.4730749 0.9442763 9.15588e-5 -0.3291538 0.9469853 -3.05194e-5 -0.3212773 0.9822971 -8.85062e-4 -0.187328 0.9838114 -0.01400822 -0.1786584 0.9455084 -0.3224024 -0.04550379 0.9964963 -0.02569669 -0.0795927 0.9964963 0.02569669 0.0795927 0.9965943 0 0.08246201 0.9838114 0.01400822 0.1786584 0.9965943 0 -0.08246201 0.9822971 8.85062e-4 0.187328 0.9469853 3.05194e-5 0.3212773 0.9455084 0.3224024 0.04550379 0.9442763 -9.15588e-5 0.3291538 0.8810096 1.22074e-4 0.4730986 0.8774181 -6.10378e-5 0.4797264 0.8023449 -5.18823e-4 0.5968604 0.7987114 -0.01367247 0.6015591 0.7265132 -0.1573578 0.6688926 0.6771942 -0.02545315 0.7353641 0.6768198 0 0.7361487 0.6063224 -0.1578446 0.7793961 0.5343004 -0.01455765 0.8451694 0.5266065 -0.001190185 0.8501085 0.4079839 4.27272e-4 0.912989 0.3946154 0 0.9188465 0.2544662 8.54528e-4 0.9670814 0.2358227 -5.79867e-4 0.971796 0.09317421 0.001098632 0.9956493 0.07168942 -0.00100708 0.9974265 -0.07168942 0.00100708 0.9974265 -0.09317421 -0.001098632 0.9956493 -0.2358227 5.79867e-4 0.971796 -0.2544662 -8.54528e-4 0.9670814 -0.3946154 0 0.9188465 -0.4079839 -4.27272e-4 0.912989 -0.5266065 0.001190185 0.8501085 -0.5343222 0.01455742 0.8451555 -0.6063561 0.1578454 0.7793697 -0.6771942 0.02545315 0.7353641 -0.7265424 0.1573575 0.6688609 -0.7987114 0.01367247 0.6015591 -0.6768198 0 0.7361487 -0.8023449 5.18823e-4 0.5968604 -0.877431 6.10387e-5 0.479703 -0.8810223 -1.22076e-4 0.4730749 -0.9442763 9.15588e-5 0.3291538 -0.9469853 -3.05194e-5 0.3212773 -0.9822971 -8.85062e-4 0.187328 0 1 2.03074e-6 0 1 1.4202e-6 0 1 7.36266e-7 0 1 1.58135e-6 0 1 3.43753e-6 0 1 3.43501e-6 0 1 -1.65517e-6 0 1 1.65904e-6 0 1 8.31121e-7 0 1 -8.3057e-7 0 1 -1.76531e-6 0 1 1.91521e-6 0 1 1.44231e-6 0 1 2.08891e-6 0 1 -2.03074e-6 0 1 -1.4202e-6 0 1 -7.36266e-7 0 1 -1.58135e-6 0 1 -3.43753e-6 0 1 -3.43501e-6 0 1 1.65517e-6 0 1 -1.65904e-6 0 1 -8.31121e-7 0 1 8.3057e-7 0 1 1.76531e-6 0 1 -1.91521e-6 0 1 -1.44231e-6 0 1 -2.08891e-6 -0.9818162 0.1743836 -0.07501488 -0.9818822 0.1731027 -0.07709056 -0.9726589 0.1749076 -0.152781 -0.9743276 0.1710605 0.1463704 -0.9842034 0.1621468 0.07107847 -0.9857797 0.1600698 0.05114907 -0.9821522 0.1731629 0.07342791 -0.9412464 0.1720069 -0.2906355 -0.9362847 0.176734 -0.3035395 0 1 -5.46199e-7 -0.9738705 0.1737463 -0.1462484 0 1 8.35414e-7 -0.8877468 0.1709999 -0.427393 -0.8771243 0.1778969 -0.4461004 0 1 0 -0.8149754 0.1694712 -0.5541613 -0.8057629 0.1737142 -0.5661886 -0.7515044 0.171121 -0.637149 -0.7227563 0.1668486 -0.67066 -0.6941902 0.1702057 -0.6993784 -0.6423974 0.1704799 -0.7471696 -0.614812 0.1676732 -0.7706438 -0.5748286 0.1685268 -0.8007315 -0.5174566 0.1697489 -0.8387038 -0.4948107 0.167002 -0.8528029 -0.4302601 0.1773167 -0.8851187 -0.3616492 0.1676099 -0.9171242 -0.3018096 0.1812567 -0.9359791 -0.2212352 0.1673684 -0.9607512 -0.1515277 0.1813755 -0.9716698 -0.07580953 0.1672754 -0.9829913 0.002166867 0.181315 -0.9834228 0.07141393 0.167304 -0.9833156 0.1556783 0.1811313 -0.9710591 0.2172685 0.1674606 -0.9616399 0.3052483 0.180854 -0.9349414 0.3584513 0.1677045 -0.9183616 0.4473485 0.1804897 -0.8759582 0.4918193 0.1680395 -0.8543282 0.5786451 0.1800636 -0.795454 0.6142884 0.1684959 -0.770882 0.6959559 0.1795129 -0.6952846 0.7228842 0.1690778 -0.6699635 0.7960541 0.1789016 -0.5781799 0.8148741 0.1698112 -0.554206 0.8765697 0.1781095 -0.4471049 0.8882365 0.1706644 -0.4265086 0.9358196 0.1771352 -0.3047373 0.941661 0.1716994 -0.2894718 0.9692159 0.1752694 -0.1729195 0 1 -4.2097e-7 0.9743276 0.1710605 -0.1463704 0.9842034 0.1621468 -0.07107847 0 1 -1.37394e-7 0 1 -6.64364e-7 0.9857797 0.1600698 -0.05114907 0.9818162 0.1743836 0.07501488 0.9818822 0.1731027 0.07709056 0.9726589 0.1749076 0.152781 0.9821522 0.1731629 -0.07342791 0.9412464 0.1720069 0.2906355 0.9362847 0.176734 0.3035395 0.9738705 0.1737463 0.1462484 0.8877468 0.1709999 0.427393 0.8771243 0.1778969 0.4461004 0.8149754 0.1694712 0.5541613 0.8057629 0.1737142 0.5661886 0.7515044 0.171121 0.637149 0.7227563 0.1668486 0.67066 0.6941902 0.1702057 0.6993784 0.6423974 0.1704799 0.7471696 0.614812 0.1676732 0.7706438 0.5748286 0.1685268 0.8007315 0.5174566 0.1697489 0.8387038 0.4948107 0.167002 0.8528029 0.4302601 0.1773167 0.8851187 0.3616492 0.1676099 0.9171242 0.3018096 0.1812567 0.9359791 0.2212352 0.1673684 0.9607512 0.1515277 0.1813755 0.9716698 0.07580953 0.1672754 0.9829913 -0.002166867 0.181315 0.9834228 -0.07141393 0.167304 0.9833156 -0.1556783 0.1811313 0.9710591 -0.2172685 0.1674606 0.9616399 -0.3052483 0.180854 0.9349414 -0.3584513 0.1677045 0.9183616 -0.4473485 0.1804897 0.8759582 -0.4918193 0.1680395 0.8543282 -0.5786451 0.1800636 0.795454 -0.6142884 0.1684959 0.770882 -0.6959559 0.1795129 0.6952846 -0.7228842 0.1690778 0.6699635 -0.7960541 0.1789016 0.5781799 -0.8148741 0.1698112 0.554206 -0.8765697 0.1781095 0.4471049 -0.8882365 0.1706644 0.4265086 -0.9358196 0.1771352 0.3047373 -0.941661 0.1716994 0.2894718 -0.9692159 0.1752694 0.1729195 0 -1 -1.43082e-6 0 -1 -4.40491e-7 0 -1 3.59572e-7 0 -1 0 0 -1 -1.3622e-7 0 -1 -1.0339e-6 0 -1 8.6272e-7 0 -1 -2.51831e-7 0 -1 2.97874e-7 0 -1 1.69293e-6 0 -1 -1.21032e-6 0 -1 7.24116e-7 0 -1 1.4367e-6 0 -1 -2.73011e-7 0 -1 3.69314e-7 0 -1 -3.75738e-7 0 -1 1.3622e-7 0 -1 4.40491e-7 0 -1 0 0 -1 1.43082e-6 0 -1 -3.59572e-7 0 -1 1.0339e-6 0 -1 -8.6272e-7 0 -1 2.51831e-7 0 -1 -2.97874e-7 0 -1 -1.69293e-6 0 -1 1.21032e-6 0 -1 -7.24116e-7 0 -1 -1.4367e-6 0 -1 2.73011e-7 0 -1 -3.69314e-7 0 -1 3.75738e-7 -0.998205 0.01413011 -0.0581991 -0.9957408 0 -0.09219765 -0.9829488 0.00125122 -0.1838756 -0.9829488 -0.00125122 0.1838756 -0.9961537 -0.01059019 0.08698034 -0.998205 -0.01413011 0.0581991 -0.9957408 0 0.09219765 -0.9816856 0.006988883 -0.1903797 -0.9323842 0.00137335 -0.3614664 -0.9961537 0.01059019 -0.08698034 -0.9233242 -1.22076e-4 -0.3840215 -0.8501448 2.44154e-4 -0.526549 -0.9629915 0.01046794 -0.2693288 -0.849386 -1.52597e-4 -0.5277723 -0.7542777 1.52595e-4 -0.6565557 -0.7403103 -0.004272699 -0.6722519 -0.6734725 -0.001190245 -0.7392113 -0.5997555 -0.004181027 -0.8001725 -0.5833725 9.15573e-5 -0.8122047 -0.4455525 -9.15582e-5 -0.8952558 -0.4444525 2.74674e-4 -0.8958024 -0.27406 -2.44151e-4 -0.9617127 -0.2719871 3.6623e-4 -0.9623008 -0.09335863 -3.66232e-4 -0.9956325 -0.09067332 3.96753e-4 -0.9958807 0.09067332 -3.96753e-4 -0.9958807 0.09335863 3.66232e-4 -0.9956325 0.2719871 -3.6623e-4 -0.9623008 0.27406 2.44151e-4 -0.9617127 0.4444525 -2.74674e-4 -0.8958024 0.4455525 9.15582e-5 -0.8952558 0.5833725 -9.15573e-5 -0.8122047 0.5997555 0.004181027 -0.8001725 0.6734725 0.001190245 -0.7392113 0.7403103 0.004272699 -0.6722519 0.7542777 -1.52595e-4 -0.6565557 0.849386 1.52597e-4 -0.5277723 0.8501448 -2.44154e-4 -0.526549 0.9233242 1.22076e-4 -0.3840215 0.9323842 -0.00137335 -0.3614664 0.9629915 -0.01046794 -0.2693288 0.9816856 -0.006988883 -0.1903797 0.9829488 -0.00125122 -0.1838756 0.9961537 -0.01059019 -0.08698034 0.998205 -0.01413011 -0.0581991 0.998205 0.01413011 0.0581991 0.9957408 0 0.09219765 0.9829488 0.00125122 0.1838756 0.9957408 0 -0.09219765 0.9816856 0.006988883 0.1903797 0.9323842 0.00137335 0.3614664 0.9961537 0.01059019 0.08698034 0.9233242 -1.22076e-4 0.3840215 0.8501448 2.44154e-4 0.526549 0.9629915 0.01046794 0.2693288 0.849386 -1.52597e-4 0.5277723 0.7542777 1.52595e-4 0.6565557 0.7403103 -0.004272699 0.6722519 0.6734725 -0.001190245 0.7392113 0.5997555 -0.004181027 0.8001725 0.5833725 9.15573e-5 0.8122047 0.4455525 -9.15582e-5 0.8952558 0.4444525 2.74674e-4 0.8958024 0.27406 -2.44151e-4 0.9617127 0.2719871 3.6623e-4 0.9623008 0.09335863 -3.66232e-4 0.9956325 0.09067332 3.96753e-4 0.9958807 -0.09067332 -3.96753e-4 0.9958807 -0.09335863 3.66232e-4 0.9956325 -0.2719871 -3.6623e-4 0.9623008 -0.27406 2.44151e-4 0.9617127 -0.4444525 -2.74674e-4 0.8958024 -0.4455525 9.15582e-5 0.8952558 -0.5833725 -9.15573e-5 0.8122047 -0.5997555 0.004181027 0.8001725 -0.6734725 0.001190245 0.7392113 -0.7403103 0.004272699 0.6722519 -0.7542777 -1.52595e-4 0.6565557 -0.849386 1.52597e-4 0.5277723 -0.8501448 -2.44154e-4 0.526549 -0.9233242 1.22076e-4 0.3840215 -0.9323842 -0.00137335 0.3614664 -0.9629915 -0.01046794 0.2693288 -0.9816856 -0.006988883 0.1903797 0 -1 7.90004e-7 0 -1 3.4694e-7 0 -1 -5.04964e-7 0 -1 5.14737e-7 0 -1 2.37884e-7 0 -1 0 0 -1 0 0 -1 -3.29064e-7 0 -1 0 0 -1 -1.67052e-7 0 -1 2.72506e-7 0 -1 0 0 -1 0 0 -1 -2.64488e-7 0 -1 0 0 -1 1.49889e-7 0 -1 -5.14737e-7 0 -1 5.04964e-7 0 -1 -3.4694e-7 0 -1 5.57173e-7 0.5002261 -0.8658947 -7.62366e-5 0.500003 -0.8660237 0 -0.4999883 0.8660321 1.16996e-5 -0.5000051 0.8660225 0 -0.6516939 0.7584784 0.00238043 -0.6205513 0.7841659 0 -0.789557 0.6136761 -0.001190185 -0.7824473 0.6227106 0.002807736 -0.9167075 0.3995584 -6.40905e-4 -0.9560477 0.293199 0.002716183 -0.9837111 0.1797555 6.40894e-4 -0.9995415 -0.03027522 -4.88311e-4 -0.9971393 -0.07556444 0.001861631 -0.9725455 -0.2327065 0.001739561 -0.9149681 -0.403526 5.18828e-4 -0.9012116 -0.4333775 0.001312315 -0.8342824 -0.5513356 0.00137335 -0.7344499 -0.6786604 0.001861631 -0.6810371 -0.7322484 8.54539e-4 -0.6017466 -0.7986868 6.40903e-4 -0.4437411 -0.8961495 0.003173887 -0.3672084 -0.9301372 0.001648008 -0.25062 -0.9680855 -1.83113e-4 -0.02771109 -0.9996144 0.001800596 -0.04232996 -0.9991036 -5.18825e-4 0.2590168 -0.9658728 3.66231e-4 0.1789956 -0.98385 -9.15578e-5 0.3854236 -0.9227398 1.83114e-4 0.3825558 -0.9239324 0 -0.008423268 0.04815936 -0.9988042 0 0.08246201 -0.9965943 -4.2727e-4 0.1644682 -0.9863823 4.2727e-4 -0.1644682 -0.9863823 0.005310297 -0.07995998 -0.9967839 0.008423268 -0.04815936 -0.9988042 0 -0.08246201 -0.9965943 9.15562e-5 0.1856759 -0.9826111 -1.22077e-4 0.3246021 -0.9458507 -0.005310297 0.07995998 -0.9967839 1.22075e-4 0.3258797 -0.9454113 -1.22074e-4 0.4758151 -0.8795453 9.15572e-5 0.4768602 -0.8789792 -6.10383e-5 0.5977172 -0.801707 0.002349972 0.6132943 -0.789851 3.35716e-4 0.6771689 -0.7358276 0.00463891 0.7357613 -0.6772251 0 0.735886 -0.6771055 3.35708e-4 0.7896775 -0.6135222 0.002410948 0.8379305 -0.5457718 -1.52593e-4 0.8489382 -0.5284921 1.83116e-4 0.9155188 -0.4022753 -3.05192e-4 0.9165219 -0.3999845 2.74672e-4 0.9691033 -0.2466553 -3.66227e-4 0.9699213 -0.2434187 3.66227e-4 0.9964436 -0.08426278 -3.66228e-4 0.9967514 -0.0805397 3.66228e-4 0.9967514 0.0805397 -3.66227e-4 0.9964436 0.08426278 3.66227e-4 0.9699213 0.2434187 -2.74672e-4 0.9691033 0.2466553 3.05192e-4 0.9165219 0.3999845 -1.83116e-4 0.9155188 0.4022753 1.52593e-4 0.8489382 0.5284921 -0.002410948 0.8379305 0.5457718 -3.35708e-4 0.7896775 0.6135222 -0.00463891 0.7357613 0.6772251 -3.35716e-4 0.6771689 0.7358276 -0.002349972 0.6132943 0.789851 0 0.735886 0.6771055 6.10383e-5 0.5977172 0.801707 -9.15572e-5 0.4768602 0.8789792 1.22074e-4 0.4758151 0.8795453 -1.22075e-4 0.3258797 0.9454113 1.22077e-4 0.3246021 0.9458507 -9.15562e-5 0.1856759 0.9826111 4.2727e-4 0.1644682 0.9863823 0.005310297 0.07995998 0.9967839 0.008423268 0.04815936 0.9988042 -0.008423268 -0.04815936 0.9988042 0 -0.08246201 0.9965943 -4.2727e-4 -0.1644682 0.9863823 0 0.08246201 0.9965943 9.15562e-5 -0.1856759 0.9826111 -1.22077e-4 -0.3246021 0.9458507 -0.005310297 -0.07995998 0.9967839 1.22075e-4 -0.3258797 0.9454113 -1.22074e-4 -0.4758151 0.8795453 9.15572e-5 -0.4768602 0.8789792 -6.10383e-5 -0.5977172 0.801707 0.002349972 -0.6132943 0.789851 3.35716e-4 -0.6771689 0.7358276 0.00463891 -0.7357613 0.6772251 0 -0.735886 0.6771055 3.35708e-4 -0.7896775 0.6135222 0.002410948 -0.8379305 0.5457718 -1.52593e-4 -0.8489382 0.5284921 1.83116e-4 -0.9155188 0.4022753 -3.05192e-4 -0.9165219 0.3999845 2.74672e-4 -0.9691033 0.2466553 -3.66227e-4 -0.9699213 0.2434187 3.66227e-4 -0.9964436 0.08426278 -3.66228e-4 -0.9967514 0.0805397 3.66228e-4 -0.9967514 -0.0805397 -3.66227e-4 -0.9964436 -0.08426278 3.66227e-4 -0.9699213 -0.2434187 -2.74672e-4 -0.9691033 -0.2466553 3.05192e-4 -0.9165219 -0.3999845 -1.83116e-4 -0.9155188 -0.4022753 1.52593e-4 -0.8489382 -0.5284921 -0.002410948 -0.8379305 -0.5457718 -3.35708e-4 -0.7896775 -0.6135222 -0.00463891 -0.7357613 -0.6772251 -3.35716e-4 -0.6771689 -0.7358276 -0.002349972 -0.6132943 -0.789851 0 -0.735886 -0.6771055 6.10383e-5 -0.5977172 -0.801707 -9.15572e-5 -0.4768602 -0.8789792 1.22074e-4 -0.4758151 -0.8795453 -1.22075e-4 -0.3258797 -0.9454113 1.22077e-4 -0.3246021 -0.9458507 -9.15562e-5 -0.1856759 -0.9826111 1 1.02955e-6 0 1 1.97421e-6 0 1 1.05891e-6 0 1 -1.97421e-6 0 1 -1.2949e-6 0 1 -2.58141e-6 0 1 2.25697e-6 0 1 7.45433e-7 0 1 2.66744e-6 0 1 2.03628e-6 0 1 -6.45357e-6 0 1 -4.41354e-6 0 1 -1.41469e-6 0 1 1.08918e-5 0 1 2.82806e-6 0 1 1.21768e-5 0 1 -6.14147e-6 0 1 -9.02887e-6 0 1 -1.05891e-6 0 1 1.2949e-6 0 1 2.58142e-6 0 1 -2.25697e-6 0 1 -7.45431e-7 0 1 -2.66744e-6 0 1 -2.03628e-6 0 1 6.45357e-6 0 1 4.41355e-6 0 1 1.41469e-6 0 1 -1.08918e-5 0 1 -2.82806e-6 0 1 -1.21768e-5 0 1 6.14148e-6 0 1 9.02896e-6 0 1.95298e-6 0 1 4.08918e-6 0 1 -4.08918e-6 0 1 6.16861e-6 0 1 -2.52272e-6 0 1 -0.8660254 0.5000002 0 -0.4999665 0.8660449 0 -0.5660923 0.824342 0 -0.9931306 0.1170112 0 -0.9969457 0.07809907 0 -0.8660259 0.499999 0 -1 0 0 -0.9969457 -0.07809907 0 -0.9931271 -0.1170413 0 -0.8660254 -0.5000002 0 -0.5661622 -0.8242939 0 -0.5000254 -0.8660107 0 -0.8660259 -0.499999 0 -0.4308053 -0.9024449 0 0.4308053 -0.9024449 0 0.5000254 -0.8660107 0 0.5661622 -0.8242939 0 0.8660254 -0.5000002 0 0.9931271 -0.1170413 0 0.9969457 -0.07809907 0 0.8660259 -0.499999 0 0.9969457 0.07809907 0 0.9931306 0.1170112 0 0.8660254 0.5000002 0 0.5660923 0.824342 0 0.4999665 0.8660449 0 0.8660259 0.499999 0 0.4308053 0.9024449 0 -0.4308053 0.9024449 0 -3.87765e-6 0 1 -9.70233e-6 0 1 3.99233e-6 0 1 1.1969e-5 0 1 -7.0375e-6 0 1 5.73566e-6 0 1 9.70252e-6 0 1 -9.09058e-6 0 1 4.94315e-4 0 1 4.36392e-6 0 1 -3.99208e-6 0 1 -3.98928e-6 0 1 -2.86816e-6 0 1 9.48992e-5 0 1 0.9858715 0.1595815 -0.05090492 0.9749147 0.2225787 0 0.8996222 0.4365808 -0.008789598 0.8996101 -0.4366055 0.008789479 0.9789318 -0.1965737 0.05523961 0.9858705 -0.1595863 0.05090647 0.9749147 -0.2225787 0 0.8747642 0.4845491 9.15568e-5 0.6235108 0.7818148 -2.13636e-4 0.978936 0.1965441 -0.05527037 0.6227988 0.7823821 1.52594e-4 0.2228173 0.9748602 -1.83112e-4 0.2219944 0.975048 1.52594e-4 -0.2219944 0.975048 -1.52594e-4 -0.2228173 0.9748602 1.83112e-4 -0.6227988 0.7823821 -1.52594e-4 -0.6235108 0.7818148 2.13636e-4 -0.8747642 0.4845491 -9.15568e-5 -0.8996222 0.4365808 0.008789598 -0.978936 0.1965441 0.05527037 -0.9858715 0.1595815 0.05090492 -0.9858705 -0.1595863 -0.05090647 -0.9749147 -0.2225787 0 -0.8996101 -0.4366055 -0.008789479 -0.9749147 0.2225787 0 -0.8747642 -0.4845491 9.15568e-5 -0.6235294 -0.7817999 -2.13632e-4 -0.9789318 -0.1965737 -0.05523961 -0.6227988 -0.7823821 1.52594e-4 -0.2228173 -0.9748602 -1.83112e-4 -0.2219944 -0.975048 1.52594e-4 0.2219944 -0.975048 -1.52594e-4 0.2228173 -0.9748602 1.83112e-4 0.6227988 -0.7823821 -1.52594e-4 0.6235294 -0.7817999 2.13632e-4 0.8747642 -0.4845491 -9.15568e-5 -2.56353e-5 0 1 1.31445e-5 0 1 2.56371e-5 0 1 -5.54994e-6 0 1 0.965938 0.2587737 1.52597e-4 0.9660031 0.2585306 0 0.8969641 0.4421035 0 0.8969641 -0.4421035 0 0.8729753 -0.4873939 -0.01901352 0.965938 -0.2587737 -1.52597e-4 0.9660031 -0.2585306 0 0.8729753 0.4873939 0.01901352 0.7067351 0.7074066 0.01007133 0.5005141 0.8649128 0.03756904 0.4982016 0.8670613 0 0.256973 0.9663652 0.01016294 0.0534687 0.998388 0.01904362 -0.0534687 0.998388 -0.01904362 -0.256973 0.9663652 -0.01016294 -0.5005141 0.8649128 -0.03756904 -0.7067351 0.7074066 -0.01007133 -0.8729753 0.4873939 -0.01901352 -0.4982016 0.8670613 0 -0.8969641 0.4421035 0 -0.965938 0.2587737 -1.52597e-4 -0.965938 -0.2587737 1.52597e-4 -0.9660031 -0.2585306 0 -0.8969641 -0.4421035 0 -0.9660031 0.2585306 0 -0.8729753 -0.4873939 0.01901352 -0.7067351 -0.7074066 0.01007133 -0.5005141 -0.8649128 0.03756904 -0.4982016 -0.8670613 0 -0.256973 -0.9663652 0.01016294 -0.0534687 -0.998388 0.01904362 0.0534687 -0.998388 -0.01904362 0.256973 -0.9663652 -0.01016294 0.5005141 -0.8649128 -0.03756904 0.7067351 -0.7074066 -0.01007133 0.4982016 -0.8670613 0 5.2004e-6 0 1 3.0045e-6 0 1 -1.03559e-5 0 1 5.17794e-6 0 1 -7.18928e-6 0 1 - - - - - - - - - - 0.168547 0.426867 0.141981 0.464168 0.16604 0.464168 0.143157 0.507913 0.16604 0.464168 0.141981 0.464168 0.09109896 0.433505 0.168547 0.426867 0.16604 0.464168 0.08998799 0.464168 0.09109896 0.433505 0.16604 0.464168 0.168338 0.499887 0.08998799 0.464168 0.16604 0.464168 0.168338 0.499887 0.16604 0.464168 0.143157 0.507913 0.168547 0.426867 0.142284 0.441947 0.141981 0.464168 0.143157 0.507913 0.141981 0.464168 0.142284 0.441947 0.168547 0.426867 0.143173 0.420147 0.142284 0.441947 0.143157 0.507913 0.142284 0.441947 0.143173 0.420147 0.1766549 0.388019 0.146665 0.378283 0.143173 0.420147 0.146624 0.549698 0.143173 0.420147 0.146665 0.378283 0.168547 0.426867 0.1766549 0.388019 0.143173 0.420147 0.143157 0.507913 0.143173 0.420147 0.146624 0.549698 0.190195 0.350796 0.15222 0.340457 0.146665 0.378283 0.150132 0.44292 0.146665 0.378283 0.15222 0.340457 0.1766549 0.388019 0.190195 0.350796 0.146665 0.378283 0.150106 0.484456 0.146624 0.549698 0.146665 0.378283 0.150132 0.44292 0.150106 0.484456 0.146665 0.378283 0.209464 0.315026 0.159465 0.308135 0.15222 0.340457 0.152423 0.402474 0.15222 0.340457 0.159465 0.308135 0.190195 0.350796 0.209464 0.315026 0.15222 0.340457 0.152423 0.402474 0.150132 0.44292 0.15222 0.340457 0.238286 0.267285 0.168123 0.281727 0.159465 0.308135 0.163079 0.332085 0.159465 0.308135 0.168123 0.281727 0.234534 0.281547 0.238286 0.267285 0.159465 0.308135 0.209464 0.315026 0.234534 0.281547 0.159465 0.308135 0.156827 0.365011 0.152423 0.402474 0.159465 0.308135 0.163079 0.332085 0.156827 0.365011 0.159465 0.308135 0.246377 0.244359 0.177721 0.261935 0.168123 0.281727 0.17083 0.304808 0.168123 0.281727 0.177721 0.261935 0.242249 0.254885 0.246377 0.244359 0.168123 0.281727 0.238286 0.267285 0.242249 0.254885 0.168123 0.281727 0.17083 0.304808 0.163079 0.332085 0.168123 0.281727 0.254945 0.228855 0.187831 0.2488099 0.177721 0.261935 0.179678 0.283856 0.177721 0.261935 0.187831 0.2488099 0.250623 0.235694 0.254945 0.228855 0.177721 0.261935 0.246377 0.244359 0.250623 0.235694 0.177721 0.261935 0.179678 0.283856 0.17083 0.304808 0.177721 0.261935 0.263659 0.220435 0.198088 0.242057 0.187831 0.2488099 0.189107 0.269592 0.187831 0.2488099 0.198088 0.242057 0.259302 0.22379 0.263659 0.220435 0.187831 0.2488099 0.254945 0.228855 0.259302 0.22379 0.187831 0.2488099 0.189107 0.269592 0.179678 0.283856 0.187831 0.2488099 0.272239 0.2185479 0.208182 0.241217 0.198088 0.242057 0.198875 0.261648 0.198088 0.242057 0.208182 0.241217 0.267981 0.218715 0.272239 0.2185479 0.198088 0.242057 0.263659 0.220435 0.267981 0.218715 0.198088 0.242057 0.198875 0.261648 0.189107 0.269592 0.198088 0.242057 0.280463 0.222536 0.2178609 0.245746 0.208182 0.241217 0.208608 0.259786 0.208182 0.241217 0.2178609 0.245746 0.276408 0.219851 0.280463 0.222536 0.208182 0.241217 0.272239 0.2185479 0.276408 0.219851 0.208182 0.241217 0.208608 0.259786 0.198875 0.261648 0.208182 0.241217 0.288163 0.231705 0.226929 0.25506 0.2178609 0.245746 0.2179909 0.263531 0.2178609 0.245746 0.226929 0.25506 0.284387 0.226516 0.288163 0.231705 0.2178609 0.245746 0.280463 0.222536 0.284387 0.226516 0.2178609 0.245746 0.213342 0.260991 0.2178609 0.245746 0.2179909 0.263531 0.213342 0.260991 0.208608 0.259786 0.2178609 0.245746 0.295221 0.245373 0.235242 0.268577 0.226929 0.25506 0.2347469 0.285269 0.226929 0.25506 0.235242 0.268577 0.291778 0.238018 0.295221 0.245373 0.226929 0.25506 0.288163 0.231705 0.291778 0.238018 0.226929 0.25506 0.226733 0.272218 0.2179909 0.263531 0.226929 0.25506 0.2347469 0.285269 0.226733 0.272218 0.226929 0.25506 0.301558 0.262894 0.242697 0.285734 0.235242 0.268577 0.241888 0.302042 0.235242 0.268577 0.242697 0.285734 0.298483 0.25369 0.301558 0.262894 0.235242 0.268577 0.295221 0.245373 0.298483 0.25369 0.235242 0.268577 0.241888 0.302042 0.2347469 0.285269 0.235242 0.268577 0.30444 0.272911 0.246078 0.29551 0.242697 0.285734 0.241888 0.302042 0.242697 0.285734 0.246078 0.29551 0.301558 0.262894 0.30444 0.272911 0.242697 0.285734 0.307126 0.28367 0.249221 0.30599 0.246078 0.29551 0.248057 0.321857 0.246078 0.29551 0.249221 0.30599 0.30444 0.272911 0.307126 0.28367 0.246078 0.29551 0.248057 0.321857 0.241888 0.302042 0.246078 0.29551 0.309614 0.295106 0.252119 0.317123 0.249221 0.30599 0.250798 0.33287 0.249221 0.30599 0.252119 0.317123 0.307126 0.28367 0.309614 0.295106 0.249221 0.30599 0.250798 0.33287 0.248057 0.321857 0.249221 0.30599 0.311901 0.307154 0.254769 0.328827 0.252119 0.317123 0.253291 0.344484 0.252119 0.317123 0.254769 0.328827 0.309614 0.295106 0.311901 0.307154 0.252119 0.317123 0.253291 0.344484 0.250798 0.33287 0.252119 0.317123 0.313988 0.319753 0.257165 0.341052 0.254769 0.328827 0.255519 0.356607 0.254769 0.328827 0.257165 0.341052 0.311901 0.307154 0.313988 0.319753 0.254769 0.328827 0.255519 0.356607 0.253291 0.344484 0.254769 0.328827 0.315873 0.332844 0.259304 0.353692 0.257165 0.341052 0.257485 0.369174 0.257165 0.341052 0.259304 0.353692 0.313988 0.319753 0.315873 0.332844 0.257165 0.341052 0.257485 0.369174 0.255519 0.356607 0.257165 0.341052 0.319041 0.360281 0.262794 0.379889 0.259304 0.353692 0.260625 0.39539 0.259304 0.353692 0.262794 0.379889 0.317557 0.346371 0.319041 0.360281 0.259304 0.353692 0.315873 0.332844 0.317557 0.346371 0.259304 0.353692 0.260625 0.39539 0.257485 0.369174 0.259304 0.353692 0.321409 0.389041 0.265298 0.407368 0.262794 0.379889 0.263741 0.450489 0.262794 0.379889 0.265298 0.407368 0.320324 0.374521 0.321409 0.389041 0.262794 0.379889 0.319041 0.360281 0.320324 0.374521 0.262794 0.379889 0.262708 0.422645 0.260625 0.39539 0.262794 0.379889 0.263741 0.450489 0.262708 0.422645 0.262794 0.379889 0.322984 0.418727 0.266798 0.435612 0.265298 0.407368 0.266792 0.492908 0.265298 0.407368 0.266798 0.435612 0.322295 0.403792 0.322984 0.418727 0.265298 0.407368 0.321409 0.389041 0.322295 0.403792 0.265298 0.407368 0.26528 0.521216 0.265298 0.407368 0.266792 0.492908 0.263741 0.450489 0.265298 0.407368 0.26528 0.521216 0.323868 0.464168 0.267297 0.464168 0.266798 0.435612 0.267169 0.478612 0.266798 0.435612 0.267297 0.464168 0.323769 0.448961 0.323868 0.464168 0.266798 0.435612 0.323475 0.433798 0.323769 0.448961 0.266798 0.435612 0.322984 0.418727 0.323475 0.433798 0.266798 0.435612 0.266792 0.492908 0.266798 0.435612 0.267169 0.478612 0.323769 0.479376 0.267297 0.464168 0.323868 0.464168 0.267169 0.478612 0.267297 0.464168 0.323769 0.479376 0.353653 0.464168 0.323868 0.464168 0.323769 0.448961 0.3534 0.492191 0.323868 0.464168 0.353653 0.464168 0.3534 0.492191 0.323769 0.479376 0.323868 0.464168 0.3534 0.436146 0.323769 0.448961 0.323475 0.433798 0.3534 0.436146 0.353653 0.464168 0.323769 0.448961 0.3534 0.436146 0.323475 0.433798 0.322984 0.418727 0.352639 0.408346 0.322984 0.418727 0.322295 0.403792 0.352639 0.408346 0.3534 0.436146 0.322984 0.418727 0.352639 0.408346 0.322295 0.403792 0.321409 0.389041 0.351366 0.380996 0.321409 0.389041 0.320324 0.374521 0.351366 0.380996 0.352639 0.408346 0.321409 0.389041 0.349578 0.35433 0.320324 0.374521 0.319041 0.360281 0.349578 0.35433 0.351366 0.380996 0.320324 0.374521 0.349578 0.35433 0.319041 0.360281 0.317557 0.346371 0.347267 0.328593 0.317557 0.346371 0.315873 0.332844 0.347267 0.328593 0.349578 0.35433 0.317557 0.346371 0.347267 0.328593 0.315873 0.332844 0.313988 0.319753 0.344426 0.30405 0.313988 0.319753 0.311901 0.307154 0.344426 0.30405 0.347267 0.328593 0.313988 0.319753 0.341048 0.280981 0.311901 0.307154 0.309614 0.295106 0.341048 0.280981 0.344426 0.30405 0.311901 0.307154 0.341048 0.280981 0.309614 0.295106 0.307126 0.28367 0.33713 0.259696 0.307126 0.28367 0.30444 0.272911 0.33713 0.259696 0.341048 0.280981 0.307126 0.28367 0.33713 0.259696 0.30444 0.272911 0.301558 0.262894 0.332673 0.24053 0.301558 0.262894 0.298483 0.25369 0.332673 0.24053 0.33713 0.259696 0.301558 0.262894 0.327684 0.223854 0.298483 0.25369 0.295221 0.245373 0.327684 0.223854 0.332673 0.24053 0.298483 0.25369 0.327684 0.223854 0.295221 0.245373 0.291778 0.238018 0.322182 0.210075 0.291778 0.238018 0.288163 0.231705 0.322182 0.210075 0.327684 0.223854 0.291778 0.238018 0.322182 0.210075 0.288163 0.231705 0.284387 0.226516 0.316201 0.1996369 0.284387 0.226516 0.280463 0.222536 0.316201 0.1996369 0.322182 0.210075 0.284387 0.226516 0.316201 0.1996369 0.280463 0.222536 0.276408 0.219851 0.309791 0.1930209 0.276408 0.219851 0.272239 0.2185479 0.309791 0.1930209 0.316201 0.1996369 0.276408 0.219851 0.303031 0.190735 0.272239 0.2185479 0.267981 0.218715 0.303031 0.190735 0.309791 0.1930209 0.272239 0.2185479 0.303031 0.190735 0.267981 0.218715 0.263659 0.220435 0.296025 0.193304 0.263659 0.220435 0.259302 0.22379 0.296025 0.193304 0.303031 0.190735 0.263659 0.220435 0.296025 0.193304 0.259302 0.22379 0.254945 0.228855 0.28891 0.201242 0.254945 0.228855 0.250623 0.235694 0.28891 0.201242 0.296025 0.193304 0.254945 0.228855 0.281856 0.215011 0.250623 0.235694 0.246377 0.244359 0.281856 0.215011 0.28891 0.201242 0.250623 0.235694 0.281856 0.215011 0.246377 0.244359 0.242249 0.254885 0.274962 0.234896 0.242249 0.254885 0.238286 0.267285 0.281856 0.215011 0.242249 0.254885 0.274962 0.234896 0.255748 0.254707 0.238286 0.267285 0.234534 0.281547 0.274962 0.234896 0.238286 0.267285 0.255748 0.254707 0.16039 0.232811 0.234534 0.281547 0.209464 0.315026 0.179038 0.207861 0.255748 0.254707 0.234534 0.281547 0.16039 0.232811 0.179038 0.207861 0.234534 0.281547 0.129774 0.285984 0.209464 0.315026 0.190195 0.350796 0.144001 0.25885 0.16039 0.232811 0.209464 0.315026 0.129774 0.285984 0.144001 0.25885 0.209464 0.315026 0.107684 0.343274 0.190195 0.350796 0.1766549 0.388019 0.117648 0.314212 0.129774 0.285984 0.190195 0.350796 0.107684 0.343274 0.117648 0.314212 0.190195 0.350796 0.09994399 0.372982 0.1766549 0.388019 0.168547 0.426867 0.09994399 0.372982 0.107684 0.343274 0.1766549 0.388019 0.09440398 0.403153 0.09994399 0.372982 0.168547 0.426867 0.09109896 0.433505 0.09440398 0.403153 0.168547 0.426867 0.199791 0.184312 0.274962 0.234896 0.255748 0.254707 0.179038 0.207861 0.199791 0.184312 0.255748 0.254707 0.222553 0.162441 0.28051 0.229799 0.274962 0.234896 0.281856 0.215011 0.274962 0.234896 0.28051 0.229799 0.199791 0.184312 0.222553 0.162441 0.274962 0.234896 0.247205 0.142373 0.308761 0.207342 0.28051 0.229799 0.281856 0.215011 0.28051 0.229799 0.308761 0.207342 0.222553 0.162441 0.247205 0.142373 0.28051 0.229799 0.273624 0.124296 0.320742 0.1993319 0.308761 0.207342 0.281856 0.215011 0.308761 0.207342 0.320742 0.1993319 0.247205 0.142373 0.273624 0.124296 0.308761 0.207342 0.273624 0.124296 0.340349 0.187869 0.320742 0.1993319 0.371386 0.169657 0.320742 0.1993319 0.340349 0.187869 0.327189 0.181913 0.281856 0.215011 0.320742 0.1993319 0.327189 0.181913 0.320742 0.1993319 0.371386 0.169657 0.331122 0.09460496 0.383976 0.169753 0.340349 0.187869 0.371386 0.169657 0.340349 0.187869 0.383976 0.169753 0.301652 0.108325 0.331122 0.09460496 0.340349 0.187869 0.273624 0.124296 0.301652 0.108325 0.340349 0.187869 0.393544 0.07431197 0.430021 0.158322 0.383976 0.169753 0.38208 0.164475 0.383976 0.169753 0.430021 0.158322 0.361826 0.08322995 0.393544 0.07431197 0.383976 0.169753 0.331122 0.09460496 0.361826 0.08322995 0.383976 0.169753 0.371386 0.169657 0.383976 0.169753 0.38208 0.164475 0.45903 0.06407898 0.477354 0.153809 0.430021 0.158322 0.424481 0.148683 0.430021 0.158322 0.477354 0.153809 0.426031 0.067905 0.45903 0.06407898 0.430021 0.158322 0.393544 0.07431197 0.426031 0.067905 0.430021 0.158322 0.38208 0.164475 0.430021 0.158322 0.424481 0.148683 0.525488 0.06422799 0.524559 0.15625 0.477354 0.153809 0.472402 0.1389 0.477354 0.153809 0.524559 0.15625 0.492274 0.06284499 0.525488 0.06422799 0.477354 0.153809 0.45903 0.06407898 0.492274 0.06284499 0.477354 0.153809 0.426501 0.148106 0.477354 0.153809 0.472402 0.1389 0.424481 0.148683 0.477354 0.153809 0.426501 0.148106 0.590749 0.07471299 0.570424 0.165427 0.524559 0.15625 0.518568 0.136789 0.524559 0.15625 0.570424 0.165427 0.558403 0.06819099 0.590749 0.07471299 0.524559 0.15625 0.525488 0.06422799 0.558403 0.06819099 0.524559 0.15625 0.477273 0.138346 0.524559 0.15625 0.518568 0.136789 0.472402 0.1389 0.524559 0.15625 0.477273 0.138346 0.622282 0.08371496 0.59253 0.172433 0.570424 0.165427 0.563848 0.141517 0.570424 0.165427 0.59253 0.172433 0.590749 0.07471299 0.622282 0.08371496 0.570424 0.165427 0.528728 0.13726 0.570424 0.165427 0.563848 0.141517 0.518568 0.136789 0.570424 0.165427 0.528728 0.13726 0.652761 0.09513098 0.613912 0.1809689 0.59253 0.172433 0.577795 0.14437 0.59253 0.172433 0.613912 0.1809689 0.622282 0.08371496 0.652761 0.09513098 0.59253 0.172433 0.563848 0.141517 0.59253 0.172433 0.577795 0.14437 0.681987 0.10885 0.634432 0.190953 0.613912 0.1809689 0.607211 0.152675 0.613912 0.1809689 0.634432 0.190953 0.652761 0.09513098 0.681987 0.10885 0.613912 0.1809689 0.577795 0.14437 0.613912 0.1809689 0.607211 0.152675 0.681987 0.10885 0.654051 0.20234 0.634432 0.190953 0.647786 0.169735 0.634432 0.190953 0.654051 0.20234 0.623571 0.158724 0.634432 0.190953 0.647786 0.169735 0.607211 0.152675 0.634432 0.190953 0.623571 0.158724 0.709765 0.124773 0.672737 0.215101 0.654051 0.20234 0.665365 0.1794289 0.654051 0.20234 0.672737 0.215101 0.681987 0.10885 0.709765 0.124773 0.654051 0.20234 0.647786 0.169735 0.654051 0.20234 0.665365 0.1794289 0.735943 0.142765 0.690353 0.229134 0.672737 0.215101 0.684882 0.192094 0.672737 0.215101 0.690353 0.229134 0.709765 0.124773 0.735943 0.142765 0.672737 0.215101 0.665365 0.1794289 0.672737 0.215101 0.684882 0.192094 0.76038 0.162712 0.7068 0.244336 0.690353 0.229134 0.702696 0.2056609 0.690353 0.229134 0.7068 0.244336 0.735943 0.142765 0.76038 0.162712 0.690353 0.229134 0.684882 0.192094 0.690353 0.229134 0.702696 0.2056609 0.782957 0.184441 0.72202 0.260627 0.7068 0.244336 0.717974 0.21909 0.7068 0.244336 0.72202 0.260627 0.76038 0.162712 0.782957 0.184441 0.7068 0.244336 0.702696 0.2056609 0.7068 0.244336 0.717974 0.21909 0.80357 0.207837 0.735953 0.27791 0.72202 0.260627 0.735249 0.236679 0.72202 0.260627 0.735953 0.27791 0.782957 0.184441 0.80357 0.207837 0.72202 0.260627 0.717974 0.21909 0.72202 0.260627 0.735249 0.236679 0.822117 0.232637 0.748563 0.296111 0.735953 0.27791 0.746736 0.250095 0.735953 0.27791 0.748563 0.296111 0.80357 0.207837 0.822117 0.232637 0.735953 0.27791 0.735249 0.236679 0.735953 0.27791 0.746736 0.250095 0.838448 0.258543 0.759815 0.315158 0.748563 0.296111 0.763075 0.272215 0.748563 0.296111 0.759815 0.315158 0.822117 0.232637 0.838448 0.258543 0.748563 0.296111 0.746736 0.250095 0.748563 0.296111 0.763075 0.272215 0.852653 0.285569 0.769663 0.33495 0.759815 0.315158 0.770367 0.283545 0.759815 0.315158 0.769663 0.33495 0.838448 0.258543 0.852653 0.285569 0.759815 0.315158 0.763075 0.272215 0.759815 0.315158 0.770367 0.283545 0.86479 0.313725 0.778064 0.355382 0.769663 0.33495 0.785566 0.311212 0.769663 0.33495 0.778064 0.355382 0.852653 0.285569 0.86479 0.313725 0.769663 0.33495 0.770367 0.283545 0.769663 0.33495 0.785566 0.311212 0.874786 0.34276 0.784998 0.376378 0.778064 0.355382 0.797678 0.339191 0.778064 0.355382 0.784998 0.376378 0.86479 0.313725 0.874786 0.34276 0.778064 0.355382 0.787026 0.314241 0.778064 0.355382 0.797678 0.339191 0.785566 0.311212 0.778064 0.355382 0.787026 0.314241 0.882575 0.372499 0.790438 0.397867 0.784998 0.376378 0.804683 0.359535 0.784998 0.376378 0.790438 0.397867 0.874786 0.34276 0.882575 0.372499 0.784998 0.376378 0.803039 0.354371 0.784998 0.376378 0.804683 0.359535 0.797678 0.339191 0.784998 0.376378 0.803039 0.354371 0.888164 0.402762 0.794351 0.419734 0.790438 0.397867 0.813228 0.392925 0.790438 0.397867 0.794351 0.419734 0.882575 0.372499 0.888164 0.402762 0.790438 0.397867 0.80958 0.376955 0.790438 0.397867 0.813228 0.392925 0.804683 0.359535 0.790438 0.397867 0.80958 0.376955 0.891503 0.433276 0.796711 0.441871 0.794351 0.419734 0.817225 0.416602 0.794351 0.419734 0.796711 0.441871 0.888164 0.402762 0.891503 0.433276 0.794351 0.419734 0.816053 0.408564 0.794351 0.419734 0.817225 0.416602 0.815379 0.404445 0.794351 0.419734 0.816053 0.408564 0.813228 0.392925 0.794351 0.419734 0.815379 0.404445 0.892637 0.464168 0.797503 0.464168 0.796711 0.441871 0.819791 0.443343 0.796711 0.441871 0.797503 0.464168 0.891503 0.433276 0.892637 0.464168 0.796711 0.441871 0.819112 0.433842 0.796711 0.441871 0.819791 0.443343 0.818248 0.424978 0.796711 0.441871 0.819112 0.433842 0.817225 0.416602 0.796711 0.441871 0.818248 0.424978 0.891526 0.494831 0.797503 0.464168 0.892637 0.464168 0.820325 0.456998 0.797503 0.464168 0.820396 0.464168 0.796711 0.486472 0.820396 0.464168 0.797503 0.464168 0.820119 0.450055 0.797503 0.464168 0.820325 0.456998 0.819791 0.443343 0.797503 0.464168 0.820119 0.450055 0.796711 0.486472 0.797503 0.464168 0.891526 0.494831 0.891526 0.494831 0.892637 0.464168 0.891503 0.433276 0.888221 0.525184 0.891503 0.433276 0.888164 0.402762 0.891526 0.494831 0.891503 0.433276 0.888221 0.525184 0.882682 0.555355 0.888164 0.402762 0.882575 0.372499 0.888221 0.525184 0.888164 0.402762 0.882682 0.555355 0.874941 0.585063 0.882575 0.372499 0.874786 0.34276 0.882682 0.555355 0.882575 0.372499 0.874941 0.585063 0.864978 0.614125 0.874786 0.34276 0.86479 0.313725 0.874941 0.585063 0.874786 0.34276 0.864978 0.614125 0.852851 0.642353 0.86479 0.313725 0.852653 0.285569 0.864978 0.614125 0.86479 0.313725 0.852851 0.642353 0.848447 0.464168 0.852653 0.285569 0.838448 0.258543 0.848447 0.464168 0.852851 0.642353 0.852653 0.285569 0.830588 0.350424 0.838448 0.258543 0.822117 0.232637 0.843984 0.406672 0.848447 0.464168 0.838448 0.258543 0.830588 0.350424 0.843984 0.406672 0.838448 0.258543 0.808396 0.296993 0.822117 0.232637 0.80357 0.207837 0.808396 0.296993 0.830588 0.350424 0.822117 0.232637 0.808396 0.296993 0.80357 0.207837 0.782957 0.184441 0.777812 0.2479439 0.782957 0.184441 0.76038 0.162712 0.777812 0.2479439 0.808396 0.296993 0.782957 0.184441 0.759273 0.225193 0.76038 0.162712 0.735943 0.142765 0.759273 0.225193 0.777812 0.2479439 0.76038 0.162712 0.716342 0.184466 0.735943 0.142765 0.709765 0.124773 0.738737 0.203938 0.759273 0.225193 0.735943 0.142765 0.716342 0.184466 0.738737 0.203938 0.735943 0.142765 0.692223 0.166882 0.709765 0.124773 0.681987 0.10885 0.692223 0.166882 0.716342 0.184466 0.709765 0.124773 0.692223 0.166882 0.681987 0.10885 0.652761 0.09513098 0.63943 0.137993 0.652761 0.09513098 0.622282 0.08371496 0.63943 0.137993 0.692223 0.166882 0.652761 0.09513098 0.63943 0.137993 0.622282 0.08371496 0.590749 0.07471299 0.581861 0.118227 0.590749 0.07471299 0.558403 0.06819099 0.581861 0.118227 0.63943 0.137993 0.590749 0.07471299 0.581861 0.118227 0.558403 0.06819099 0.525488 0.06422799 0.521334 0.108245 0.525488 0.06422799 0.492274 0.06284499 0.521334 0.108245 0.581861 0.118227 0.525488 0.06422799 0.459869 0.108362 0.492274 0.06284499 0.45903 0.06407898 0.459869 0.108362 0.521334 0.108245 0.492274 0.06284499 0.459869 0.108362 0.45903 0.06407898 0.426031 0.067905 0.399545 0.118536 0.426031 0.067905 0.393544 0.07431197 0.399545 0.118536 0.459869 0.108362 0.426031 0.067905 0.399545 0.118536 0.393544 0.07431197 0.361826 0.08322995 0.342342 0.13837 0.361826 0.08322995 0.331122 0.09460496 0.342342 0.13837 0.399545 0.118536 0.361826 0.08322995 0.342342 0.13837 0.331122 0.09460496 0.301652 0.108325 0.289973 0.167168 0.301652 0.108325 0.273624 0.124296 0.289973 0.167168 0.342342 0.13837 0.301652 0.108325 0.289973 0.167168 0.273624 0.124296 0.247205 0.142373 0.24382 0.204003 0.247205 0.142373 0.222553 0.162441 0.24382 0.204003 0.289973 0.167168 0.247205 0.142373 0.204963 0.247744 0.222553 0.162441 0.199791 0.184312 0.204963 0.247744 0.24382 0.204003 0.222553 0.162441 0.204963 0.247744 0.199791 0.184312 0.179038 0.207861 0.174439 0.296587 0.179038 0.207861 0.16039 0.232811 0.174439 0.296587 0.204963 0.247744 0.179038 0.207861 0.152193 0.349945 0.16039 0.232811 0.144001 0.25885 0.152193 0.349945 0.174439 0.296587 0.16039 0.232811 0.138697 0.406317 0.144001 0.25885 0.129774 0.285984 0.138697 0.406317 0.152193 0.349945 0.144001 0.25885 0.117835 0.614612 0.129774 0.285984 0.117648 0.314212 0.129972 0.642768 0.129774 0.285984 0.117835 0.614612 0.1341789 0.464168 0.129774 0.285984 0.129972 0.642768 0.135325 0.435047 0.138697 0.406317 0.129774 0.285984 0.1341789 0.464168 0.135325 0.435047 0.129774 0.285984 0.107839 0.585576 0.117648 0.314212 0.107684 0.343274 0.117835 0.614612 0.117648 0.314212 0.107839 0.585576 0.10005 0.555838 0.107684 0.343274 0.09994399 0.372982 0.107839 0.585576 0.107684 0.343274 0.10005 0.555838 0.09446197 0.525575 0.09994399 0.372982 0.09440398 0.403153 0.10005 0.555838 0.09994399 0.372982 0.09446197 0.525575 0.09112298 0.495061 0.09440398 0.403153 0.09109896 0.433505 0.09446197 0.525575 0.09440398 0.403153 0.09112298 0.495061 0.09112298 0.495061 0.09109896 0.433505 0.08998799 0.464168 0.09112298 0.495061 0.08998799 0.464168 0.168338 0.499887 0.354115 0.464168 0.353653 0.464168 0.3534 0.436146 0.384726 0.494784 0.353653 0.464168 0.354115 0.464168 0.384726 0.494784 0.3534 0.492191 0.353653 0.464168 0.384726 0.433553 0.3534 0.436146 0.352639 0.408346 0.384946 0.464168 0.3534 0.436146 0.384726 0.433553 0.354115 0.464168 0.3534 0.436146 0.384946 0.464168 0.384065 0.403177 0.352639 0.408346 0.351366 0.380996 0.384726 0.433553 0.352639 0.408346 0.384065 0.403177 0.382958 0.373286 0.351366 0.380996 0.349578 0.35433 0.384065 0.403177 0.351366 0.380996 0.382958 0.373286 0.381399 0.344133 0.349578 0.35433 0.347267 0.328593 0.382958 0.373286 0.349578 0.35433 0.381399 0.344133 0.37938 0.315987 0.347267 0.328593 0.344426 0.30405 0.381399 0.344133 0.347267 0.328593 0.37938 0.315987 0.376891 0.289138 0.344426 0.30405 0.341048 0.280981 0.37938 0.315987 0.344426 0.30405 0.376891 0.289138 0.373921 0.263903 0.341048 0.280981 0.33713 0.259696 0.376891 0.289138 0.341048 0.280981 0.373921 0.263903 0.370464 0.240629 0.33713 0.259696 0.332673 0.24053 0.373921 0.263903 0.33713 0.259696 0.370464 0.240629 0.366515 0.219705 0.332673 0.24053 0.327684 0.223854 0.370464 0.240629 0.332673 0.24053 0.366515 0.219705 0.362077 0.201562 0.327684 0.223854 0.322182 0.210075 0.366515 0.219705 0.327684 0.223854 0.362077 0.201562 0.357161 0.186686 0.322182 0.210075 0.316201 0.1996369 0.362077 0.201562 0.322182 0.210075 0.357161 0.186686 0.351795 0.175616 0.316201 0.1996369 0.309791 0.1930209 0.357161 0.186686 0.316201 0.1996369 0.351795 0.175616 0.346026 0.168946 0.309791 0.1930209 0.303031 0.190735 0.351795 0.175616 0.309791 0.1930209 0.346026 0.168946 0.339928 0.1673229 0.303031 0.190735 0.296025 0.193304 0.346026 0.168946 0.303031 0.190735 0.339928 0.1673229 0.333602 0.17142 0.296025 0.193304 0.28891 0.201242 0.339928 0.1673229 0.296025 0.193304 0.333602 0.17142 0.327189 0.181913 0.28891 0.201242 0.281856 0.215011 0.333602 0.17142 0.28891 0.201242 0.327189 0.181913 0.817463 0.464168 0.814787 0.464168 0.806829 0.464168 0.817345 0.469794 0.806829 0.464168 0.814787 0.464168 0.817345 0.458542 0.817463 0.464168 0.806829 0.464168 0.816993 0.453025 0.817345 0.458542 0.806829 0.464168 0.816415 0.447721 0.816993 0.453025 0.806829 0.464168 0.815623 0.44273 0.816415 0.447721 0.806829 0.464168 0.814633 0.438146 0.815623 0.44273 0.806829 0.464168 0.813465 0.434049 0.814633 0.438146 0.806829 0.464168 0.812144 0.430512 0.813465 0.434049 0.806829 0.464168 0.810694 0.427592 0.812144 0.430512 0.806829 0.464168 0.809145 0.425334 0.810694 0.427592 0.806829 0.464168 0.807525 0.423768 0.809145 0.425334 0.806829 0.464168 0.805864 0.422912 0.807525 0.423768 0.806829 0.464168 0.804192 0.42277 0.805864 0.422912 0.806829 0.464168 0.802536 0.423334 0.804192 0.42277 0.806829 0.464168 0.800925 0.424583 0.802536 0.423334 0.806829 0.464168 0.799385 0.426486 0.800925 0.424583 0.806829 0.464168 0.79794 0.429004 0.799385 0.426486 0.806829 0.464168 0.796612 0.432088 0.79794 0.429004 0.806829 0.464168 0.795421 0.435682 0.796612 0.432088 0.806829 0.464168 0.794384 0.439723 0.795421 0.435682 0.806829 0.464168 0.793515 0.444145 0.794384 0.439723 0.806829 0.464168 0.792827 0.448876 0.793515 0.444145 0.806829 0.464168 0.792329 0.453842 0.792827 0.448876 0.806829 0.464168 0.792027 0.458965 0.792329 0.453842 0.806829 0.464168 0.791926 0.464168 0.792027 0.458965 0.806829 0.464168 0.792027 0.469371 0.791926 0.464168 0.806829 0.464168 0.816993 0.475312 0.806829 0.464168 0.817345 0.469794 0.816415 0.480616 0.806829 0.464168 0.816993 0.475312 0.815623 0.485606 0.806829 0.464168 0.816415 0.480616 0.814633 0.490191 0.806829 0.464168 0.815623 0.485606 0.813465 0.494287 0.806829 0.464168 0.814633 0.490191 0.812144 0.497824 0.806829 0.464168 0.813465 0.494287 0.810694 0.500745 0.806829 0.464168 0.812144 0.497824 0.809145 0.503003 0.806829 0.464168 0.810694 0.500745 0.807525 0.504569 0.806829 0.464168 0.809145 0.503003 0.805864 0.505425 0.806829 0.464168 0.807525 0.504569 0.804192 0.505566 0.806829 0.464168 0.805864 0.505425 0.802536 0.505003 0.806829 0.464168 0.804192 0.505566 0.800925 0.503754 0.806829 0.464168 0.802536 0.505003 0.799385 0.50185 0.806829 0.464168 0.800925 0.503754 0.79794 0.499332 0.806829 0.464168 0.799385 0.50185 0.796612 0.496249 0.806829 0.464168 0.79794 0.499332 0.795421 0.492655 0.806829 0.464168 0.796612 0.496249 0.794384 0.488614 0.806829 0.464168 0.795421 0.492655 0.793515 0.484192 0.806829 0.464168 0.794384 0.488614 0.792827 0.479461 0.806829 0.464168 0.793515 0.484192 0.792329 0.474495 0.806829 0.464168 0.792827 0.479461 0.792027 0.469371 0.806829 0.464168 0.792329 0.474495 0.817345 0.469794 0.814787 0.464168 0.817463 0.464168 0.820396 0.464168 0.817463 0.464168 0.817345 0.458542 0.82032 0.47156 0.817463 0.464168 0.820396 0.464168 0.817345 0.469794 0.817463 0.464168 0.82032 0.47156 0.820119 0.450055 0.817345 0.458542 0.816993 0.453025 0.820325 0.456998 0.820396 0.464168 0.817345 0.458542 0.820119 0.450055 0.820325 0.456998 0.817345 0.458542 0.819791 0.443343 0.816993 0.453025 0.816415 0.447721 0.819791 0.443343 0.820119 0.450055 0.816993 0.453025 0.819112 0.433842 0.816415 0.447721 0.815623 0.44273 0.819112 0.433842 0.819791 0.443343 0.816415 0.447721 0.818248 0.424978 0.815623 0.44273 0.814633 0.438146 0.818248 0.424978 0.819112 0.433842 0.815623 0.44273 0.816053 0.408564 0.814633 0.438146 0.813465 0.434049 0.817225 0.416602 0.818248 0.424978 0.814633 0.438146 0.816053 0.408564 0.817225 0.416602 0.814633 0.438146 0.812768 0.397212 0.813465 0.434049 0.812144 0.430512 0.815379 0.404445 0.816053 0.408564 0.813465 0.434049 0.812768 0.397212 0.815379 0.404445 0.813465 0.434049 0.809837 0.391217 0.812144 0.430512 0.810694 0.427592 0.809837 0.391217 0.812768 0.397212 0.812144 0.430512 0.806713 0.386657 0.810694 0.427592 0.809145 0.425334 0.806713 0.386657 0.809837 0.391217 0.810694 0.427592 0.803463 0.383577 0.809145 0.425334 0.807525 0.423768 0.803463 0.383577 0.806713 0.386657 0.809145 0.425334 0.80015 0.381991 0.807525 0.423768 0.805864 0.422912 0.80015 0.381991 0.803463 0.383577 0.807525 0.423768 0.796837 0.38188 0.805864 0.422912 0.804192 0.42277 0.796837 0.38188 0.80015 0.381991 0.805864 0.422912 0.793582 0.383202 0.804192 0.42277 0.802536 0.423334 0.793582 0.383202 0.796837 0.38188 0.804192 0.42277 0.790441 0.38589 0.802536 0.423334 0.800925 0.424583 0.790441 0.38589 0.793582 0.383202 0.802536 0.423334 0.787461 0.389861 0.800925 0.424583 0.799385 0.426486 0.787461 0.389861 0.790441 0.38589 0.800925 0.424583 0.784687 0.395016 0.799385 0.426486 0.79794 0.429004 0.784687 0.395016 0.787461 0.389861 0.799385 0.426486 0.782155 0.401245 0.79794 0.429004 0.796612 0.432088 0.782155 0.401245 0.784687 0.395016 0.79794 0.429004 0.7799 0.408427 0.796612 0.432088 0.795421 0.435682 0.7799 0.408427 0.782155 0.401245 0.796612 0.432088 0.777947 0.416436 0.795421 0.435682 0.794384 0.439723 0.777947 0.416436 0.7799 0.408427 0.795421 0.435682 0.776321 0.425141 0.794384 0.439723 0.793515 0.444145 0.776321 0.425141 0.777947 0.416436 0.794384 0.439723 0.775038 0.434405 0.793515 0.444145 0.792827 0.448876 0.775038 0.434405 0.776321 0.425141 0.793515 0.444145 0.774112 0.444091 0.792827 0.448876 0.792329 0.453842 0.774112 0.444091 0.775038 0.434405 0.792827 0.448876 0.773553 0.454059 0.792329 0.453842 0.792027 0.458965 0.773553 0.454059 0.774112 0.444091 0.792329 0.453842 0.773553 0.454059 0.792027 0.458965 0.791926 0.464168 0.773553 0.454059 0.791926 0.464168 0.773366 0.464168 0.792027 0.469371 0.773366 0.464168 0.791926 0.464168 0.751967 0.449664 0.773553 0.454059 0.773366 0.464168 0.751967 0.449664 0.773366 0.464168 0.751718 0.464168 0.773547 0.474108 0.751718 0.464168 0.773366 0.464168 0.773547 0.474108 0.773366 0.464168 0.792027 0.469371 0.796711 0.486472 0.82032 0.47156 0.820396 0.464168 0.813228 0.392925 0.815379 0.404445 0.812768 0.397212 0.80958 0.376955 0.812768 0.397212 0.809837 0.391217 0.80958 0.376955 0.813228 0.392925 0.812768 0.397212 0.798351 0.347673 0.809837 0.391217 0.806713 0.386657 0.804683 0.359535 0.80958 0.376955 0.809837 0.391217 0.803039 0.354371 0.804683 0.359535 0.809837 0.391217 0.798351 0.347673 0.803039 0.354371 0.809837 0.391217 0.793595 0.343623 0.806713 0.386657 0.803463 0.383577 0.793595 0.343623 0.798351 0.347673 0.806713 0.386657 0.788795 0.341846 0.803463 0.383577 0.80015 0.381991 0.788795 0.341846 0.793595 0.343623 0.803463 0.383577 0.784044 0.34227 0.80015 0.381991 0.796837 0.38188 0.784044 0.34227 0.788795 0.341846 0.80015 0.381991 0.779423 0.344787 0.796837 0.38188 0.793582 0.383202 0.779423 0.344787 0.784044 0.34227 0.796837 0.38188 0.775005 0.349263 0.793582 0.383202 0.790441 0.38589 0.775005 0.349263 0.779423 0.344787 0.793582 0.383202 0.770854 0.355546 0.790441 0.38589 0.787461 0.389861 0.770854 0.355546 0.775005 0.349263 0.790441 0.38589 0.767022 0.363468 0.787461 0.389861 0.784687 0.395016 0.767022 0.363468 0.770854 0.355546 0.787461 0.389861 0.763554 0.372854 0.784687 0.395016 0.782155 0.401245 0.763554 0.372854 0.767022 0.363468 0.784687 0.395016 0.760487 0.383522 0.782155 0.401245 0.7799 0.408427 0.760487 0.383522 0.763554 0.372854 0.782155 0.401245 0.757848 0.395289 0.7799 0.408427 0.777947 0.416436 0.757848 0.395289 0.760487 0.383522 0.7799 0.408427 0.755662 0.407971 0.777947 0.416436 0.776321 0.425141 0.755662 0.407971 0.757848 0.395289 0.777947 0.416436 0.753946 0.421383 0.776321 0.425141 0.775038 0.434405 0.753946 0.421383 0.755662 0.407971 0.776321 0.425141 0.752711 0.435342 0.775038 0.434405 0.774112 0.444091 0.752711 0.435342 0.753946 0.421383 0.775038 0.434405 0.751967 0.449664 0.774112 0.444091 0.773553 0.454059 0.751967 0.449664 0.752711 0.435342 0.774112 0.444091 0.727766 0.445456 0.751967 0.449664 0.751718 0.464168 0.727766 0.445456 0.751718 0.464168 0.72747 0.464168 0.751939 0.477845 0.72747 0.464168 0.751718 0.464168 0.773547 0.474108 0.751939 0.477845 0.751718 0.464168 0.797678 0.339191 0.803039 0.354371 0.798351 0.347673 0.779327 0.30554 0.798351 0.347673 0.793595 0.343623 0.787026 0.314241 0.797678 0.339191 0.798351 0.347673 0.785566 0.311212 0.787026 0.314241 0.798351 0.347673 0.779327 0.30554 0.785566 0.311212 0.798351 0.347673 0.773201 0.303344 0.793595 0.343623 0.788795 0.341846 0.773201 0.303344 0.779327 0.30554 0.793595 0.343623 0.767176 0.304146 0.788795 0.341846 0.784044 0.34227 0.767176 0.304146 0.773201 0.303344 0.788795 0.341846 0.761359 0.30775 0.784044 0.34227 0.779423 0.344787 0.761359 0.30775 0.767176 0.304146 0.784044 0.34227 0.755839 0.313934 0.779423 0.344787 0.775005 0.349263 0.755839 0.313934 0.761359 0.30775 0.779423 0.344787 0.75069 0.322457 0.775005 0.349263 0.770854 0.355546 0.75069 0.322457 0.755839 0.313934 0.775005 0.349263 0.745973 0.333071 0.770854 0.355546 0.767022 0.363468 0.745973 0.333071 0.75069 0.322457 0.770854 0.355546 0.741732 0.345528 0.767022 0.363468 0.763554 0.372854 0.741732 0.345528 0.745973 0.333071 0.767022 0.363468 0.738004 0.359579 0.763554 0.372854 0.760487 0.383522 0.738004 0.359579 0.741732 0.345528 0.763554 0.372854 0.734815 0.374982 0.760487 0.383522 0.757848 0.395289 0.734815 0.374982 0.738004 0.359579 0.760487 0.383522 0.732185 0.391501 0.757848 0.395289 0.755662 0.407971 0.732185 0.391501 0.734815 0.374982 0.757848 0.395289 0.730128 0.408902 0.755662 0.407971 0.753946 0.421383 0.730128 0.408902 0.732185 0.391501 0.755662 0.407971 0.728653 0.426961 0.753946 0.421383 0.752711 0.435342 0.728653 0.426961 0.730128 0.408902 0.753946 0.421383 0.727766 0.445456 0.752711 0.435342 0.751967 0.449664 0.727766 0.445456 0.728653 0.426961 0.752711 0.435342 0.701346 0.442439 0.727766 0.445456 0.72747 0.464168 0.701346 0.442439 0.72747 0.464168 0.701047 0.464168 0.727701 0.480709 0.701047 0.464168 0.72747 0.464168 0.751939 0.477845 0.727701 0.480709 0.72747 0.464168 0.770367 0.283545 0.785566 0.311212 0.779327 0.30554 0.756043 0.2677 0.779327 0.30554 0.773201 0.303344 0.763075 0.272215 0.770367 0.283545 0.779327 0.30554 0.756043 0.2677 0.763075 0.272215 0.779327 0.30554 0.749229 0.267105 0.773201 0.303344 0.767176 0.304146 0.749229 0.267105 0.756043 0.2677 0.773201 0.303344 0.742624 0.269905 0.767176 0.304146 0.761359 0.30775 0.742624 0.269905 0.749229 0.267105 0.767176 0.304146 0.736331 0.275813 0.761359 0.30775 0.755839 0.313934 0.736331 0.275813 0.742624 0.269905 0.761359 0.30775 0.73043 0.284529 0.755839 0.313934 0.75069 0.322457 0.73043 0.284529 0.736331 0.275813 0.755839 0.313934 0.724984 0.295751 0.75069 0.322457 0.745973 0.333071 0.724984 0.295751 0.73043 0.284529 0.75069 0.322457 0.720041 0.309182 0.745973 0.333071 0.741732 0.345528 0.720041 0.309182 0.724984 0.295751 0.745973 0.333071 0.715633 0.324536 0.741732 0.345528 0.738004 0.359579 0.715633 0.324536 0.720041 0.309182 0.741732 0.345528 0.711786 0.341537 0.738004 0.359579 0.734815 0.374982 0.711786 0.341537 0.715633 0.324536 0.738004 0.359579 0.708515 0.359923 0.734815 0.374982 0.732185 0.391501 0.708515 0.359923 0.711786 0.341537 0.734815 0.374982 0.705831 0.379442 0.732185 0.391501 0.730128 0.408902 0.705831 0.379442 0.708515 0.359923 0.732185 0.391501 0.70374 0.399854 0.730128 0.408902 0.728653 0.426961 0.70374 0.399854 0.705831 0.379442 0.730128 0.408902 0.702244 0.420928 0.728653 0.426961 0.727766 0.445456 0.702244 0.420928 0.70374 0.399854 0.728653 0.426961 0.701346 0.442439 0.702244 0.420928 0.727766 0.445456 0.673116 0.439724 0.701346 0.442439 0.701047 0.464168 0.673116 0.439724 0.701047 0.464168 0.672827 0.464168 0.701346 0.485896 0.672827 0.464168 0.701047 0.464168 0.727701 0.480709 0.701346 0.485896 0.701047 0.464168 0.746736 0.250095 0.763075 0.272215 0.756043 0.2677 0.72806 0.233491 0.756043 0.2677 0.749229 0.267105 0.735249 0.236679 0.746736 0.250095 0.756043 0.2677 0.72806 0.233491 0.735249 0.236679 0.756043 0.2677 0.720963 0.234363 0.749229 0.267105 0.742624 0.269905 0.720963 0.234363 0.72806 0.233491 0.749229 0.267105 0.714159 0.238992 0.742624 0.269905 0.736331 0.275813 0.714159 0.238992 0.720963 0.234363 0.742624 0.269905 0.707742 0.247001 0.736331 0.275813 0.73043 0.284529 0.707742 0.247001 0.714159 0.238992 0.736331 0.275813 0.70178 0.258019 0.73043 0.284529 0.724984 0.295751 0.70178 0.258019 0.707742 0.247001 0.73043 0.284529 0.696323 0.271688 0.724984 0.295751 0.720041 0.309182 0.696323 0.271688 0.70178 0.258019 0.724984 0.295751 0.691407 0.287667 0.720041 0.309182 0.715633 0.324536 0.691407 0.287667 0.696323 0.271688 0.720041 0.309182 0.687052 0.305636 0.715633 0.324536 0.711786 0.341537 0.687052 0.305636 0.691407 0.287667 0.715633 0.324536 0.683273 0.325296 0.711786 0.341537 0.708515 0.359923 0.683273 0.325296 0.687052 0.305636 0.711786 0.341537 0.680075 0.346368 0.708515 0.359923 0.705831 0.379442 0.680075 0.346368 0.683273 0.325296 0.708515 0.359923 0.677462 0.368589 0.705831 0.379442 0.70374 0.399854 0.677462 0.368589 0.680075 0.346368 0.705831 0.379442 0.675432 0.391711 0.70374 0.399854 0.702244 0.420928 0.675432 0.391711 0.677462 0.368589 0.70374 0.399854 0.673984 0.415498 0.702244 0.420928 0.701346 0.442439 0.673984 0.415498 0.675432 0.391711 0.702244 0.420928 0.673116 0.439724 0.673984 0.415498 0.701346 0.442439 0.643408 0.437308 0.673116 0.439724 0.672827 0.464168 0.643408 0.437308 0.672827 0.464168 0.643142 0.464168 0.673116 0.488612 0.643142 0.464168 0.672827 0.464168 0.701346 0.485896 0.673116 0.488612 0.672827 0.464168 0.717974 0.21909 0.735249 0.236679 0.72806 0.233491 0.695598 0.203266 0.72806 0.233491 0.720963 0.234363 0.702696 0.2056609 0.717974 0.21909 0.72806 0.233491 0.695598 0.203266 0.702696 0.2056609 0.72806 0.233491 0.688661 0.205383 0.720963 0.234363 0.714159 0.238992 0.688661 0.205383 0.695598 0.203266 0.720963 0.234363 0.682067 0.211596 0.714159 0.238992 0.707742 0.247001 0.682067 0.211596 0.688661 0.205383 0.714159 0.238992 0.675898 0.221446 0.707742 0.247001 0.70178 0.258019 0.675898 0.221446 0.682067 0.211596 0.707742 0.247001 0.670208 0.23449 0.70178 0.258019 0.696323 0.271688 0.670208 0.23449 0.675898 0.221446 0.70178 0.258019 0.665037 0.250319 0.696323 0.271688 0.691407 0.287667 0.665037 0.250319 0.670208 0.23449 0.696323 0.271688 0.660405 0.268551 0.691407 0.287667 0.687052 0.305636 0.660405 0.268551 0.665037 0.250319 0.691407 0.287667 0.656326 0.288837 0.687052 0.305636 0.683273 0.325296 0.656326 0.288837 0.660405 0.268551 0.687052 0.305636 0.652802 0.310855 0.683273 0.325296 0.680075 0.346368 0.652802 0.310855 0.656326 0.288837 0.683273 0.325296 0.649833 0.334312 0.680075 0.346368 0.677462 0.368589 0.649833 0.334312 0.652802 0.310855 0.680075 0.346368 0.647414 0.358933 0.677462 0.368589 0.675432 0.391711 0.647414 0.358933 0.649833 0.334312 0.677462 0.368589 0.64554 0.384464 0.675432 0.391711 0.673984 0.415498 0.64554 0.384464 0.647414 0.358933 0.675432 0.391711 0.644206 0.410665 0.673984 0.415498 0.673116 0.439724 0.644206 0.410665 0.64554 0.384464 0.673984 0.415498 0.643408 0.437308 0.644206 0.410665 0.673116 0.439724 0.612524 0.435197 0.643408 0.437308 0.643142 0.464168 0.612524 0.435197 0.643142 0.464168 0.612294 0.464168 0.643332 0.486877 0.612294 0.464168 0.643142 0.464168 0.673116 0.488612 0.643332 0.486877 0.643142 0.464168 0.658881 0.177524 0.702696 0.2056609 0.695598 0.203266 0.658881 0.177524 0.684882 0.192094 0.702696 0.2056609 0.652578 0.1805689 0.695598 0.203266 0.688661 0.205383 0.652578 0.1805689 0.658881 0.177524 0.695598 0.203266 0.646627 0.188045 0.688661 0.205383 0.682067 0.211596 0.646627 0.188045 0.652578 0.1805689 0.688661 0.205383 0.641093 0.199406 0.682067 0.211596 0.675898 0.221446 0.641093 0.199406 0.646627 0.188045 0.682067 0.211596 0.636021 0.214147 0.675898 0.221446 0.670208 0.23449 0.636021 0.214147 0.641093 0.199406 0.675898 0.221446 0.631436 0.231804 0.670208 0.23449 0.665037 0.250319 0.631436 0.231804 0.636021 0.214147 0.670208 0.23449 0.62735 0.251959 0.665037 0.250319 0.660405 0.268551 0.62735 0.251959 0.631436 0.231804 0.665037 0.250319 0.623768 0.274234 0.660405 0.268551 0.656326 0.288837 0.623768 0.274234 0.62735 0.251959 0.660405 0.268551 0.620685 0.298287 0.656326 0.288837 0.652802 0.310855 0.620685 0.298287 0.623768 0.274234 0.656326 0.288837 0.618097 0.323808 0.652802 0.310855 0.649833 0.334312 0.618097 0.323808 0.620685 0.298287 0.652802 0.310855 0.615994 0.350513 0.649833 0.334312 0.647414 0.358933 0.615994 0.350513 0.618097 0.323808 0.649833 0.334312 0.614369 0.378141 0.647414 0.358933 0.64554 0.384464 0.614369 0.378141 0.615994 0.350513 0.647414 0.358933 0.613214 0.406447 0.64554 0.384464 0.644206 0.410665 0.613214 0.406447 0.614369 0.378141 0.64554 0.384464 0.612524 0.435197 0.644206 0.410665 0.643408 0.437308 0.612524 0.435197 0.613214 0.406447 0.644206 0.410665 0.580738 0.433401 0.612524 0.435197 0.612294 0.464168 0.580738 0.433401 0.612294 0.464168 0.580556 0.464168 0.612524 0.493139 0.580556 0.464168 0.612294 0.464168 0.643332 0.486877 0.612524 0.493139 0.612294 0.464168 0.658881 0.177524 0.665365 0.1794289 0.684882 0.192094 0.618231 0.156866 0.665365 0.1794289 0.658881 0.177524 0.618231 0.156866 0.647786 0.169735 0.665365 0.1794289 0.613046 0.160407 0.658881 0.177524 0.652578 0.1805689 0.613046 0.160407 0.618231 0.156866 0.658881 0.177524 0.608173 0.168722 0.652578 0.1805689 0.646627 0.188045 0.608173 0.168722 0.613046 0.160407 0.652578 0.1805689 0.603664 0.1811839 0.646627 0.188045 0.641093 0.199406 0.603664 0.1811839 0.608173 0.168722 0.646627 0.188045 0.599549 0.1972219 0.641093 0.199406 0.636021 0.214147 0.599549 0.1972219 0.603664 0.1811839 0.641093 0.199406 0.595845 0.216321 0.636021 0.214147 0.631436 0.231804 0.595845 0.216321 0.599549 0.1972219 0.636021 0.214147 0.592558 0.238026 0.631436 0.231804 0.62735 0.251959 0.592558 0.238026 0.595845 0.216321 0.631436 0.231804 0.589686 0.261928 0.62735 0.251959 0.623768 0.274234 0.589686 0.261928 0.592558 0.238026 0.62735 0.251959 0.587224 0.287665 0.623768 0.274234 0.620685 0.298287 0.587224 0.287665 0.589686 0.261928 0.623768 0.274234 0.585161 0.31491 0.620685 0.298287 0.618097 0.323808 0.585161 0.31491 0.587224 0.287665 0.620685 0.298287 0.583489 0.343368 0.618097 0.323808 0.615994 0.350513 0.583489 0.343368 0.585161 0.31491 0.618097 0.323808 0.5822 0.372768 0.615994 0.350513 0.614369 0.378141 0.5822 0.372768 0.583489 0.343368 0.615994 0.350513 0.581284 0.402858 0.614369 0.378141 0.613214 0.406447 0.581284 0.402858 0.5822 0.372768 0.614369 0.378141 0.580738 0.433401 0.613214 0.406447 0.612524 0.435197 0.580738 0.433401 0.581284 0.402858 0.613214 0.406447 0.548305 0.431924 0.580738 0.433401 0.580556 0.464168 0.548305 0.431924 0.580556 0.464168 0.548182 0.464168 0.580738 0.494935 0.548182 0.464168 0.580556 0.464168 0.612524 0.493139 0.580738 0.494935 0.580556 0.464168 0.618231 0.156866 0.623571 0.158724 0.647786 0.169735 0.574102 0.141959 0.623571 0.158724 0.618231 0.156866 0.574102 0.141959 0.607211 0.152675 0.623571 0.158724 0.570496 0.145425 0.618231 0.156866 0.613046 0.160407 0.570496 0.145425 0.574102 0.141959 0.618231 0.156866 0.567115 0.154041 0.613046 0.160407 0.608173 0.168722 0.567115 0.154041 0.570496 0.145425 0.613046 0.160407 0.563995 0.167097 0.608173 0.168722 0.603664 0.1811839 0.563995 0.167097 0.567115 0.154041 0.608173 0.168722 0.561157 0.183955 0.603664 0.1811839 0.599549 0.1972219 0.561157 0.183955 0.563995 0.167097 0.603664 0.1811839 0.55861 0.204049 0.599549 0.1972219 0.595845 0.216321 0.55861 0.204049 0.561157 0.183955 0.599549 0.1972219 0.556356 0.226881 0.595845 0.216321 0.592558 0.238026 0.556356 0.226881 0.55861 0.204049 0.595845 0.216321 0.554392 0.252012 0.592558 0.238026 0.589686 0.261928 0.554392 0.252012 0.556356 0.226881 0.592558 0.238026 0.552711 0.279054 0.589686 0.261928 0.587224 0.287665 0.552711 0.279054 0.554392 0.252012 0.589686 0.261928 0.551307 0.307662 0.587224 0.287665 0.585161 0.31491 0.551307 0.307662 0.552711 0.279054 0.587224 0.287665 0.550171 0.337525 0.585161 0.31491 0.583489 0.343368 0.550171 0.337525 0.551307 0.307662 0.585161 0.31491 0.549295 0.368361 0.583489 0.343368 0.5822 0.372768 0.549295 0.368361 0.550171 0.337525 0.583489 0.343368 0.548675 0.399909 0.5822 0.372768 0.581284 0.402858 0.548675 0.399909 0.549295 0.368361 0.5822 0.372768 0.548305 0.431924 0.581284 0.402858 0.580738 0.433401 0.548305 0.431924 0.548675 0.399909 0.581284 0.402858 0.515465 0.430767 0.548305 0.431924 0.548182 0.464168 0.515465 0.430767 0.548182 0.464168 0.515739 0.464168 0.548238 0.486101 0.515739 0.464168 0.548182 0.464168 0.580738 0.494935 0.548238 0.486101 0.548182 0.464168 0.574102 0.141959 0.577795 0.14437 0.607211 0.152675 0.527099 0.133518 0.577795 0.14437 0.574102 0.141959 0.527099 0.133518 0.563848 0.141517 0.577795 0.14437 0.525466 0.136185 0.574102 0.141959 0.570496 0.145425 0.525466 0.136185 0.527099 0.133518 0.574102 0.141959 0.523936 0.144434 0.570496 0.145425 0.567115 0.154041 0.523936 0.144434 0.525466 0.136185 0.570496 0.145425 0.522524 0.157471 0.567115 0.154041 0.563995 0.167097 0.522524 0.157471 0.523936 0.144434 0.567115 0.154041 0.521241 0.174588 0.563995 0.167097 0.561157 0.183955 0.521241 0.174588 0.522524 0.157471 0.563995 0.167097 0.520092 0.195161 0.561157 0.183955 0.55861 0.204049 0.520092 0.195161 0.521241 0.174588 0.561157 0.183955 0.519077 0.218647 0.55861 0.204049 0.556356 0.226881 0.519077 0.218647 0.520092 0.195161 0.55861 0.204049 0.518193 0.244569 0.556356 0.226881 0.554392 0.252012 0.518193 0.244569 0.519077 0.218647 0.556356 0.226881 0.517439 0.272509 0.554392 0.252012 0.552711 0.279054 0.517439 0.272509 0.518193 0.244569 0.554392 0.252012 0.516809 0.302098 0.552711 0.279054 0.551307 0.307662 0.516809 0.302098 0.517439 0.272509 0.552711 0.279054 0.5163 0.333005 0.551307 0.307662 0.550171 0.337525 0.5163 0.333005 0.516809 0.302098 0.551307 0.307662 0.515908 0.364933 0.550171 0.337525 0.549295 0.368361 0.515908 0.364933 0.5163 0.333005 0.550171 0.337525 0.515631 0.397606 0.549295 0.368361 0.548675 0.399909 0.515631 0.397606 0.515908 0.364933 0.549295 0.368361 0.515465 0.430767 0.548675 0.399909 0.548305 0.431924 0.515465 0.430767 0.515631 0.397606 0.548675 0.399909 0.51541 0.464168 0.515465 0.430767 0.515739 0.464168 0.548238 0.486101 0.51541 0.464168 0.515739 0.464168 0.527099 0.133518 0.528728 0.13726 0.563848 0.141517 0.477934 0.132473 0.528728 0.13726 0.527099 0.133518 0.477934 0.132473 0.518568 0.136789 0.528728 0.13726 0.478524 0.132818 0.527099 0.133518 0.525466 0.136185 0.478524 0.132818 0.477934 0.132473 0.527099 0.133518 0.479081 0.138617 0.525466 0.136185 0.523936 0.144434 0.479081 0.138617 0.478524 0.132818 0.525466 0.136185 0.479601 0.149137 0.523936 0.144434 0.522524 0.157471 0.479601 0.149137 0.479081 0.138617 0.523936 0.144434 0.480078 0.163715 0.522524 0.157471 0.521241 0.174588 0.480078 0.163715 0.479601 0.149137 0.522524 0.157471 0.48051 0.1817629 0.521241 0.174588 0.520092 0.195161 0.48051 0.1817629 0.480078 0.163715 0.521241 0.174588 0.480897 0.202763 0.520092 0.195161 0.519077 0.218647 0.480897 0.202763 0.48051 0.1817629 0.520092 0.195161 0.481238 0.226261 0.519077 0.218647 0.518193 0.244569 0.481238 0.226261 0.480897 0.202763 0.519077 0.218647 0.481536 0.251858 0.518193 0.244569 0.517439 0.272509 0.481536 0.251858 0.481238 0.226261 0.518193 0.244569 0.48179 0.279201 0.517439 0.272509 0.516809 0.302098 0.48179 0.279201 0.481536 0.251858 0.517439 0.272509 0.482002 0.307974 0.516809 0.302098 0.5163 0.333005 0.482002 0.307974 0.48179 0.279201 0.516809 0.302098 0.482173 0.337896 0.5163 0.333005 0.515908 0.364933 0.482173 0.337896 0.482002 0.307974 0.5163 0.333005 0.482305 0.368709 0.515908 0.364933 0.515631 0.397606 0.482305 0.368709 0.482173 0.337896 0.515908 0.364933 0.482399 0.400174 0.515631 0.397606 0.515465 0.430767 0.482399 0.400174 0.482305 0.368709 0.515631 0.397606 0.482455 0.432065 0.515465 0.430767 0.51541 0.464168 0.482455 0.432065 0.482399 0.400174 0.515465 0.430767 0.482455 0.432065 0.51541 0.464168 0.482835 0.464168 0.515457 0.494898 0.482835 0.464168 0.51541 0.464168 0.515457 0.494898 0.51541 0.464168 0.548238 0.486101 0.482473 0.464168 0.482455 0.432065 0.482835 0.464168 0.515457 0.494898 0.482473 0.464168 0.482835 0.464168 0.477934 0.132473 0.477273 0.138346 0.518568 0.136789 0.427423 0.139556 0.477273 0.138346 0.477934 0.132473 0.427423 0.139556 0.472402 0.1389 0.477273 0.138346 0.430258 0.13725 0.477934 0.132473 0.478524 0.132818 0.430258 0.13725 0.427423 0.139556 0.477934 0.132473 0.43296 0.140941 0.478524 0.132818 0.479081 0.138617 0.43296 0.140941 0.430258 0.13725 0.478524 0.132818 0.43549 0.149835 0.479081 0.138617 0.479601 0.149137 0.43549 0.149835 0.43296 0.140941 0.479081 0.138617 0.437822 0.163203 0.479601 0.149137 0.480078 0.163715 0.437822 0.163203 0.43549 0.149835 0.479601 0.149137 0.439941 0.1803939 0.480078 0.163715 0.48051 0.1817629 0.439941 0.1803939 0.437822 0.163203 0.480078 0.163715 0.441841 0.200836 0.48051 0.1817629 0.480897 0.202763 0.441841 0.200836 0.439941 0.1803939 0.48051 0.1817629 0.44352 0.224022 0.480897 0.202763 0.481238 0.226261 0.44352 0.224022 0.441841 0.200836 0.480897 0.202763 0.444982 0.249512 0.481238 0.226261 0.481536 0.251858 0.444982 0.249512 0.44352 0.224022 0.481238 0.226261 0.446232 0.276914 0.481536 0.251858 0.48179 0.279201 0.446232 0.276914 0.444982 0.249512 0.481536 0.251858 0.447276 0.305881 0.48179 0.279201 0.482002 0.307974 0.447276 0.305881 0.446232 0.276914 0.48179 0.279201 0.44812 0.336103 0.482002 0.307974 0.482173 0.337896 0.44812 0.336103 0.447276 0.305881 0.482002 0.307974 0.44877 0.367296 0.482173 0.337896 0.482305 0.368709 0.44877 0.367296 0.44812 0.336103 0.482173 0.337896 0.449231 0.3992 0.482305 0.368709 0.482399 0.400174 0.449231 0.3992 0.44877 0.367296 0.482305 0.368709 0.449505 0.431569 0.482399 0.400174 0.482455 0.432065 0.449505 0.431569 0.449231 0.3992 0.482399 0.400174 0.449505 0.431569 0.482455 0.432065 0.482473 0.464168 0.449505 0.431569 0.482473 0.464168 0.44999 0.464168 0.482454 0.497193 0.44999 0.464168 0.482473 0.464168 0.515457 0.494898 0.482454 0.497193 0.482473 0.464168 0.449597 0.464168 0.449505 0.431569 0.44999 0.464168 0.482454 0.497193 0.449597 0.464168 0.44999 0.464168 0.427423 0.139556 0.426501 0.148106 0.472402 0.1389 0.427423 0.139556 0.424481 0.148683 0.426501 0.148106 0.376309 0.1565819 0.424481 0.148683 0.427423 0.139556 0.376309 0.1565819 0.38208 0.164475 0.424481 0.148683 0.381036 0.150104 0.427423 0.139556 0.430258 0.13725 0.381036 0.150104 0.376309 0.1565819 0.427423 0.139556 0.385621 0.149607 0.430258 0.13725 0.43296 0.140941 0.385621 0.149607 0.381036 0.150104 0.430258 0.13725 0.389985 0.1543869 0.43296 0.140941 0.43549 0.149835 0.389985 0.1543869 0.385621 0.149607 0.43296 0.140941 0.394069 0.163775 0.43549 0.149835 0.437822 0.163203 0.394069 0.163775 0.389985 0.1543869 0.43549 0.149835 0.397837 0.177153 0.437822 0.163203 0.439941 0.1803939 0.397837 0.177153 0.394069 0.163775 0.437822 0.163203 0.401265 0.193964 0.439941 0.1803939 0.441841 0.200836 0.401265 0.193964 0.397837 0.177153 0.439941 0.1803939 0.404345 0.213711 0.441841 0.200836 0.44352 0.224022 0.404345 0.213711 0.401265 0.193964 0.441841 0.200836 0.407074 0.2359549 0.44352 0.224022 0.444982 0.249512 0.407074 0.2359549 0.404345 0.213711 0.44352 0.224022 0.409455 0.260303 0.444982 0.249512 0.446232 0.276914 0.409455 0.260303 0.407074 0.2359549 0.444982 0.249512 0.411495 0.286408 0.446232 0.276914 0.447276 0.305881 0.411495 0.286408 0.409455 0.260303 0.446232 0.276914 0.413202 0.313956 0.447276 0.305881 0.44812 0.336103 0.413202 0.313956 0.411495 0.286408 0.447276 0.305881 0.414585 0.342665 0.44812 0.336103 0.44877 0.367296 0.414585 0.342665 0.413202 0.313956 0.44812 0.336103 0.415651 0.372275 0.44877 0.367296 0.449231 0.3992 0.415651 0.372275 0.414585 0.342665 0.44877 0.367296 0.416408 0.402546 0.449231 0.3992 0.449505 0.431569 0.416408 0.402546 0.415651 0.372275 0.449231 0.3992 0.416859 0.43325 0.449505 0.431569 0.449597 0.464168 0.416859 0.43325 0.416408 0.402546 0.449505 0.431569 0.416859 0.43325 0.449597 0.464168 0.41743 0.464168 0.449505 0.496767 0.41743 0.464168 0.449597 0.464168 0.482454 0.497193 0.449505 0.496767 0.449597 0.464168 0.41701 0.464168 0.416859 0.43325 0.41743 0.464168 0.449505 0.496767 0.41701 0.464168 0.41743 0.464168 0.376309 0.1565819 0.371386 0.169657 0.38208 0.164475 0.327189 0.181913 0.371386 0.169657 0.376309 0.1565819 0.333602 0.17142 0.376309 0.1565819 0.381036 0.150104 0.333602 0.17142 0.327189 0.181913 0.376309 0.1565819 0.339928 0.1673229 0.381036 0.150104 0.385621 0.149607 0.339928 0.1673229 0.333602 0.17142 0.381036 0.150104 0.346026 0.168946 0.385621 0.149607 0.389985 0.1543869 0.346026 0.168946 0.339928 0.1673229 0.385621 0.149607 0.351795 0.175616 0.389985 0.1543869 0.394069 0.163775 0.351795 0.175616 0.346026 0.168946 0.389985 0.1543869 0.357161 0.186686 0.394069 0.163775 0.397837 0.177153 0.357161 0.186686 0.351795 0.175616 0.394069 0.163775 0.362077 0.201562 0.397837 0.177153 0.401265 0.193964 0.362077 0.201562 0.357161 0.186686 0.397837 0.177153 0.366515 0.219705 0.401265 0.193964 0.404345 0.213711 0.366515 0.219705 0.362077 0.201562 0.401265 0.193964 0.370464 0.240629 0.404345 0.213711 0.407074 0.2359549 0.370464 0.240629 0.366515 0.219705 0.404345 0.213711 0.373921 0.263903 0.407074 0.2359549 0.409455 0.260303 0.373921 0.263903 0.370464 0.240629 0.407074 0.2359549 0.376891 0.289138 0.409455 0.260303 0.411495 0.286408 0.376891 0.289138 0.373921 0.263903 0.409455 0.260303 0.37938 0.315987 0.411495 0.286408 0.413202 0.313956 0.37938 0.315987 0.376891 0.289138 0.411495 0.286408 0.381399 0.344133 0.413202 0.313956 0.414585 0.342665 0.381399 0.344133 0.37938 0.315987 0.413202 0.313956 0.382958 0.373286 0.414585 0.342665 0.415651 0.372275 0.382958 0.373286 0.381399 0.344133 0.414585 0.342665 0.384065 0.403177 0.415651 0.372275 0.416408 0.402546 0.384065 0.403177 0.382958 0.373286 0.415651 0.372275 0.384726 0.433553 0.416408 0.402546 0.416859 0.43325 0.384726 0.433553 0.384065 0.403177 0.416408 0.402546 0.384726 0.433553 0.416859 0.43325 0.41701 0.464168 0.384726 0.433553 0.41701 0.464168 0.38539 0.464168 0.416933 0.486187 0.38539 0.464168 0.41701 0.464168 0.449505 0.496767 0.416933 0.486187 0.41701 0.464168 0.384946 0.464168 0.384726 0.433553 0.38539 0.464168 0.416933 0.486187 0.384946 0.464168 0.38539 0.464168 0.384726 0.494784 0.354115 0.464168 0.384946 0.464168 0.416933 0.486187 0.384726 0.494784 0.384946 0.464168 0.3534 0.492191 0.323475 0.494538 0.323769 0.479376 0.267169 0.478612 0.323769 0.479376 0.323475 0.494538 0.352639 0.51999 0.322984 0.50961 0.323475 0.494538 0.266792 0.492908 0.323475 0.494538 0.322984 0.50961 0.3534 0.492191 0.352639 0.51999 0.323475 0.494538 0.266792 0.492908 0.267169 0.478612 0.323475 0.494538 0.352639 0.51999 0.322295 0.524544 0.322984 0.50961 0.311088 0.509904 0.322984 0.50961 0.322295 0.524544 0.311088 0.509904 0.266792 0.492908 0.322984 0.50961 0.351366 0.54734 0.321409 0.539296 0.322295 0.524544 0.311712 0.5355 0.322295 0.524544 0.321409 0.539296 0.352639 0.51999 0.351366 0.54734 0.322295 0.524544 0.311365 0.522763 0.311088 0.509904 0.322295 0.524544 0.311712 0.5355 0.311365 0.522763 0.322295 0.524544 0.351366 0.54734 0.320324 0.553816 0.321409 0.539296 0.311564 0.542102 0.321409 0.539296 0.320324 0.553816 0.311564 0.542102 0.311712 0.5355 0.321409 0.539296 0.349578 0.574007 0.319041 0.568056 0.320324 0.553816 0.307949 0.554083 0.320324 0.553816 0.319041 0.568056 0.351366 0.54734 0.349578 0.574007 0.320324 0.553816 0.310799 0.547288 0.311564 0.542102 0.320324 0.553816 0.309559 0.55124 0.310799 0.547288 0.320324 0.553816 0.307949 0.554083 0.309559 0.55124 0.320324 0.553816 0.347267 0.599743 0.317557 0.581966 0.319041 0.568056 0.26277 0.54866 0.319041 0.568056 0.317557 0.581966 0.349578 0.574007 0.347267 0.599743 0.319041 0.568056 0.302306 0.556529 0.319041 0.568056 0.26277 0.54866 0.306085 0.555861 0.307949 0.554083 0.319041 0.568056 0.304192 0.556612 0.306085 0.555861 0.319041 0.568056 0.302306 0.556529 0.304192 0.556612 0.319041 0.568056 0.347267 0.599743 0.315873 0.595493 0.317557 0.581966 0.259287 0.574749 0.317557 0.581966 0.315873 0.595493 0.259287 0.574749 0.26277 0.54866 0.317557 0.581966 0.344426 0.624287 0.313988 0.608584 0.315873 0.595493 0.259287 0.574749 0.315873 0.595493 0.313988 0.608584 0.347267 0.599743 0.344426 0.624287 0.315873 0.595493 0.344426 0.624287 0.311901 0.621183 0.313988 0.608584 0.254779 0.599464 0.313988 0.608584 0.311901 0.621183 0.254779 0.599464 0.259287 0.574749 0.313988 0.608584 0.341048 0.647356 0.309614 0.63323 0.311901 0.621183 0.254779 0.599464 0.311901 0.621183 0.309614 0.63323 0.344426 0.624287 0.341048 0.647356 0.311901 0.621183 0.33713 0.668641 0.307126 0.644666 0.309614 0.63323 0.249276 0.622149 0.309614 0.63323 0.307126 0.644666 0.341048 0.647356 0.33713 0.668641 0.309614 0.63323 0.249276 0.622149 0.254779 0.599464 0.309614 0.63323 0.33713 0.668641 0.30444 0.655426 0.307126 0.644666 0.249276 0.622149 0.307126 0.644666 0.30444 0.655426 0.332673 0.687807 0.301558 0.665443 0.30444 0.655426 0.242811 0.642293 0.30444 0.655426 0.301558 0.665443 0.33713 0.668641 0.332673 0.687807 0.30444 0.655426 0.242811 0.642293 0.249276 0.622149 0.30444 0.655426 0.332673 0.687807 0.298483 0.674646 0.301558 0.665443 0.242811 0.642293 0.301558 0.665443 0.298483 0.674646 0.327684 0.704482 0.295221 0.682964 0.298483 0.674646 0.235419 0.659412 0.298483 0.674646 0.295221 0.682964 0.332673 0.687807 0.327684 0.704482 0.298483 0.674646 0.235419 0.659412 0.242811 0.642293 0.298483 0.674646 0.322182 0.718261 0.291778 0.690319 0.295221 0.682964 0.235419 0.659412 0.295221 0.682964 0.291778 0.690319 0.327684 0.704482 0.322182 0.718261 0.295221 0.682964 0.322182 0.718261 0.288163 0.696632 0.291778 0.690319 0.227158 0.672973 0.291778 0.690319 0.288163 0.696632 0.227158 0.672973 0.235419 0.659412 0.291778 0.690319 0.316201 0.728699 0.284387 0.701821 0.288163 0.696632 0.227158 0.672973 0.288163 0.696632 0.284387 0.701821 0.322182 0.718261 0.316201 0.728699 0.288163 0.696632 0.316201 0.728699 0.280463 0.705801 0.284387 0.701821 0.21812 0.682395 0.284387 0.701821 0.280463 0.705801 0.21812 0.682395 0.227158 0.672973 0.284387 0.701821 0.309791 0.735316 0.276408 0.708486 0.280463 0.705801 0.21812 0.682395 0.280463 0.705801 0.276408 0.708486 0.316201 0.728699 0.309791 0.735316 0.280463 0.705801 0.309791 0.735316 0.272239 0.709789 0.276408 0.708486 0.208443 0.687066 0.276408 0.708486 0.272239 0.709789 0.208443 0.687066 0.21812 0.682395 0.276408 0.708486 0.303031 0.737602 0.267981 0.709622 0.272239 0.709789 0.208443 0.687066 0.272239 0.709789 0.267981 0.709622 0.309791 0.735316 0.303031 0.737602 0.272239 0.709789 0.296025 0.735032 0.263659 0.707902 0.267981 0.709622 0.198319 0.686362 0.267981 0.709622 0.263659 0.707902 0.303031 0.737602 0.296025 0.735032 0.267981 0.709622 0.198319 0.686362 0.208443 0.687066 0.267981 0.709622 0.296025 0.735032 0.259302 0.704546 0.263659 0.707902 0.198319 0.686362 0.263659 0.707902 0.259302 0.704546 0.28891 0.727094 0.254945 0.699482 0.259302 0.704546 0.188 0.679689 0.259302 0.704546 0.254945 0.699482 0.296025 0.735032 0.28891 0.727094 0.259302 0.704546 0.188 0.679689 0.198319 0.686362 0.259302 0.704546 0.28891 0.727094 0.250623 0.692643 0.254945 0.699482 0.182867 0.673949 0.254945 0.699482 0.250623 0.692643 0.182867 0.673949 0.188 0.679689 0.254945 0.699482 0.281856 0.713326 0.246377 0.683978 0.250623 0.692643 0.177812 0.666552 0.250623 0.692643 0.246377 0.683978 0.28891 0.727094 0.281856 0.713326 0.250623 0.692643 0.177812 0.666552 0.182867 0.673949 0.250623 0.692643 0.274962 0.69344 0.242249 0.673452 0.246377 0.683978 0.172885 0.657449 0.246377 0.683978 0.242249 0.673452 0.281856 0.713326 0.274962 0.69344 0.246377 0.683978 0.172885 0.657449 0.177812 0.666552 0.246377 0.683978 0.274962 0.69344 0.238286 0.661051 0.242249 0.673452 0.1681399 0.646654 0.242249 0.673452 0.238286 0.661051 0.1681399 0.646654 0.172885 0.657449 0.242249 0.673452 0.255748 0.67363 0.234534 0.646789 0.238286 0.661051 0.163637 0.634163 0.238286 0.661051 0.234534 0.646789 0.274962 0.69344 0.255748 0.67363 0.238286 0.661051 0.163637 0.634163 0.1681399 0.646654 0.238286 0.661051 0.179056 0.720499 0.234534 0.646789 0.255748 0.67363 0.1594319 0.62008 0.234534 0.646789 0.212484 0.617942 0.144178 0.669793 0.212484 0.617942 0.234534 0.646789 0.1594319 0.62008 0.163637 0.634163 0.234534 0.646789 0.160509 0.6957 0.144178 0.669793 0.234534 0.646789 0.179056 0.720499 0.160509 0.6957 0.234534 0.646789 0.199668 0.743895 0.255748 0.67363 0.274962 0.69344 0.199668 0.743895 0.179056 0.720499 0.255748 0.67363 0.28051 0.698537 0.274962 0.69344 0.281856 0.713326 0.199668 0.743895 0.274962 0.69344 0.28051 0.698537 0.327189 0.746424 0.281856 0.713326 0.28891 0.727094 0.308761 0.720995 0.28051 0.698537 0.281856 0.713326 0.320742 0.729004 0.308761 0.720995 0.281856 0.713326 0.327189 0.746424 0.320742 0.729004 0.281856 0.713326 0.333602 0.756916 0.28891 0.727094 0.296025 0.735032 0.333602 0.756916 0.327189 0.746424 0.28891 0.727094 0.339928 0.761014 0.296025 0.735032 0.303031 0.737602 0.339928 0.761014 0.333602 0.756916 0.296025 0.735032 0.346026 0.75939 0.303031 0.737602 0.309791 0.735316 0.346026 0.75939 0.339928 0.761014 0.303031 0.737602 0.351795 0.752721 0.309791 0.735316 0.316201 0.728699 0.351795 0.752721 0.346026 0.75939 0.309791 0.735316 0.357161 0.741651 0.316201 0.728699 0.322182 0.718261 0.357161 0.741651 0.351795 0.752721 0.316201 0.728699 0.362077 0.726775 0.322182 0.718261 0.327684 0.704482 0.362077 0.726775 0.357161 0.741651 0.322182 0.718261 0.366515 0.708632 0.327684 0.704482 0.332673 0.687807 0.366515 0.708632 0.362077 0.726775 0.327684 0.704482 0.370464 0.687707 0.332673 0.687807 0.33713 0.668641 0.370464 0.687707 0.366515 0.708632 0.332673 0.687807 0.373921 0.664434 0.33713 0.668641 0.341048 0.647356 0.373921 0.664434 0.370464 0.687707 0.33713 0.668641 0.376891 0.639198 0.341048 0.647356 0.344426 0.624287 0.376891 0.639198 0.373921 0.664434 0.341048 0.647356 0.37938 0.61235 0.344426 0.624287 0.347267 0.599743 0.37938 0.61235 0.376891 0.639198 0.344426 0.624287 0.381399 0.584204 0.347267 0.599743 0.349578 0.574007 0.381399 0.584204 0.37938 0.61235 0.347267 0.599743 0.382958 0.555051 0.349578 0.574007 0.351366 0.54734 0.382958 0.555051 0.381399 0.584204 0.349578 0.574007 0.384065 0.525159 0.351366 0.54734 0.352639 0.51999 0.384065 0.525159 0.382958 0.555051 0.351366 0.54734 0.384726 0.494784 0.352639 0.51999 0.3534 0.492191 0.384726 0.494784 0.384065 0.525159 0.352639 0.51999 0.222245 0.765625 0.28051 0.698537 0.308761 0.720995 0.222245 0.765625 0.199668 0.743895 0.28051 0.698537 0.246682 0.785572 0.308761 0.720995 0.320742 0.729004 0.246682 0.785572 0.222245 0.765625 0.308761 0.720995 0.340349 0.740468 0.320742 0.729004 0.327189 0.746424 0.272861 0.803563 0.320742 0.729004 0.340349 0.740468 0.272861 0.803563 0.246682 0.785572 0.320742 0.729004 0.37651 0.772157 0.327189 0.746424 0.333602 0.756916 0.371388 0.758681 0.340349 0.740468 0.327189 0.746424 0.37651 0.772157 0.371388 0.758681 0.327189 0.746424 0.381429 0.778496 0.333602 0.756916 0.339928 0.761014 0.381429 0.778496 0.37651 0.772157 0.333602 0.756916 0.386186 0.778403 0.339928 0.761014 0.346026 0.75939 0.386186 0.778403 0.381429 0.778496 0.339928 0.761014 0.390693 0.772674 0.346026 0.75939 0.351795 0.752721 0.390693 0.772674 0.386186 0.778403 0.346026 0.75939 0.394889 0.762059 0.351795 0.752721 0.357161 0.741651 0.394889 0.762059 0.390693 0.772674 0.351795 0.752721 0.398735 0.747244 0.357161 0.741651 0.362077 0.726775 0.398735 0.747244 0.394889 0.762059 0.357161 0.741651 0.402209 0.728842 0.362077 0.726775 0.366515 0.708632 0.402209 0.728842 0.398735 0.747244 0.362077 0.726775 0.405303 0.707397 0.366515 0.708632 0.370464 0.687707 0.405303 0.707397 0.402209 0.728842 0.366515 0.708632 0.408016 0.683391 0.370464 0.687707 0.373921 0.664434 0.408016 0.683391 0.405303 0.707397 0.370464 0.687707 0.410354 0.657247 0.373921 0.664434 0.376891 0.639198 0.410354 0.657247 0.408016 0.683391 0.373921 0.664434 0.412326 0.629343 0.376891 0.639198 0.37938 0.61235 0.412326 0.629343 0.410354 0.657247 0.376891 0.639198 0.41394 0.600017 0.37938 0.61235 0.381399 0.584204 0.41394 0.600017 0.412326 0.629343 0.37938 0.61235 0.414748 0.569488 0.381399 0.584204 0.382958 0.555051 0.415223 0.569655 0.41394 0.600017 0.381399 0.584204 0.414748 0.569488 0.415223 0.569655 0.381399 0.584204 0.406425 0.553508 0.382958 0.555051 0.384065 0.525159 0.412891 0.568276 0.414748 0.569488 0.382958 0.555051 0.411038 0.566117 0.412891 0.568276 0.382958 0.555051 0.409297 0.563008 0.411038 0.566117 0.382958 0.555051 0.407729 0.558856 0.409297 0.563008 0.382958 0.555051 0.406425 0.553508 0.407729 0.558856 0.382958 0.555051 0.403137 0.508277 0.384065 0.525159 0.384726 0.494784 0.405529 0.546743 0.406425 0.553508 0.384065 0.525159 0.404148 0.527588 0.405529 0.546743 0.384065 0.525159 0.403137 0.508277 0.404148 0.527588 0.384065 0.525159 0.411651 0.508175 0.403137 0.508277 0.384726 0.494784 0.416704 0.508121 0.411651 0.508175 0.384726 0.494784 0.416933 0.486187 0.416704 0.508121 0.384726 0.494784 0.384061 0.758612 0.340349 0.740468 0.371388 0.758681 0.300639 0.819487 0.272861 0.803563 0.340349 0.740468 0.384061 0.758612 0.300639 0.819487 0.340349 0.740468 0.382023 0.763835 0.371388 0.758681 0.37651 0.772157 0.384061 0.758612 0.371388 0.758681 0.382023 0.763835 0.427423 0.788781 0.37651 0.772157 0.381429 0.778496 0.424483 0.779655 0.382023 0.763835 0.37651 0.772157 0.427423 0.788781 0.424483 0.779655 0.37651 0.772157 0.430258 0.791087 0.381429 0.778496 0.386186 0.778403 0.430258 0.791087 0.427423 0.788781 0.381429 0.778496 0.43296 0.787395 0.386186 0.778403 0.390693 0.772674 0.43296 0.787395 0.430258 0.791087 0.386186 0.778403 0.43549 0.778501 0.390693 0.772674 0.394889 0.762059 0.43549 0.778501 0.43296 0.787395 0.390693 0.772674 0.437822 0.765133 0.394889 0.762059 0.398735 0.747244 0.437822 0.765133 0.43549 0.778501 0.394889 0.762059 0.439941 0.747941 0.398735 0.747244 0.402209 0.728842 0.439941 0.747941 0.437822 0.765133 0.398735 0.747244 0.441841 0.7275 0.402209 0.728842 0.405303 0.707397 0.441841 0.7275 0.439941 0.747941 0.402209 0.728842 0.44352 0.704313 0.405303 0.707397 0.408016 0.683391 0.44352 0.704313 0.441841 0.7275 0.405303 0.707397 0.444982 0.678823 0.408016 0.683391 0.410354 0.657247 0.444982 0.678823 0.44352 0.704313 0.408016 0.683391 0.446232 0.651422 0.410354 0.657247 0.412326 0.629343 0.446232 0.651422 0.444982 0.678823 0.410354 0.657247 0.447276 0.622455 0.412326 0.629343 0.41394 0.600017 0.447276 0.622455 0.446232 0.651422 0.412326 0.629343 0.44812 0.592233 0.41394 0.600017 0.415223 0.569655 0.44812 0.592233 0.447276 0.622455 0.41394 0.600017 0.416842 0.508986 0.415223 0.569655 0.414748 0.569488 0.416456 0.56981 0.44812 0.592233 0.415223 0.569655 0.416842 0.508986 0.416456 0.56981 0.415223 0.569655 0.413467 0.509004 0.414748 0.569488 0.412891 0.568276 0.416842 0.508986 0.414748 0.569488 0.413467 0.509004 0.413467 0.509004 0.412891 0.568276 0.411038 0.566117 0.410758 0.508975 0.411038 0.566117 0.409297 0.563008 0.413467 0.509004 0.411038 0.566117 0.410758 0.508975 0.408407 0.50891 0.409297 0.563008 0.407729 0.558856 0.410758 0.508975 0.409297 0.563008 0.408407 0.50891 0.40661 0.508818 0.407729 0.558856 0.406425 0.553508 0.408407 0.50891 0.407729 0.558856 0.40661 0.508818 0.40661 0.508818 0.406425 0.553508 0.405529 0.546743 0.403137 0.508277 0.405529 0.546743 0.404148 0.527588 0.405529 0.508704 0.405529 0.546743 0.403137 0.508277 0.40661 0.508818 0.405529 0.546743 0.405529 0.508704 0.422751 0.508506 0.403137 0.508277 0.411651 0.508175 0.422989 0.508655 0.405529 0.508704 0.403137 0.508277 0.422751 0.508506 0.422989 0.508655 0.403137 0.508277 0.422751 0.508506 0.411651 0.508175 0.416704 0.508121 0.420205 0.508085 0.416704 0.508121 0.416933 0.486187 0.422751 0.508506 0.416704 0.508121 0.420205 0.508085 0.420205 0.508085 0.416933 0.486187 0.449505 0.496767 0.430046 0.770019 0.382023 0.763835 0.424483 0.779655 0.384061 0.758612 0.382023 0.763835 0.430046 0.770019 0.426383 0.780198 0.424483 0.779655 0.427423 0.788781 0.430046 0.770019 0.424483 0.779655 0.426383 0.780198 0.47792 0.795799 0.427423 0.788781 0.430258 0.791087 0.472223 0.789415 0.426383 0.780198 0.427423 0.788781 0.477271 0.78999 0.472223 0.789415 0.427423 0.788781 0.47792 0.795799 0.477271 0.78999 0.427423 0.788781 0.478496 0.795665 0.430258 0.791087 0.43296 0.787395 0.478496 0.795665 0.47792 0.795799 0.430258 0.791087 0.479043 0.790299 0.43296 0.787395 0.43549 0.778501 0.479043 0.790299 0.478496 0.795665 0.43296 0.787395 0.479553 0.780388 0.43549 0.778501 0.437822 0.765133 0.479553 0.780388 0.479043 0.790299 0.43549 0.778501 0.464601 0.761951 0.437822 0.765133 0.439941 0.747941 0.479948 0.766601 0.479553 0.780388 0.437822 0.765133 0.472116 0.764864 0.479948 0.766601 0.437822 0.765133 0.464601 0.761951 0.472116 0.764864 0.437822 0.765133 0.45386 0.748783 0.439941 0.747941 0.441841 0.7275 0.458722 0.758108 0.464601 0.761951 0.439941 0.747941 0.45507 0.753662 0.458722 0.758108 0.439941 0.747941 0.45386 0.748783 0.45507 0.753662 0.439941 0.747941 0.481164 0.707682 0.441841 0.7275 0.44352 0.704313 0.455311 0.743883 0.45386 0.748783 0.441841 0.7275 0.459283 0.739384 0.455311 0.743883 0.441841 0.7275 0.465401 0.735601 0.459283 0.739384 0.441841 0.7275 0.473177 0.732758 0.465401 0.735601 0.441841 0.7275 0.480751 0.731186 0.473177 0.732758 0.441841 0.7275 0.481164 0.707682 0.480751 0.731186 0.441841 0.7275 0.481479 0.681784 0.44352 0.704313 0.444982 0.678823 0.481479 0.681784 0.481164 0.707682 0.44352 0.704313 0.481749 0.653965 0.444982 0.678823 0.446232 0.651422 0.481749 0.653965 0.481479 0.681784 0.444982 0.678823 0.481974 0.624578 0.446232 0.651422 0.447276 0.622455 0.481974 0.624578 0.481749 0.653965 0.446232 0.651422 0.482155 0.593933 0.447276 0.622455 0.44812 0.592233 0.482155 0.593933 0.481974 0.624578 0.447276 0.622455 0.422053 0.562599 0.44877 0.56104 0.44812 0.592233 0.482295 0.562315 0.44812 0.592233 0.44877 0.56104 0.420984 0.56577 0.422053 0.562599 0.44812 0.592233 0.419629 0.568016 0.420984 0.56577 0.44812 0.592233 0.418079 0.569347 0.419629 0.568016 0.44812 0.592233 0.416456 0.56981 0.418079 0.569347 0.44812 0.592233 0.482295 0.562315 0.482155 0.593933 0.44812 0.592233 0.422751 0.546378 0.449231 0.529136 0.44877 0.56104 0.482394 0.529987 0.44877 0.56104 0.449231 0.529136 0.423052 0.553079 0.422751 0.546378 0.44877 0.56104 0.422773 0.558418 0.423052 0.553079 0.44877 0.56104 0.422053 0.562599 0.422773 0.558418 0.44877 0.56104 0.482394 0.529987 0.482295 0.562315 0.44877 0.56104 0.420205 0.508085 0.449505 0.496767 0.449231 0.529136 0.482454 0.497193 0.449231 0.529136 0.449505 0.496767 0.421281 0.527312 0.420205 0.508085 0.449231 0.529136 0.422751 0.546378 0.421281 0.527312 0.449231 0.529136 0.482454 0.497193 0.482394 0.529987 0.449231 0.529136 0.422751 0.508506 0.420205 0.508085 0.421281 0.527312 0.422751 0.508506 0.421281 0.527312 0.422751 0.546378 0.422751 0.508506 0.422751 0.546378 0.423052 0.553079 0.422989 0.508655 0.423052 0.553079 0.422773 0.558418 0.422751 0.508506 0.423052 0.553079 0.422989 0.508655 0.422989 0.508655 0.422773 0.558418 0.422053 0.562599 0.421962 0.508798 0.422053 0.562599 0.420984 0.56577 0.422989 0.508655 0.422053 0.562599 0.421962 0.508798 0.419813 0.508914 0.420984 0.56577 0.419629 0.568016 0.421962 0.508798 0.420984 0.56577 0.419813 0.508914 0.419813 0.508914 0.419629 0.568016 0.418079 0.569347 0.416842 0.508986 0.418079 0.569347 0.416456 0.56981 0.419813 0.508914 0.418079 0.569347 0.416842 0.508986 0.477244 0.774525 0.426383 0.780198 0.472223 0.789415 0.430046 0.770019 0.426383 0.780198 0.477244 0.774525 0.477244 0.774525 0.472223 0.789415 0.477271 0.78999 0.518333 0.791554 0.477271 0.78999 0.47792 0.795799 0.524176 0.772134 0.477271 0.78999 0.518333 0.791554 0.477244 0.774525 0.477271 0.78999 0.524176 0.772134 0.527205 0.794779 0.47792 0.795799 0.478496 0.795665 0.528724 0.791077 0.518333 0.791554 0.47792 0.795799 0.527205 0.794779 0.528724 0.791077 0.47792 0.795799 0.525669 0.792817 0.478496 0.795665 0.479043 0.790299 0.525669 0.792817 0.527205 0.794779 0.478496 0.795665 0.524219 0.785867 0.479043 0.790299 0.479553 0.780388 0.524219 0.785867 0.525669 0.792817 0.479043 0.790299 0.522871 0.774591 0.479553 0.780388 0.479948 0.766601 0.522871 0.774591 0.524219 0.785867 0.479553 0.780388 0.480303 0.703615 0.479948 0.766601 0.472116 0.764864 0.481228 0.76679 0.522871 0.774591 0.479948 0.766601 0.480303 0.703615 0.481228 0.76679 0.479948 0.766601 0.470261 0.702505 0.472116 0.764864 0.464601 0.761951 0.470261 0.702505 0.480303 0.703615 0.472116 0.764864 0.462164 0.7008 0.464601 0.761951 0.458722 0.758108 0.462164 0.7008 0.470261 0.702505 0.464601 0.761951 0.456649 0.698681 0.458722 0.758108 0.45507 0.753662 0.456649 0.698681 0.462164 0.7008 0.458722 0.758108 0.45405 0.696341 0.45507 0.753662 0.45386 0.748783 0.45405 0.696341 0.456649 0.698681 0.45507 0.753662 0.45448 0.693983 0.45386 0.748783 0.455311 0.743883 0.45448 0.693983 0.45405 0.696341 0.45386 0.748783 0.457819 0.691782 0.455311 0.743883 0.459283 0.739384 0.457819 0.691782 0.45448 0.693983 0.455311 0.743883 0.463706 0.689908 0.459283 0.739384 0.465401 0.735601 0.463706 0.689908 0.457819 0.691782 0.459283 0.739384 0.471662 0.688479 0.465401 0.735601 0.473177 0.732758 0.471662 0.688479 0.463706 0.689908 0.465401 0.735601 0.471662 0.688479 0.473177 0.732758 0.480751 0.731186 0.481981 0.731017 0.480751 0.731186 0.481164 0.707682 0.481107 0.68758 0.480751 0.731186 0.481981 0.731017 0.481107 0.68758 0.471662 0.688479 0.480751 0.731186 0.518495 0.69332 0.481164 0.707682 0.481479 0.681784 0.519346 0.716496 0.481164 0.707682 0.518495 0.69332 0.491313 0.73043 0.481164 0.707682 0.519346 0.716496 0.491313 0.73043 0.481981 0.731017 0.481164 0.707682 0.517754 0.668314 0.481479 0.681784 0.481749 0.653965 0.518495 0.69332 0.481479 0.681784 0.517754 0.668314 0.51712 0.641782 0.481749 0.653965 0.481974 0.624578 0.517754 0.668314 0.481749 0.653965 0.51712 0.641782 0.516591 0.613992 0.481974 0.624578 0.482155 0.593933 0.51712 0.641782 0.481974 0.624578 0.516591 0.613992 0.516162 0.585192 0.482155 0.593933 0.482295 0.562315 0.516591 0.613992 0.482155 0.593933 0.516162 0.585192 0.515831 0.555604 0.482295 0.562315 0.482394 0.529987 0.516162 0.585192 0.482295 0.562315 0.515831 0.555604 0.515597 0.52544 0.482394 0.529987 0.482454 0.497193 0.515831 0.555604 0.482394 0.529987 0.515597 0.52544 0.515597 0.52544 0.482454 0.497193 0.515457 0.494898 0.524176 0.772134 0.518333 0.791554 0.528724 0.791077 0.563564 0.78687 0.528724 0.791077 0.527205 0.794779 0.569996 0.763027 0.528724 0.791077 0.563564 0.78687 0.524176 0.772134 0.528724 0.791077 0.569996 0.763027 0.574234 0.786396 0.527205 0.794779 0.525669 0.792817 0.57779 0.783968 0.563564 0.78687 0.527205 0.794779 0.574234 0.786396 0.57779 0.783968 0.527205 0.794779 0.570745 0.783337 0.525669 0.792817 0.524219 0.785867 0.570745 0.783337 0.574234 0.786396 0.525669 0.792817 0.567463 0.775436 0.524219 0.785867 0.522871 0.774591 0.567463 0.775436 0.570745 0.783337 0.524219 0.785867 0.518594 0.76166 0.521928 0.759642 0.522871 0.774591 0.564421 0.763339 0.522871 0.774591 0.521928 0.759642 0.510578 0.764842 0.518594 0.76166 0.522871 0.774591 0.501216 0.766814 0.510578 0.764842 0.522871 0.774591 0.491313 0.767471 0.501216 0.766814 0.522871 0.774591 0.481228 0.76679 0.491313 0.767471 0.522871 0.774591 0.564421 0.763339 0.567463 0.775436 0.522871 0.774591 0.520307 0.700844 0.521928 0.759642 0.518594 0.76166 0.524516 0.757552 0.564421 0.763339 0.521928 0.759642 0.525869 0.69874 0.524516 0.757552 0.521928 0.759642 0.520307 0.700844 0.525869 0.69874 0.521928 0.759642 0.512241 0.702525 0.518594 0.76166 0.510578 0.764842 0.512241 0.702525 0.520307 0.700844 0.518594 0.76166 0.502279 0.703618 0.510578 0.764842 0.501216 0.766814 0.502279 0.703618 0.512241 0.702525 0.510578 0.764842 0.502279 0.703618 0.501216 0.766814 0.491313 0.767471 0.491313 0.703997 0.491313 0.767471 0.481228 0.76679 0.491313 0.703997 0.502279 0.703618 0.491313 0.767471 0.480303 0.703615 0.491313 0.703997 0.481228 0.76679 0.569996 0.763027 0.563564 0.78687 0.57779 0.783968 0.606891 0.775769 0.57779 0.783968 0.574234 0.786396 0.592108 0.756055 0.57779 0.783968 0.606891 0.775769 0.569996 0.763027 0.57779 0.783968 0.592108 0.756055 0.618231 0.77147 0.574234 0.786396 0.570745 0.783337 0.623566 0.769615 0.606891 0.775769 0.574234 0.786396 0.618231 0.77147 0.623566 0.769615 0.574234 0.786396 0.613046 0.76793 0.570745 0.783337 0.567463 0.775436 0.613046 0.76793 0.618231 0.77147 0.570745 0.783337 0.608173 0.759614 0.567463 0.775436 0.564421 0.763339 0.608173 0.759614 0.613046 0.76793 0.567463 0.775436 0.524516 0.757552 0.561639 0.747624 0.564421 0.763339 0.603664 0.747152 0.564421 0.763339 0.561639 0.747624 0.603664 0.747152 0.608173 0.759614 0.564421 0.763339 0.52053 0.737394 0.559127 0.728811 0.561639 0.747624 0.599549 0.731115 0.561639 0.747624 0.559127 0.728811 0.522683 0.738864 0.52053 0.737394 0.561639 0.747624 0.526821 0.743099 0.522683 0.738864 0.561639 0.747624 0.528699 0.74787 0.526821 0.743099 0.561639 0.747624 0.527952 0.752834 0.528699 0.74787 0.561639 0.747624 0.524516 0.757552 0.527952 0.752834 0.561639 0.747624 0.599549 0.731115 0.603664 0.747152 0.561639 0.747624 0.519346 0.716496 0.556888 0.707357 0.559127 0.728811 0.595845 0.712015 0.559127 0.728811 0.556888 0.707357 0.52053 0.737394 0.519346 0.716496 0.559127 0.728811 0.595845 0.712015 0.599549 0.731115 0.559127 0.728811 0.518495 0.69332 0.55492 0.683668 0.556888 0.707357 0.592558 0.690311 0.556888 0.707357 0.55492 0.683668 0.519346 0.716496 0.518495 0.69332 0.556888 0.707357 0.592558 0.690311 0.595845 0.712015 0.556888 0.707357 0.517754 0.668314 0.553217 0.658104 0.55492 0.683668 0.589686 0.666409 0.55492 0.683668 0.553217 0.658104 0.518495 0.69332 0.517754 0.668314 0.55492 0.683668 0.589686 0.666409 0.592558 0.690311 0.55492 0.683668 0.51712 0.641782 0.551774 0.630984 0.553217 0.658104 0.587224 0.640672 0.553217 0.658104 0.551774 0.630984 0.517754 0.668314 0.51712 0.641782 0.553217 0.658104 0.587224 0.640672 0.589686 0.666409 0.553217 0.658104 0.516591 0.613992 0.550583 0.602597 0.551774 0.630984 0.585161 0.613427 0.551774 0.630984 0.550583 0.602597 0.51712 0.641782 0.516591 0.613992 0.551774 0.630984 0.585161 0.613427 0.587224 0.640672 0.551774 0.630984 0.516162 0.585192 0.549637 0.573205 0.550583 0.602597 0.583489 0.584969 0.550583 0.602597 0.549637 0.573205 0.516591 0.613992 0.516162 0.585192 0.550583 0.602597 0.583489 0.584969 0.585161 0.613427 0.550583 0.602597 0.547207 0.545699 0.54893 0.54305 0.549637 0.573205 0.5822 0.555569 0.549637 0.573205 0.54893 0.54305 0.54655 0.552422 0.547207 0.545699 0.549637 0.573205 0.545444 0.557749 0.54655 0.552422 0.549637 0.573205 0.544037 0.561892 0.545444 0.557749 0.549637 0.573205 0.542423 0.565005 0.544037 0.561892 0.549637 0.573205 0.540667 0.56718 0.542423 0.565005 0.549637 0.573205 0.538868 0.568433 0.540667 0.56718 0.549637 0.573205 0.537146 0.568819 0.538868 0.568433 0.549637 0.573205 0.535473 0.568419 0.537146 0.568819 0.549637 0.573205 0.516162 0.585192 0.535473 0.568419 0.549637 0.573205 0.5822 0.555569 0.583489 0.584969 0.549637 0.573205 0.548011 0.526904 0.548484 0.512361 0.54893 0.54305 0.581284 0.525478 0.54893 0.54305 0.548484 0.512361 0.547207 0.545699 0.548011 0.526904 0.54893 0.54305 0.581284 0.525478 0.5822 0.555569 0.54893 0.54305 0.547207 0.508384 0.548484 0.512361 0.548011 0.526904 0.548601 0.507962 0.581284 0.525478 0.548484 0.512361 0.547207 0.508384 0.548601 0.507962 0.548484 0.512361 0.547207 0.508384 0.548011 0.526904 0.547207 0.545699 0.547207 0.508384 0.547207 0.545699 0.54655 0.552422 0.546258 0.508512 0.54655 0.552422 0.545444 0.557749 0.547207 0.508384 0.54655 0.552422 0.546258 0.508512 0.54441 0.508617 0.545444 0.557749 0.544037 0.561892 0.546258 0.508512 0.545444 0.557749 0.54441 0.508617 0.54441 0.508617 0.544037 0.561892 0.542423 0.565005 0.541865 0.508689 0.542423 0.565005 0.540667 0.56718 0.54441 0.508617 0.542423 0.565005 0.541865 0.508689 0.538883 0.508719 0.540667 0.56718 0.538868 0.568433 0.541865 0.508689 0.540667 0.56718 0.538883 0.508719 0.538883 0.508719 0.538868 0.568433 0.537146 0.568819 0.535762 0.5087 0.537146 0.568819 0.535473 0.568419 0.538883 0.508719 0.537146 0.568819 0.535762 0.5087 0.515831 0.555604 0.533805 0.567123 0.535473 0.568419 0.535762 0.5087 0.535473 0.568419 0.533805 0.567123 0.516162 0.585192 0.515831 0.555604 0.535473 0.568419 0.515831 0.555604 0.532307 0.564888 0.533805 0.567123 0.532995 0.508635 0.533805 0.567123 0.532307 0.564888 0.535762 0.5087 0.533805 0.567123 0.532995 0.508635 0.515831 0.555604 0.531075 0.561722 0.532307 0.564888 0.532995 0.508635 0.532307 0.564888 0.531075 0.561722 0.515831 0.555604 0.530168 0.557538 0.531075 0.561722 0.53092 0.508531 0.531075 0.561722 0.530168 0.557538 0.532995 0.508635 0.531075 0.561722 0.53092 0.508531 0.515831 0.555604 0.529676 0.552191 0.530168 0.557538 0.529789 0.508403 0.530168 0.557538 0.529676 0.552191 0.53092 0.508531 0.530168 0.557538 0.529789 0.508403 0.515597 0.52544 0.529741 0.54548 0.529676 0.552191 0.529789 0.508403 0.529676 0.552191 0.529741 0.54548 0.515831 0.555604 0.515597 0.52544 0.529676 0.552191 0.531298 0.507846 0.529741 0.54548 0.530638 0.526738 0.515597 0.52544 0.530638 0.526738 0.529741 0.54548 0.529741 0.508265 0.529741 0.54548 0.531298 0.507846 0.529789 0.508403 0.529741 0.54548 0.529741 0.508265 0.515597 0.52544 0.531298 0.507846 0.530638 0.526738 0.548409 0.50796 0.531298 0.507846 0.539962 0.507898 0.515457 0.494898 0.539962 0.507898 0.531298 0.507846 0.548601 0.507962 0.531298 0.507846 0.548409 0.50796 0.515597 0.52544 0.515457 0.494898 0.531298 0.507846 0.529741 0.508265 0.531298 0.507846 0.548601 0.507962 0.515457 0.494898 0.548409 0.50796 0.539962 0.507898 0.515457 0.494898 0.548238 0.486101 0.548409 0.50796 0.580738 0.494935 0.548409 0.50796 0.548238 0.486101 0.548601 0.507962 0.548409 0.50796 0.580738 0.494935 0.516694 0.735353 0.519346 0.716496 0.52053 0.737394 0.500525 0.731002 0.491313 0.73043 0.519346 0.716496 0.50915 0.732677 0.500525 0.731002 0.519346 0.716496 0.516694 0.735353 0.50915 0.732677 0.519346 0.716496 0.519076 0.689946 0.52053 0.737394 0.522683 0.738864 0.519076 0.689946 0.516694 0.735353 0.52053 0.737394 0.524927 0.691836 0.522683 0.738864 0.526821 0.743099 0.524927 0.691836 0.519076 0.689946 0.522683 0.738864 0.528193 0.694041 0.526821 0.743099 0.528699 0.74787 0.528193 0.694041 0.524927 0.691836 0.526821 0.743099 0.528548 0.6964 0.528699 0.74787 0.527952 0.752834 0.528548 0.6964 0.528193 0.694041 0.528699 0.74787 0.525869 0.69874 0.527952 0.752834 0.524516 0.757552 0.525869 0.69874 0.528548 0.6964 0.527952 0.752834 0.613496 0.747551 0.606891 0.775769 0.623566 0.769615 0.592108 0.756055 0.606891 0.775769 0.613496 0.747551 0.647436 0.758779 0.623566 0.769615 0.618231 0.77147 0.634006 0.73761 0.623566 0.769615 0.647436 0.758779 0.613496 0.747551 0.623566 0.769615 0.634006 0.73761 0.658881 0.750813 0.618231 0.77147 0.613046 0.76793 0.665359 0.748911 0.647436 0.758779 0.618231 0.77147 0.658881 0.750813 0.665359 0.748911 0.618231 0.77147 0.652578 0.747767 0.613046 0.76793 0.608173 0.759614 0.652578 0.747767 0.658881 0.750813 0.613046 0.76793 0.646627 0.740292 0.608173 0.759614 0.603664 0.747152 0.646627 0.740292 0.652578 0.747767 0.608173 0.759614 0.641093 0.72893 0.603664 0.747152 0.599549 0.731115 0.641093 0.72893 0.646627 0.740292 0.603664 0.747152 0.636021 0.71419 0.599549 0.731115 0.595845 0.712015 0.636021 0.71419 0.641093 0.72893 0.599549 0.731115 0.631436 0.696533 0.595845 0.712015 0.592558 0.690311 0.631436 0.696533 0.636021 0.71419 0.595845 0.712015 0.62735 0.676378 0.592558 0.690311 0.589686 0.666409 0.62735 0.676378 0.631436 0.696533 0.592558 0.690311 0.623768 0.654103 0.589686 0.666409 0.587224 0.640672 0.623768 0.654103 0.62735 0.676378 0.589686 0.666409 0.620685 0.63005 0.587224 0.640672 0.585161 0.613427 0.620685 0.63005 0.623768 0.654103 0.587224 0.640672 0.618097 0.604529 0.585161 0.613427 0.583489 0.584969 0.618097 0.604529 0.620685 0.63005 0.585161 0.613427 0.615994 0.577823 0.583489 0.584969 0.5822 0.555569 0.615994 0.577823 0.618097 0.604529 0.583489 0.584969 0.614369 0.550195 0.5822 0.555569 0.581284 0.525478 0.614369 0.550195 0.615994 0.577823 0.5822 0.555569 0.548601 0.507962 0.580738 0.494935 0.581284 0.525478 0.613214 0.52189 0.581284 0.525478 0.580738 0.494935 0.613214 0.52189 0.614369 0.550195 0.581284 0.525478 0.612524 0.493139 0.613214 0.52189 0.580738 0.494935 0.547207 0.508384 0.529741 0.508265 0.548601 0.507962 0.653612 0.726273 0.647436 0.758779 0.665359 0.748911 0.634006 0.73761 0.647436 0.758779 0.653612 0.726273 0.684541 0.736483 0.665359 0.748911 0.658881 0.750813 0.67229 0.713565 0.665359 0.748911 0.684541 0.736483 0.653612 0.726273 0.665359 0.748911 0.67229 0.713565 0.695533 0.725071 0.658881 0.750813 0.652578 0.747767 0.702701 0.722671 0.684541 0.736483 0.658881 0.750813 0.695533 0.725071 0.702701 0.722671 0.658881 0.750813 0.688537 0.722875 0.652578 0.747767 0.646627 0.740292 0.688537 0.722875 0.695533 0.725071 0.652578 0.747767 0.681892 0.716517 0.646627 0.740292 0.641093 0.72893 0.681892 0.716517 0.688537 0.722875 0.646627 0.740292 0.675681 0.706468 0.641093 0.72893 0.636021 0.71419 0.675681 0.706468 0.681892 0.716517 0.641093 0.72893 0.669961 0.693182 0.636021 0.71419 0.631436 0.696533 0.669961 0.693182 0.675681 0.706468 0.636021 0.71419 0.664769 0.677079 0.631436 0.696533 0.62735 0.676378 0.664769 0.677079 0.669961 0.693182 0.631436 0.696533 0.660128 0.658549 0.62735 0.676378 0.623768 0.654103 0.660128 0.658549 0.664769 0.677079 0.62735 0.676378 0.65605 0.637949 0.623768 0.654103 0.620685 0.63005 0.65605 0.637949 0.660128 0.658549 0.623768 0.654103 0.652538 0.615608 0.620685 0.63005 0.618097 0.604529 0.652538 0.615608 0.65605 0.637949 0.620685 0.63005 0.64959 0.591826 0.618097 0.604529 0.615994 0.577823 0.64959 0.591826 0.652538 0.615608 0.618097 0.604529 0.637531 0.571221 0.615994 0.577823 0.614369 0.550195 0.641932 0.5727 0.64959 0.591826 0.615994 0.577823 0.640307 0.573046 0.641932 0.5727 0.615994 0.577823 0.63885 0.572593 0.640307 0.573046 0.615994 0.577823 0.637531 0.571221 0.63885 0.572593 0.615994 0.577823 0.639828 0.529174 0.614369 0.550195 0.613214 0.52189 0.636505 0.568879 0.637531 0.571221 0.614369 0.550195 0.635856 0.565577 0.636505 0.568879 0.614369 0.550195 0.63564 0.561228 0.635856 0.565577 0.614369 0.550195 0.63594 0.555692 0.63564 0.561228 0.614369 0.550195 0.636884 0.548758 0.63594 0.555692 0.614369 0.550195 0.639828 0.529174 0.636884 0.548758 0.614369 0.550195 0.641987 0.509397 0.613214 0.52189 0.612524 0.493139 0.641987 0.509397 0.639828 0.529174 0.613214 0.52189 0.643903 0.509443 0.641987 0.509397 0.612524 0.493139 0.643332 0.486877 0.643903 0.509443 0.612524 0.493139 0.689902 0.699589 0.684541 0.736483 0.702701 0.722671 0.67229 0.713565 0.684541 0.736483 0.689902 0.699589 0.717583 0.709613 0.702701 0.722671 0.695533 0.725071 0.706344 0.684452 0.702701 0.722671 0.717583 0.709613 0.689902 0.699589 0.702701 0.722671 0.706344 0.684452 0.720963 0.693973 0.695533 0.725071 0.688537 0.722875 0.72806 0.694845 0.717583 0.709613 0.695533 0.725071 0.720963 0.693973 0.72806 0.694845 0.695533 0.725071 0.71416 0.689345 0.688537 0.722875 0.681892 0.716517 0.71416 0.689345 0.720963 0.693973 0.688537 0.722875 0.707742 0.681336 0.681892 0.716517 0.675681 0.706468 0.707742 0.681336 0.71416 0.689345 0.681892 0.716517 0.70178 0.670318 0.675681 0.706468 0.669961 0.693182 0.70178 0.670318 0.707742 0.681336 0.675681 0.706468 0.696323 0.656649 0.669961 0.693182 0.664769 0.677079 0.696323 0.656649 0.70178 0.670318 0.669961 0.693182 0.691407 0.640671 0.664769 0.677079 0.660128 0.658549 0.691407 0.640671 0.696323 0.656649 0.664769 0.677079 0.687052 0.622701 0.660128 0.658549 0.65605 0.637949 0.687052 0.622701 0.691407 0.640671 0.660128 0.658549 0.683273 0.603041 0.65605 0.637949 0.652538 0.615608 0.683273 0.603041 0.687052 0.622701 0.65605 0.637949 0.680075 0.581969 0.652538 0.615608 0.64959 0.591826 0.680075 0.581969 0.683273 0.603041 0.652538 0.615608 0.645697 0.569309 0.647203 0.566972 0.64959 0.591826 0.677462 0.559748 0.64959 0.591826 0.647203 0.566972 0.643762 0.571476 0.645697 0.569309 0.64959 0.591826 0.641932 0.5727 0.643762 0.571476 0.64959 0.591826 0.677462 0.559748 0.680075 0.581969 0.64959 0.591826 0.646228 0.510424 0.647203 0.566972 0.645697 0.569309 0.64764 0.566175 0.677462 0.559748 0.647203 0.566972 0.64886 0.510386 0.64764 0.566175 0.647203 0.566972 0.64886 0.510386 0.647203 0.566972 0.646228 0.510424 0.646228 0.510424 0.645697 0.569309 0.643762 0.571476 0.642763 0.510419 0.643762 0.571476 0.641932 0.5727 0.646228 0.510424 0.643762 0.571476 0.642763 0.510419 0.642763 0.510419 0.641932 0.5727 0.640307 0.573046 0.63962 0.510355 0.640307 0.573046 0.63885 0.572593 0.642763 0.510419 0.640307 0.573046 0.63962 0.510355 0.63962 0.510355 0.63885 0.572593 0.637531 0.571221 0.637217 0.510243 0.637531 0.571221 0.636505 0.568879 0.63962 0.510355 0.637531 0.571221 0.637217 0.510243 0.635865 0.5101 0.636505 0.568879 0.635856 0.565577 0.637217 0.510243 0.636505 0.568879 0.635865 0.5101 0.635865 0.5101 0.635856 0.565577 0.63564 0.561228 0.635744 0.509944 0.63564 0.561228 0.63594 0.555692 0.635865 0.5101 0.63564 0.561228 0.635744 0.509944 0.635744 0.509944 0.63594 0.555692 0.636884 0.548758 0.641987 0.509397 0.636884 0.548758 0.639828 0.529174 0.636884 0.509797 0.636884 0.548758 0.641987 0.509397 0.635744 0.509944 0.636884 0.548758 0.636884 0.509797 0.636884 0.509797 0.641987 0.509397 0.643903 0.509443 0.673116 0.488612 0.643903 0.509443 0.643332 0.486877 0.649949 0.509594 0.643903 0.509443 0.673116 0.488612 0.636884 0.509797 0.643903 0.509443 0.649949 0.509594 0.72806 0.694845 0.735213 0.691697 0.717583 0.709613 0.721573 0.668223 0.717583 0.709613 0.735213 0.691697 0.706344 0.684452 0.717583 0.709613 0.721573 0.668223 0.75604 0.660637 0.735213 0.691697 0.72806 0.694845 0.75604 0.660637 0.74655 0.678472 0.735213 0.691697 0.735533 0.650987 0.735213 0.691697 0.74655 0.678472 0.721573 0.668223 0.735213 0.691697 0.735533 0.650987 0.749226 0.661231 0.72806 0.694845 0.720963 0.693973 0.749226 0.661231 0.75604 0.660637 0.72806 0.694845 0.742622 0.65843 0.720963 0.693973 0.71416 0.689345 0.742622 0.65843 0.749226 0.661231 0.720963 0.693973 0.736329 0.652521 0.71416 0.689345 0.707742 0.681336 0.736329 0.652521 0.742622 0.65843 0.71416 0.689345 0.730428 0.643805 0.707742 0.681336 0.70178 0.670318 0.730428 0.643805 0.736329 0.652521 0.707742 0.681336 0.724983 0.632582 0.70178 0.670318 0.696323 0.656649 0.724983 0.632582 0.730428 0.643805 0.70178 0.670318 0.720039 0.61915 0.696323 0.656649 0.691407 0.640671 0.720039 0.61915 0.724983 0.632582 0.696323 0.656649 0.715632 0.603797 0.691407 0.640671 0.687052 0.622701 0.715632 0.603797 0.720039 0.61915 0.691407 0.640671 0.711785 0.586796 0.687052 0.622701 0.683273 0.603041 0.711785 0.586796 0.715632 0.603797 0.687052 0.622701 0.708515 0.568411 0.683273 0.603041 0.680075 0.581969 0.708515 0.568411 0.711785 0.586796 0.683273 0.603041 0.705831 0.548892 0.680075 0.581969 0.677462 0.559748 0.705831 0.548892 0.708515 0.568411 0.680075 0.581969 0.652814 0.549528 0.675432 0.536626 0.677462 0.559748 0.70374 0.52848 0.677462 0.559748 0.675432 0.536626 0.651309 0.556499 0.652814 0.549528 0.677462 0.559748 0.649539 0.561964 0.651309 0.556499 0.677462 0.559748 0.64764 0.566175 0.649539 0.561964 0.677462 0.559748 0.70374 0.52848 0.705831 0.548892 0.677462 0.559748 0.655704 0.529756 0.673984 0.512839 0.675432 0.536626 0.702244 0.507407 0.675432 0.536626 0.673984 0.512839 0.652814 0.549528 0.655704 0.529756 0.675432 0.536626 0.702244 0.507407 0.70374 0.52848 0.675432 0.536626 0.657821 0.509802 0.673116 0.488612 0.673984 0.512839 0.701346 0.485896 0.673984 0.512839 0.673116 0.488612 0.655704 0.529756 0.657821 0.509802 0.673984 0.512839 0.701346 0.485896 0.702244 0.507407 0.673984 0.512839 0.657821 0.509802 0.649949 0.509594 0.673116 0.488612 0.636884 0.509797 0.649949 0.509594 0.657821 0.509802 0.652814 0.510213 0.657821 0.509802 0.655704 0.529756 0.635744 0.509944 0.636884 0.509797 0.657821 0.509802 0.635865 0.5101 0.635744 0.509944 0.657821 0.509802 0.652814 0.510213 0.635865 0.5101 0.657821 0.509802 0.652814 0.510213 0.655704 0.529756 0.652814 0.549528 0.652814 0.510213 0.652814 0.549528 0.651309 0.556499 0.651124 0.510313 0.651309 0.556499 0.649539 0.561964 0.652814 0.510213 0.651309 0.556499 0.651124 0.510313 0.64886 0.510386 0.649539 0.561964 0.64764 0.566175 0.651124 0.510313 0.649539 0.561964 0.64886 0.510386 0.75604 0.660637 0.76312 0.656056 0.74655 0.678472 0.748194 0.632799 0.74655 0.678472 0.76312 0.656056 0.735533 0.650987 0.74655 0.678472 0.748194 0.632799 0.779297 0.622814 0.76312 0.656056 0.75604 0.660637 0.779297 0.622814 0.770096 0.645231 0.76312 0.656056 0.748194 0.632799 0.76312 0.656056 0.770096 0.645231 0.773158 0.624997 0.75604 0.660637 0.749226 0.661231 0.773158 0.624997 0.779297 0.622814 0.75604 0.660637 0.76712 0.62417 0.749226 0.661231 0.742622 0.65843 0.76712 0.62417 0.773158 0.624997 0.749226 0.661231 0.761293 0.620529 0.742622 0.65843 0.736329 0.652521 0.761293 0.620529 0.76712 0.62417 0.742622 0.65843 0.755765 0.6143 0.736329 0.652521 0.730428 0.643805 0.755765 0.6143 0.761293 0.620529 0.736329 0.652521 0.750611 0.605724 0.730428 0.643805 0.724983 0.632582 0.750611 0.605724 0.755765 0.6143 0.730428 0.643805 0.74589 0.595052 0.724983 0.632582 0.720039 0.61915 0.74589 0.595052 0.750611 0.605724 0.724983 0.632582 0.741649 0.582534 0.720039 0.61915 0.715632 0.603797 0.741649 0.582534 0.74589 0.595052 0.720039 0.61915 0.737925 0.568418 0.715632 0.603797 0.711785 0.586796 0.737925 0.568418 0.741649 0.582534 0.715632 0.603797 0.7191 0.579932 0.711785 0.586796 0.708515 0.568411 0.723207 0.5791 0.737925 0.568418 0.711785 0.586796 0.72153 0.580274 0.723207 0.5791 0.711785 0.586796 0.720177 0.580525 0.72153 0.580274 0.711785 0.586796 0.7191 0.579932 0.720177 0.580525 0.711785 0.586796 0.721356 0.554478 0.708515 0.568411 0.705831 0.548892 0.718299 0.578363 0.7191 0.579932 0.708515 0.568411 0.717904 0.575795 0.718299 0.578363 0.708515 0.568411 0.717958 0.572243 0.717904 0.575795 0.708515 0.568411 0.718502 0.567616 0.717958 0.572243 0.708515 0.568411 0.719603 0.561765 0.718502 0.567616 0.708515 0.568411 0.721356 0.554478 0.719603 0.561765 0.708515 0.568411 0.726171 0.533478 0.705831 0.548892 0.70374 0.52848 0.726171 0.533478 0.721356 0.554478 0.705831 0.548892 0.729561 0.513195 0.70374 0.52848 0.702244 0.507407 0.728073 0.523001 0.726171 0.533478 0.70374 0.52848 0.729561 0.513195 0.728073 0.523001 0.70374 0.52848 0.728394 0.4971 0.702244 0.507407 0.701346 0.485896 0.728394 0.4971 0.729561 0.513195 0.702244 0.507407 0.727701 0.480709 0.728394 0.4971 0.701346 0.485896 0.779297 0.622814 0.785517 0.617226 0.770096 0.645231 0.759537 0.61369 0.770096 0.645231 0.785517 0.617226 0.748194 0.632799 0.770096 0.645231 0.759537 0.61369 0.798712 0.580257 0.785517 0.617226 0.779297 0.622814 0.798712 0.580257 0.786559 0.615073 0.785517 0.617226 0.774305 0.604159 0.785517 0.617226 0.786559 0.615073 0.767754 0.614538 0.759537 0.61369 0.785517 0.617226 0.768708 0.613713 0.767754 0.614538 0.785517 0.617226 0.770153 0.611737 0.768708 0.613713 0.785517 0.617226 0.772045 0.608548 0.770153 0.611737 0.785517 0.617226 0.774305 0.604159 0.772045 0.608548 0.785517 0.617226 0.794352 0.584226 0.779297 0.622814 0.773158 0.624997 0.794352 0.584226 0.798712 0.580257 0.779297 0.622814 0.785549 0.586453 0.773158 0.624997 0.76712 0.62417 0.789942 0.586269 0.794352 0.584226 0.773158 0.624997 0.785549 0.586453 0.789942 0.586269 0.773158 0.624997 0.781752 0.592544 0.76712 0.62417 0.761293 0.620529 0.457819 0.691782 0.456649 0.698681 0.45448 0.693983 0.783441 0.590142 0.785549 0.586453 0.76712 0.62417 0.781752 0.592544 0.783441 0.590142 0.76712 0.62417 0.776612 0.580949 0.761293 0.620529 0.755765 0.6143 0.780487 0.593793 0.781752 0.592544 0.761293 0.620529 0.77969 0.593982 0.780487 0.593793 0.761293 0.620529 0.779292 0.593234 0.77969 0.593982 0.761293 0.620529 0.779319 0.591453 0.779292 0.593234 0.761293 0.620529 0.779824 0.588595 0.779319 0.591453 0.761293 0.620529 0.780818 0.584661 0.779824 0.588595 0.761293 0.620529 0.463706 0.689908 0.462164 0.7008 0.457819 0.691782 0.776612 0.580949 0.780818 0.584661 0.761293 0.620529 0.772592 0.575686 0.755765 0.6143 0.750611 0.605724 0.772592 0.575686 0.776612 0.580949 0.755765 0.6143 0.768836 0.568902 0.750611 0.605724 0.74589 0.595052 0.768836 0.568902 0.772592 0.575686 0.750611 0.605724 0.765386 0.56074 0.74589 0.595052 0.741649 0.582534 0.765386 0.56074 0.768836 0.568902 0.74589 0.595052 0.762275 0.55135 0.741649 0.582534 0.737925 0.568418 0.762275 0.55135 0.765386 0.56074 0.741649 0.582534 0.73413 0.55583 0.734852 0.552992 0.737925 0.568418 0.759531 0.540886 0.737925 0.568418 0.734852 0.552992 0.73183 0.563414 0.73413 0.55583 0.737925 0.568418 0.7295 0.569256 0.73183 0.563414 0.737925 0.568418 0.727252 0.57368 0.7295 0.569256 0.737925 0.568418 0.725141 0.576917 0.727252 0.57368 0.737925 0.568418 0.723207 0.5791 0.725141 0.576917 0.737925 0.568418 0.759531 0.540886 0.762275 0.55135 0.737925 0.568418 0.73413 0.513625 0.734852 0.552992 0.73413 0.55583 0.757175 0.529502 0.759531 0.540886 0.734852 0.552992 0.738979 0.534433 0.757175 0.529502 0.734852 0.552992 0.73413 0.513625 0.738979 0.534433 0.734852 0.552992 0.73413 0.513625 0.73413 0.55583 0.73183 0.563414 0.730019 0.51373 0.73183 0.563414 0.7295 0.569256 0.732202 0.513689 0.73413 0.513625 0.73183 0.563414 0.730019 0.51373 0.732202 0.513689 0.73183 0.563414 0.730019 0.51373 0.7295 0.569256 0.727252 0.57368 0.726247 0.513738 0.727252 0.57368 0.725141 0.576917 0.726247 0.513738 0.730019 0.51373 0.727252 0.57368 0.726247 0.513738 0.725141 0.576917 0.723207 0.5791 0.722704 0.513676 0.723207 0.5791 0.72153 0.580274 0.722704 0.513676 0.726247 0.513738 0.723207 0.5791 0.722704 0.513676 0.72153 0.580274 0.720177 0.580525 0.719902 0.513553 0.720177 0.580525 0.7191 0.579932 0.719902 0.513553 0.722704 0.513676 0.720177 0.580525 0.719902 0.513553 0.7191 0.579932 0.718299 0.578363 0.718235 0.513389 0.718299 0.578363 0.717904 0.575795 0.718235 0.513389 0.719902 0.513553 0.718299 0.578363 0.717929 0.513207 0.717904 0.575795 0.717958 0.572243 0.717929 0.513207 0.718235 0.513389 0.717904 0.575795 0.717929 0.513207 0.717958 0.572243 0.718502 0.567616 0.719021 0.513034 0.718502 0.567616 0.719603 0.561765 0.719021 0.513034 0.717929 0.513207 0.718502 0.567616 0.719021 0.513034 0.719603 0.561765 0.721356 0.554478 0.728073 0.523001 0.721356 0.554478 0.726171 0.533478 0.729561 0.513195 0.721356 0.554478 0.728073 0.523001 0.729648 0.51255 0.721356 0.554478 0.729561 0.513195 0.721356 0.512893 0.721356 0.554478 0.729648 0.51255 0.721356 0.512893 0.719021 0.513034 0.721356 0.554478 0.729648 0.51255 0.729561 0.513195 0.728394 0.4971 0.751939 0.477845 0.728394 0.4971 0.727701 0.480709 0.751939 0.477845 0.752601 0.491369 0.728394 0.4971 0.729648 0.51255 0.728394 0.4971 0.752601 0.491369 0.798712 0.580257 0.797165 0.590487 0.786559 0.615073 0.776909 0.598459 0.786559 0.615073 0.797165 0.590487 0.776909 0.598459 0.774305 0.604159 0.786559 0.615073 0.798712 0.580257 0.803002 0.57408 0.797165 0.590487 0.783064 0.582238 0.797165 0.590487 0.803002 0.57408 0.779839 0.591251 0.776909 0.598459 0.797165 0.590487 0.783064 0.582238 0.779839 0.591251 0.797165 0.590487 0.809641 0.537457 0.803002 0.57408 0.798712 0.580257 0.812666 0.531366 0.804195 0.570366 0.803002 0.57408 0.783064 0.582238 0.803002 0.57408 0.804195 0.570366 0.809641 0.537457 0.812666 0.531366 0.803002 0.57408 0.806417 0.542027 0.798712 0.580257 0.794352 0.584226 0.806417 0.542027 0.809641 0.537457 0.798712 0.580257 0.803065 0.545029 0.794352 0.584226 0.789942 0.586269 0.803065 0.545029 0.806417 0.542027 0.794352 0.584226 0.787879 0.581686 0.789942 0.586269 0.785549 0.586453 0.799663 0.546316 0.803065 0.545029 0.789942 0.586269 0.793534 0.567118 0.799663 0.546316 0.789942 0.586269 0.790579 0.5753 0.793534 0.567118 0.789942 0.586269 0.787879 0.581686 0.790579 0.5753 0.789942 0.586269 0.45448 0.693983 0.456649 0.698681 0.45405 0.696341 0.789162 0.519769 0.787879 0.581686 0.785549 0.586453 0.784984 0.519698 0.785549 0.586453 0.783441 0.590142 0.784984 0.519698 0.789162 0.519769 0.785549 0.586453 0.784984 0.519698 0.783441 0.590142 0.781752 0.592544 0.781678 0.519545 0.781752 0.592544 0.780487 0.593793 0.781678 0.519545 0.784984 0.519698 0.781752 0.592544 0.781678 0.519545 0.780487 0.593793 0.77969 0.593982 0.779689 0.519335 0.77969 0.593982 0.779292 0.593234 0.779689 0.519335 0.781678 0.519545 0.77969 0.593982 0.779311 0.5191 0.779292 0.593234 0.779319 0.591453 0.779311 0.5191 0.779689 0.519335 0.779292 0.593234 0.779311 0.5191 0.779319 0.591453 0.779824 0.588595 0.780567 0.518879 0.779824 0.588595 0.780818 0.584661 0.780567 0.518879 0.779311 0.5191 0.779824 0.588595 0.457819 0.691782 0.462164 0.7008 0.456649 0.698681 0.782324 0.579548 0.780818 0.584661 0.776612 0.580949 0.780567 0.518879 0.780818 0.584661 0.782324 0.579548 0.789928 0.541867 0.776612 0.580949 0.772592 0.575686 0.793062 0.544619 0.776612 0.580949 0.789928 0.541867 0.787048 0.564988 0.776612 0.580949 0.793062 0.544619 0.784382 0.573077 0.782324 0.579548 0.776612 0.580949 0.787048 0.564988 0.784382 0.573077 0.776612 0.580949 0.787027 0.537769 0.772592 0.575686 0.768836 0.568902 0.789928 0.541867 0.772592 0.575686 0.787027 0.537769 0.784331 0.532543 0.768836 0.568902 0.765386 0.56074 0.787027 0.537769 0.768836 0.568902 0.784331 0.532543 0.781875 0.526294 0.765386 0.56074 0.762275 0.55135 0.784331 0.532543 0.765386 0.56074 0.781875 0.526294 0.779689 0.519138 0.762275 0.55135 0.759531 0.540886 0.781875 0.526294 0.762275 0.55135 0.779689 0.519138 0.777798 0.511194 0.759531 0.540886 0.757175 0.529502 0.779689 0.519138 0.759531 0.540886 0.777798 0.511194 0.738979 0.534433 0.755227 0.517351 0.757175 0.529502 0.776224 0.502589 0.757175 0.529502 0.755227 0.517351 0.777798 0.511194 0.757175 0.529502 0.776224 0.502589 0.742454 0.513267 0.753699 0.504589 0.755227 0.517351 0.774983 0.493452 0.755227 0.517351 0.753699 0.504589 0.740883 0.523817 0.742454 0.513267 0.755227 0.517351 0.738979 0.534433 0.740883 0.523817 0.755227 0.517351 0.776224 0.502589 0.755227 0.517351 0.774983 0.493452 0.729648 0.51255 0.752601 0.491369 0.753699 0.504589 0.774087 0.483914 0.753699 0.504589 0.752601 0.491369 0.736136 0.512901 0.729648 0.51255 0.753699 0.504589 0.742454 0.513267 0.736136 0.512901 0.753699 0.504589 0.774983 0.493452 0.753699 0.504589 0.774087 0.483914 0.773547 0.474108 0.752601 0.491369 0.751939 0.477845 0.774087 0.483914 0.752601 0.491369 0.773547 0.474108 0.73413 0.513625 0.729648 0.51255 0.736136 0.512901 0.732202 0.513689 0.729648 0.51255 0.73413 0.513625 0.730019 0.51373 0.729648 0.51255 0.732202 0.513689 0.726247 0.513738 0.729648 0.51255 0.730019 0.51373 0.721356 0.512893 0.729648 0.51255 0.726247 0.513738 0.73413 0.513625 0.736136 0.512901 0.742454 0.513267 0.73413 0.513625 0.742454 0.513267 0.740883 0.523817 0.73413 0.513625 0.740883 0.523817 0.738979 0.534433 0.812666 0.531366 0.809172 0.552976 0.804195 0.570366 0.790909 0.555589 0.804195 0.570366 0.809172 0.552976 0.790909 0.555589 0.783064 0.582238 0.804195 0.570366 0.812666 0.531366 0.812924 0.536888 0.809172 0.552976 0.796832 0.528168 0.809172 0.552976 0.812924 0.536888 0.790909 0.555589 0.809172 0.552976 0.796832 0.528168 0.812666 0.531366 0.815372 0.523936 0.812924 0.536888 0.796832 0.528168 0.812924 0.536888 0.815372 0.523936 0.813465 0.494287 0.815372 0.523936 0.812666 0.531366 0.814633 0.490191 0.815851 0.521042 0.815372 0.523936 0.796832 0.528168 0.815372 0.523936 0.815851 0.521042 0.813465 0.494287 0.814633 0.490191 0.815372 0.523936 0.812144 0.497824 0.812666 0.531366 0.809641 0.537457 0.812144 0.497824 0.813465 0.494287 0.812666 0.531366 0.810694 0.500745 0.809641 0.537457 0.806417 0.542027 0.810694 0.500745 0.812144 0.497824 0.809641 0.537457 0.809145 0.503003 0.806417 0.542027 0.803065 0.545029 0.809145 0.503003 0.810694 0.500745 0.806417 0.542027 0.807525 0.504569 0.803065 0.545029 0.799663 0.546316 0.807525 0.504569 0.809145 0.503003 0.803065 0.545029 0.793534 0.519745 0.799663 0.546316 0.793534 0.567118 0.805394 0.519536 0.807525 0.504569 0.799663 0.546316 0.800621 0.542506 0.805394 0.519536 0.799663 0.546316 0.793534 0.519745 0.800621 0.542506 0.799663 0.546316 0.793534 0.519745 0.793534 0.567118 0.790579 0.5753 0.789162 0.519769 0.790579 0.5753 0.787879 0.581686 0.789162 0.519769 0.793534 0.519745 0.790579 0.5753 0.814633 0.490191 0.81707 0.512872 0.815851 0.521042 0.794343 0.508661 0.815851 0.521042 0.81707 0.512872 0.796832 0.528168 0.815851 0.521042 0.794343 0.508661 0.814633 0.490191 0.818137 0.504347 0.81707 0.512872 0.794343 0.508661 0.81707 0.512872 0.818137 0.504347 0.815623 0.485606 0.819042 0.495302 0.818137 0.504347 0.794343 0.508661 0.818137 0.504347 0.819042 0.495302 0.814633 0.490191 0.815623 0.485606 0.818137 0.504347 0.816415 0.480616 0.819757 0.485581 0.819042 0.495302 0.796711 0.486472 0.819042 0.495302 0.819757 0.485581 0.815623 0.485606 0.816415 0.480616 0.819042 0.495302 0.794343 0.508661 0.819042 0.495302 0.796711 0.486472 0.816993 0.475312 0.820102 0.478699 0.819757 0.485581 0.796711 0.486472 0.819757 0.485581 0.820102 0.478699 0.816415 0.480616 0.816993 0.475312 0.819757 0.485581 0.817345 0.469794 0.82032 0.47156 0.820102 0.478699 0.796711 0.486472 0.820102 0.478699 0.82032 0.47156 0.816993 0.475312 0.817345 0.469794 0.820102 0.478699 0.805394 0.519536 0.805864 0.505425 0.807525 0.504569 0.802193 0.518956 0.804192 0.505566 0.805864 0.505425 0.803832 0.519244 0.802193 0.518956 0.805864 0.505425 0.805394 0.519536 0.803832 0.519244 0.805864 0.505425 0.800477 0.518673 0.802536 0.505003 0.804192 0.505566 0.802193 0.518956 0.800477 0.518673 0.804192 0.505566 0.798687 0.518394 0.800925 0.503754 0.802536 0.505003 0.800477 0.518673 0.798687 0.518394 0.802536 0.505003 0.789928 0.541867 0.799385 0.50185 0.800925 0.503754 0.798687 0.518394 0.789928 0.541867 0.800925 0.503754 0.787027 0.537769 0.79794 0.499332 0.799385 0.50185 0.789928 0.541867 0.787027 0.537769 0.799385 0.50185 0.784331 0.532543 0.796612 0.496249 0.79794 0.499332 0.787027 0.537769 0.784331 0.532543 0.79794 0.499332 0.781875 0.526294 0.795421 0.492655 0.796612 0.496249 0.784331 0.532543 0.781875 0.526294 0.796612 0.496249 0.779689 0.519138 0.794384 0.488614 0.795421 0.492655 0.781875 0.526294 0.779689 0.519138 0.795421 0.492655 0.777798 0.511194 0.793515 0.484192 0.794384 0.488614 0.779689 0.519138 0.777798 0.511194 0.794384 0.488614 0.776224 0.502589 0.792827 0.479461 0.793515 0.484192 0.777798 0.511194 0.776224 0.502589 0.793515 0.484192 0.774983 0.493452 0.792329 0.474495 0.792827 0.479461 0.776224 0.502589 0.774983 0.493452 0.792827 0.479461 0.774087 0.483914 0.792027 0.469371 0.792329 0.474495 0.774983 0.493452 0.774087 0.483914 0.792329 0.474495 0.774087 0.483914 0.773547 0.474108 0.792027 0.469371 0.794002 0.540888 0.793062 0.544619 0.789928 0.541867 0.798687 0.518394 0.794002 0.540888 0.789928 0.541867 0.798687 0.518394 0.793062 0.544619 0.794002 0.540888 0.787048 0.564988 0.793062 0.544619 0.798687 0.518394 0.805394 0.519536 0.798687 0.518394 0.800477 0.518673 0.793534 0.519745 0.798687 0.518394 0.805394 0.519536 0.787048 0.51859 0.787048 0.564988 0.798687 0.518394 0.787048 0.51859 0.798687 0.518394 0.793534 0.519745 0.803832 0.519244 0.800477 0.518673 0.802193 0.518956 0.805394 0.519536 0.800477 0.518673 0.803832 0.519244 0.793534 0.519745 0.805394 0.519536 0.800621 0.542506 0.783272 0.5187 0.782324 0.579548 0.784382 0.573077 0.783272 0.5187 0.780567 0.518879 0.782324 0.579548 0.783272 0.5187 0.784382 0.573077 0.787048 0.564988 0.787048 0.51859 0.783272 0.5187 0.787048 0.564988 0.481107 0.68758 0.481981 0.731017 0.491313 0.73043 0.491313 0.687273 0.491313 0.73043 0.500525 0.731002 0.481107 0.68758 0.491313 0.73043 0.491313 0.687273 0.501559 0.687582 0.500525 0.731002 0.50915 0.732677 0.501559 0.687582 0.491313 0.687273 0.500525 0.731002 0.511083 0.688495 0.50915 0.732677 0.516694 0.735353 0.511083 0.688495 0.501559 0.687582 0.50915 0.732677 0.519076 0.689946 0.511083 0.688495 0.516694 0.735353 0.143157 0.507913 0.169953 0.535003 0.175265 0.535253 0.183606 0.534474 0.175265 0.535253 0.169953 0.535003 0.168338 0.499887 0.143157 0.507913 0.175265 0.535253 0.09446197 0.525575 0.168338 0.499887 0.175265 0.535253 0.172843 0.535998 0.175265 0.535253 0.183606 0.534474 0.09446197 0.525575 0.175265 0.535253 0.172843 0.535998 0.143157 0.507913 0.164679 0.534752 0.169953 0.535003 0.183606 0.534474 0.169953 0.535003 0.164679 0.534752 0.146624 0.549698 0.172929 0.555827 0.164679 0.534752 0.183606 0.534474 0.164679 0.534752 0.172929 0.555827 0.143157 0.507913 0.146624 0.549698 0.164679 0.534752 0.152169 0.587601 0.183606 0.577051 0.172929 0.555827 0.183606 0.534474 0.172929 0.555827 0.183606 0.577051 0.146624 0.549698 0.152169 0.587601 0.172929 0.555827 0.152169 0.587601 0.187285 0.582512 0.183606 0.577051 0.183606 0.534474 0.183606 0.577051 0.187285 0.582512 0.152169 0.587601 0.190891 0.58596 0.187285 0.582512 0.187268 0.534452 0.187285 0.582512 0.190891 0.58596 0.183606 0.534474 0.187285 0.582512 0.187268 0.534452 0.152169 0.587601 0.193005 0.587105 0.190891 0.58596 0.190891 0.534495 0.190891 0.58596 0.193005 0.587105 0.187268 0.534452 0.190891 0.58596 0.190891 0.534495 0.152169 0.587601 0.194876 0.587472 0.193005 0.587105 0.190891 0.534495 0.193005 0.587105 0.194876 0.587472 0.152169 0.587601 0.212484 0.617942 0.194876 0.587472 0.197492 0.594609 0.194876 0.587472 0.212484 0.617942 0.190891 0.534495 0.194876 0.587472 0.195545 0.534668 0.197492 0.594609 0.195545 0.534668 0.194876 0.587472 0.152169 0.587601 0.1594319 0.62008 0.212484 0.617942 0.154431 0.642667 0.212484 0.617942 0.144178 0.669793 0.1993809 0.60009 0.197492 0.594609 0.212484 0.617942 0.200536 0.604047 0.1993809 0.60009 0.212484 0.617942 0.200944 0.606496 0.200536 0.604047 0.212484 0.617942 0.200684 0.607519 0.200944 0.606496 0.212484 0.617942 0.152966 0.630988 0.200684 0.607519 0.212484 0.617942 0.154631 0.63634 0.152966 0.630988 0.212484 0.617942 0.155381 0.640009 0.154631 0.63634 0.212484 0.617942 0.155277 0.64205 0.155381 0.640009 0.212484 0.617942 0.154431 0.642667 0.155277 0.64205 0.212484 0.617942 0.293037 0.522375 0.26528 0.521216 0.266792 0.492908 0.301963 0.50994 0.292825 0.509971 0.266792 0.492908 0.293037 0.522375 0.266792 0.492908 0.292825 0.509971 0.311088 0.509904 0.301963 0.50994 0.266792 0.492908 0.296527 0.550762 0.26277 0.54866 0.26528 0.521216 0.263729 0.478497 0.26528 0.521216 0.26277 0.54866 0.294983 0.546724 0.296527 0.550762 0.26528 0.521216 0.29385 0.541437 0.294983 0.546724 0.26528 0.521216 0.293302 0.534696 0.29385 0.541437 0.26528 0.521216 0.293037 0.522375 0.293302 0.534696 0.26528 0.521216 0.263729 0.478497 0.263741 0.450489 0.26528 0.521216 0.262676 0.506259 0.26277 0.54866 0.259287 0.574749 0.300336 0.555603 0.302306 0.556529 0.26277 0.54866 0.298349 0.553694 0.300336 0.555603 0.26277 0.54866 0.296527 0.550762 0.298349 0.553694 0.26277 0.54866 0.262676 0.506259 0.263729 0.478497 0.26277 0.54866 0.257453 0.559382 0.259287 0.574749 0.254779 0.599464 0.260584 0.53336 0.262676 0.506259 0.259287 0.574749 0.257453 0.559382 0.260584 0.53336 0.259287 0.574749 0.253283 0.58389 0.254779 0.599464 0.249276 0.622149 0.253283 0.58389 0.257453 0.559382 0.254779 0.599464 0.248082 0.606388 0.249276 0.622149 0.242811 0.642293 0.248082 0.606388 0.253283 0.58389 0.249276 0.622149 0.241941 0.626149 0.242811 0.642293 0.235419 0.659412 0.241941 0.626149 0.248082 0.606388 0.242811 0.642293 0.234813 0.642937 0.235419 0.659412 0.227158 0.672973 0.234813 0.642937 0.241941 0.626149 0.235419 0.659412 0.226785 0.656051 0.227158 0.672973 0.21812 0.682395 0.226785 0.656051 0.234813 0.642937 0.227158 0.672973 0.2179909 0.664805 0.21812 0.682395 0.208443 0.687066 0.22249 0.660994 0.226785 0.656051 0.21812 0.682395 0.2179909 0.664805 0.22249 0.660994 0.21812 0.682395 0.19896 0.66673 0.208443 0.687066 0.198319 0.686362 0.208667 0.668544 0.2179909 0.664805 0.208443 0.687066 0.19896 0.66673 0.208667 0.668544 0.208443 0.687066 0.1891829 0.658832 0.198319 0.686362 0.188 0.679689 0.1891829 0.658832 0.19896 0.66673 0.198319 0.686362 0.1891829 0.658832 0.188 0.679689 0.182867 0.673949 0.179717 0.644556 0.182867 0.673949 0.177812 0.666552 0.179717 0.644556 0.1891829 0.658832 0.182867 0.673949 0.1751649 0.634856 0.177812 0.666552 0.172885 0.657449 0.1751649 0.634856 0.179717 0.644556 0.177812 0.666552 0.170817 0.623489 0.172885 0.657449 0.1681399 0.646654 0.170817 0.623489 0.1751649 0.634856 0.172885 0.657449 0.166754 0.610507 0.1681399 0.646654 0.163637 0.634163 0.166754 0.610507 0.170817 0.623489 0.1681399 0.646654 0.163018 0.595989 0.163637 0.634163 0.1594319 0.62008 0.163018 0.595989 0.166754 0.610507 0.163637 0.634163 0.156744 0.562777 0.1594319 0.62008 0.152169 0.587601 0.156744 0.562777 0.163018 0.595989 0.1594319 0.62008 0.150106 0.484456 0.152169 0.587601 0.146624 0.549698 0.152353 0.525052 0.156744 0.562777 0.152169 0.587601 0.150106 0.484456 0.152353 0.525052 0.152169 0.587601 0.09446197 0.525575 0.09112298 0.495061 0.168338 0.499887 0.293302 0.510315 0.292825 0.509971 0.301963 0.50994 0.293037 0.522375 0.292825 0.509971 0.293302 0.534696 0.293302 0.510315 0.293302 0.534696 0.292825 0.509971 0.300765 0.510708 0.301963 0.50994 0.311088 0.509904 0.293989 0.510452 0.293302 0.510315 0.301963 0.50994 0.295577 0.51057 0.293989 0.510452 0.301963 0.50994 0.297907 0.510658 0.295577 0.51057 0.301963 0.50994 0.300765 0.510708 0.297907 0.510658 0.301963 0.50994 0.311712 0.510253 0.311088 0.509904 0.311365 0.522763 0.304166 0.510708 0.300765 0.510708 0.311088 0.509904 0.307332 0.510652 0.304166 0.510708 0.311088 0.509904 0.309843 0.510547 0.307332 0.510652 0.311088 0.509904 0.311712 0.510253 0.309843 0.510547 0.311088 0.509904 0.311712 0.510253 0.311365 0.522763 0.311712 0.5355 0.311712 0.510253 0.311712 0.5355 0.311564 0.542102 0.31137 0.510408 0.311564 0.542102 0.310799 0.547288 0.311712 0.510253 0.311564 0.542102 0.31137 0.510408 0.309843 0.510547 0.310799 0.547288 0.309559 0.55124 0.31137 0.510408 0.310799 0.547288 0.309843 0.510547 0.309843 0.510547 0.309559 0.55124 0.307949 0.554083 0.307332 0.510652 0.307949 0.554083 0.306085 0.555861 0.309843 0.510547 0.307949 0.554083 0.307332 0.510652 0.307332 0.510652 0.306085 0.555861 0.304192 0.556612 0.304166 0.510708 0.304192 0.556612 0.302306 0.556529 0.307332 0.510652 0.304192 0.556612 0.304166 0.510708 0.300765 0.510708 0.302306 0.556529 0.300336 0.555603 0.304166 0.510708 0.302306 0.556529 0.300765 0.510708 0.300765 0.510708 0.300336 0.555603 0.298349 0.553694 0.297907 0.510658 0.298349 0.553694 0.296527 0.550762 0.300765 0.510708 0.298349 0.553694 0.297907 0.510658 0.295577 0.51057 0.296527 0.550762 0.294983 0.546724 0.297907 0.510658 0.296527 0.550762 0.295577 0.51057 0.293989 0.510452 0.294983 0.546724 0.29385 0.541437 0.295577 0.51057 0.294983 0.546724 0.293989 0.510452 0.293989 0.510452 0.29385 0.541437 0.293302 0.534696 0.293989 0.510452 0.293302 0.534696 0.293302 0.510315 0.195545 0.534668 0.189811 0.536455 0.170369 0.536757 0.189811 0.591181 0.170369 0.536757 0.189811 0.536455 0.190891 0.534495 0.195545 0.534668 0.170369 0.536757 0.187268 0.534452 0.190891 0.534495 0.170369 0.536757 0.183606 0.534474 0.187268 0.534452 0.170369 0.536757 0.172843 0.535998 0.183606 0.534474 0.170369 0.536757 0.09446197 0.525575 0.172843 0.535998 0.170369 0.536757 0.10005 0.555838 0.09446197 0.525575 0.170369 0.536757 0.125784 0.550361 0.10005 0.555838 0.170369 0.536757 0.178806 0.564607 0.170369 0.536757 0.189811 0.591181 0.125784 0.550361 0.170369 0.536757 0.178806 0.564607 0.198991 0.534948 0.194756 0.536299 0.189811 0.536455 0.189811 0.591181 0.189811 0.536455 0.194756 0.536299 0.195545 0.534668 0.198991 0.534948 0.189811 0.536455 0.200765 0.535299 0.198525 0.536025 0.194756 0.536299 0.196044 0.60265 0.194756 0.536299 0.198525 0.536025 0.198991 0.534948 0.200765 0.535299 0.194756 0.536299 0.1932 0.59785 0.194756 0.536299 0.196044 0.60265 0.189811 0.591181 0.194756 0.536299 0.1932 0.59785 0.200765 0.535299 0.200613 0.535675 0.198525 0.536025 0.199825 0.60733 0.198525 0.536025 0.200613 0.535675 0.19828 0.605776 0.198525 0.536025 0.199825 0.60733 0.196044 0.60265 0.198525 0.536025 0.19828 0.605776 0.200684 0.607519 0.200613 0.535675 0.200765 0.535299 0.199825 0.60733 0.200613 0.535675 0.200684 0.607519 0.200536 0.604047 0.200765 0.535299 0.198991 0.534948 0.200944 0.606496 0.200765 0.535299 0.200536 0.604047 0.200684 0.607519 0.200765 0.535299 0.200944 0.606496 0.197492 0.594609 0.198991 0.534948 0.195545 0.534668 0.1993809 0.60009 0.198991 0.534948 0.197492 0.594609 0.200536 0.604047 0.198991 0.534948 0.1993809 0.60009 0.12354 0.580789 0.107839 0.585576 0.10005 0.555838 0.121 0.55181 0.116051 0.553306 0.10005 0.555838 0.12354 0.580789 0.10005 0.555838 0.116051 0.553306 0.125784 0.550361 0.121 0.55181 0.10005 0.555838 0.133051 0.60763 0.117835 0.614612 0.107839 0.585576 0.12354 0.580789 0.133051 0.60763 0.107839 0.585576 0.142886 0.628368 0.129972 0.642768 0.117835 0.614612 0.1382 0.619408 0.142886 0.628368 0.117835 0.614612 0.133051 0.60763 0.1382 0.619408 0.117835 0.614612 0.154431 0.642667 0.144178 0.669793 0.129972 0.642768 0.1341789 0.464168 0.129972 0.642768 0.144178 0.669793 0.152804 0.641868 0.154431 0.642667 0.129972 0.642768 0.150288 0.639355 0.152804 0.641868 0.129972 0.642768 0.1469489 0.634918 0.150288 0.639355 0.129972 0.642768 0.142886 0.628368 0.1469489 0.634918 0.129972 0.642768 0.152038 0.577913 0.144178 0.669793 0.160509 0.6957 0.1386409 0.521665 0.1341789 0.464168 0.144178 0.669793 0.152038 0.577913 0.1386409 0.521665 0.144178 0.669793 0.174229 0.631343 0.160509 0.6957 0.179056 0.720499 0.174229 0.631343 0.152038 0.577913 0.160509 0.6957 0.174229 0.631343 0.179056 0.720499 0.199668 0.743895 0.204814 0.680393 0.199668 0.743895 0.222245 0.765625 0.204814 0.680393 0.174229 0.631343 0.199668 0.743895 0.223352 0.703144 0.222245 0.765625 0.246682 0.785572 0.223352 0.703144 0.204814 0.680393 0.222245 0.765625 0.266283 0.74387 0.246682 0.785572 0.272861 0.803563 0.243889 0.724398 0.223352 0.703144 0.246682 0.785572 0.266283 0.74387 0.243889 0.724398 0.246682 0.785572 0.290403 0.761454 0.272861 0.803563 0.300639 0.819487 0.290403 0.761454 0.266283 0.74387 0.272861 0.803563 0.384061 0.758612 0.329864 0.833205 0.300639 0.819487 0.290403 0.761454 0.300639 0.819487 0.329864 0.833205 0.384061 0.758612 0.360344 0.844622 0.329864 0.833205 0.343195 0.790344 0.329864 0.833205 0.360344 0.844622 0.343195 0.790344 0.290403 0.761454 0.329864 0.833205 0.430046 0.770019 0.391877 0.853624 0.360344 0.844622 0.343195 0.790344 0.360344 0.844622 0.391877 0.853624 0.384061 0.758612 0.430046 0.770019 0.360344 0.844622 0.430046 0.770019 0.424223 0.860146 0.391877 0.853624 0.400765 0.81011 0.391877 0.853624 0.424223 0.860146 0.400765 0.81011 0.343195 0.790344 0.391877 0.853624 0.477244 0.774525 0.457137 0.864109 0.424223 0.860146 0.400765 0.81011 0.424223 0.860146 0.457137 0.864109 0.430046 0.770019 0.477244 0.774525 0.424223 0.860146 0.477244 0.774525 0.490351 0.865492 0.457137 0.864109 0.461291 0.820092 0.457137 0.864109 0.490351 0.865492 0.461291 0.820092 0.400765 0.81011 0.457137 0.864109 0.524176 0.772134 0.523595 0.864258 0.490351 0.865492 0.522757 0.819974 0.490351 0.865492 0.523595 0.864258 0.477244 0.774525 0.524176 0.772134 0.490351 0.865492 0.522757 0.819974 0.461291 0.820092 0.490351 0.865492 0.524176 0.772134 0.556595 0.860432 0.523595 0.864258 0.522757 0.819974 0.523595 0.864258 0.556595 0.860432 0.569996 0.763027 0.589081 0.854025 0.556595 0.860432 0.58308 0.8098 0.556595 0.860432 0.589081 0.854025 0.524176 0.772134 0.569996 0.763027 0.556595 0.860432 0.58308 0.8098 0.522757 0.819974 0.556595 0.860432 0.569996 0.763027 0.620799 0.845107 0.589081 0.854025 0.58308 0.8098 0.589081 0.854025 0.620799 0.845107 0.592108 0.756055 0.651503 0.833731 0.620799 0.845107 0.640283 0.789966 0.620799 0.845107 0.651503 0.833731 0.569996 0.763027 0.592108 0.756055 0.620799 0.845107 0.640283 0.789966 0.58308 0.8098 0.620799 0.845107 0.634006 0.73761 0.680974 0.820012 0.651503 0.833731 0.640283 0.789966 0.651503 0.833731 0.680974 0.820012 0.613496 0.747551 0.634006 0.73761 0.651503 0.833731 0.592108 0.756055 0.613496 0.747551 0.651503 0.833731 0.653612 0.726273 0.709001 0.80404 0.680974 0.820012 0.692652 0.761168 0.680974 0.820012 0.709001 0.80404 0.634006 0.73761 0.653612 0.726273 0.680974 0.820012 0.692652 0.761168 0.640283 0.789966 0.680974 0.820012 0.67229 0.713565 0.73542 0.785963 0.709001 0.80404 0.692652 0.761168 0.709001 0.80404 0.73542 0.785963 0.653612 0.726273 0.67229 0.713565 0.709001 0.80404 0.689902 0.699589 0.760073 0.765896 0.73542 0.785963 0.738805 0.724333 0.73542 0.785963 0.760073 0.765896 0.67229 0.713565 0.689902 0.699589 0.73542 0.785963 0.738805 0.724333 0.692652 0.761168 0.73542 0.785963 0.706344 0.684452 0.782834 0.744025 0.760073 0.765896 0.777662 0.680593 0.760073 0.765896 0.782834 0.744025 0.689902 0.699589 0.706344 0.684452 0.760073 0.765896 0.777662 0.680593 0.738805 0.724333 0.760073 0.765896 0.721573 0.668223 0.803588 0.720475 0.782834 0.744025 0.777662 0.680593 0.782834 0.744025 0.803588 0.720475 0.706344 0.684452 0.721573 0.668223 0.782834 0.744025 0.735533 0.650987 0.822236 0.695526 0.803588 0.720475 0.808187 0.631749 0.803588 0.720475 0.822236 0.695526 0.721573 0.668223 0.735533 0.650987 0.803588 0.720475 0.808187 0.631749 0.777662 0.680593 0.803588 0.720475 0.748194 0.632799 0.838624 0.669486 0.822236 0.695526 0.830432 0.578392 0.822236 0.695526 0.838624 0.669486 0.735533 0.650987 0.748194 0.632799 0.822236 0.695526 0.830432 0.578392 0.808187 0.631749 0.822236 0.695526 0.835777 0.63477 0.852851 0.642353 0.838624 0.669486 0.843928 0.52202 0.838624 0.669486 0.852851 0.642353 0.748194 0.632799 0.759537 0.61369 0.838624 0.669486 0.828243 0.642663 0.838624 0.669486 0.759537 0.61369 0.832442 0.639232 0.835777 0.63477 0.838624 0.669486 0.829907 0.641801 0.832442 0.639232 0.838624 0.669486 0.828243 0.642663 0.829907 0.641801 0.838624 0.669486 0.843928 0.52202 0.830432 0.578392 0.838624 0.669486 0.844471 0.619314 0.864978 0.614125 0.852851 0.642353 0.83982 0.628228 0.844471 0.619314 0.852851 0.642353 0.835777 0.63477 0.83982 0.628228 0.852851 0.642353 0.8473 0.49329 0.852851 0.642353 0.848447 0.464168 0.8473 0.49329 0.843928 0.52202 0.852851 0.642353 0.859086 0.580789 0.874941 0.585063 0.864978 0.614125 0.849575 0.60763 0.859086 0.580789 0.864978 0.614125 0.844471 0.619314 0.849575 0.60763 0.864978 0.614125 0.866575 0.553306 0.882682 0.555355 0.874941 0.585063 0.859086 0.580789 0.866575 0.553306 0.874941 0.585063 0.7904 0.530643 0.888221 0.525184 0.882682 0.555355 0.814226 0.537362 0.7904 0.530643 0.882682 0.555355 0.861626 0.55181 0.856841 0.550361 0.882682 0.555355 0.821207 0.539502 0.882682 0.555355 0.856841 0.550361 0.866575 0.553306 0.861626 0.55181 0.882682 0.555355 0.817666 0.538417 0.814226 0.537362 0.882682 0.555355 0.821207 0.539502 0.817666 0.538417 0.882682 0.555355 0.794343 0.508661 0.891526 0.494831 0.888221 0.525184 0.7904 0.530643 0.794343 0.508661 0.888221 0.525184 0.794343 0.508661 0.796711 0.486472 0.891526 0.494831 0.791391 0.529809 0.794343 0.508661 0.7904 0.530643 0.794154 0.528978 0.796832 0.528168 0.794343 0.508661 0.791391 0.529809 0.794154 0.528978 0.794343 0.508661 0.808935 0.557873 0.784912 0.552254 0.7904 0.530643 0.791391 0.529809 0.7904 0.530643 0.784912 0.552254 0.808935 0.557873 0.7904 0.530643 0.814226 0.537362 0.802337 0.578001 0.777929 0.573319 0.784912 0.552254 0.78522 0.55665 0.784912 0.552254 0.777929 0.573319 0.808935 0.557873 0.802337 0.578001 0.784912 0.552254 0.78522 0.55665 0.791391 0.529809 0.784912 0.552254 0.793065 0.603295 0.769471 0.593808 0.777929 0.573319 0.777042 0.582974 0.777929 0.573319 0.769471 0.593808 0.795367 0.596838 0.793065 0.603295 0.777929 0.573319 0.798456 0.588514 0.795367 0.596838 0.777929 0.573319 0.802337 0.578001 0.798456 0.588514 0.777929 0.573319 0.777042 0.582974 0.78522 0.55665 0.777929 0.573319 0.790818 0.613015 0.759537 0.61369 0.769471 0.593808 0.770856 0.600493 0.769471 0.593808 0.759537 0.61369 0.790808 0.611324 0.790818 0.613015 0.769471 0.593808 0.791544 0.608096 0.790808 0.611324 0.769471 0.593808 0.793065 0.603295 0.791544 0.608096 0.769471 0.593808 0.773516 0.592922 0.777042 0.582974 0.769471 0.593808 0.770856 0.600493 0.773516 0.592922 0.769471 0.593808 0.82737 0.642103 0.828243 0.642663 0.759537 0.61369 0.790818 0.613015 0.82737 0.642103 0.759537 0.61369 0.76897 0.606153 0.770856 0.600493 0.759537 0.61369 0.767775 0.610231 0.76897 0.606153 0.759537 0.61369 0.76721 0.612933 0.767775 0.610231 0.759537 0.61369 0.767236 0.61433 0.76721 0.612933 0.759537 0.61369 0.767754 0.614538 0.767236 0.61433 0.759537 0.61369 0.150377 0.623876 0.199825 0.60733 0.200684 0.607519 0.152966 0.630988 0.150377 0.623876 0.200684 0.607519 0.150377 0.623876 0.19828 0.605776 0.199825 0.60733 0.150377 0.623876 0.196044 0.60265 0.19828 0.605776 0.146845 0.614807 0.1932 0.59785 0.196044 0.60265 0.150377 0.623876 0.146845 0.614807 0.196044 0.60265 0.146845 0.614807 0.189811 0.591181 0.1932 0.59785 0.142346 0.603473 0.178806 0.564607 0.189811 0.591181 0.146845 0.614807 0.142346 0.603473 0.189811 0.591181 0.133073 0.577225 0.125784 0.550361 0.178806 0.564607 0.142346 0.603473 0.133073 0.577225 0.178806 0.564607 0.829088 0.551542 0.856841 0.550361 0.861626 0.55181 0.849553 0.577225 0.856841 0.550361 0.84028 0.603473 0.84028 0.550755 0.84028 0.603473 0.856841 0.550361 0.815794 0.560378 0.856841 0.550361 0.849553 0.577225 0.815794 0.560378 0.821207 0.539502 0.856841 0.550361 0.833136 0.551086 0.84028 0.550755 0.856841 0.550361 0.829088 0.551542 0.833136 0.551086 0.856841 0.550361 0.831085 0.553211 0.861626 0.55181 0.866575 0.553306 0.827264 0.5521 0.829088 0.551542 0.861626 0.55181 0.827948 0.552685 0.827264 0.5521 0.861626 0.55181 0.831085 0.553211 0.827948 0.552685 0.861626 0.55181 0.849575 0.55374 0.866575 0.553306 0.859086 0.580789 0.836263 0.553599 0.831085 0.553211 0.866575 0.553306 0.842747 0.553786 0.836263 0.553599 0.866575 0.553306 0.849575 0.55374 0.842747 0.553786 0.866575 0.553306 0.849575 0.55374 0.859086 0.580789 0.849575 0.60763 0.849575 0.55374 0.849575 0.60763 0.844471 0.619314 0.842747 0.553786 0.844471 0.619314 0.83982 0.628228 0.849575 0.55374 0.844471 0.619314 0.842747 0.553786 0.836263 0.553599 0.83982 0.628228 0.835777 0.63477 0.842747 0.553786 0.83982 0.628228 0.836263 0.553599 0.836263 0.553599 0.835777 0.63477 0.832442 0.639232 0.831085 0.553211 0.832442 0.639232 0.829907 0.641801 0.836263 0.553599 0.832442 0.639232 0.831085 0.553211 0.831085 0.553211 0.829907 0.641801 0.828243 0.642663 0.827948 0.552685 0.828243 0.642663 0.82737 0.642103 0.831085 0.553211 0.828243 0.642663 0.827948 0.552685 0.790818 0.613015 0.827232 0.640132 0.82737 0.642103 0.827948 0.552685 0.82737 0.642103 0.827232 0.640132 0.790818 0.613015 0.827949 0.636508 0.827232 0.640132 0.827264 0.5521 0.827232 0.640132 0.827949 0.636508 0.827948 0.552685 0.827232 0.640132 0.827264 0.5521 0.791469 0.613387 0.829599 0.631164 0.827949 0.636508 0.829088 0.551542 0.827949 0.636508 0.829599 0.631164 0.790818 0.613015 0.791469 0.613387 0.827949 0.636508 0.827264 0.5521 0.827949 0.636508 0.829088 0.551542 0.794864 0.609934 0.832191 0.624028 0.829599 0.631164 0.829088 0.551542 0.829599 0.631164 0.832191 0.624028 0.792797 0.612441 0.794864 0.609934 0.829599 0.631164 0.791469 0.613387 0.792797 0.612441 0.829599 0.631164 0.797596 0.605743 0.835743 0.614903 0.832191 0.624028 0.833136 0.551086 0.832191 0.624028 0.835743 0.614903 0.794864 0.609934 0.797596 0.605743 0.832191 0.624028 0.829088 0.551542 0.832191 0.624028 0.833136 0.551086 0.804789 0.591531 0.84028 0.603473 0.835743 0.614903 0.838835 0.550794 0.835743 0.614903 0.84028 0.603473 0.800928 0.599701 0.804789 0.591531 0.835743 0.614903 0.797596 0.605743 0.800928 0.599701 0.835743 0.614903 0.833136 0.551086 0.835743 0.614903 0.838835 0.550794 0.809056 0.580858 0.849553 0.577225 0.84028 0.603473 0.804789 0.591531 0.809056 0.580858 0.84028 0.603473 0.839553 0.550773 0.84028 0.603473 0.84028 0.550755 0.838835 0.550794 0.84028 0.603473 0.839553 0.550773 0.809056 0.580858 0.815794 0.560378 0.849553 0.577225 0.133051 0.55374 0.116051 0.553306 0.121 0.55181 0.12354 0.580789 0.116051 0.553306 0.133051 0.60763 0.133051 0.55374 0.133051 0.60763 0.116051 0.553306 0.154677 0.552685 0.121 0.55181 0.125784 0.550361 0.139878 0.553786 0.133051 0.55374 0.121 0.55181 0.146362 0.553599 0.139878 0.553786 0.121 0.55181 0.151539 0.553211 0.146362 0.553599 0.121 0.55181 0.154677 0.552685 0.151539 0.553211 0.121 0.55181 0.142346 0.550755 0.125784 0.550361 0.133073 0.577225 0.155362 0.552101 0.154677 0.552685 0.125784 0.550361 0.153538 0.551542 0.155362 0.552101 0.125784 0.550361 0.1494899 0.551087 0.153538 0.551542 0.125784 0.550361 0.142346 0.550755 0.1494899 0.551087 0.125784 0.550361 0.142346 0.550755 0.133073 0.577225 0.142346 0.603473 0.142346 0.550755 0.142346 0.603473 0.146845 0.614807 0.1494899 0.551087 0.146845 0.614807 0.150377 0.623876 0.143791 0.550794 0.146845 0.614807 0.1494899 0.551087 0.143073 0.550773 0.146845 0.614807 0.143791 0.550794 0.142346 0.550755 0.146845 0.614807 0.143073 0.550773 0.1494899 0.551087 0.150377 0.623876 0.152966 0.630988 0.153538 0.551542 0.152966 0.630988 0.154631 0.63634 0.1494899 0.551087 0.152966 0.630988 0.153538 0.551542 0.155362 0.552101 0.154631 0.63634 0.155381 0.640009 0.153538 0.551542 0.154631 0.63634 0.155362 0.552101 0.155362 0.552101 0.155381 0.640009 0.155277 0.64205 0.154677 0.552685 0.155277 0.64205 0.154431 0.642667 0.155362 0.552101 0.155277 0.64205 0.154677 0.552685 0.154677 0.552685 0.154431 0.642667 0.152804 0.641868 0.151539 0.553211 0.152804 0.641868 0.150288 0.639355 0.154677 0.552685 0.152804 0.641868 0.151539 0.553211 0.151539 0.553211 0.150288 0.639355 0.1469489 0.634918 0.146362 0.553599 0.1469489 0.634918 0.142886 0.628368 0.151539 0.553211 0.1469489 0.634918 0.146362 0.553599 0.139878 0.553786 0.142886 0.628368 0.1382 0.619408 0.146362 0.553599 0.142886 0.628368 0.139878 0.553786 0.139878 0.553786 0.1382 0.619408 0.133051 0.60763 0.139878 0.553786 0.133051 0.60763 0.133051 0.55374 0.792586 0.538104 0.814226 0.537362 0.817666 0.538417 0.808935 0.557873 0.814226 0.537362 0.802337 0.578001 0.802337 0.537565 0.802337 0.578001 0.814226 0.537362 0.796171 0.537787 0.802337 0.537565 0.814226 0.537362 0.792586 0.538104 0.796171 0.537787 0.814226 0.537362 0.793677 0.5393 0.817666 0.538417 0.821207 0.539502 0.790848 0.538499 0.792586 0.538104 0.817666 0.538417 0.791219 0.538918 0.790848 0.538499 0.817666 0.538417 0.793677 0.5393 0.791219 0.538918 0.817666 0.538417 0.809056 0.539722 0.821207 0.539502 0.815794 0.560378 0.797899 0.539589 0.793677 0.5393 0.821207 0.539502 0.803289 0.539738 0.797899 0.539589 0.821207 0.539502 0.809056 0.539722 0.803289 0.539738 0.821207 0.539502 0.809056 0.539722 0.815794 0.560378 0.809056 0.580858 0.809056 0.539722 0.809056 0.580858 0.804789 0.591531 0.803289 0.539738 0.804789 0.591531 0.800928 0.599701 0.809056 0.539722 0.804789 0.591531 0.803289 0.539738 0.797899 0.539589 0.800928 0.599701 0.797596 0.605743 0.803289 0.539738 0.800928 0.599701 0.797899 0.539589 0.797899 0.539589 0.797596 0.605743 0.794864 0.609934 0.793677 0.5393 0.794864 0.609934 0.792797 0.612441 0.797899 0.539589 0.794864 0.609934 0.793677 0.5393 0.793677 0.5393 0.792797 0.612441 0.791469 0.613387 0.791219 0.538918 0.791469 0.613387 0.790818 0.613015 0.793677 0.5393 0.791469 0.613387 0.791219 0.538918 0.791219 0.538918 0.790818 0.613015 0.790808 0.611324 0.790848 0.538499 0.790808 0.611324 0.791544 0.608096 0.791219 0.538918 0.790808 0.611324 0.790848 0.538499 0.792586 0.538104 0.791544 0.608096 0.793065 0.603295 0.790848 0.538499 0.791544 0.608096 0.792586 0.538104 0.792586 0.538104 0.793065 0.603295 0.795367 0.596838 0.796171 0.537787 0.795367 0.596838 0.798456 0.588514 0.792586 0.538104 0.795367 0.596838 0.796171 0.537787 0.8011 0.53759 0.798456 0.588514 0.802337 0.578001 0.796171 0.537787 0.798456 0.588514 0.8011 0.53759 0.801715 0.537576 0.802337 0.578001 0.802337 0.537565 0.8011 0.53759 0.802337 0.578001 0.801715 0.537576 0.850682 0.464168 0.848447 0.464168 0.843984 0.406672 0.846196 0.52201 0.8473 0.49329 0.848447 0.464168 0.846196 0.52201 0.848447 0.464168 0.850682 0.464168 0.84614 0.40597 0.843984 0.406672 0.830588 0.350424 0.84953 0.434872 0.850682 0.464168 0.843984 0.406672 0.84614 0.40597 0.84953 0.434872 0.843984 0.406672 0.832573 0.349258 0.830588 0.350424 0.808396 0.296993 0.832573 0.349258 0.84614 0.40597 0.830588 0.350424 0.810208 0.295574 0.808396 0.296993 0.777812 0.2479439 0.810208 0.295574 0.832573 0.349258 0.808396 0.296993 0.779512 0.2464269 0.777812 0.2479439 0.759273 0.225193 0.779512 0.2464269 0.810208 0.295574 0.777812 0.2479439 0.740427 0.202409 0.759273 0.225193 0.738737 0.203938 0.740427 0.202409 0.779512 0.2464269 0.759273 0.225193 0.740427 0.202409 0.738737 0.203938 0.716342 0.184466 0.69399 0.1653349 0.716342 0.184466 0.692223 0.166882 0.69399 0.1653349 0.740427 0.202409 0.716342 0.184466 0.641285 0.1363469 0.692223 0.166882 0.63943 0.137993 0.641285 0.1363469 0.69399 0.1653349 0.692223 0.166882 0.583703 0.116379 0.63943 0.137993 0.581861 0.118227 0.583703 0.116379 0.641285 0.1363469 0.63943 0.137993 0.522971 0.106136 0.581861 0.118227 0.521334 0.108245 0.522971 0.106136 0.583703 0.116379 0.581861 0.118227 0.461086 0.106018 0.521334 0.108245 0.459869 0.108362 0.461086 0.106018 0.522971 0.106136 0.521334 0.108245 0.40015 0.116068 0.459869 0.108362 0.399545 0.118536 0.40015 0.116068 0.461086 0.106018 0.459869 0.108362 0.342198 0.135967 0.399545 0.118536 0.342342 0.13837 0.342198 0.135967 0.40015 0.116068 0.399545 0.118536 0.289067 0.165047 0.342342 0.13837 0.289973 0.167168 0.289067 0.165047 0.342198 0.135967 0.342342 0.13837 0.264798 0.1827459 0.289973 0.167168 0.24382 0.204003 0.264798 0.1827459 0.289067 0.165047 0.289973 0.167168 0.2216089 0.223734 0.24382 0.204003 0.204963 0.247744 0.242267 0.202343 0.264798 0.1827459 0.24382 0.204003 0.2216089 0.223734 0.242267 0.202343 0.24382 0.204003 0.2029629 0.246628 0.204963 0.247744 0.174439 0.296587 0.2029629 0.246628 0.2216089 0.223734 0.204963 0.247744 0.1722069 0.295983 0.174439 0.296587 0.152193 0.349945 0.1722069 0.295983 0.2029629 0.246628 0.174439 0.296587 0.149896 0.34974 0.152193 0.349945 0.138697 0.406317 0.149896 0.34974 0.1722069 0.295983 0.152193 0.349945 0.136429 0.406327 0.138697 0.406317 0.135325 0.435047 0.136429 0.406327 0.149896 0.34974 0.138697 0.406317 0.136429 0.406327 0.135325 0.435047 0.1341789 0.464168 0.131943 0.464168 0.1341789 0.464168 0.1386409 0.521665 0.131943 0.464168 0.136429 0.406327 0.1341789 0.464168 0.136485 0.522367 0.1386409 0.521665 0.152038 0.577913 0.133096 0.493464 0.131943 0.464168 0.1386409 0.521665 0.136485 0.522367 0.133096 0.493464 0.1386409 0.521665 0.150052 0.579079 0.152038 0.577913 0.174229 0.631343 0.150052 0.579079 0.136485 0.522367 0.152038 0.577913 0.172417 0.632763 0.174229 0.631343 0.204814 0.680393 0.172417 0.632763 0.150052 0.579079 0.174229 0.631343 0.203113 0.68191 0.204814 0.680393 0.223352 0.703144 0.203113 0.68191 0.172417 0.632763 0.204814 0.680393 0.242198 0.725928 0.223352 0.703144 0.243889 0.724398 0.242198 0.725928 0.203113 0.68191 0.223352 0.703144 0.242198 0.725928 0.243889 0.724398 0.266283 0.74387 0.288635 0.763002 0.266283 0.74387 0.290403 0.761454 0.288635 0.763002 0.242198 0.725928 0.266283 0.74387 0.34134 0.79199 0.290403 0.761454 0.343195 0.790344 0.34134 0.79199 0.288635 0.763002 0.290403 0.761454 0.398922 0.811957 0.343195 0.790344 0.400765 0.81011 0.398922 0.811957 0.34134 0.79199 0.343195 0.790344 0.459654 0.8222 0.400765 0.81011 0.461291 0.820092 0.459654 0.8222 0.398922 0.811957 0.400765 0.81011 0.521539 0.822319 0.461291 0.820092 0.522757 0.819974 0.521539 0.822319 0.459654 0.8222 0.461291 0.820092 0.582476 0.812269 0.522757 0.819974 0.58308 0.8098 0.582476 0.812269 0.521539 0.822319 0.522757 0.819974 0.640427 0.79237 0.58308 0.8098 0.640283 0.789966 0.640427 0.79237 0.582476 0.812269 0.58308 0.8098 0.693558 0.763289 0.640283 0.789966 0.692652 0.761168 0.693558 0.763289 0.640427 0.79237 0.640283 0.789966 0.717828 0.745591 0.692652 0.761168 0.738805 0.724333 0.717828 0.745591 0.693558 0.763289 0.692652 0.761168 0.761016 0.704603 0.738805 0.724333 0.777662 0.680593 0.740358 0.725993 0.717828 0.745591 0.738805 0.724333 0.761016 0.704603 0.740358 0.725993 0.738805 0.724333 0.779662 0.681709 0.777662 0.680593 0.808187 0.631749 0.779662 0.681709 0.761016 0.704603 0.777662 0.680593 0.810418 0.632354 0.808187 0.631749 0.830432 0.578392 0.810418 0.632354 0.779662 0.681709 0.808187 0.631749 0.83273 0.578597 0.830432 0.578392 0.843928 0.52202 0.83273 0.578597 0.810418 0.632354 0.830432 0.578392 0.846196 0.52201 0.843928 0.52202 0.8473 0.49329 0.846196 0.52201 0.83273 0.578597 0.843928 0.52202 0.855793 0.284627 0.850682 0.464168 0.84953 0.434872 0.855595 0.644127 0.846196 0.52201 0.850682 0.464168 0.855595 0.644127 0.850682 0.464168 0.855793 0.284627 0.855793 0.284627 0.84953 0.434872 0.84614 0.40597 0.855793 0.284627 0.84614 0.40597 0.832573 0.349258 0.824969 0.231036 0.832573 0.349258 0.810208 0.295574 0.824969 0.231036 0.855793 0.284627 0.832573 0.349258 0.806188 0.205886 0.810208 0.295574 0.779512 0.2464269 0.806188 0.205886 0.824969 0.231036 0.810208 0.295574 0.762348 0.160094 0.779512 0.2464269 0.740427 0.202409 0.785281 0.1821449 0.806188 0.205886 0.779512 0.2464269 0.762348 0.160094 0.785281 0.1821449 0.779512 0.2464269 0.737505 0.13986 0.740427 0.202409 0.69399 0.1653349 0.737505 0.13986 0.762348 0.160094 0.740427 0.202409 0.682619 0.105523 0.69399 0.1653349 0.641285 0.1363469 0.710876 0.121631 0.737505 0.13986 0.69399 0.1653349 0.682619 0.105523 0.710876 0.121631 0.69399 0.1653349 0.621937 0.08021098 0.641285 0.1363469 0.583703 0.116379 0.621937 0.08021098 0.682619 0.105523 0.641285 0.1363469 0.557172 0.06475198 0.583703 0.116379 0.522971 0.106136 0.557172 0.06475198 0.621937 0.08021098 0.583703 0.116379 0.490341 0.05964791 0.522971 0.106136 0.461086 0.106018 0.490341 0.05964791 0.557172 0.06475198 0.522971 0.106136 0.423626 0.06504195 0.461086 0.106018 0.40015 0.116068 0.423626 0.06504195 0.490341 0.05964791 0.461086 0.106018 0.35919 0.080702 0.40015 0.116068 0.342198 0.135967 0.35919 0.080702 0.423626 0.06504195 0.40015 0.116068 0.298982 0.106055 0.342198 0.135967 0.289067 0.165047 0.298982 0.106055 0.35919 0.080702 0.342198 0.135967 0.298982 0.106055 0.289067 0.165047 0.264798 0.1827459 0.2445909 0.140257 0.264798 0.1827459 0.242267 0.202343 0.2445909 0.140257 0.298982 0.106055 0.264798 0.1827459 0.2445909 0.140257 0.242267 0.202343 0.2216089 0.223734 0.2445909 0.140257 0.2216089 0.223734 0.2029629 0.246628 0.197218 0.182278 0.2029629 0.246628 0.1722069 0.295983 0.197218 0.182278 0.2445909 0.140257 0.2029629 0.246628 0.1577759 0.230862 0.1722069 0.295983 0.149896 0.34974 0.1577759 0.230862 0.197218 0.182278 0.1722069 0.295983 0.1577759 0.230862 0.149896 0.34974 0.136429 0.406327 0.127031 0.28421 0.136429 0.406327 0.131943 0.464168 0.127031 0.28421 0.1577759 0.230862 0.136429 0.406327 0.126832 0.643709 0.131943 0.464168 0.133096 0.493464 0.126832 0.643709 0.127031 0.28421 0.131943 0.464168 0.126832 0.643709 0.133096 0.493464 0.136485 0.522367 0.126832 0.643709 0.136485 0.522367 0.150052 0.579079 0.157657 0.697301 0.150052 0.579079 0.172417 0.632763 0.157657 0.697301 0.126832 0.643709 0.150052 0.579079 0.176438 0.72245 0.172417 0.632763 0.203113 0.68191 0.176438 0.72245 0.157657 0.697301 0.172417 0.632763 0.220277 0.768242 0.203113 0.68191 0.242198 0.725928 0.197344 0.746191 0.176438 0.72245 0.203113 0.68191 0.220277 0.768242 0.197344 0.746191 0.203113 0.68191 0.245121 0.788476 0.242198 0.725928 0.288635 0.763002 0.245121 0.788476 0.220277 0.768242 0.242198 0.725928 0.300006 0.822813 0.288635 0.763002 0.34134 0.79199 0.27175 0.806706 0.245121 0.788476 0.288635 0.763002 0.300006 0.822813 0.27175 0.806706 0.288635 0.763002 0.360689 0.848125 0.34134 0.79199 0.398922 0.811957 0.360689 0.848125 0.300006 0.822813 0.34134 0.79199 0.425454 0.863585 0.398922 0.811957 0.459654 0.8222 0.425454 0.863585 0.360689 0.848125 0.398922 0.811957 0.492285 0.868689 0.459654 0.8222 0.521539 0.822319 0.492285 0.868689 0.425454 0.863585 0.459654 0.8222 0.559 0.863295 0.521539 0.822319 0.582476 0.812269 0.559 0.863295 0.492285 0.868689 0.521539 0.822319 0.623436 0.847635 0.582476 0.812269 0.640427 0.79237 0.623436 0.847635 0.559 0.863295 0.582476 0.812269 0.683644 0.822282 0.640427 0.79237 0.693558 0.763289 0.683644 0.822282 0.623436 0.847635 0.640427 0.79237 0.683644 0.822282 0.693558 0.763289 0.717828 0.745591 0.738035 0.788079 0.717828 0.745591 0.740358 0.725993 0.738035 0.788079 0.683644 0.822282 0.717828 0.745591 0.738035 0.788079 0.740358 0.725993 0.761016 0.704603 0.738035 0.788079 0.761016 0.704603 0.779662 0.681709 0.785408 0.746059 0.779662 0.681709 0.810418 0.632354 0.785408 0.746059 0.738035 0.788079 0.779662 0.681709 0.82485 0.697474 0.810418 0.632354 0.83273 0.578597 0.82485 0.697474 0.785408 0.746059 0.810418 0.632354 0.82485 0.697474 0.83273 0.578597 0.846196 0.52201 0.855595 0.644127 0.82485 0.697474 0.846196 0.52201 0.894693 0.495293 0.891391 0.402693 0.895835 0.464168 0.956799 0.464168 0.895835 0.464168 0.891391 0.402693 0.952327 0.53099 0.894693 0.495293 0.895835 0.464168 0.952327 0.53099 0.895835 0.464168 0.956799 0.464168 0.891333 0.526038 0.878027 0.342358 0.891391 0.402693 0.938683 0.330994 0.891391 0.402693 0.878027 0.342358 0.894693 0.495293 0.891333 0.526038 0.891391 0.402693 0.952267 0.396909 0.956799 0.464168 0.891391 0.402693 0.938683 0.330994 0.952267 0.396909 0.891391 0.402693 0.877871 0.586495 0.855793 0.284627 0.878027 0.342358 0.916107 0.267757 0.878027 0.342358 0.855793 0.284627 0.891333 0.526038 0.877871 0.586495 0.878027 0.342358 0.916107 0.267757 0.938683 0.330994 0.878027 0.342358 0.884775 0.208649 0.855793 0.284627 0.824969 0.231036 0.877871 0.586495 0.855595 0.644127 0.855793 0.284627 0.884775 0.208649 0.916107 0.267757 0.855793 0.284627 0.884775 0.208649 0.824969 0.231036 0.806188 0.205886 0.844246 0.154072 0.806188 0.205886 0.785281 0.1821449 0.844246 0.154072 0.884775 0.208649 0.806188 0.205886 0.844246 0.154072 0.785281 0.1821449 0.762348 0.160094 0.79499 0.105755 0.762348 0.160094 0.737505 0.13986 0.79499 0.105755 0.844246 0.154072 0.762348 0.160094 0.79499 0.105755 0.737505 0.13986 0.710876 0.121631 0.737711 0.06512999 0.710876 0.121631 0.682619 0.105523 0.737711 0.06512999 0.79499 0.105755 0.710876 0.121631 0.673398 0.03335493 0.682619 0.105523 0.621937 0.08021098 0.673398 0.03335493 0.737711 0.06512999 0.682619 0.105523 0.603499 0.01144397 0.621937 0.08021098 0.557172 0.06475198 0.603499 0.01144397 0.673398 0.03335493 0.621937 0.08021098 0.529944 1.76e-4 0.557172 0.06475198 0.490341 0.05964791 0.529944 1.76e-4 0.603499 0.01144397 0.557172 0.06475198 0.455036 0 0.490341 0.05964791 0.423626 0.06504195 0.455036 0 0.529944 1.76e-4 0.490341 0.05964791 0.381227 0.01096296 0.423626 0.06504195 0.35919 0.080702 0.381227 0.01096296 0.455036 0 0.423626 0.06504195 0.310866 0.03270393 0.35919 0.080702 0.298982 0.106055 0.310866 0.03270393 0.381227 0.01096296 0.35919 0.080702 0.245983 0.06449598 0.298982 0.106055 0.2445909 0.140257 0.245983 0.06449598 0.310866 0.03270393 0.298982 0.106055 0.188159 0.105318 0.2445909 0.140257 0.197218 0.182278 0.188159 0.105318 0.245983 0.06449598 0.2445909 0.140257 0.138484 0.153952 0.197218 0.182278 0.1577759 0.230862 0.138484 0.153952 0.188159 0.105318 0.197218 0.182278 0.09771096 0.208869 0.1577759 0.230862 0.127031 0.28421 0.09771096 0.208869 0.138484 0.153952 0.1577759 0.230862 0.126832 0.643709 0.104754 0.341841 0.127031 0.28421 0.06630599 0.268239 0.127031 0.28421 0.104754 0.341841 0.06630599 0.268239 0.09771096 0.208869 0.127031 0.28421 0.104598 0.585978 0.09129196 0.402299 0.104754 0.341841 0.04377889 0.331575 0.104754 0.341841 0.09129196 0.402299 0.126832 0.643709 0.104598 0.585978 0.104754 0.341841 0.04377889 0.331575 0.06630599 0.268239 0.104754 0.341841 0.09123396 0.525644 0.08793199 0.433043 0.09129196 0.402299 0.03029888 0.397347 0.09129196 0.402299 0.08793199 0.433043 0.104598 0.585978 0.09123396 0.525644 0.09129196 0.402299 0.03029888 0.397347 0.04377889 0.331575 0.09129196 0.402299 0.09123396 0.525644 0.08679097 0.464168 0.08793199 0.433043 0.03029888 0.397347 0.08793199 0.433043 0.08679097 0.464168 0.02582591 0.464168 0.08679097 0.464168 0.09123396 0.525644 0.02582591 0.464168 0.03029888 0.397347 0.08679097 0.464168 0.04394197 0.597343 0.09123396 0.525644 0.104598 0.585978 0.03035897 0.531427 0.02582591 0.464168 0.09123396 0.525644 0.04394197 0.597343 0.03035897 0.531427 0.09123396 0.525644 0.066518 0.660579 0.104598 0.585978 0.126832 0.643709 0.066518 0.660579 0.04394197 0.597343 0.104598 0.585978 0.09785097 0.719687 0.126832 0.643709 0.157657 0.697301 0.09785097 0.719687 0.066518 0.660579 0.126832 0.643709 0.09785097 0.719687 0.157657 0.697301 0.176438 0.72245 0.138379 0.774265 0.176438 0.72245 0.197344 0.746191 0.138379 0.774265 0.09785097 0.719687 0.176438 0.72245 0.138379 0.774265 0.197344 0.746191 0.220277 0.768242 0.187635 0.822581 0.220277 0.768242 0.245121 0.788476 0.187635 0.822581 0.138379 0.774265 0.220277 0.768242 0.187635 0.822581 0.245121 0.788476 0.27175 0.806706 0.244915 0.863206 0.27175 0.806706 0.300006 0.822813 0.244915 0.863206 0.187635 0.822581 0.27175 0.806706 0.309227 0.894981 0.300006 0.822813 0.360689 0.848125 0.309227 0.894981 0.244915 0.863206 0.300006 0.822813 0.379126 0.916893 0.360689 0.848125 0.425454 0.863585 0.379126 0.916893 0.309227 0.894981 0.360689 0.848125 0.452681 0.928161 0.425454 0.863585 0.492285 0.868689 0.452681 0.928161 0.379126 0.916893 0.425454 0.863585 0.52759 0.928337 0.492285 0.868689 0.559 0.863295 0.52759 0.928337 0.452681 0.928161 0.492285 0.868689 0.601399 0.917374 0.559 0.863295 0.623436 0.847635 0.601399 0.917374 0.52759 0.928337 0.559 0.863295 0.67176 0.895632 0.623436 0.847635 0.683644 0.822282 0.67176 0.895632 0.601399 0.917374 0.623436 0.847635 0.736642 0.86384 0.683644 0.822282 0.738035 0.788079 0.736642 0.86384 0.67176 0.895632 0.683644 0.822282 0.794466 0.823018 0.738035 0.788079 0.785408 0.746059 0.794466 0.823018 0.736642 0.86384 0.738035 0.788079 0.844142 0.774385 0.785408 0.746059 0.82485 0.697474 0.844142 0.774385 0.794466 0.823018 0.785408 0.746059 0.884914 0.719467 0.82485 0.697474 0.855595 0.644127 0.884914 0.719467 0.844142 0.774385 0.82485 0.697474 0.91632 0.660098 0.855595 0.644127 0.877871 0.586495 0.91632 0.660098 0.884914 0.719467 0.855595 0.644127 0.938847 0.596762 0.877871 0.586495 0.891333 0.526038 0.938847 0.596762 0.91632 0.660098 0.877871 0.586495 0.952327 0.53099 0.891333 0.526038 0.894693 0.495293 0.952327 0.53099 0.938847 0.596762 0.891333 0.526038 0.952327 0.53099 0.956799 0.464168 0.952267 0.396909 0.938847 0.596762 0.952267 0.396909 0.938683 0.330994 0.952327 0.53099 0.952267 0.396909 0.938847 0.596762 0.91632 0.660098 0.938683 0.330994 0.916107 0.267757 0.938847 0.596762 0.938683 0.330994 0.91632 0.660098 0.884914 0.719467 0.916107 0.267757 0.884775 0.208649 0.91632 0.660098 0.916107 0.267757 0.884914 0.719467 0.884914 0.719467 0.884775 0.208649 0.844246 0.154072 0.823608 0.464168 0.844246 0.154072 0.79499 0.105755 0.884914 0.719467 0.844246 0.154072 0.844142 0.774385 0.823608 0.464168 0.844142 0.774385 0.844246 0.154072 0.776678 0.291529 0.79499 0.105755 0.737711 0.06512999 0.818356 0.404238 0.823608 0.464168 0.79499 0.105755 0.802618 0.346002 0.818356 0.404238 0.79499 0.105755 0.776678 0.291529 0.802618 0.346002 0.79499 0.105755 0.719617 0.2205899 0.737711 0.06512999 0.673398 0.03335493 0.741071 0.242671 0.776678 0.291529 0.737711 0.06512999 0.719617 0.2205899 0.741071 0.242671 0.737711 0.06512999 0.643456 0.1676 0.673398 0.03335493 0.603499 0.01144397 0.696129 0.200643 0.719617 0.2205899 0.673398 0.03335493 0.643456 0.1676 0.696129 0.200643 0.673398 0.03335493 0.584858 0.144848 0.603499 0.01144397 0.529944 1.76e-4 0.584858 0.144848 0.643456 0.1676 0.603499 0.01144397 0.522575 0.133298 0.529944 1.76e-4 0.455036 0 0.522575 0.133298 0.584858 0.144848 0.529944 1.76e-4 0.397034 0.145057 0.455036 0 0.381227 0.01096296 0.459108 0.133385 0.522575 0.133298 0.455036 0 0.397034 0.145057 0.459108 0.133385 0.455036 0 0.33879 0.167789 0.381227 0.01096296 0.310866 0.03270393 0.33879 0.167789 0.397034 0.145057 0.381227 0.01096296 0.286474 0.200658 0.310866 0.03270393 0.245983 0.06449598 0.286474 0.200658 0.33879 0.167789 0.310866 0.03270393 0.241758 0.242437 0.245983 0.06449598 0.188159 0.105318 0.241758 0.242437 0.286474 0.200658 0.245983 0.06449598 0.180187 0.345515 0.188159 0.105318 0.138484 0.153952 0.206203 0.291099 0.241758 0.242437 0.188159 0.105318 0.180187 0.345515 0.206203 0.291099 0.188159 0.105318 0.138379 0.774265 0.138484 0.153952 0.09771096 0.208869 0.159017 0.464168 0.138484 0.153952 0.138379 0.774265 0.170974 0.374304 0.180187 0.345515 0.138484 0.153952 0.164331 0.40389 0.170974 0.374304 0.138484 0.153952 0.160364 0.433795 0.164331 0.40389 0.138484 0.153952 0.159017 0.464168 0.160364 0.433795 0.138484 0.153952 0.066518 0.660579 0.09771096 0.208869 0.06630599 0.268239 0.09785097 0.719687 0.09771096 0.208869 0.066518 0.660579 0.138379 0.774265 0.09771096 0.208869 0.09785097 0.719687 0.04394197 0.597343 0.06630599 0.268239 0.04377889 0.331575 0.066518 0.660579 0.06630599 0.268239 0.04394197 0.597343 0.03035897 0.531427 0.04377889 0.331575 0.03029888 0.397347 0.04394197 0.597343 0.04377889 0.331575 0.03035897 0.531427 0.03035897 0.531427 0.03029888 0.397347 0.02582591 0.464168 0.159017 0.464168 0.138379 0.774265 0.187635 0.822581 0.2059479 0.636807 0.187635 0.822581 0.244915 0.863206 0.16427 0.524099 0.159017 0.464168 0.187635 0.822581 0.1800079 0.582334 0.16427 0.524099 0.187635 0.822581 0.2059479 0.636807 0.1800079 0.582334 0.187635 0.822581 0.263008 0.707747 0.244915 0.863206 0.309227 0.894981 0.241554 0.685665 0.2059479 0.636807 0.244915 0.863206 0.263008 0.707747 0.241554 0.685665 0.244915 0.863206 0.339169 0.760737 0.309227 0.894981 0.379126 0.916893 0.286496 0.727694 0.263008 0.707747 0.309227 0.894981 0.339169 0.760737 0.286496 0.727694 0.309227 0.894981 0.397767 0.783489 0.379126 0.916893 0.452681 0.928161 0.397767 0.783489 0.339169 0.760737 0.379126 0.916893 0.46005 0.795038 0.452681 0.928161 0.52759 0.928337 0.46005 0.795038 0.397767 0.783489 0.452681 0.928161 0.585591 0.78328 0.52759 0.928337 0.601399 0.917374 0.523517 0.794951 0.46005 0.795038 0.52759 0.928337 0.585591 0.78328 0.523517 0.794951 0.52759 0.928337 0.643835 0.760547 0.601399 0.917374 0.67176 0.895632 0.643835 0.760547 0.585591 0.78328 0.601399 0.917374 0.696151 0.727678 0.67176 0.895632 0.736642 0.86384 0.696151 0.727678 0.643835 0.760547 0.67176 0.895632 0.740867 0.685899 0.736642 0.86384 0.794466 0.823018 0.740867 0.685899 0.696151 0.727678 0.736642 0.86384 0.802439 0.582822 0.794466 0.823018 0.844142 0.774385 0.776423 0.637238 0.740867 0.685899 0.794466 0.823018 0.802439 0.582822 0.776423 0.637238 0.794466 0.823018 0.822262 0.494541 0.844142 0.774385 0.823608 0.464168 0.811651 0.554033 0.802439 0.582822 0.844142 0.774385 0.818295 0.524447 0.811651 0.554033 0.844142 0.774385 0.822262 0.494541 0.818295 0.524447 0.844142 0.774385 0.878361 0.464168 0.823608 0.464168 0.818356 0.404238 0.872403 0.533527 0.822262 0.494541 0.823608 0.464168 0.872403 0.533527 0.823608 0.464168 0.878361 0.464168 0.872334 0.394407 0.818356 0.404238 0.802618 0.346002 0.876834 0.429022 0.878361 0.464168 0.818356 0.404238 0.872334 0.394407 0.876834 0.429022 0.818356 0.404238 0.854307 0.326767 0.802618 0.346002 0.776678 0.291529 0.864789 0.36014 0.872334 0.394407 0.802618 0.346002 0.854307 0.326767 0.864789 0.36014 0.802618 0.346002 0.824591 0.263568 0.776678 0.291529 0.741071 0.242671 0.824591 0.263568 0.854307 0.326767 0.776678 0.291529 0.783722 0.206875 0.741071 0.242671 0.719617 0.2205899 0.783722 0.206875 0.824591 0.263568 0.741071 0.242671 0.731947 0.158022 0.719617 0.2205899 0.696129 0.200643 0.731947 0.158022 0.783722 0.206875 0.719617 0.2205899 0.67092 0.119445 0.696129 0.200643 0.643456 0.1676 0.67092 0.119445 0.731947 0.158022 0.696129 0.200643 0.60254 0.09267801 0.643456 0.1676 0.584858 0.144848 0.60254 0.09267801 0.67092 0.119445 0.643456 0.1676 0.529346 0.07890599 0.584858 0.144848 0.522575 0.133298 0.529346 0.07890599 0.60254 0.09267801 0.584858 0.144848 0.454391 0.078803 0.522575 0.133298 0.459108 0.133385 0.454391 0.078803 0.529346 0.07890599 0.522575 0.133298 0.380947 0.09243196 0.459108 0.133385 0.397034 0.145057 0.380947 0.09243196 0.454391 0.078803 0.459108 0.133385 0.312149 0.119222 0.397034 0.145057 0.33879 0.167789 0.312149 0.119222 0.380947 0.09243196 0.397034 0.145057 0.250704 0.158004 0.33879 0.167789 0.286474 0.200658 0.250704 0.158004 0.312149 0.119222 0.33879 0.167789 0.223459 0.181351 0.286474 0.200658 0.241758 0.242437 0.223459 0.181351 0.250704 0.158004 0.286474 0.200658 0.198667 0.207147 0.241758 0.242437 0.206203 0.291099 0.198667 0.207147 0.223459 0.181351 0.241758 0.242437 0.157742 0.264069 0.206203 0.291099 0.180187 0.345515 0.157742 0.264069 0.198667 0.207147 0.206203 0.291099 0.1281149 0.327332 0.180187 0.345515 0.170974 0.374304 0.1281149 0.327332 0.157742 0.264069 0.180187 0.345515 0.1281149 0.327332 0.170974 0.374304 0.164331 0.40389 0.110222 0.39481 0.164331 0.40389 0.160364 0.433795 0.110222 0.39481 0.1281149 0.327332 0.164331 0.40389 0.110222 0.39481 0.160364 0.433795 0.159017 0.464168 0.104264 0.464168 0.159017 0.464168 0.16427 0.524099 0.104264 0.464168 0.110222 0.39481 0.159017 0.464168 0.110291 0.53393 0.16427 0.524099 0.1800079 0.582334 0.105791 0.499314 0.104264 0.464168 0.16427 0.524099 0.110291 0.53393 0.105791 0.499314 0.16427 0.524099 0.128319 0.60157 0.1800079 0.582334 0.2059479 0.636807 0.117837 0.568197 0.110291 0.53393 0.1800079 0.582334 0.128319 0.60157 0.117837 0.568197 0.1800079 0.582334 0.158034 0.664769 0.2059479 0.636807 0.241554 0.685665 0.158034 0.664769 0.128319 0.60157 0.2059479 0.636807 0.198903 0.721462 0.241554 0.685665 0.263008 0.707747 0.198903 0.721462 0.158034 0.664769 0.241554 0.685665 0.250679 0.770315 0.263008 0.707747 0.286496 0.727694 0.250679 0.770315 0.198903 0.721462 0.263008 0.707747 0.311705 0.808892 0.286496 0.727694 0.339169 0.760737 0.311705 0.808892 0.250679 0.770315 0.286496 0.727694 0.380085 0.835658 0.339169 0.760737 0.397767 0.783489 0.380085 0.835658 0.311705 0.808892 0.339169 0.760737 0.453279 0.84943 0.397767 0.783489 0.46005 0.795038 0.453279 0.84943 0.380085 0.835658 0.397767 0.783489 0.528234 0.849533 0.46005 0.795038 0.523517 0.794951 0.528234 0.849533 0.453279 0.84943 0.46005 0.795038 0.601678 0.835904 0.523517 0.794951 0.585591 0.78328 0.601678 0.835904 0.528234 0.849533 0.523517 0.794951 0.670476 0.809115 0.585591 0.78328 0.643835 0.760547 0.670476 0.809115 0.601678 0.835904 0.585591 0.78328 0.731921 0.770333 0.643835 0.760547 0.696151 0.727678 0.731921 0.770333 0.670476 0.809115 0.643835 0.760547 0.759167 0.746986 0.696151 0.727678 0.740867 0.685899 0.759167 0.746986 0.731921 0.770333 0.696151 0.727678 0.783958 0.721189 0.740867 0.685899 0.776423 0.637238 0.783958 0.721189 0.759167 0.746986 0.740867 0.685899 0.824883 0.664268 0.776423 0.637238 0.802439 0.582822 0.824883 0.664268 0.783958 0.721189 0.776423 0.637238 0.854511 0.601005 0.802439 0.582822 0.811651 0.554033 0.854511 0.601005 0.824883 0.664268 0.802439 0.582822 0.854511 0.601005 0.811651 0.554033 0.818295 0.524447 0.872403 0.533527 0.818295 0.524447 0.822262 0.494541 0.872403 0.533527 0.854511 0.601005 0.818295 0.524447 0.872403 0.533527 0.878361 0.464168 0.876834 0.429022 0.872403 0.533527 0.876834 0.429022 0.872334 0.394407 0.872403 0.533527 0.872334 0.394407 0.864789 0.36014 0.854511 0.601005 0.864789 0.36014 0.854307 0.326767 0.872403 0.533527 0.864789 0.36014 0.854511 0.601005 0.824883 0.664268 0.854307 0.326767 0.824591 0.263568 0.854511 0.601005 0.854307 0.326767 0.824883 0.664268 0.783958 0.721189 0.824591 0.263568 0.783722 0.206875 0.824883 0.664268 0.824591 0.263568 0.783958 0.721189 0.759167 0.746986 0.783722 0.206875 0.731947 0.158022 0.783958 0.721189 0.783722 0.206875 0.759167 0.746986 0.731921 0.770333 0.731947 0.158022 0.67092 0.119445 0.759167 0.746986 0.731947 0.158022 0.731921 0.770333 0.670476 0.809115 0.67092 0.119445 0.60254 0.09267801 0.731921 0.770333 0.67092 0.119445 0.670476 0.809115 0.601678 0.835904 0.60254 0.09267801 0.529346 0.07890599 0.670476 0.809115 0.60254 0.09267801 0.601678 0.835904 0.528234 0.849533 0.529346 0.07890599 0.454391 0.078803 0.601678 0.835904 0.529346 0.07890599 0.528234 0.849533 0.453279 0.84943 0.454391 0.078803 0.380947 0.09243196 0.528234 0.849533 0.454391 0.078803 0.453279 0.84943 0.380085 0.835658 0.380947 0.09243196 0.312149 0.119222 0.453279 0.84943 0.380947 0.09243196 0.380085 0.835658 0.311705 0.808892 0.312149 0.119222 0.250704 0.158004 0.380085 0.835658 0.312149 0.119222 0.311705 0.808892 0.250679 0.770315 0.250704 0.158004 0.223459 0.181351 0.311705 0.808892 0.250704 0.158004 0.250679 0.770315 0.198903 0.721462 0.223459 0.181351 0.198667 0.207147 0.250679 0.770315 0.223459 0.181351 0.198903 0.721462 0.158034 0.664769 0.198667 0.207147 0.157742 0.264069 0.198903 0.721462 0.198667 0.207147 0.158034 0.664769 0.128319 0.60157 0.157742 0.264069 0.1281149 0.327332 0.158034 0.664769 0.157742 0.264069 0.128319 0.60157 0.117837 0.568197 0.1281149 0.327332 0.110222 0.39481 0.128319 0.60157 0.1281149 0.327332 0.117837 0.568197 0.105791 0.499314 0.110222 0.39481 0.104264 0.464168 0.110291 0.53393 0.110222 0.39481 0.105791 0.499314 0.117837 0.568197 0.110222 0.39481 0.110291 0.53393 0.783064 0.527967 0.796832 0.528168 0.794154 0.528978 0.790909 0.555589 0.796832 0.528168 0.783064 0.582238 0.783064 0.527967 0.783064 0.582238 0.796832 0.528168 0.783064 0.527967 0.794154 0.528978 0.791391 0.529809 0.777042 0.529588 0.791391 0.529809 0.78522 0.55665 0.779746 0.527945 0.783064 0.527967 0.791391 0.529809 0.777042 0.529588 0.779746 0.527945 0.791391 0.529809 0.777042 0.529588 0.78522 0.55665 0.777042 0.582974 0.777042 0.529588 0.777042 0.582974 0.773516 0.592922 0.772599 0.529456 0.773516 0.592922 0.770856 0.600493 0.777042 0.529588 0.773516 0.592922 0.772599 0.529456 0.769241 0.529229 0.770856 0.600493 0.76897 0.606153 0.772599 0.529456 0.770856 0.600493 0.769241 0.529229 0.769241 0.529229 0.76897 0.606153 0.767775 0.610231 0.767416 0.52894 0.767775 0.610231 0.76721 0.612933 0.769241 0.529229 0.767775 0.610231 0.767416 0.52894 0.767416 0.52894 0.76721 0.612933 0.767236 0.61433 0.767347 0.528631 0.767236 0.61433 0.767754 0.614538 0.767416 0.52894 0.767236 0.61433 0.767347 0.528631 0.767347 0.528631 0.767754 0.614538 0.768708 0.613713 0.76902 0.528344 0.768708 0.613713 0.770153 0.611737 0.767347 0.528631 0.768708 0.613713 0.76902 0.528344 0.76902 0.528344 0.770153 0.611737 0.772045 0.608548 0.772197 0.528116 0.772045 0.608548 0.774305 0.604159 0.76902 0.528344 0.772045 0.608548 0.772197 0.528116 0.776451 0.527978 0.774305 0.604159 0.776909 0.598459 0.772197 0.528116 0.774305 0.604159 0.776451 0.527978 0.779746 0.527945 0.776909 0.598459 0.779839 0.591251 0.776451 0.527978 0.776909 0.598459 0.779746 0.527945 0.779746 0.527945 0.779839 0.591251 0.783064 0.582238 0.779746 0.527945 0.783064 0.582238 0.783064 0.527967 0.777042 0.529588 0.776451 0.527978 0.779746 0.527945 0.777042 0.529588 0.772197 0.528116 0.776451 0.527978 0.777042 0.529588 0.76902 0.528344 0.772197 0.528116 0.772599 0.529456 0.767347 0.528631 0.76902 0.528344 0.777042 0.529588 0.772599 0.529456 0.76902 0.528344 0.769241 0.529229 0.767416 0.52894 0.767347 0.528631 0.772599 0.529456 0.769241 0.529229 0.767347 0.528631 0.838835 0.550794 0.839553 0.550773 0.84028 0.550755 0.833136 0.551086 0.838835 0.550794 0.84028 0.550755 0.143073 0.550773 0.143791 0.550794 0.1494899 0.551087 0.142346 0.550755 0.143073 0.550773 0.1494899 0.551087 0.8011 0.53759 0.801715 0.537576 0.802337 0.537565 0.796171 0.537787 0.8011 0.53759 0.802337 0.537565 0.091623 0.272003 0.2179909 0.263531 0.226733 0.272218 0.07880097 0.268957 0.213342 0.260991 0.2179909 0.263531 0.07880097 0.268957 0.2179909 0.263531 0.091623 0.272003 0.103784 0.279933 0.226733 0.272218 0.2347469 0.285269 0.09783697 0.275413 0.091623 0.272003 0.226733 0.272218 0.103784 0.279933 0.09783697 0.275413 0.226733 0.272218 0.11494 0.292152 0.2347469 0.285269 0.241888 0.302042 0.11494 0.292152 0.103784 0.279933 0.2347469 0.285269 0.124889 0.308016 0.241888 0.302042 0.248057 0.321857 0.124889 0.308016 0.11494 0.292152 0.241888 0.302042 0.133493 0.326853 0.248057 0.321857 0.250798 0.33287 0.133493 0.326853 0.124889 0.308016 0.248057 0.321857 0.1408039 0.348427 0.250798 0.33287 0.253291 0.344484 0.1408039 0.348427 0.133493 0.326853 0.250798 0.33287 0.1408039 0.348427 0.253291 0.344484 0.255519 0.356607 0.1466799 0.372027 0.255519 0.356607 0.257485 0.369174 0.1466799 0.372027 0.1408039 0.348427 0.255519 0.356607 0.151099 0.397161 0.257485 0.369174 0.260625 0.39539 0.151099 0.397161 0.1466799 0.372027 0.257485 0.369174 0.154057 0.423386 0.260625 0.39539 0.262708 0.422645 0.154057 0.423386 0.151099 0.397161 0.260625 0.39539 0.155547 0.450281 0.262708 0.422645 0.263741 0.450489 0.155547 0.450281 0.154057 0.423386 0.262708 0.422645 0.155564 0.477426 0.263741 0.450489 0.263729 0.478497 0.155564 0.477426 0.155547 0.450281 0.263741 0.450489 0.154102 0.504401 0.263729 0.478497 0.262676 0.506259 0.154102 0.504401 0.155564 0.477426 0.263729 0.478497 0.151156 0.530777 0.262676 0.506259 0.260584 0.53336 0.151156 0.530777 0.154102 0.504401 0.262676 0.506259 0.146724 0.556097 0.260584 0.53336 0.257453 0.559382 0.146724 0.556097 0.151156 0.530777 0.260584 0.53336 0.1439509 0.568209 0.257453 0.559382 0.253283 0.58389 0.1439509 0.568209 0.146724 0.556097 0.257453 0.559382 0.137308 0.591024 0.253283 0.58389 0.248082 0.606388 0.140814 0.579873 0.1439509 0.568209 0.253283 0.58389 0.137308 0.591024 0.140814 0.579873 0.253283 0.58389 0.133459 0.601571 0.248082 0.606388 0.241941 0.626149 0.133459 0.601571 0.137308 0.591024 0.248082 0.606388 0.124816 0.620459 0.241941 0.626149 0.234813 0.642937 0.124816 0.620459 0.133459 0.601571 0.241941 0.626149 0.114848 0.636307 0.234813 0.642937 0.226785 0.656051 0.114848 0.636307 0.124816 0.620459 0.234813 0.642937 0.103712 0.648466 0.226785 0.656051 0.22249 0.660994 0.103712 0.648466 0.114848 0.636307 0.226785 0.656051 0.103712 0.648466 0.22249 0.660994 0.2179909 0.664805 0.091623 0.656334 0.2179909 0.664805 0.208667 0.668544 0.091623 0.656334 0.103712 0.648466 0.2179909 0.664805 0.07871896 0.659382 0.208667 0.668544 0.19896 0.66673 0.085222 0.658504 0.091623 0.656334 0.208667 0.668544 0.07871896 0.659382 0.085222 0.658504 0.208667 0.668544 0.06541299 0.657024 0.19896 0.66673 0.1891829 0.658832 0.06541299 0.657024 0.07871896 0.659382 0.19896 0.66673 0.05214196 0.648874 0.1891829 0.658832 0.179717 0.644556 0.05214196 0.648874 0.06541299 0.657024 0.1891829 0.658832 0.03941088 0.634785 0.179717 0.644556 0.1751649 0.634856 0.03941088 0.634785 0.05214196 0.648874 0.179717 0.644556 0.02753597 0.614483 0.1751649 0.634856 0.170817 0.623489 0.02753597 0.614483 0.03941088 0.634785 0.1751649 0.634856 0.02753597 0.614483 0.170817 0.623489 0.166754 0.610507 0.017192 0.588394 0.166754 0.610507 0.163018 0.595989 0.017192 0.588394 0.02753597 0.614483 0.166754 0.610507 0.008887946 0.5572 0.163018 0.595989 0.156744 0.562777 0.008887946 0.5572 0.017192 0.588394 0.163018 0.595989 0.00305891 0.521949 0.156744 0.562777 0.152353 0.525052 0.00305891 0.521949 0.008887946 0.5572 0.156744 0.562777 3.5e-5 0.48405 0.152353 0.525052 0.150106 0.484456 3.5e-5 0.48405 0.00305891 0.521949 0.152353 0.525052 0 0.445186 0.150106 0.484456 0.150132 0.44292 0 0.445186 3.5e-5 0.48405 0.150106 0.484456 0.002967894 0.407148 0.150132 0.44292 0.152423 0.402474 0.002967894 0.407148 0 0.445186 0.150132 0.44292 0.008777976 0.371655 0.152423 0.402474 0.156827 0.365011 0.008777976 0.371655 0.002967894 0.407148 0.152423 0.402474 0.017111 0.340193 0.156827 0.365011 0.163079 0.332085 0.017111 0.340193 0.008777976 0.371655 0.156827 0.365011 0.022089 0.326344 0.163079 0.332085 0.17083 0.304808 0.022089 0.326344 0.017111 0.340193 0.163079 0.332085 0.03334498 0.302916 0.17083 0.304808 0.179678 0.283856 0.02751797 0.313891 0.022089 0.326344 0.17083 0.304808 0.03334498 0.302916 0.02751797 0.313891 0.17083 0.304808 0.03946393 0.293478 0.179678 0.283856 0.189107 0.269592 0.03946393 0.293478 0.03334498 0.302916 0.179678 0.283856 0.05224597 0.279374 0.189107 0.269592 0.198875 0.261648 0.05224597 0.279374 0.03946393 0.293478 0.189107 0.269592 0.06553 0.271267 0.198875 0.261648 0.208608 0.259786 0.06553 0.271267 0.05224597 0.279374 0.198875 0.261648 0.07880097 0.268957 0.208608 0.259786 0.213342 0.260991 0.07880097 0.268957 0.06553 0.271267 0.208608 0.259786 0.091623 0.656334 0.091623 0.272003 0.09783697 0.275413 0.085222 0.658504 0.091623 0.272003 0.091623 0.656334 0.07880097 0.268957 0.091623 0.272003 0.085222 0.658504 0.103712 0.648466 0.09783697 0.275413 0.103784 0.279933 0.091623 0.656334 0.09783697 0.275413 0.103712 0.648466 0.114848 0.636307 0.103784 0.279933 0.11494 0.292152 0.103712 0.648466 0.103784 0.279933 0.114848 0.636307 0.124816 0.620459 0.11494 0.292152 0.124889 0.308016 0.114848 0.636307 0.11494 0.292152 0.124816 0.620459 0.133459 0.601571 0.124889 0.308016 0.133493 0.326853 0.124816 0.620459 0.124889 0.308016 0.133459 0.601571 0.137308 0.591024 0.133493 0.326853 0.1408039 0.348427 0.133459 0.601571 0.133493 0.326853 0.137308 0.591024 0.140814 0.579873 0.1408039 0.348427 0.1466799 0.372027 0.137308 0.591024 0.1408039 0.348427 0.140814 0.579873 0.146724 0.556097 0.1466799 0.372027 0.151099 0.397161 0.1439509 0.568209 0.1466799 0.372027 0.146724 0.556097 0.140814 0.579873 0.1466799 0.372027 0.1439509 0.568209 0.151156 0.530777 0.151099 0.397161 0.154057 0.423386 0.146724 0.556097 0.151099 0.397161 0.151156 0.530777 0.154102 0.504401 0.154057 0.423386 0.155547 0.450281 0.151156 0.530777 0.154057 0.423386 0.154102 0.504401 0.154102 0.504401 0.155547 0.450281 0.155564 0.477426 0.07880097 0.268957 0.085222 0.658504 0.07871896 0.659382 0.06553 0.271267 0.07871896 0.659382 0.06541299 0.657024 0.07880097 0.268957 0.07871896 0.659382 0.06553 0.271267 0.05224597 0.279374 0.06541299 0.657024 0.05214196 0.648874 0.06553 0.271267 0.06541299 0.657024 0.05224597 0.279374 0.03946393 0.293478 0.05214196 0.648874 0.03941088 0.634785 0.05224597 0.279374 0.05214196 0.648874 0.03946393 0.293478 0.03334498 0.302916 0.03941088 0.634785 0.02753597 0.614483 0.03946393 0.293478 0.03941088 0.634785 0.03334498 0.302916 0.02751797 0.313891 0.02753597 0.614483 0.017192 0.588394 0.03334498 0.302916 0.02753597 0.614483 0.02751797 0.313891 0.017111 0.340193 0.017192 0.588394 0.008887946 0.5572 0.022089 0.326344 0.017192 0.588394 0.017111 0.340193 0.02751797 0.313891 0.017192 0.588394 0.022089 0.326344 0.008777976 0.371655 0.008887946 0.5572 0.00305891 0.521949 0.017111 0.340193 0.008887946 0.5572 0.008777976 0.371655 0.002967894 0.407148 0.00305891 0.521949 3.5e-5 0.48405 0.008777976 0.371655 0.00305891 0.521949 0.002967894 0.407148 0.002967894 0.407148 3.5e-5 0.48405 0 0.445186 0.311712 0.510253 0.31137 0.510408 0.309843 0.510547 0.421962 0.508798 0.40661 0.508818 0.405529 0.508704 0.422989 0.508655 0.421962 0.508798 0.405529 0.508704 0.419813 0.508914 0.408407 0.50891 0.40661 0.508818 0.421962 0.508798 0.419813 0.508914 0.40661 0.508818 0.416842 0.508986 0.410758 0.508975 0.408407 0.50891 0.419813 0.508914 0.416842 0.508986 0.408407 0.50891 0.416842 0.508986 0.413467 0.509004 0.410758 0.508975 0.547207 0.508384 0.529789 0.508403 0.529741 0.508265 0.547207 0.508384 0.53092 0.508531 0.529789 0.508403 0.546258 0.508512 0.532995 0.508635 0.53092 0.508531 0.547207 0.508384 0.546258 0.508512 0.53092 0.508531 0.54441 0.508617 0.535762 0.5087 0.532995 0.508635 0.546258 0.508512 0.54441 0.508617 0.532995 0.508635 0.541865 0.508689 0.538883 0.508719 0.535762 0.5087 0.54441 0.508617 0.541865 0.508689 0.535762 0.5087 0.787048 0.51859 0.793534 0.519745 0.789162 0.519769 0.780567 0.518879 0.789162 0.519769 0.784984 0.519698 0.783272 0.5187 0.789162 0.519769 0.780567 0.518879 0.787048 0.51859 0.789162 0.519769 0.783272 0.5187 0.779311 0.5191 0.784984 0.519698 0.781678 0.519545 0.780567 0.518879 0.784984 0.519698 0.779311 0.5191 0.779311 0.5191 0.781678 0.519545 0.779689 0.519335 0.721356 0.512893 0.726247 0.513738 0.722704 0.513676 0.719021 0.513034 0.722704 0.513676 0.719902 0.513553 0.721356 0.512893 0.722704 0.513676 0.719021 0.513034 0.717929 0.513207 0.719902 0.513553 0.718235 0.513389 0.719021 0.513034 0.719902 0.513553 0.717929 0.513207 0.652814 0.510213 0.637217 0.510243 0.635865 0.5101 0.652814 0.510213 0.63962 0.510355 0.637217 0.510243 0.651124 0.510313 0.642763 0.510419 0.63962 0.510355 0.652814 0.510213 0.651124 0.510313 0.63962 0.510355 0.64886 0.510386 0.646228 0.510424 0.642763 0.510419 0.651124 0.510313 0.64886 0.510386 0.642763 0.510419 0.491313 0.703997 0.491313 0.687273 0.501559 0.687582 0.480303 0.703615 0.491313 0.687273 0.491313 0.703997 0.481107 0.68758 0.491313 0.687273 0.480303 0.703615 0.512241 0.702525 0.501559 0.687582 0.511083 0.688495 0.502279 0.703618 0.501559 0.687582 0.512241 0.702525 0.491313 0.703997 0.501559 0.687582 0.502279 0.703618 0.520307 0.700844 0.511083 0.688495 0.519076 0.689946 0.512241 0.702525 0.511083 0.688495 0.520307 0.700844 0.525869 0.69874 0.519076 0.689946 0.524927 0.691836 0.520307 0.700844 0.519076 0.689946 0.525869 0.69874 0.528548 0.6964 0.524927 0.691836 0.528193 0.694041 0.525869 0.69874 0.524927 0.691836 0.528548 0.6964 0.471662 0.688479 0.480303 0.703615 0.470261 0.702505 0.481107 0.68758 0.480303 0.703615 0.471662 0.688479 0.463706 0.689908 0.470261 0.702505 0.462164 0.7008 0.471662 0.688479 0.470261 0.702505 0.463706 0.689908 0.053267 0.006302893 0.053047 0.00444597 0.04321491 8.7e-4 0.04321491 0.01459091 0.04321491 8.7e-4 0.053047 0.00444597 0.04391497 0.01014691 0.053267 0.006302893 0.04321491 8.7e-4 0.03981095 3.75e-4 0.04391497 0.01014691 0.04321491 8.7e-4 0.03981095 0.01406788 0.03981095 3.75e-4 0.04321491 8.7e-4 0.03981095 0.01406788 0.04321491 8.7e-4 0.04321491 0.01459091 0.05345588 0.00583595 0.05334496 0.004904985 0.053047 0.00444597 0.053047 0.01836699 0.053047 0.00444597 0.05334496 0.004904985 0.053267 0.006302893 0.05345588 0.00583595 0.053047 0.00444597 0.053047 0.01836699 0.04321491 0.01459091 0.053047 0.00444597 0.05345588 0.00583595 0.05348193 0.005368888 0.05334496 0.004904985 0.05334496 0.01885098 0.05334496 0.004904985 0.05348193 0.005368888 0.05334496 0.01885098 0.053047 0.01836699 0.05334496 0.004904985 0.05348193 0.01934099 0.05348193 0.005368888 0.05345588 0.00583595 0.05334496 0.01885098 0.05348193 0.005368888 0.05348193 0.01934099 0.05345588 0.01983398 0.05345588 0.00583595 0.053267 0.006302893 0.05345588 0.01983398 0.05348193 0.01934099 0.05345588 0.00583595 0.053267 0.02032589 0.053267 0.006302893 0.04391497 0.01014691 0.05345588 0.01983398 0.053267 0.006302893 0.053267 0.02032589 0.03981095 3.75e-4 0.04043096 0.01070892 0.04391497 0.01014691 0.04391497 0.02438396 0.04391497 0.01014691 0.04043096 0.01070892 0.053267 0.02032589 0.04391497 0.01014691 0.04391497 0.02438396 0.03610998 0 0.0365889 0.01113992 0.04043096 0.01070892 0.04043096 0.0249769 0.04043096 0.01070892 0.0365889 0.01113992 0.03981095 3.75e-4 0.03610998 0 0.04043096 0.01070892 0.04043096 0.0249769 0.04391497 0.02438396 0.04043096 0.01070892 0.01737296 0 0.01689291 0.01113992 0.0365889 0.01113992 0.0365889 0.02543199 0.0365889 0.01113992 0.01689291 0.01113992 0.03610998 0 0.01737296 0 0.0365889 0.01113992 0.04043096 0.0249769 0.0365889 0.01113992 0.0365889 0.02543199 0.01367098 3.75e-4 0.01305097 0.01070892 0.01689291 0.01113992 0.01689291 0.02543199 0.01689291 0.01113992 0.01305097 0.01070892 0.01737296 0 0.01367098 3.75e-4 0.01689291 0.01113992 0.0365889 0.02543199 0.01689291 0.01113992 0.01689291 0.02543199 0.0102669 8.7e-4 0.009566962 0.01014691 0.01305097 0.01070892 0.01305097 0.0249769 0.01305097 0.01070892 0.009566962 0.01014691 0.01367098 3.75e-4 0.0102669 8.7e-4 0.01305097 0.01070892 0.01305097 0.0249769 0.01689291 0.02543199 0.01305097 0.01070892 4.36e-4 0.00444597 2.16e-4 0.006302893 0.009566962 0.01014691 0.009566962 0.02438396 0.009566962 0.01014691 2.16e-4 0.006302893 0.0102669 8.7e-4 4.36e-4 0.00444597 0.009566962 0.01014691 0.01305097 0.0249769 0.009566962 0.01014691 0.009566962 0.02438396 1.37e-4 0.004904985 2.6e-5 0.00583595 2.16e-4 0.006302893 2.16e-4 0.02032589 2.16e-4 0.006302893 2.6e-5 0.00583595 4.36e-4 0.00444597 1.37e-4 0.004904985 2.16e-4 0.006302893 0.009566962 0.02438396 2.16e-4 0.006302893 2.16e-4 0.02032589 1.37e-4 0.004904985 0 0.005368888 2.6e-5 0.00583595 2.6e-5 0.01983398 2.6e-5 0.00583595 0 0.005368888 2.6e-5 0.01983398 2.16e-4 0.02032589 2.6e-5 0.00583595 0 0.01934099 0 0.005368888 1.37e-4 0.004904985 0 0.01934099 2.6e-5 0.01983398 0 0.005368888 1.37e-4 0.01885098 1.37e-4 0.004904985 4.36e-4 0.00444597 1.37e-4 0.01885098 0 0.01934099 1.37e-4 0.004904985 4.36e-4 0.01836699 4.36e-4 0.00444597 0.0102669 8.7e-4 1.37e-4 0.01885098 4.36e-4 0.00444597 4.36e-4 0.01836699 0.0102669 0.01459091 0.0102669 8.7e-4 0.01367098 3.75e-4 4.36e-4 0.01836699 0.0102669 8.7e-4 0.0102669 0.01459091 0.01367098 0.01406788 0.01367098 3.75e-4 0.01737296 0 0.01367098 0.01406788 0.0102669 0.01459091 0.01367098 3.75e-4 0.01737296 0.01367199 0.01737296 0 0.03610998 0 0.01367098 0.01406788 0.01737296 0 0.01737296 0.01367199 0.03610998 0.01367199 0.03610998 0 0.03981095 3.75e-4 0.01737296 0.01367199 0.03610998 0 0.03610998 0.01367199 0.03981095 0.01406788 0.03610998 0.01367199 0.03981095 3.75e-4 0.04582893 0.01720988 0.04321491 0.01459091 0.053047 0.01836699 0.03984797 0.01552498 0.03981095 0.01406788 0.04321491 0.01459091 0.04582893 0.01720988 0.03984797 0.01552498 0.04321491 0.01459091 0.053267 0.02032589 0.04391497 0.02438396 0.053047 0.01836699 0.04813593 0.01937097 0.053047 0.01836699 0.04391497 0.02438396 0.05334496 0.01885098 0.053267 0.02032589 0.053047 0.01836699 0.04749697 0.01825499 0.04582893 0.01720988 0.053047 0.01836699 0.04813593 0.01937097 0.04749697 0.01825499 0.053047 0.01836699 0.03984797 0.01552498 0.03610998 0.01367199 0.03981095 0.01406788 0.02206999 0.01460593 0.01737296 0.01367199 0.03610998 0.01367199 0.03139698 0.01460492 0.02206999 0.01460593 0.03610998 0.01367199 0.03984797 0.01552498 0.03139698 0.01460492 0.03610998 0.01367199 0.01361989 0.01552695 0.01367098 0.01406788 0.01737296 0.01367199 0.02206999 0.01460593 0.01361989 0.01552695 0.01737296 0.01367199 0.007642984 0.01721495 0.0102669 0.01459091 0.01367098 0.01406788 2.16e-4 0.02032589 4.36e-4 0.01836699 0.0102669 0.01459091 0.005346 0.01937097 2.16e-4 0.02032589 0.0102669 0.01459091 0.007642984 0.01721495 0.005346 0.01937097 0.0102669 0.01459091 0.01361989 0.01552695 0.007642984 0.01721495 0.01367098 0.01406788 2.6e-5 0.01983398 4.36e-4 0.01836699 2.16e-4 0.02032589 1.37e-4 0.01885098 4.36e-4 0.01836699 2.6e-5 0.01983398 0.007294893 0.02159088 0.009566962 0.02438396 2.16e-4 0.02032589 0.005785942 0.02050197 2.16e-4 0.02032589 0.005346 0.01937097 0.005785942 0.02050197 0.007294893 0.02159088 2.16e-4 0.02032589 1.37e-4 0.01885098 2.6e-5 0.01983398 0 0.01934099 0.013188 0.02340698 0.01305097 0.0249769 0.009566962 0.02438396 0.007294893 0.02159088 0.013188 0.02340698 0.009566962 0.02438396 0.013188 0.02340698 0.01689291 0.02543199 0.01305097 0.0249769 0.0316109 0.02443099 0.0365889 0.02543199 0.01689291 0.02543199 0.021887 0.024432 0.0316109 0.02443099 0.01689291 0.02543199 0.013188 0.02340698 0.021887 0.024432 0.01689291 0.02543199 0.04030895 0.02340495 0.04043096 0.0249769 0.0365889 0.02543199 0.0316109 0.02443099 0.04030895 0.02340495 0.0365889 0.02543199 0.04619693 0.021586 0.04391497 0.02438396 0.04043096 0.0249769 0.04619693 0.021586 0.04813593 0.01937097 0.04391497 0.02438396 0.04030895 0.02340495 0.04619693 0.021586 0.04043096 0.0249769 0.05334496 0.01885098 0.05345588 0.01983398 0.053267 0.02032589 0.05334496 0.01885098 0.05348193 0.01934099 0.05345588 0.01983398 0.005346 0.03057998 0.005346 0.01937097 0.007642984 0.01721495 0.007284939 0.03288698 0.005785942 0.02050197 0.005346 0.01937097 0.007284939 0.03288698 0.005346 0.01937097 0.005346 0.03057998 0.007653951 0.02832895 0.007642984 0.01721495 0.01361989 0.01552695 0.005984902 0.02941799 0.005346 0.03057998 0.007642984 0.01721495 0.007653951 0.02832895 0.005984902 0.02941799 0.007642984 0.01721495 0.0136339 0.026573 0.01361989 0.01552695 0.02206999 0.01460593 0.0136339 0.026573 0.007653951 0.02832895 0.01361989 0.01552695 0.02208596 0.02561396 0.02206999 0.01460593 0.03139698 0.01460492 0.02208596 0.02561396 0.0136339 0.026573 0.02206999 0.01460593 0.031412 0.02561491 0.03139698 0.01460492 0.03984797 0.01552498 0.031412 0.02561491 0.02208596 0.02561396 0.03139698 0.01460492 0.03986191 0.0265749 0.03984797 0.01552498 0.04582893 0.01720988 0.03986191 0.0265749 0.031412 0.02561491 0.03984797 0.01552498 0.04583895 0.02833396 0.04582893 0.01720988 0.04749697 0.01825499 0.04583895 0.02833396 0.03986191 0.0265749 0.04582893 0.01720988 0.04583895 0.02833396 0.04749697 0.01825499 0.04813593 0.01937097 0.04813593 0.03057998 0.04813593 0.01937097 0.04619693 0.021586 0.04813593 0.03057998 0.04583895 0.02833396 0.04813593 0.01937097 0.04618698 0.032893 0.04619693 0.021586 0.04030895 0.02340495 0.04769599 0.03175896 0.04813593 0.03057998 0.04619693 0.021586 0.04618698 0.032893 0.04769599 0.03175896 0.04619693 0.021586 0.040295 0.03478497 0.04030895 0.02340495 0.0316109 0.02443099 0.040295 0.03478497 0.04618698 0.032893 0.04030895 0.02340495 0.03159499 0.03585195 0.0316109 0.02443099 0.021887 0.024432 0.03159499 0.03585195 0.040295 0.03478497 0.0316109 0.02443099 0.02187097 0.035851 0.021887 0.024432 0.013188 0.02340698 0.02187097 0.035851 0.03159499 0.03585195 0.021887 0.024432 0.01317298 0.03478199 0.013188 0.02340698 0.007294893 0.02159088 0.01317298 0.03478199 0.02187097 0.035851 0.013188 0.02340698 0.007284939 0.03288698 0.007294893 0.02159088 0.005785942 0.02050197 0.007284939 0.03288698 0.01317298 0.03478199 0.007294893 0.02159088 0.007284939 0.03288698 0.005346 0.03057998 0.005984902 0.02941799 0.007284939 0.03288698 0.005984902 0.02941799 0.007653951 0.02832895 0.009445965 0.03059995 0.007653951 0.02832895 0.0136339 0.026573 0.009445965 0.03059995 0.007284939 0.03288698 0.007653951 0.02832895 0.01466298 0.02765196 0.0136339 0.026573 0.02208596 0.02561396 0.01188695 0.02850699 0.009445965 0.03059995 0.0136339 0.026573 0.01466298 0.02765196 0.01188695 0.02850699 0.0136339 0.026573 0.02237999 0.02659696 0.02208596 0.02561396 0.031412 0.02561491 0.01824992 0.02699995 0.01466298 0.02765196 0.02208596 0.02561396 0.02237999 0.02659696 0.01824992 0.02699995 0.02208596 0.02561396 0.03527593 0.02700597 0.031412 0.02561491 0.03986191 0.0265749 0.02678495 0.026461 0.02237999 0.02659696 0.031412 0.02561491 0.03527593 0.02700597 0.02678495 0.026461 0.031412 0.02561491 0.04158896 0.02850395 0.03986191 0.0265749 0.04583895 0.02833396 0.04158896 0.02850395 0.03527593 0.02700597 0.03986191 0.0265749 0.04769599 0.03175896 0.04583895 0.02833396 0.04813593 0.03057998 0.04618698 0.032893 0.04583895 0.02833396 0.04769599 0.03175896 0.04403597 0.03059995 0.04583895 0.02833396 0.04618698 0.032893 0.04403597 0.03059995 0.04158896 0.02850395 0.04583895 0.02833396 0.04403597 0.03059995 0.04618698 0.032893 0.040295 0.03478497 0.03911799 0.03365296 0.040295 0.03478497 0.03159499 0.03585195 0.04185491 0.032745 0.04403597 0.03059995 0.040295 0.03478497 0.03911799 0.03365296 0.04185491 0.032745 0.040295 0.03478497 0.03125 0.03479999 0.03159499 0.03585195 0.02187097 0.035851 0.03549093 0.03435695 0.03911799 0.03365296 0.03159499 0.03585195 0.03125 0.03479999 0.03549093 0.03435695 0.03159499 0.03585195 0.01794689 0.03435099 0.02187097 0.035851 0.01317298 0.03478199 0.0266959 0.03494799 0.03125 0.03479999 0.02187097 0.035851 0.01794689 0.03435099 0.0266959 0.03494799 0.02187097 0.035851 0.01163399 0.03274798 0.01317298 0.03478199 0.007284939 0.03288698 0.01163399 0.03274798 0.01794689 0.03435099 0.01317298 0.03478199 0.01163399 0.03274798 0.007284939 0.03288698 0.009445965 0.03059995 0.009445965 0.04224199 0.009445965 0.03059995 0.01188695 0.02850699 0.01162797 0.04447489 0.01163399 0.03274798 0.009445965 0.03059995 0.01162797 0.04447489 0.009445965 0.03059995 0.009445965 0.04224199 0.01189297 0.04005998 0.01188695 0.02850699 0.01466298 0.02765196 0.01189297 0.04005998 0.009445965 0.04224199 0.01188695 0.02850699 0.018206 0.03849995 0.01466298 0.02765196 0.01824992 0.02699995 0.018206 0.03849995 0.01189297 0.04005998 0.01466298 0.02765196 0.018206 0.03849995 0.01824992 0.02699995 0.02237999 0.02659696 0.02669799 0.03793299 0.02237999 0.02659696 0.02678495 0.026461 0.02669799 0.03793299 0.018206 0.03849995 0.02237999 0.02659696 0.031102 0.03807389 0.02678495 0.026461 0.03527593 0.02700597 0.031102 0.03807389 0.02669799 0.03793299 0.02678495 0.026461 0.03881895 0.03917199 0.03527593 0.02700597 0.04158896 0.02850395 0.03523188 0.03849399 0.031102 0.03807389 0.03527593 0.02700597 0.03881895 0.03917199 0.03523188 0.03849399 0.03527593 0.02700597 0.04159599 0.04006296 0.04158896 0.02850395 0.04403597 0.03059995 0.04159599 0.04006296 0.03881895 0.03917199 0.04158896 0.02850395 0.04403597 0.04224199 0.04403597 0.03059995 0.04185491 0.032745 0.04403597 0.04224199 0.04159599 0.04006296 0.04403597 0.03059995 0.041848 0.04447793 0.04185491 0.032745 0.03911799 0.03365296 0.041848 0.04447793 0.04403597 0.04224199 0.04185491 0.032745 0.03553491 0.04614692 0.03911799 0.03365296 0.03549093 0.03435695 0.03553491 0.04614692 0.041848 0.04447793 0.03911799 0.03365296 0.03553491 0.04614692 0.03549093 0.03435695 0.03125 0.03479999 0.02678591 0.04676896 0.03125 0.03479999 0.0266959 0.03494799 0.02678591 0.04676896 0.03553491 0.04614692 0.03125 0.03479999 0.02223199 0.04661399 0.0266959 0.03494799 0.01794689 0.03435099 0.02223199 0.04661399 0.02678591 0.04676896 0.0266959 0.03494799 0.014364 0.04541999 0.01794689 0.03435099 0.01163399 0.03274798 0.017991 0.04615288 0.02223199 0.04661399 0.01794689 0.03435099 0.014364 0.04541999 0.017991 0.04615288 0.01794689 0.03435099 0.01162797 0.04447489 0.014364 0.04541999 0.01163399 0.03274798 0.01162797 0.04447489 0.009445965 0.04224199 0.01189297 0.04005998 0.014364 0.04541999 0.01189297 0.04005998 0.018206 0.03849995 0.01162797 0.04447489 0.01189297 0.04005998 0.014364 0.04541999 0.017991 0.04615288 0.018206 0.03849995 0.02669799 0.03793299 0.014364 0.04541999 0.018206 0.03849995 0.017991 0.04615288 0.02678591 0.04676896 0.02669799 0.03793299 0.031102 0.03807389 0.02223199 0.04661399 0.02669799 0.03793299 0.02678591 0.04676896 0.017991 0.04615288 0.02669799 0.03793299 0.02223199 0.04661399 0.02678591 0.04676896 0.031102 0.03807389 0.03523188 0.03849399 0.03553491 0.04614692 0.03523188 0.03849399 0.03881895 0.03917199 0.02678591 0.04676896 0.03523188 0.03849399 0.03553491 0.04614692 0.041848 0.04447793 0.03881895 0.03917199 0.04159599 0.04006296 0.03553491 0.04614692 0.03881895 0.03917199 0.041848 0.04447793 0.041848 0.04447793 0.04159599 0.04006296 0.04403597 0.04224199 - - - - - - - - - - - - - - -

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 7 7 7 8 8 8 9 9 9 6 6 10 8 8 11 10 10 12 11 11 13 12 12 14 13 13 15 4 4 16 3 3 17 0 0 18 14 14 19 1 1 20 15 15 21 16 15 22 17 15 23 0 0 24 18 16 25 14 14 26 15 17 27 17 17 28 19 17 29 20 18 30 21 19 31 18 16 32 22 20 33 19 20 34 23 20 35 0 0 36 20 18 37 18 16 38 15 21 39 19 21 40 22 21 41 24 22 42 25 23 43 21 19 44 26 24 45 23 24 46 27 24 47 20 18 48 24 22 49 21 19 50 28 24 51 22 24 52 23 24 53 26 24 54 28 24 55 23 24 56 29 25 57 30 26 58 25 23 59 31 24 60 27 24 61 32 24 62 24 22 63 29 25 64 25 23 65 31 27 66 26 27 67 27 27 68 33 28 69 34 29 70 30 26 71 35 30 72 32 30 73 36 30 74 37 31 75 33 28 76 30 26 77 29 25 78 37 31 79 30 26 80 38 24 81 31 24 82 32 24 83 35 32 84 38 32 85 32 32 86 39 33 87 40 34 88 34 29 89 41 24 90 36 24 91 42 24 92 43 35 93 39 33 94 34 29 95 33 28 96 43 35 97 34 29 98 41 36 99 35 36 100 36 36 101 44 37 102 45 38 103 40 34 104 46 24 105 42 24 106 47 24 107 48 39 108 44 37 109 40 34 110 39 33 111 48 39 112 40 34 113 46 24 114 41 24 115 42 24 116 49 40 117 50 41 118 45 38 119 51 24 120 47 24 121 52 24 122 53 42 123 49 40 124 45 38 125 44 37 126 53 42 127 45 38 128 51 43 129 46 43 130 47 43 131 54 44 132 55 45 133 50 41 134 56 46 135 52 46 136 57 46 137 58 47 138 54 44 139 50 41 140 49 40 141 58 47 142 50 41 143 56 48 144 51 48 145 52 48 146 59 49 147 60 50 148 55 45 149 61 24 150 57 24 151 62 24 152 63 51 153 59 49 154 55 45 155 54 44 156 63 51 157 55 45 158 61 24 159 56 24 160 57 24 161 64 52 162 65 53 163 60 50 164 66 54 165 62 54 166 67 54 167 68 55 168 64 52 169 60 50 170 59 49 171 68 55 172 60 50 173 69 24 174 62 24 175 66 24 176 69 24 177 61 24 178 62 24 179 70 56 180 71 57 181 65 53 182 72 24 183 67 24 184 73 24 185 74 58 186 70 56 187 65 53 188 64 52 189 74 58 190 65 53 191 75 24 192 66 24 193 67 24 194 72 24 195 75 24 196 67 24 197 76 59 198 77 60 199 71 57 200 78 61 201 73 61 202 79 61 203 80 62 204 76 59 205 71 57 206 70 56 207 80 62 208 71 57 209 78 63 210 72 63 211 73 63 212 81 64 213 82 65 214 77 60 215 78 24 216 79 24 217 83 24 218 76 59 219 81 64 220 77 60 221 84 66 222 85 67 223 82 65 224 86 24 225 83 24 226 87 24 227 81 64 228 84 66 229 82 65 230 86 24 231 78 24 232 83 24 233 88 68 234 89 69 235 85 67 236 90 24 237 87 24 238 91 24 239 84 66 240 88 68 241 85 67 242 90 24 243 86 24 244 87 24 245 92 70 246 93 71 247 89 69 248 94 72 249 91 72 250 95 72 251 88 68 252 92 70 253 89 69 254 94 73 255 90 73 256 91 73 257 96 74 258 97 75 259 93 71 260 98 76 261 95 76 262 99 76 263 92 70 264 96 74 265 93 71 266 98 77 267 94 77 268 95 77 269 100 78 270 101 79 271 97 75 272 102 80 273 99 80 274 103 80 275 96 74 276 100 78 277 97 75 278 102 81 279 98 81 280 99 81 281 104 82 282 105 83 283 101 79 284 106 24 285 103 24 286 107 24 287 108 84 288 104 82 289 101 79 290 100 78 291 108 84 292 101 79 293 106 24 294 102 24 295 103 24 296 109 85 297 110 86 298 105 83 299 111 87 300 107 87 301 112 87 302 113 88 303 109 85 304 105 83 305 104 82 306 113 88 307 105 83 308 114 89 309 106 89 310 107 89 311 111 90 312 114 90 313 107 90 314 115 91 315 116 92 316 110 86 317 117 93 318 112 93 319 118 93 320 119 94 321 115 91 322 110 86 323 109 85 324 119 94 325 110 86 326 120 95 327 112 95 328 117 95 329 111 24 330 112 24 331 120 24 332 121 96 333 122 97 334 116 92 335 123 98 336 118 98 337 124 98 338 125 99 339 121 96 340 116 92 341 126 100 342 125 99 343 116 92 344 115 91 345 126 100 346 116 92 347 117 24 348 118 24 349 123 24 350 127 101 351 128 102 352 129 103 353 130 104 354 128 102 355 127 101 356 131 105 357 132 106 358 133 107 359 134 108 360 135 109 361 136 110 362 134 108 363 137 111 364 135 109 365 138 112 366 133 107 367 139 113 368 138 112 369 131 105 370 133 107 371 138 112 372 139 113 373 140 114 374 141 115 375 140 114 376 142 116 377 141 115 378 138 112 379 140 114 380 141 115 381 142 116 382 143 117 383 144 118 384 143 117 385 145 119 386 144 118 387 141 115 388 143 117 389 146 120 390 145 119 391 147 121 392 146 120 393 144 118 394 145 119 395 146 120 396 147 121 397 148 122 398 149 123 399 148 122 400 150 124 401 149 123 402 146 120 403 148 122 404 149 123 405 150 124 406 151 125 407 152 126 408 151 125 409 153 127 410 152 126 411 149 123 412 151 125 413 154 128 414 153 127 415 155 129 416 154 128 417 152 126 418 153 127 419 154 128 420 155 129 421 156 130 422 157 131 423 156 130 424 158 132 425 157 131 426 154 128 427 156 130 428 157 131 429 158 132 430 159 133 431 160 134 432 159 133 433 161 135 434 160 134 435 157 131 436 159 133 437 162 136 438 161 135 439 163 137 440 162 136 441 160 134 442 161 135 443 162 136 444 163 137 445 164 138 446 165 139 447 164 138 448 166 140 449 165 139 450 162 136 451 164 138 452 165 139 453 166 140 454 167 141 455 168 142 456 167 141 457 169 143 458 168 142 459 165 139 460 167 141 461 168 142 462 169 143 463 170 144 464 171 145 465 170 144 466 172 146 467 171 145 468 168 142 469 170 144 470 173 147 471 172 146 472 174 148 473 173 147 474 171 145 475 172 146 476 173 147 477 174 148 478 175 149 479 176 150 480 175 149 481 177 151 482 176 150 483 173 147 484 175 149 485 176 150 486 177 151 487 178 152 488 179 153 489 178 152 490 180 154 491 179 153 492 176 150 493 178 152 494 181 155 495 180 154 496 182 156 497 181 155 498 179 153 499 180 154 500 181 155 501 182 156 502 183 157 503 184 158 504 183 157 505 185 159 506 181 155 507 183 157 508 184 158 509 186 160 510 185 159 511 187 161 512 184 158 513 185 159 514 186 160 515 188 162 516 189 163 517 190 164 518 191 165 519 192 166 520 189 163 521 188 162 522 191 165 523 189 163 524 193 167 525 190 164 526 194 168 527 195 169 528 188 162 529 190 164 530 193 167 531 195 169 532 190 164 533 196 170 534 194 168 535 197 171 536 198 172 537 193 167 538 194 168 539 196 170 540 198 172 541 194 168 542 199 173 543 197 171 544 7 7 545 199 173 546 196 170 547 197 171 548 200 174 549 199 173 550 7 7 551 6 6 552 200 174 553 7 7 554 201 175 555 202 176 556 192 166 557 191 165 558 201 175 559 192 166 560 203 177 561 204 178 562 202 176 563 181 155 564 184 158 565 205 179 566 201 175 567 203 177 568 202 176 569 206 180 570 207 181 571 204 178 572 181 155 573 205 179 574 208 182 575 203 177 576 206 180 577 204 178 578 209 183 579 210 184 580 207 181 581 181 155 582 208 182 583 211 185 584 206 180 585 209 183 586 207 181 587 209 183 588 212 186 589 210 184 590 213 187 591 211 185 592 214 188 593 215 189 594 181 155 595 211 185 596 215 189 597 211 185 598 213 187 599 216 190 600 217 191 601 212 186 602 218 192 603 219 193 604 220 194 605 221 195 606 216 190 607 212 186 608 209 183 609 221 195 610 212 186 611 222 196 612 223 197 613 217 191 614 224 198 615 220 194 616 225 199 617 226 200 618 222 196 619 217 191 620 216 190 621 226 200 622 217 191 623 218 192 624 220 194 625 224 198 626 227 201 627 228 202 628 223 197 629 229 203 630 225 199 631 230 204 632 231 205 633 227 201 634 223 197 635 222 196 636 231 205 637 223 197 638 224 198 639 225 199 640 229 203 641 232 206 642 233 207 643 228 202 644 234 208 645 230 204 646 235 209 647 236 210 648 232 206 649 228 202 650 227 201 651 236 210 652 228 202 653 237 211 654 230 204 655 234 208 656 229 203 657 230 204 658 237 211 659 238 212 660 239 213 661 233 207 662 240 214 663 235 209 664 241 215 665 242 216 666 238 212 667 233 207 668 232 206 669 242 216 670 233 207 671 243 217 672 235 209 673 240 214 674 234 208 675 235 209 676 243 217 677 244 218 678 245 219 679 239 213 680 246 220 681 241 215 682 247 221 683 238 212 684 244 218 685 239 213 686 248 222 687 241 215 688 246 220 689 240 214 690 241 215 691 248 222 692 249 223 693 250 224 694 245 219 695 251 225 696 247 221 697 252 226 698 244 218 699 249 223 700 245 219 701 246 220 702 247 221 703 251 225 704 253 227 705 254 228 706 250 224 707 255 229 708 252 226 709 256 230 710 249 223 711 253 227 712 250 224 713 251 225 714 252 226 715 255 229 716 253 227 717 257 231 718 254 228 719 258 232 720 256 230 721 259 233 722 260 234 723 256 230 724 258 232 725 255 229 726 256 230 727 260 234 728 261 235 729 262 236 730 257 231 731 263 237 732 259 233 733 264 238 734 253 227 735 261 235 736 257 231 737 258 232 738 259 233 739 263 237 740 265 239 741 266 240 742 262 236 743 267 241 744 264 238 745 268 242 746 261 235 747 265 239 748 262 236 749 263 237 750 264 238 751 267 241 752 269 243 753 270 244 754 266 240 755 271 245 756 268 242 757 272 246 758 265 239 759 269 243 760 266 240 761 267 241 762 268 242 763 271 245 764 273 247 765 274 248 766 270 244 767 275 249 768 272 246 769 276 250 770 269 243 771 273 247 772 270 244 773 271 245 774 272 246 775 275 249 776 277 251 777 278 252 778 274 248 779 279 253 780 276 250 781 280 254 782 273 247 783 277 251 784 274 248 785 275 249 786 276 250 787 279 253 788 281 255 789 282 256 790 278 252 791 283 257 792 280 254 793 284 258 794 277 251 795 281 255 796 278 252 797 279 253 798 280 254 799 283 257 800 285 259 801 286 260 802 282 256 803 287 261 804 284 258 805 288 262 806 281 255 807 285 259 808 282 256 809 283 257 810 284 258 811 287 261 812 289 263 813 290 264 814 286 260 815 291 265 816 288 262 817 292 266 818 285 259 819 289 263 820 286 260 821 287 261 822 288 262 823 291 265 824 293 267 825 294 268 826 290 264 827 295 269 828 292 266 829 296 270 830 289 263 831 293 267 832 290 264 833 291 265 834 292 266 835 295 269 836 297 271 837 298 272 838 294 268 839 299 273 840 296 270 841 300 274 842 293 267 843 297 271 844 294 268 845 301 275 846 296 270 847 299 273 848 295 269 849 296 270 850 301 275 851 302 276 852 303 277 853 298 272 854 304 278 855 300 274 856 305 279 857 297 271 858 302 276 859 298 272 860 306 280 861 300 274 862 304 278 863 299 273 864 300 274 865 306 280 866 307 281 867 308 282 868 303 277 869 309 283 870 305 279 871 310 284 872 302 276 873 307 281 874 303 277 875 311 285 876 305 279 877 309 283 878 304 278 879 305 279 880 311 285 881 312 286 882 313 287 883 308 282 884 314 288 885 310 284 886 315 289 887 307 281 888 312 286 889 308 282 890 316 290 891 310 284 892 314 288 893 317 291 894 310 284 895 316 290 896 309 283 897 310 284 898 317 291 899 318 292 900 319 293 901 313 287 902 320 294 903 315 289 904 321 295 905 312 286 906 318 292 907 313 287 908 322 296 909 315 289 910 320 294 911 323 297 912 315 289 913 322 296 914 314 288 915 315 289 916 323 297 917 324 298 918 325 299 919 326 300 920 327 301 921 321 295 922 328 302 923 329 303 924 328 302 925 321 295 926 330 304 927 321 295 928 327 301 929 320 294 930 321 295 931 330 304 932 331 305 933 325 299 934 324 298 935 332 306 936 333 306 937 334 306 938 335 307 939 334 307 940 336 307 941 332 308 942 334 308 943 335 308 944 337 309 945 336 309 946 338 309 947 335 308 948 336 308 949 337 308 950 339 308 951 338 308 952 340 308 953 337 308 954 338 308 955 339 308 956 341 308 957 340 308 958 342 308 959 339 308 960 340 308 961 341 308 962 343 308 963 342 308 964 344 308 965 341 308 966 342 308 967 343 308 968 345 308 969 344 308 970 346 308 971 345 310 972 343 310 973 344 310 974 347 308 975 346 308 976 348 308 977 349 308 978 345 308 979 346 308 980 347 308 981 349 308 982 346 308 983 350 308 984 348 308 985 351 308 986 350 311 987 347 311 988 348 311 989 350 312 990 351 312 991 352 312 992 353 308 993 352 308 994 354 308 995 353 313 996 350 313 997 352 313 998 355 308 999 354 308 1000 356 308 1001 355 314 1002 353 314 1003 354 314 1004 357 308 1005 356 308 1006 358 308 1007 359 308 1008 355 308 1009 356 308 1010 357 315 1011 359 315 1012 356 315 1013 360 308 1014 358 308 1015 361 308 1016 360 316 1017 357 316 1018 358 316 1019 360 308 1020 361 308 1021 362 308 1022 363 308 1023 362 308 1024 364 308 1025 363 317 1026 360 317 1027 362 317 1028 363 318 1029 364 318 1030 365 318 1031 366 319 1032 365 319 1033 367 319 1034 366 308 1035 363 308 1036 365 308 1037 366 320 1038 367 320 1039 368 320 1040 369 308 1041 368 308 1042 370 308 1043 369 321 1044 366 321 1045 368 321 1046 371 308 1047 370 308 1048 372 308 1049 371 322 1050 369 322 1051 370 322 1052 371 308 1053 372 308 1054 373 308 1055 374 308 1056 373 308 1057 375 308 1058 374 323 1059 371 323 1060 373 323 1061 374 308 1062 375 308 1063 376 308 1064 377 308 1065 376 308 1066 378 308 1067 377 324 1068 374 324 1069 376 324 1070 377 325 1071 378 325 1072 379 325 1073 380 308 1074 379 308 1075 381 308 1076 380 326 1077 377 326 1078 379 326 1079 380 308 1080 381 308 1081 382 308 1082 383 308 1083 382 308 1084 384 308 1085 383 327 1086 380 327 1087 382 327 1088 385 308 1089 384 308 1090 386 308 1091 385 308 1092 383 308 1093 384 308 1094 385 308 1095 386 308 1096 387 308 1097 388 328 1098 387 328 1099 389 328 1100 388 308 1101 385 308 1102 387 308 1103 390 308 1104 389 308 1105 391 308 1106 390 329 1107 388 329 1108 389 329 1109 392 330 1110 391 330 1111 393 330 1112 392 331 1113 390 331 1114 391 331 1115 394 308 1116 393 308 1117 395 308 1118 396 308 1119 393 308 1120 394 308 1121 397 332 1122 393 332 1123 396 332 1124 398 333 1125 392 333 1126 393 333 1127 397 308 1128 398 308 1129 393 308 1130 399 308 1131 395 308 1132 400 308 1133 394 308 1134 395 308 1135 399 308 1136 401 308 1137 400 308 1138 402 308 1139 399 308 1140 400 308 1141 401 308 1142 403 308 1143 402 308 1144 404 308 1145 401 334 1146 402 334 1147 403 334 1148 405 308 1149 404 308 1150 406 308 1151 403 335 1152 404 335 1153 405 335 1154 405 336 1155 406 336 1156 407 336 1157 408 337 1158 11 11 1159 10 10 1160 409 338 1161 131 105 1162 138 112 1163 410 339 1164 136 110 1165 411 340 1166 410 339 1167 134 108 1168 136 110 1169 412 341 1170 138 112 1171 141 115 1172 413 342 1173 138 112 1174 412 341 1175 409 338 1176 138 112 1177 413 342 1178 414 343 1179 141 115 1180 144 118 1181 412 341 1182 141 115 1183 414 343 1184 415 344 1185 144 118 1186 146 120 1187 414 343 1188 144 118 1189 415 344 1190 416 345 1191 146 120 1192 149 123 1193 415 344 1194 146 120 1195 416 345 1196 417 346 1197 149 123 1198 152 126 1199 416 345 1200 149 123 1201 417 346 1202 418 347 1203 152 126 1204 154 128 1205 417 346 1206 152 126 1207 418 347 1208 419 348 1209 154 128 1210 157 131 1211 418 347 1212 154 128 1213 419 348 1214 420 349 1215 157 131 1216 160 134 1217 419 348 1218 157 131 1219 420 349 1220 421 350 1221 160 134 1222 162 136 1223 420 349 1224 160 134 1225 421 350 1226 422 351 1227 162 136 1228 165 139 1229 421 350 1230 162 136 1231 422 351 1232 423 352 1233 165 139 1234 168 142 1235 422 351 1236 165 139 1237 423 352 1238 424 353 1239 168 142 1240 171 145 1241 423 352 1242 168 142 1243 424 353 1244 425 354 1245 171 145 1246 173 147 1247 424 353 1248 171 145 1249 425 354 1250 426 355 1251 173 147 1252 176 150 1253 425 354 1254 173 147 1255 426 355 1256 427 356 1257 176 150 1258 179 153 1259 426 355 1260 176 150 1261 427 356 1262 215 189 1263 179 153 1264 181 155 1265 427 356 1266 179 153 1267 215 189 1268 428 357 1269 429 358 1270 430 359 1271 431 360 1272 432 361 1273 433 362 1274 434 363 1275 428 357 1276 430 359 1277 435 364 1278 434 363 1279 430 359 1280 436 365 1281 435 364 1282 430 359 1283 437 366 1284 436 365 1285 430 359 1286 438 367 1287 437 366 1288 430 359 1289 439 368 1290 438 367 1291 430 359 1292 440 369 1293 439 368 1294 430 359 1295 441 370 1296 440 369 1297 430 359 1298 442 371 1299 441 370 1300 430 359 1301 443 372 1302 442 371 1303 430 359 1304 444 373 1305 443 372 1306 430 359 1307 445 374 1308 444 373 1309 430 359 1310 446 375 1311 445 374 1312 430 359 1313 447 376 1314 446 375 1315 430 359 1316 448 377 1317 447 376 1318 430 359 1319 449 378 1320 448 377 1321 430 359 1322 450 379 1323 449 378 1324 430 359 1325 451 380 1326 450 379 1327 430 359 1328 452 381 1329 451 380 1330 430 359 1331 453 382 1332 452 381 1333 430 359 1334 454 383 1335 453 382 1336 430 359 1337 455 384 1338 454 383 1339 430 359 1340 456 385 1341 455 384 1342 430 359 1343 457 386 1344 456 385 1345 430 359 1346 458 387 1347 459 388 1348 432 361 1349 460 389 1350 432 361 1351 431 360 1352 461 390 1353 432 361 1354 460 389 1355 462 391 1356 432 361 1357 461 390 1358 463 392 1359 432 361 1360 462 391 1361 464 393 1362 432 361 1363 463 392 1364 465 394 1365 432 361 1366 464 393 1367 466 395 1368 432 361 1369 465 394 1370 467 396 1371 432 361 1372 466 395 1373 468 397 1374 432 361 1375 467 396 1376 469 398 1377 432 361 1378 468 397 1379 470 399 1380 432 361 1381 469 398 1382 471 400 1383 432 361 1384 470 399 1385 472 401 1386 432 361 1387 471 400 1388 473 402 1389 432 361 1390 472 401 1391 474 403 1392 432 361 1393 473 402 1394 475 404 1395 432 361 1396 474 403 1397 476 405 1398 432 361 1399 475 404 1400 477 406 1401 432 361 1402 476 405 1403 478 407 1404 432 361 1405 477 406 1406 479 408 1407 432 361 1408 478 407 1409 480 409 1410 432 361 1411 479 408 1412 458 387 1413 432 361 1414 480 409 1415 431 360 1416 433 362 1417 481 410 1418 482 411 1419 428 357 1420 434 363 1421 483 412 1422 481 410 1423 484 413 1424 431 360 1425 481 410 1426 483 412 1427 485 414 1428 434 363 1429 435 364 1430 486 415 1431 482 411 1432 434 363 1433 485 414 1434 486 415 1435 434 363 1436 487 416 1437 435 364 1438 436 365 1439 487 416 1440 485 414 1441 435 364 1442 488 417 1443 436 365 1444 437 366 1445 488 417 1446 487 416 1447 436 365 1448 489 418 1449 437 366 1450 438 367 1451 489 418 1452 488 417 1453 437 366 1454 490 419 1455 438 367 1456 439 368 1457 491 420 1458 489 418 1459 438 367 1460 490 419 1461 491 420 1462 438 367 1463 492 421 1464 439 368 1465 440 369 1466 493 422 1467 490 419 1468 439 368 1469 492 421 1470 493 422 1471 439 368 1472 494 423 1473 440 369 1474 441 370 1475 494 423 1476 492 421 1477 440 369 1478 495 424 1479 441 370 1480 442 371 1481 495 424 1482 494 423 1483 441 370 1484 496 425 1485 442 371 1486 443 372 1487 496 425 1488 495 424 1489 442 371 1490 497 426 1491 443 372 1492 444 373 1493 497 426 1494 496 425 1495 443 372 1496 498 427 1497 444 373 1498 445 374 1499 498 427 1500 497 426 1501 444 373 1502 499 428 1503 445 374 1504 446 375 1505 499 428 1506 498 427 1507 445 374 1508 500 429 1509 446 375 1510 447 376 1511 500 429 1512 499 428 1513 446 375 1514 501 430 1515 447 376 1516 448 377 1517 501 430 1518 500 429 1519 447 376 1520 502 431 1521 448 377 1522 449 378 1523 502 431 1524 501 430 1525 448 377 1526 503 432 1527 449 378 1528 450 379 1529 503 432 1530 502 431 1531 449 378 1532 504 433 1533 450 379 1534 451 380 1535 504 433 1536 503 432 1537 450 379 1538 505 434 1539 451 380 1540 452 381 1541 505 434 1542 504 433 1543 451 380 1544 506 435 1545 452 381 1546 453 382 1547 506 435 1548 505 434 1549 452 381 1550 507 436 1551 453 382 1552 454 383 1553 507 436 1554 506 435 1555 453 382 1556 508 437 1557 454 383 1558 455 384 1559 508 437 1560 507 436 1561 454 383 1562 509 438 1563 455 384 1564 456 385 1565 509 438 1566 508 437 1567 455 384 1568 509 438 1569 456 385 1570 457 386 1571 509 438 1572 457 386 1573 510 439 1574 458 387 1575 511 440 1576 459 388 1577 512 441 1578 509 438 1579 510 439 1580 512 441 1581 510 439 1582 513 442 1583 514 443 1584 515 444 1585 511 440 1586 514 443 1587 511 440 1588 458 387 1589 329 303 1590 516 445 1591 328 302 1592 517 446 1593 493 422 1594 492 421 1595 518 447 1596 492 421 1597 494 423 1598 518 447 1599 517 446 1600 492 421 1601 519 448 1602 494 423 1603 495 424 1604 520 449 1605 518 447 1606 494 423 1607 521 450 1608 520 449 1609 494 423 1610 519 448 1611 521 450 1612 494 423 1613 522 451 1614 495 424 1615 496 425 1616 522 451 1617 519 448 1618 495 424 1619 523 452 1620 496 425 1621 497 426 1622 523 452 1623 522 451 1624 496 425 1625 524 453 1626 497 426 1627 498 427 1628 524 453 1629 523 452 1630 497 426 1631 525 454 1632 498 427 1633 499 428 1634 525 454 1635 524 453 1636 498 427 1637 526 455 1638 499 428 1639 500 429 1640 526 455 1641 525 454 1642 499 428 1643 527 456 1644 500 429 1645 501 430 1646 527 456 1647 526 455 1648 500 429 1649 528 457 1650 501 430 1651 502 431 1652 528 457 1653 527 456 1654 501 430 1655 529 458 1656 502 431 1657 503 432 1658 529 458 1659 528 457 1660 502 431 1661 530 459 1662 503 432 1663 504 433 1664 530 459 1665 529 458 1666 503 432 1667 531 460 1668 504 433 1669 505 434 1670 531 460 1671 530 459 1672 504 433 1673 532 461 1674 505 434 1675 506 435 1676 532 461 1677 531 460 1678 505 434 1679 533 462 1680 506 435 1681 507 436 1682 533 462 1683 532 461 1684 506 435 1685 534 463 1686 507 436 1687 508 437 1688 534 463 1689 533 462 1690 507 436 1691 512 441 1692 508 437 1693 509 438 1694 512 441 1695 534 463 1696 508 437 1697 535 464 1698 512 441 1699 513 442 1700 535 464 1701 513 442 1702 536 465 1703 537 466 1704 538 467 1705 515 444 1706 514 443 1707 537 466 1708 515 444 1709 539 468 1710 521 450 1711 519 448 1712 540 469 1713 519 448 1714 522 451 1715 541 470 1716 539 468 1717 519 448 1718 542 471 1719 541 470 1720 519 448 1721 540 469 1722 542 471 1723 519 448 1724 543 472 1725 522 451 1726 523 452 1727 543 472 1728 540 469 1729 522 451 1730 544 473 1731 523 452 1732 524 453 1733 544 473 1734 543 472 1735 523 452 1736 545 474 1737 524 453 1738 525 454 1739 545 474 1740 544 473 1741 524 453 1742 546 475 1743 525 454 1744 526 455 1745 546 475 1746 545 474 1747 525 454 1748 547 476 1749 526 455 1750 527 456 1751 547 476 1752 546 475 1753 526 455 1754 548 477 1755 527 456 1756 528 457 1757 548 477 1758 547 476 1759 527 456 1760 549 478 1761 528 457 1762 529 458 1763 549 478 1764 548 477 1765 528 457 1766 550 479 1767 529 458 1768 530 459 1769 550 479 1770 549 478 1771 529 458 1772 551 480 1773 530 459 1774 531 460 1775 551 480 1776 550 479 1777 530 459 1778 552 481 1779 531 460 1780 532 461 1781 552 481 1782 551 480 1783 531 460 1784 553 482 1785 532 461 1786 533 462 1787 553 482 1788 552 481 1789 532 461 1790 554 483 1791 533 462 1792 534 463 1793 554 483 1794 553 482 1795 533 462 1796 535 464 1797 534 463 1798 512 441 1799 535 464 1800 554 483 1801 534 463 1802 555 484 1803 535 464 1804 536 465 1805 555 484 1806 536 465 1807 556 485 1808 557 486 1809 558 487 1810 538 467 1811 537 466 1812 557 486 1813 538 467 1814 559 488 1815 542 471 1816 540 469 1817 560 489 1818 540 469 1819 543 472 1820 561 490 1821 559 488 1822 540 469 1823 560 489 1824 561 490 1825 540 469 1826 562 491 1827 543 472 1828 544 473 1829 562 491 1830 560 489 1831 543 472 1832 563 492 1833 544 473 1834 545 474 1835 563 492 1836 562 491 1837 544 473 1838 564 493 1839 545 474 1840 546 475 1841 564 493 1842 563 492 1843 545 474 1844 565 494 1845 546 475 1846 547 476 1847 565 494 1848 564 493 1849 546 475 1850 566 495 1851 547 476 1852 548 477 1853 566 495 1854 565 494 1855 547 476 1856 567 496 1857 548 477 1858 549 478 1859 567 496 1860 566 495 1861 548 477 1862 568 497 1863 549 478 1864 550 479 1865 568 497 1866 567 496 1867 549 478 1868 569 498 1869 550 479 1870 551 480 1871 569 498 1872 568 497 1873 550 479 1874 570 499 1875 551 480 1876 552 481 1877 570 499 1878 569 498 1879 551 480 1880 571 500 1881 552 481 1882 553 482 1883 571 500 1884 570 499 1885 552 481 1886 572 501 1887 553 482 1888 554 483 1889 572 501 1890 571 500 1891 553 482 1892 573 502 1893 554 483 1894 535 464 1895 573 502 1896 572 501 1897 554 483 1898 555 484 1899 573 502 1900 535 464 1901 574 503 1902 555 484 1903 556 485 1904 574 503 1905 556 485 1906 575 504 1907 576 505 1908 577 506 1909 558 487 1910 557 486 1911 576 505 1912 558 487 1913 578 507 1914 561 490 1915 560 489 1916 579 508 1917 560 489 1918 562 491 1919 580 509 1920 578 507 1921 560 489 1922 579 508 1923 580 509 1924 560 489 1925 581 510 1926 562 491 1927 563 492 1928 581 510 1929 579 508 1930 562 491 1931 582 511 1932 563 492 1933 564 493 1934 582 511 1935 581 510 1936 563 492 1937 583 512 1938 564 493 1939 565 494 1940 583 512 1941 582 511 1942 564 493 1943 584 513 1944 565 494 1945 566 495 1946 584 513 1947 583 512 1948 565 494 1949 585 514 1950 566 495 1951 567 496 1952 585 514 1953 584 513 1954 566 495 1955 586 515 1956 567 496 1957 568 497 1958 586 515 1959 585 514 1960 567 496 1961 587 516 1962 568 497 1963 569 498 1964 587 516 1965 586 515 1966 568 497 1967 588 517 1968 569 498 1969 570 499 1970 588 517 1971 587 516 1972 569 498 1973 589 518 1974 570 499 1975 571 500 1976 589 518 1977 588 517 1978 570 499 1979 590 519 1980 571 500 1981 572 501 1982 590 519 1983 589 518 1984 571 500 1985 591 520 1986 572 501 1987 573 502 1988 591 520 1989 590 519 1990 572 501 1991 592 521 1992 573 502 1993 555 484 1994 592 521 1995 591 520 1996 573 502 1997 574 503 1998 592 521 1999 555 484 2000 593 522 2001 574 503 2002 575 504 2003 593 522 2004 575 504 2005 594 523 2006 595 524 2007 596 525 2008 577 506 2009 576 505 2010 595 524 2011 577 506 2012 597 526 2013 580 509 2014 579 508 2015 598 527 2016 579 508 2017 581 510 2018 599 528 2019 597 526 2020 579 508 2021 598 527 2022 599 528 2023 579 508 2024 600 529 2025 581 510 2026 582 511 2027 600 529 2028 598 527 2029 581 510 2030 601 530 2031 582 511 2032 583 512 2033 601 530 2034 600 529 2035 582 511 2036 602 531 2037 583 512 2038 584 513 2039 602 531 2040 601 530 2041 583 512 2042 603 532 2043 584 513 2044 585 514 2045 603 532 2046 602 531 2047 584 513 2048 604 533 2049 585 514 2050 586 515 2051 604 533 2052 603 532 2053 585 514 2054 605 534 2055 586 515 2056 587 516 2057 605 534 2058 604 533 2059 586 515 2060 606 535 2061 587 516 2062 588 517 2063 606 535 2064 605 534 2065 587 516 2066 607 536 2067 588 517 2068 589 518 2069 607 536 2070 606 535 2071 588 517 2072 608 537 2073 589 518 2074 590 519 2075 608 537 2076 607 536 2077 589 518 2078 609 538 2079 590 519 2080 591 520 2081 609 538 2082 608 537 2083 590 519 2084 610 539 2085 591 520 2086 592 521 2087 610 539 2088 609 538 2089 591 520 2090 611 540 2091 592 521 2092 574 503 2093 611 540 2094 610 539 2095 592 521 2096 593 522 2097 611 540 2098 574 503 2099 612 541 2100 593 522 2101 594 523 2102 612 541 2103 594 523 2104 613 542 2105 614 543 2106 615 544 2107 596 525 2108 595 524 2109 614 543 2110 596 525 2111 616 545 2112 599 528 2113 598 527 2114 616 545 2115 617 546 2116 599 528 2117 618 547 2118 598 527 2119 600 529 2120 618 547 2121 616 545 2122 598 527 2123 619 548 2124 600 529 2125 601 530 2126 619 548 2127 618 547 2128 600 529 2129 620 549 2130 601 530 2131 602 531 2132 620 549 2133 619 548 2134 601 530 2135 621 550 2136 602 531 2137 603 532 2138 621 550 2139 620 549 2140 602 531 2141 622 551 2142 603 532 2143 604 533 2144 622 551 2145 621 550 2146 603 532 2147 623 552 2148 604 533 2149 605 534 2150 623 552 2151 622 551 2152 604 533 2153 624 553 2154 605 534 2155 606 535 2156 624 553 2157 623 552 2158 605 534 2159 625 554 2160 606 535 2161 607 536 2162 625 554 2163 624 553 2164 606 535 2165 626 555 2166 607 536 2167 608 537 2168 626 555 2169 625 554 2170 607 536 2171 627 556 2172 608 537 2173 609 538 2174 627 556 2175 626 555 2176 608 537 2177 628 557 2178 609 538 2179 610 539 2180 628 557 2181 627 556 2182 609 538 2183 629 558 2184 610 539 2185 611 540 2186 629 558 2187 628 557 2188 610 539 2189 612 541 2190 611 540 2191 593 522 2192 612 541 2193 629 558 2194 611 540 2195 630 559 2196 612 541 2197 613 542 2198 630 559 2199 613 542 2200 631 560 2201 632 561 2202 633 562 2203 615 544 2204 614 543 2205 632 561 2206 615 544 2207 616 545 2208 634 563 2209 617 546 2210 635 564 2211 634 563 2212 616 545 2213 635 564 2214 636 565 2215 634 563 2216 637 566 2217 616 545 2218 618 547 2219 637 566 2220 635 564 2221 616 545 2222 638 567 2223 618 547 2224 619 548 2225 638 567 2226 637 566 2227 618 547 2228 639 568 2229 619 548 2230 620 549 2231 639 568 2232 638 567 2233 619 548 2234 640 569 2235 620 549 2236 621 550 2237 640 569 2238 639 568 2239 620 549 2240 641 570 2241 621 550 2242 622 551 2243 641 570 2244 640 569 2245 621 550 2246 642 571 2247 622 551 2248 623 552 2249 642 571 2250 641 570 2251 622 551 2252 643 572 2253 623 552 2254 624 553 2255 643 572 2256 642 571 2257 623 552 2258 644 573 2259 624 553 2260 625 554 2261 644 573 2262 643 572 2263 624 553 2264 645 574 2265 625 554 2266 626 555 2267 645 574 2268 644 573 2269 625 554 2270 646 575 2271 626 555 2272 627 556 2273 646 575 2274 645 574 2275 626 555 2276 647 576 2277 627 556 2278 628 557 2279 647 576 2280 646 575 2281 627 556 2282 648 577 2283 628 557 2284 629 558 2285 648 577 2286 647 576 2287 628 557 2288 630 559 2289 629 558 2290 612 541 2291 630 559 2292 648 577 2293 629 558 2294 649 578 2295 630 559 2296 631 560 2297 649 578 2298 631 560 2299 650 579 2300 651 580 2301 652 581 2302 633 562 2303 632 561 2304 651 580 2305 633 562 2306 635 564 2307 653 582 2308 636 565 2309 654 583 2310 653 582 2311 635 564 2312 654 583 2313 655 584 2314 653 582 2315 656 585 2316 635 564 2317 637 566 2318 656 585 2319 654 583 2320 635 564 2321 657 586 2322 637 566 2323 638 567 2324 657 586 2325 656 585 2326 637 566 2327 658 587 2328 638 567 2329 639 568 2330 658 587 2331 657 586 2332 638 567 2333 659 588 2334 639 568 2335 640 569 2336 659 588 2337 658 587 2338 639 568 2339 660 589 2340 640 569 2341 641 570 2342 660 589 2343 659 588 2344 640 569 2345 661 590 2346 641 570 2347 642 571 2348 661 590 2349 660 589 2350 641 570 2351 662 591 2352 642 571 2353 643 572 2354 662 591 2355 661 590 2356 642 571 2357 663 592 2358 643 572 2359 644 573 2360 663 592 2361 662 591 2362 643 572 2363 664 593 2364 644 573 2365 645 574 2366 664 593 2367 663 592 2368 644 573 2369 665 594 2370 645 574 2371 646 575 2372 665 594 2373 664 593 2374 645 574 2375 666 595 2376 646 575 2377 647 576 2378 666 595 2379 665 594 2380 646 575 2381 667 596 2382 647 576 2383 648 577 2384 667 596 2385 666 595 2386 647 576 2387 649 578 2388 648 577 2389 630 559 2390 649 578 2391 667 596 2392 648 577 2393 668 597 2394 649 578 2395 650 579 2396 668 597 2397 650 579 2398 669 598 2399 670 599 2400 671 600 2401 652 581 2402 651 580 2403 670 599 2404 652 581 2405 654 583 2406 672 601 2407 655 584 2408 673 602 2409 672 601 2410 654 583 2411 673 602 2412 674 603 2413 672 601 2414 675 604 2415 654 583 2416 656 585 2417 675 604 2418 673 602 2419 654 583 2420 676 605 2421 656 585 2422 657 586 2423 676 605 2424 675 604 2425 656 585 2426 677 606 2427 657 586 2428 658 587 2429 677 606 2430 676 605 2431 657 586 2432 678 607 2433 658 587 2434 659 588 2435 678 607 2436 677 606 2437 658 587 2438 679 608 2439 659 588 2440 660 589 2441 679 608 2442 678 607 2443 659 588 2444 680 609 2445 660 589 2446 661 590 2447 680 609 2448 679 608 2449 660 589 2450 681 610 2451 661 590 2452 662 591 2453 681 610 2454 680 609 2455 661 590 2456 682 611 2457 662 591 2458 663 592 2459 682 611 2460 681 610 2461 662 591 2462 683 612 2463 663 592 2464 664 593 2465 683 612 2466 682 611 2467 663 592 2468 684 613 2469 664 593 2470 665 594 2471 684 613 2472 683 612 2473 664 593 2474 685 614 2475 665 594 2476 666 595 2477 685 614 2478 684 613 2479 665 594 2480 686 615 2481 666 595 2482 667 596 2483 686 615 2484 685 614 2485 666 595 2486 668 597 2487 667 596 2488 649 578 2489 668 597 2490 686 615 2491 667 596 2492 687 616 2493 668 597 2494 669 598 2495 670 599 2496 688 617 2497 671 600 2498 673 602 2499 689 618 2500 674 603 2501 690 619 2502 689 618 2503 673 602 2504 690 619 2505 691 620 2506 689 618 2507 692 621 2508 673 602 2509 675 604 2510 692 621 2511 690 619 2512 673 602 2513 693 622 2514 675 604 2515 676 605 2516 693 622 2517 692 621 2518 675 604 2519 694 623 2520 676 605 2521 677 606 2522 694 623 2523 693 622 2524 676 605 2525 695 624 2526 677 606 2527 678 607 2528 695 624 2529 694 623 2530 677 606 2531 696 625 2532 678 607 2533 679 608 2534 696 625 2535 695 624 2536 678 607 2537 697 626 2538 679 608 2539 680 609 2540 697 626 2541 696 625 2542 679 608 2543 698 627 2544 680 609 2545 681 610 2546 698 627 2547 697 626 2548 680 609 2549 699 628 2550 681 610 2551 682 611 2552 699 628 2553 698 627 2554 681 610 2555 700 629 2556 682 611 2557 683 612 2558 700 629 2559 699 628 2560 682 611 2561 701 630 2562 683 612 2563 684 613 2564 701 630 2565 700 629 2566 683 612 2567 702 631 2568 684 613 2569 685 614 2570 702 631 2571 701 630 2572 684 613 2573 703 632 2574 685 614 2575 686 615 2576 703 632 2577 702 631 2578 685 614 2579 704 633 2580 686 615 2581 668 597 2582 704 633 2583 703 632 2584 686 615 2585 705 634 2586 668 597 2587 687 616 2588 705 634 2589 704 633 2590 668 597 2591 705 634 2592 687 616 2593 706 635 2594 707 636 2595 708 637 2596 688 617 2597 707 636 2598 688 617 2599 670 599 2600 709 638 2601 705 634 2602 706 635 2603 707 636 2604 710 639 2605 708 637 2606 690 619 2607 711 640 2608 691 620 2609 712 641 2610 711 640 2611 690 619 2612 712 641 2613 713 642 2614 711 640 2615 714 643 2616 690 619 2617 692 621 2618 714 643 2619 712 641 2620 690 619 2621 715 644 2622 692 621 2623 693 622 2624 715 644 2625 714 643 2626 692 621 2627 716 645 2628 693 622 2629 694 623 2630 716 645 2631 715 644 2632 693 622 2633 717 646 2634 694 623 2635 695 624 2636 717 646 2637 716 645 2638 694 623 2639 718 647 2640 695 624 2641 696 625 2642 718 647 2643 717 646 2644 695 624 2645 719 648 2646 696 625 2647 697 626 2648 719 648 2649 718 647 2650 696 625 2651 720 649 2652 697 626 2653 698 627 2654 720 649 2655 719 648 2656 697 626 2657 721 650 2658 698 627 2659 699 628 2660 721 650 2661 720 649 2662 698 627 2663 722 651 2664 699 628 2665 700 629 2666 722 651 2667 721 650 2668 699 628 2669 723 652 2670 700 629 2671 701 630 2672 723 652 2673 722 651 2674 700 629 2675 724 653 2676 701 630 2677 702 631 2678 724 653 2679 723 652 2680 701 630 2681 725 654 2682 702 631 2683 703 632 2684 725 654 2685 724 653 2686 702 631 2687 726 655 2688 703 632 2689 704 633 2690 726 655 2691 725 654 2692 703 632 2693 727 656 2694 704 633 2695 705 634 2696 727 656 2697 726 655 2698 704 633 2699 727 656 2700 705 634 2701 709 638 2702 727 656 2703 709 638 2704 728 657 2705 729 658 2706 730 659 2707 710 639 2708 707 636 2709 729 658 2710 710 639 2711 731 660 2712 727 656 2713 728 657 2714 729 658 2715 732 661 2716 730 659 2717 712 641 2718 733 662 2719 713 642 2720 712 641 2721 734 663 2722 733 662 2723 735 664 2724 734 663 2725 712 641 2726 735 664 2727 736 665 2728 734 663 2729 737 666 2730 712 641 2731 714 643 2732 737 666 2733 735 664 2734 712 641 2735 738 667 2736 714 643 2737 715 644 2738 738 667 2739 737 666 2740 714 643 2741 739 668 2742 715 644 2743 716 645 2744 739 668 2745 738 667 2746 715 644 2747 740 669 2748 716 645 2749 717 646 2750 740 669 2751 739 668 2752 716 645 2753 741 670 2754 717 646 2755 718 647 2756 741 670 2757 740 669 2758 717 646 2759 742 671 2760 718 647 2761 719 648 2762 742 671 2763 741 670 2764 718 647 2765 743 672 2766 719 648 2767 720 649 2768 743 672 2769 742 671 2770 719 648 2771 744 673 2772 720 649 2773 721 650 2774 744 673 2775 743 672 2776 720 649 2777 745 674 2778 721 650 2779 722 651 2780 745 674 2781 744 673 2782 721 650 2783 746 675 2784 722 651 2785 723 652 2786 746 675 2787 745 674 2788 722 651 2789 747 676 2790 723 652 2791 724 653 2792 747 676 2793 746 675 2794 723 652 2795 748 677 2796 724 653 2797 725 654 2798 748 677 2799 747 676 2800 724 653 2801 749 678 2802 725 654 2803 726 655 2804 749 678 2805 748 677 2806 725 654 2807 750 679 2808 726 655 2809 727 656 2810 750 679 2811 749 678 2812 726 655 2813 751 680 2814 727 656 2815 731 660 2816 751 680 2817 750 679 2818 727 656 2819 751 680 2820 731 660 2821 752 681 2822 753 682 2823 754 683 2824 732 661 2825 729 658 2826 753 682 2827 732 661 2828 755 684 2829 751 680 2830 752 681 2831 753 682 2832 756 685 2833 754 683 2834 735 664 2835 213 187 2836 736 665 2837 215 189 2838 213 187 2839 735 664 2840 427 356 2841 735 664 2842 737 666 2843 427 356 2844 215 189 2845 735 664 2846 426 355 2847 737 666 2848 738 667 2849 426 355 2850 427 356 2851 737 666 2852 425 354 2853 738 667 2854 739 668 2855 425 354 2856 426 355 2857 738 667 2858 424 353 2859 739 668 2860 740 669 2861 424 353 2862 425 354 2863 739 668 2864 423 352 2865 740 669 2866 741 670 2867 423 352 2868 424 353 2869 740 669 2870 422 351 2871 741 670 2872 742 671 2873 422 351 2874 423 352 2875 741 670 2876 421 350 2877 742 671 2878 743 672 2879 421 350 2880 422 351 2881 742 671 2882 420 349 2883 743 672 2884 744 673 2885 420 349 2886 421 350 2887 743 672 2888 419 348 2889 744 673 2890 745 674 2891 419 348 2892 420 349 2893 744 673 2894 418 347 2895 745 674 2896 746 675 2897 418 347 2898 419 348 2899 745 674 2900 417 346 2901 746 675 2902 747 676 2903 417 346 2904 418 347 2905 746 675 2906 416 345 2907 747 676 2908 748 677 2909 416 345 2910 417 346 2911 747 676 2912 415 344 2913 748 677 2914 749 678 2915 415 344 2916 416 345 2917 748 677 2918 414 343 2919 749 678 2920 750 679 2921 414 343 2922 415 344 2923 749 678 2924 412 341 2925 750 679 2926 751 680 2927 412 341 2928 414 343 2929 750 679 2930 412 341 2931 751 680 2932 755 684 2933 412 341 2934 755 684 2935 757 686 2936 758 687 2937 759 688 2938 756 685 2939 753 682 2940 758 687 2941 756 685 2942 413 342 2943 412 341 2944 757 686 2945 758 687 2946 760 689 2947 759 688 2948 410 339 2949 411 340 2950 760 689 2951 758 687 2952 410 339 2953 760 689 2954 134 108 2955 761 690 2956 137 111 2957 130 104 2958 127 101 2959 762 691 2960 763 692 2961 764 693 2962 761 690 2963 765 694 2964 762 691 2965 766 695 2966 134 108 2967 763 692 2968 761 690 2969 765 694 2970 130 104 2971 762 691 2972 763 692 2973 767 696 2974 764 693 2975 768 697 2976 766 695 2977 769 698 2978 768 697 2979 765 694 2980 766 695 2981 770 699 2982 771 700 2983 767 696 2984 772 701 2985 769 698 2986 773 702 2987 763 692 2988 770 699 2989 767 696 2990 774 703 2991 768 697 2992 769 698 2993 772 701 2994 774 703 2995 769 698 2996 770 699 2997 775 704 2998 771 700 2999 776 705 3000 773 702 3001 777 706 3002 776 705 3003 772 701 3004 773 702 3005 778 707 3006 779 708 3007 775 704 3008 780 709 3009 777 706 3010 781 710 3011 770 699 3012 778 707 3013 775 704 3014 782 711 3015 776 705 3016 777 706 3017 783 712 3018 782 711 3019 777 706 3020 780 709 3021 783 712 3022 777 706 3023 784 713 3024 785 714 3025 779 708 3026 786 715 3027 781 710 3028 787 716 3029 778 707 3030 784 713 3031 779 708 3032 788 717 3033 781 710 3034 786 715 3035 789 718 3036 780 709 3037 781 710 3038 790 719 3039 789 718 3040 781 710 3041 788 717 3042 790 719 3043 781 710 3044 784 713 3045 791 720 3046 785 714 3047 792 721 3048 787 716 3049 793 722 3050 792 721 3051 786 715 3052 787 716 3053 794 723 3054 795 724 3055 791 720 3056 792 721 3057 793 722 3058 796 725 3059 784 713 3060 794 723 3061 791 720 3062 794 723 3063 797 726 3064 795 724 3065 798 727 3066 796 725 3067 799 728 3068 798 727 3069 792 721 3070 796 725 3071 800 729 3072 801 730 3073 797 726 3074 798 727 3075 799 728 3076 802 731 3077 794 723 3078 800 729 3079 797 726 3080 803 732 3081 804 733 3082 801 730 3083 805 734 3084 802 731 3085 806 735 3086 800 729 3087 803 732 3088 801 730 3089 805 734 3090 798 727 3091 802 731 3092 803 732 3093 807 736 3094 804 733 3095 805 734 3096 806 735 3097 808 737 3098 809 738 3099 810 739 3100 807 736 3101 811 740 3102 808 737 3103 812 741 3104 803 732 3105 809 738 3106 807 736 3107 811 740 3108 805 734 3109 808 737 3110 809 738 3111 813 742 3112 810 739 3113 811 740 3114 812 741 3115 814 743 3116 815 744 3117 816 745 3118 813 742 3119 817 746 3120 814 743 3121 818 747 3122 809 738 3123 815 744 3124 813 742 3125 817 746 3126 811 740 3127 814 743 3128 819 748 3129 820 749 3130 816 745 3131 817 746 3132 818 747 3133 821 750 3134 815 744 3135 819 748 3136 816 745 3137 819 748 3138 822 751 3139 820 749 3140 823 752 3141 821 750 3142 824 753 3143 823 752 3144 817 746 3145 821 750 3146 825 754 3147 826 755 3148 822 751 3149 823 752 3150 824 753 3151 827 756 3152 819 748 3153 825 754 3154 822 751 3155 825 754 3156 828 757 3157 826 755 3158 829 758 3159 827 756 3160 830 759 3161 829 758 3162 823 752 3163 827 756 3164 831 760 3165 832 761 3166 828 757 3167 829 758 3168 830 759 3169 833 762 3170 825 754 3171 831 760 3172 828 757 3173 831 760 3174 834 763 3175 832 761 3176 835 764 3177 833 762 3178 836 765 3179 835 764 3180 829 758 3181 833 762 3182 837 766 3183 838 767 3184 834 763 3185 835 764 3186 836 765 3187 839 768 3188 831 760 3189 837 766 3190 834 763 3191 840 769 3192 841 770 3193 838 767 3194 842 771 3195 839 768 3196 843 772 3197 837 766 3198 840 769 3199 838 767 3200 842 771 3201 835 764 3202 839 768 3203 840 769 3204 844 773 3205 841 770 3206 842 771 3207 843 772 3208 845 774 3209 846 775 3210 847 776 3211 844 773 3212 848 777 3213 845 774 3214 849 778 3215 840 769 3216 846 775 3217 844 773 3218 848 777 3219 842 771 3220 845 774 3221 846 775 3222 850 779 3223 847 776 3224 851 780 3225 849 778 3226 852 781 3227 851 780 3228 848 777 3229 849 778 3230 853 782 3231 854 783 3232 850 779 3233 855 784 3234 852 781 3235 856 785 3236 846 775 3237 853 782 3238 850 779 3239 855 784 3240 851 780 3241 852 781 3242 857 786 3243 858 787 3244 854 783 3245 859 788 3246 856 785 3247 860 789 3248 853 782 3249 857 786 3250 854 783 3251 859 788 3252 855 784 3253 856 785 3254 857 786 3255 861 790 3256 858 787 3257 862 791 3258 860 789 3259 863 792 3260 862 791 3261 859 788 3262 860 789 3263 864 793 3264 865 794 3265 861 790 3266 866 795 3267 863 792 3268 867 796 3269 857 786 3270 864 793 3271 861 790 3272 866 795 3273 862 791 3274 863 792 3275 868 797 3276 869 798 3277 870 799 3278 871 800 3279 867 796 3280 872 801 3281 873 802 3282 874 803 3283 869 798 3284 871 800 3285 866 795 3286 867 796 3287 875 804 3288 873 802 3289 869 798 3290 868 797 3291 875 804 3292 869 798 3293 876 805 3294 870 799 3295 877 806 3296 876 805 3297 868 797 3298 870 799 3299 878 807 3300 857 786 3301 853 782 3302 876 805 3303 877 806 3304 879 808 3305 880 809 3306 853 782 3307 846 775 3308 881 810 3309 878 807 3310 853 782 3311 882 811 3312 881 810 3313 853 782 3314 880 809 3315 882 811 3316 853 782 3317 883 812 3318 846 775 3319 840 769 3320 883 812 3321 880 809 3322 846 775 3323 884 813 3324 840 769 3325 837 766 3326 884 813 3327 883 812 3328 840 769 3329 885 814 3330 837 766 3331 831 760 3332 885 814 3333 884 813 3334 837 766 3335 886 815 3336 831 760 3337 825 754 3338 886 815 3339 885 814 3340 831 760 3341 887 816 3342 825 754 3343 819 748 3344 887 816 3345 886 815 3346 825 754 3347 888 817 3348 819 748 3349 815 744 3350 888 817 3351 887 816 3352 819 748 3353 889 818 3354 815 744 3355 809 738 3356 889 818 3357 888 817 3358 815 744 3359 890 819 3360 809 738 3361 803 732 3362 890 819 3363 889 818 3364 809 738 3365 891 820 3366 803 732 3367 800 729 3368 891 820 3369 890 819 3370 803 732 3371 892 821 3372 800 729 3373 794 723 3374 892 821 3375 891 820 3376 800 729 3377 893 822 3378 794 723 3379 784 713 3380 893 822 3381 892 821 3382 794 723 3383 894 823 3384 784 713 3385 778 707 3386 894 823 3387 893 822 3388 784 713 3389 895 824 3390 778 707 3391 770 699 3392 895 824 3393 894 823 3394 778 707 3395 896 825 3396 770 699 3397 763 692 3398 896 825 3399 895 824 3400 770 699 3401 410 339 3402 763 692 3403 134 108 3404 410 339 3405 896 825 3406 763 692 3407 897 826 3408 879 808 3409 898 827 3410 897 826 3411 876 805 3412 879 808 3413 899 828 3414 898 827 3415 900 829 3416 899 828 3417 897 826 3418 898 827 3419 901 830 3420 882 811 3421 880 809 3422 902 831 3423 900 829 3424 903 832 3425 902 831 3426 899 828 3427 900 829 3428 904 833 3429 880 809 3430 883 812 3431 905 834 3432 901 830 3433 880 809 3434 904 833 3435 905 834 3436 880 809 3437 906 835 3438 883 812 3439 884 813 3440 906 835 3441 904 833 3442 883 812 3443 907 836 3444 884 813 3445 885 814 3446 907 836 3447 906 835 3448 884 813 3449 908 837 3450 885 814 3451 886 815 3452 908 837 3453 907 836 3454 885 814 3455 909 838 3456 886 815 3457 887 816 3458 909 838 3459 908 837 3460 886 815 3461 910 839 3462 887 816 3463 888 817 3464 910 839 3465 909 838 3466 887 816 3467 911 840 3468 888 817 3469 889 818 3470 911 840 3471 910 839 3472 888 817 3473 912 841 3474 889 818 3475 890 819 3476 912 841 3477 911 840 3478 889 818 3479 913 842 3480 890 819 3481 891 820 3482 913 842 3483 912 841 3484 890 819 3485 914 843 3486 891 820 3487 892 821 3488 914 843 3489 913 842 3490 891 820 3491 915 844 3492 892 821 3493 893 822 3494 915 844 3495 914 843 3496 892 821 3497 916 845 3498 893 822 3499 894 823 3500 916 845 3501 915 844 3502 893 822 3503 917 846 3504 894 823 3505 895 824 3506 918 847 3507 916 845 3508 894 823 3509 917 846 3510 918 847 3511 894 823 3512 919 848 3513 895 824 3514 896 825 3515 920 849 3516 917 846 3517 895 824 3518 921 850 3519 920 849 3520 895 824 3521 922 851 3522 921 850 3523 895 824 3524 923 852 3525 922 851 3526 895 824 3527 919 848 3528 923 852 3529 895 824 3530 924 853 3531 896 825 3532 410 339 3533 925 854 3534 919 848 3535 896 825 3536 926 855 3537 925 854 3538 896 825 3539 924 853 3540 926 855 3541 896 825 3542 927 856 3543 924 853 3544 410 339 3545 928 857 3546 927 856 3547 410 339 3548 758 687 3549 928 857 3550 410 339 3551 929 858 3552 930 859 3553 931 860 3554 932 861 3555 902 831 3556 903 832 3557 933 862 3558 932 861 3559 903 832 3560 934 863 3561 905 834 3562 904 833 3563 929 858 3564 931 860 3565 935 864 3566 936 865 3567 904 833 3568 906 835 3569 937 866 3570 934 863 3571 904 833 3572 936 865 3573 937 866 3574 904 833 3575 938 867 3576 906 835 3577 907 836 3578 938 867 3579 936 865 3580 906 835 3581 939 868 3582 907 836 3583 908 837 3584 939 868 3585 938 867 3586 907 836 3587 940 869 3588 908 837 3589 909 838 3590 940 869 3591 939 868 3592 908 837 3593 941 870 3594 909 838 3595 910 839 3596 941 870 3597 940 869 3598 909 838 3599 942 871 3600 910 839 3601 911 840 3602 942 871 3603 941 870 3604 910 839 3605 943 872 3606 911 840 3607 912 841 3608 943 872 3609 942 871 3610 911 840 3611 944 873 3612 912 841 3613 913 842 3614 944 873 3615 943 872 3616 912 841 3617 945 874 3618 913 842 3619 914 843 3620 945 874 3621 944 873 3622 913 842 3623 946 875 3624 914 843 3625 915 844 3626 946 875 3627 945 874 3628 914 843 3629 947 876 3630 915 844 3631 916 845 3632 947 876 3633 946 875 3634 915 844 3635 948 877 3636 916 845 3637 918 847 3638 948 877 3639 947 876 3640 916 845 3641 949 878 3642 950 879 3643 951 880 3644 952 881 3645 948 877 3646 918 847 3647 949 878 3648 953 882 3649 950 879 3650 954 883 3651 951 880 3652 955 884 3653 949 878 3654 951 880 3655 954 883 3656 954 883 3657 955 884 3658 956 885 3659 957 886 3660 956 885 3661 958 887 3662 954 883 3663 956 885 3664 957 886 3665 959 888 3666 958 887 3667 960 889 3668 957 886 3669 958 887 3670 959 888 3671 961 890 3672 960 889 3673 962 891 3674 959 888 3675 960 889 3676 961 890 3677 961 890 3678 962 891 3679 963 892 3680 964 893 3681 965 893 3682 966 893 3683 967 894 3684 965 894 3685 964 894 3686 961 890 3687 963 892 3688 968 895 3689 969 896 3690 970 896 3691 971 896 3692 972 896 3693 973 896 3694 970 896 3695 969 896 3696 972 896 3697 970 896 3698 969 896 3699 971 896 3700 974 896 3701 975 897 3702 928 857 3703 758 687 3704 969 896 3705 974 896 3706 976 896 3707 975 897 3708 758 687 3709 753 682 3710 977 898 3711 935 864 3712 978 899 3713 929 858 3714 935 864 3715 977 898 3716 979 900 3717 937 866 3718 936 865 3719 977 898 3720 978 899 3721 980 901 3722 981 902 3723 936 865 3724 938 867 3725 982 903 3726 979 900 3727 936 865 3728 983 904 3729 982 903 3730 936 865 3731 981 902 3732 983 904 3733 936 865 3734 984 905 3735 938 867 3736 939 868 3737 984 905 3738 981 902 3739 938 867 3740 985 906 3741 939 868 3742 940 869 3743 985 906 3744 984 905 3745 939 868 3746 986 907 3747 940 869 3748 941 870 3749 986 907 3750 985 906 3751 940 869 3752 987 908 3753 941 870 3754 942 871 3755 988 909 3756 986 907 3757 941 870 3758 989 910 3759 988 909 3760 941 870 3761 987 908 3762 989 910 3763 941 870 3764 990 911 3765 942 871 3766 943 872 3767 991 912 3768 987 908 3769 942 871 3770 992 913 3771 991 912 3772 942 871 3773 990 911 3774 992 913 3775 942 871 3776 993 914 3777 943 872 3778 944 873 3779 994 915 3780 990 911 3781 943 872 3782 995 916 3783 994 915 3784 943 872 3785 996 917 3786 995 916 3787 943 872 3788 997 918 3789 996 917 3790 943 872 3791 998 919 3792 997 918 3793 943 872 3794 993 914 3795 998 919 3796 943 872 3797 999 920 3798 944 873 3799 945 874 3800 999 920 3801 993 914 3802 944 873 3803 1000 921 3804 945 874 3805 946 875 3806 1000 921 3807 999 920 3808 945 874 3809 1001 922 3810 946 875 3811 947 876 3812 1001 922 3813 1000 921 3814 946 875 3815 1002 923 3816 947 876 3817 948 877 3818 1002 923 3819 1001 922 3820 947 876 3821 1003 924 3822 1004 925 3823 948 877 3824 1005 926 3825 948 877 3826 1004 925 3827 1006 927 3828 1003 924 3829 948 877 3830 1007 928 3831 1006 927 3832 948 877 3833 1008 929 3834 1007 928 3835 948 877 3836 952 881 3837 1008 929 3838 948 877 3839 1005 926 3840 1002 923 3841 948 877 3842 1009 930 3843 1010 931 3844 1004 925 3845 1011 932 3846 1004 925 3847 1010 931 3848 1012 933 3849 1009 930 3850 1004 925 3851 1013 934 3852 1012 933 3853 1004 925 3854 1003 924 3855 1013 934 3856 1004 925 3857 1011 932 3858 1005 926 3859 1004 925 3860 975 897 3861 753 682 3862 1010 931 3863 729 658 3864 1010 931 3865 753 682 3866 1014 935 3867 975 897 3868 1010 931 3869 1009 930 3870 1014 935 3871 1010 931 3872 729 658 3873 1011 932 3874 1010 931 3875 1015 936 3876 1016 936 3877 1017 936 3878 1015 937 3879 1017 937 3880 1018 937 3881 1019 938 3882 1020 939 3883 1021 940 3884 1022 941 3885 1021 940 3886 1023 942 3887 1019 938 3888 1021 940 3889 1022 941 3890 1022 941 3891 1023 942 3892 1024 943 3893 1025 944 3894 1024 943 3895 1026 945 3896 1022 941 3897 1024 943 3898 1025 944 3899 1027 946 3900 1026 945 3901 1028 947 3902 1025 944 3903 1026 945 3904 1027 946 3905 1027 946 3906 1028 947 3907 1029 948 3908 949 878 3909 1029 948 3910 953 882 3911 1027 946 3912 1029 948 3913 949 878 3914 1030 949 3915 980 901 3916 1031 950 3917 977 898 3918 980 901 3919 1030 949 3920 1030 949 3921 1031 950 3922 1032 951 3923 1033 952 3924 983 904 3925 981 902 3926 1034 953 3927 1032 951 3928 1035 954 3929 1030 949 3930 1032 951 3931 1034 953 3932 1036 955 3933 981 902 3934 984 905 3935 1037 956 3936 1033 952 3937 981 902 3938 1036 955 3939 1037 956 3940 981 902 3941 1038 957 3942 984 905 3943 985 906 3944 1038 957 3945 1036 955 3946 984 905 3947 1039 958 3948 985 906 3949 986 907 3950 1039 958 3951 1038 957 3952 985 906 3953 1040 959 3954 986 907 3955 988 909 3956 1040 959 3957 1039 958 3958 986 907 3959 1041 960 3960 1042 961 3961 1043 962 3962 1044 963 3963 1040 959 3964 988 909 3965 1041 960 3966 1045 964 3967 1042 961 3968 1046 965 3969 1043 962 3970 1047 966 3971 1046 965 3972 1041 960 3973 1043 962 3974 1048 967 3975 1047 966 3976 1049 968 3977 1048 967 3978 1046 965 3979 1047 966 3980 1050 969 3981 1049 968 3982 1051 970 3983 1050 969 3984 1048 967 3985 1049 968 3986 1052 971 3987 1051 970 3988 1053 972 3989 1052 971 3990 1050 969 3991 1051 970 3992 1054 973 3993 1053 972 3994 1055 974 3995 1054 973 3996 1052 971 3997 1053 972 3998 1056 975 3999 1055 974 4000 1057 976 4001 1056 975 4002 1054 973 4003 1055 974 4004 1058 977 4005 1057 976 4006 1059 978 4007 1058 977 4008 1056 975 4009 1057 976 4010 1060 979 4011 1059 978 4012 1061 980 4013 1060 979 4014 1058 977 4015 1059 978 4016 1060 979 4017 1061 980 4018 1062 981 4019 1063 982 4020 998 919 4021 993 914 4022 1064 983 4023 1062 981 4024 1065 984 4025 1064 983 4026 1060 979 4027 1062 981 4028 1066 985 4029 993 914 4030 999 920 4031 1067 986 4032 993 914 4033 1066 985 4034 1068 987 4035 993 914 4036 1067 986 4037 1068 987 4038 1063 982 4039 993 914 4040 1069 988 4041 999 920 4042 1000 921 4043 1066 985 4044 999 920 4045 1069 988 4046 1070 989 4047 1000 921 4048 1001 922 4049 1069 988 4050 1000 921 4051 1070 989 4052 1071 990 4053 1001 922 4054 1002 923 4055 1070 989 4056 1001 922 4057 1071 990 4058 1072 991 4059 1002 923 4060 1005 926 4061 1071 990 4062 1002 923 4063 1072 991 4064 1073 992 4065 1005 926 4066 1011 932 4067 1072 991 4068 1005 926 4069 1073 992 4070 1074 993 4071 1011 932 4072 729 658 4073 1073 992 4074 1011 932 4075 1074 993 4076 1074 993 4077 729 658 4078 707 636 4079 1034 953 4080 1035 954 4081 1075 994 4082 1076 995 4083 1037 956 4084 1036 955 4085 1077 996 4086 1075 994 4087 1078 997 4088 1034 953 4089 1075 994 4090 1077 996 4091 1079 998 4092 1036 955 4093 1038 957 4094 1080 999 4095 1076 995 4096 1036 955 4097 1079 998 4098 1080 999 4099 1036 955 4100 1081 1000 4101 1038 957 4102 1039 958 4103 1081 1000 4104 1079 998 4105 1038 957 4106 1082 1001 4107 1039 958 4108 1040 959 4109 1082 1001 4110 1081 1000 4111 1039 958 4112 1083 1002 4113 1084 1003 4114 1040 959 4115 1085 1004 4116 1040 959 4117 1084 1003 4118 1086 1005 4119 1083 1002 4120 1040 959 4121 1087 1006 4122 1086 1005 4123 1040 959 4124 1088 1007 4125 1087 1006 4126 1040 959 4127 1044 963 4128 1088 1007 4129 1040 959 4130 1085 1004 4131 1082 1001 4132 1040 959 4133 1089 1008 4134 1090 1009 4135 1091 1010 4136 1092 1011 4137 1085 1004 4138 1084 1003 4139 1093 1012 4140 1094 1013 4141 1090 1009 4142 1089 1008 4143 1093 1012 4144 1090 1009 4145 1095 1014 4146 1091 1010 4147 1096 1015 4148 1095 1014 4149 1089 1008 4150 1091 1010 4151 1097 1016 4152 1096 1015 4153 1098 1017 4154 1097 1016 4155 1095 1014 4156 1096 1015 4157 1097 1016 4158 1098 1017 4159 1099 1018 4160 1100 1019 4161 1101 1020 4162 1045 964 4163 1102 1021 4164 1097 1016 4165 1099 1018 4166 1041 960 4167 1100 1019 4168 1045 964 4169 1077 996 4170 1078 997 4171 1103 1022 4172 1104 1023 4173 1080 999 4174 1079 998 4175 1105 1024 4176 1103 1022 4177 1106 1025 4178 1077 996 4179 1103 1022 4180 1105 1024 4181 1107 1026 4182 1079 998 4183 1081 1000 4184 1108 1027 4185 1104 1023 4186 1079 998 4187 1107 1026 4188 1108 1027 4189 1079 998 4190 1109 1028 4191 1081 1000 4192 1082 1001 4193 1109 1028 4194 1107 1026 4195 1081 1000 4196 1110 1029 4197 1082 1001 4198 1085 1004 4199 1110 1029 4200 1109 1028 4201 1082 1001 4202 1092 1011 4203 1111 1030 4204 1085 1004 4205 1112 1031 4206 1085 1004 4207 1111 1030 4208 1112 1031 4209 1110 1029 4210 1085 1004 4211 1113 1032 4212 1114 1033 4213 1111 1030 4214 1115 1034 4215 1111 1030 4216 1114 1033 4217 1116 1035 4218 1113 1032 4219 1111 1030 4220 1117 1036 4221 1116 1035 4222 1111 1030 4223 1118 1037 4224 1117 1036 4225 1111 1030 4226 1119 1038 4227 1118 1037 4228 1111 1030 4229 1092 1011 4230 1119 1038 4231 1111 1030 4232 1115 1034 4233 1112 1031 4234 1111 1030 4235 1067 986 4236 1120 1039 4237 1114 1033 4238 1121 1040 4239 1114 1033 4240 1120 1039 4241 1113 1032 4242 1067 986 4243 1114 1033 4244 1121 1040 4245 1115 1034 4246 1114 1033 4247 1066 985 4248 1122 1041 4249 1120 1039 4250 1123 1042 4251 1120 1039 4252 1122 1041 4253 1067 986 4254 1066 985 4255 1120 1039 4256 1123 1042 4257 1121 1040 4258 1120 1039 4259 1069 988 4260 1124 1043 4261 1122 1041 4262 1125 1044 4263 1122 1041 4264 1124 1043 4265 1066 985 4266 1069 988 4267 1122 1041 4268 1125 1044 4269 1123 1042 4270 1122 1041 4271 1070 989 4272 1126 1045 4273 1124 1043 4274 1127 1046 4275 1124 1043 4276 1126 1045 4277 1069 988 4278 1070 989 4279 1124 1043 4280 1127 1046 4281 1125 1044 4282 1124 1043 4283 1071 990 4284 1128 1047 4285 1126 1045 4286 1129 1048 4287 1126 1045 4288 1128 1047 4289 1070 989 4290 1071 990 4291 1126 1045 4292 1129 1048 4293 1127 1046 4294 1126 1045 4295 1072 991 4296 1130 1049 4297 1128 1047 4298 1131 1050 4299 1128 1047 4300 1130 1049 4301 1071 990 4302 1072 991 4303 1128 1047 4304 1131 1050 4305 1129 1048 4306 1128 1047 4307 1132 1051 4308 1133 1052 4309 1130 1049 4310 1134 1053 4311 1130 1049 4312 1133 1052 4313 1135 1054 4314 1132 1051 4315 1130 1049 4316 1136 1055 4317 1135 1054 4318 1130 1049 4319 1137 1056 4320 1136 1055 4321 1130 1049 4322 1138 1057 4323 1137 1056 4324 1130 1049 4325 1139 1058 4326 1138 1057 4327 1130 1049 4328 1140 1059 4329 1139 1058 4330 1130 1049 4331 1141 1060 4332 1140 1059 4333 1130 1049 4334 1142 1061 4335 1141 1060 4336 1130 1049 4337 1072 991 4338 1142 1061 4339 1130 1049 4340 1134 1053 4341 1131 1050 4342 1130 1049 4343 1143 1062 4344 1144 1063 4345 1133 1052 4346 1145 1064 4347 1133 1052 4348 1144 1063 4349 1132 1051 4350 1143 1062 4351 1133 1052 4352 1145 1064 4353 1134 1053 4354 1133 1052 4355 1146 1065 4356 1147 1065 4357 1148 1065 4358 1149 1066 4359 1145 1064 4360 1144 1063 4361 1146 1067 4362 1150 1067 4363 1147 1067 4364 1146 1068 4365 1148 1068 4366 1151 1068 4367 1152 1069 4368 1153 1070 4369 1154 1071 4370 1155 1072 4371 1154 1071 4372 1156 1073 4373 1152 1069 4374 1154 1071 4375 1155 1072 4376 1157 1074 4377 1156 1073 4378 1158 1075 4379 1155 1072 4380 1156 1073 4381 1157 1074 4382 1157 1074 4383 1158 1075 4384 1159 1076 4385 1160 1077 4386 1159 1076 4387 1161 1078 4388 1157 1074 4389 1159 1076 4390 1160 1077 4391 1162 1079 4392 1161 1078 4393 1163 1080 4394 1160 1077 4395 1161 1078 4396 1162 1079 4397 1162 1079 4398 1163 1080 4399 1164 1081 4400 1165 1082 4401 1164 1081 4402 1166 1083 4403 1162 1079 4404 1164 1081 4405 1165 1082 4406 1073 992 4407 1167 1084 4408 1142 1061 4409 1165 1082 4410 1166 1083 4411 1168 1085 4412 1072 991 4413 1073 992 4414 1142 1061 4415 1073 992 4416 1169 1086 4417 1167 1084 4418 1170 1087 4419 1168 1085 4420 1171 1088 4421 1165 1082 4422 1168 1085 4423 1170 1087 4424 1073 992 4425 1172 1089 4426 1169 1086 4427 1170 1087 4428 1171 1088 4429 1173 1090 4430 1073 992 4431 1174 1091 4432 1172 1089 4433 1175 1092 4434 1173 1090 4435 1176 1093 4436 1170 1087 4437 1173 1090 4438 1175 1092 4439 1073 992 4440 1177 1094 4441 1174 1091 4442 1178 1095 4443 1176 1093 4444 1179 1096 4445 1175 1092 4446 1176 1093 4447 1178 1095 4448 1074 993 4449 1180 1097 4450 1177 1094 4451 1178 1095 4452 1179 1096 4453 1181 1098 4454 1073 992 4455 1074 993 4456 1177 1094 4457 1182 1099 4458 1183 1099 4459 1184 1099 4460 1074 993 4461 1185 1100 4462 1180 1097 4463 1186 1101 4464 1183 1101 4465 1182 1101 4466 1178 1095 4467 1181 1098 4468 1187 1102 4469 1074 993 4470 1188 1103 4471 1185 1100 4472 1189 896 4473 1190 896 4474 1191 896 4475 707 636 4476 1192 1104 4477 1188 1103 4478 1193 896 4479 1190 896 4480 1189 896 4481 1074 993 4482 707 636 4483 1188 1103 4484 1194 896 4485 1190 896 4486 1193 896 4487 707 636 4488 1195 1105 4489 1192 1104 4490 707 636 4491 670 599 4492 1195 1105 4493 651 580 4494 1195 1105 4495 670 599 4496 1149 1066 4497 1195 1105 4498 651 580 4499 1196 1106 4500 1067 986 4501 1113 1032 4502 1197 1107 4503 1068 987 4504 1067 986 4505 1198 1108 4506 1197 1107 4507 1067 986 4508 1196 1106 4509 1198 1108 4510 1067 986 4511 1199 1109 4512 1200 1110 4513 1201 1111 4514 1199 1109 4515 1202 1112 4516 1200 1110 4517 1203 1113 4518 1201 1111 4519 1204 1114 4520 1203 1113 4521 1199 1109 4522 1201 1111 4523 1205 1115 4524 1204 1114 4525 1206 1116 4526 1205 1115 4527 1203 1113 4528 1204 1114 4529 1207 1117 4530 1206 1116 4531 1208 1118 4532 1207 1117 4533 1205 1115 4534 1206 1116 4535 1093 1012 4536 1208 1118 4537 1094 1013 4538 1093 1012 4539 1207 1117 4540 1208 1118 4541 1209 1119 4542 1106 1025 4543 1210 1120 4544 1105 1024 4545 1106 1025 4546 1209 1119 4547 1211 1121 4548 1108 1027 4549 1107 1026 4550 1212 1122 4551 1210 1120 4552 1213 1123 4553 1209 1119 4554 1210 1120 4555 1212 1122 4556 1214 1124 4557 1107 1026 4558 1109 1028 4559 1215 1125 4560 1211 1121 4561 1107 1026 4562 1214 1124 4563 1215 1125 4564 1107 1026 4565 1216 1126 4566 1109 1028 4567 1110 1029 4568 1216 1126 4569 1214 1124 4570 1109 1028 4571 1217 1127 4572 1110 1029 4573 1112 1031 4574 1217 1127 4575 1216 1126 4576 1110 1029 4577 1218 1128 4578 1112 1031 4579 1115 1034 4580 1218 1128 4581 1217 1127 4582 1112 1031 4583 1219 1129 4584 1115 1034 4585 1121 1040 4586 1219 1129 4587 1218 1128 4588 1115 1034 4589 1220 1130 4590 1121 1040 4591 1123 1042 4592 1220 1130 4593 1219 1129 4594 1121 1040 4595 1221 1131 4596 1123 1042 4597 1125 1044 4598 1221 1131 4599 1220 1130 4600 1123 1042 4601 1222 1132 4602 1125 1044 4603 1127 1046 4604 1222 1132 4605 1221 1131 4606 1125 1044 4607 1223 1133 4608 1127 1046 4609 1129 1048 4610 1223 1133 4611 1222 1132 4612 1127 1046 4613 1224 1134 4614 1129 1048 4615 1131 1050 4616 1224 1134 4617 1223 1133 4618 1129 1048 4619 1225 1135 4620 1131 1050 4621 1134 1053 4622 1225 1135 4623 1224 1134 4624 1131 1050 4625 1226 1136 4626 1134 1053 4627 1145 1064 4628 1226 1136 4629 1225 1135 4630 1134 1053 4631 1149 1066 4632 651 580 4633 1145 1064 4634 1227 1137 4635 1145 1064 4636 651 580 4637 1227 1137 4638 1226 1136 4639 1145 1064 4640 632 561 4641 1227 1137 4642 651 580 4643 1228 896 4644 1194 896 4645 1193 896 4646 1229 1138 4647 1213 1123 4648 1230 1139 4649 1212 1122 4650 1213 1123 4651 1229 1138 4652 1231 1140 4653 1215 1125 4654 1214 1124 4655 1232 1141 4656 1230 1139 4657 1233 1142 4658 1229 1138 4659 1230 1139 4660 1232 1141 4661 1234 1143 4662 1214 1124 4663 1216 1126 4664 1235 1144 4665 1231 1140 4666 1214 1124 4667 1234 1143 4668 1235 1144 4669 1214 1124 4670 1236 1145 4671 1216 1126 4672 1217 1127 4673 1236 1145 4674 1234 1143 4675 1216 1126 4676 1237 1146 4677 1217 1127 4678 1218 1128 4679 1237 1146 4680 1236 1145 4681 1217 1127 4682 1238 1147 4683 1218 1128 4684 1219 1129 4685 1238 1147 4686 1237 1146 4687 1218 1128 4688 1239 1148 4689 1219 1129 4690 1220 1130 4691 1239 1148 4692 1238 1147 4693 1219 1129 4694 1240 1149 4695 1220 1130 4696 1221 1131 4697 1240 1149 4698 1239 1148 4699 1220 1130 4700 1241 1150 4701 1221 1131 4702 1222 1132 4703 1241 1150 4704 1240 1149 4705 1221 1131 4706 1242 1151 4707 1222 1132 4708 1223 1133 4709 1242 1151 4710 1241 1150 4711 1222 1132 4712 1243 1152 4713 1223 1133 4714 1224 1134 4715 1243 1152 4716 1242 1151 4717 1223 1133 4718 1244 1153 4719 1224 1134 4720 1225 1135 4721 1244 1153 4722 1243 1152 4723 1224 1134 4724 1245 1154 4725 1225 1135 4726 1226 1136 4727 1246 1155 4728 1244 1153 4729 1225 1135 4730 1247 1156 4731 1246 1155 4732 1225 1135 4733 1248 1157 4734 1247 1156 4735 1225 1135 4736 1245 1154 4737 1248 1157 4738 1225 1135 4739 1249 1158 4740 1226 1136 4741 1227 1137 4742 1250 1159 4743 1245 1154 4744 1226 1136 4745 1251 1160 4746 1250 1159 4747 1226 1136 4748 1252 1161 4749 1251 1160 4750 1226 1136 4751 1253 1162 4752 1252 1161 4753 1226 1136 4754 1254 1163 4755 1253 1162 4756 1226 1136 4757 1249 1158 4758 1254 1163 4759 1226 1136 4760 1255 1164 4761 1227 1137 4762 632 561 4763 1255 1164 4764 1249 1158 4765 1227 1137 4766 1256 1165 4767 1255 1164 4768 632 561 4769 614 543 4770 1256 1165 4771 632 561 4772 1257 1166 4773 1233 1142 4774 1258 1167 4775 1232 1141 4776 1233 1142 4777 1257 1166 4778 1259 1168 4779 1235 1144 4780 1234 1143 4781 1260 1169 4782 1258 1167 4783 1261 1170 4784 1257 1166 4785 1258 1167 4786 1260 1169 4787 1262 1171 4788 1234 1143 4789 1236 1145 4790 1263 1172 4791 1259 1168 4792 1234 1143 4793 1262 1171 4794 1263 1172 4795 1234 1143 4796 1264 1173 4797 1236 1145 4798 1237 1146 4799 1264 1173 4800 1262 1171 4801 1236 1145 4802 1265 1174 4803 1237 1146 4804 1238 1147 4805 1265 1174 4806 1264 1173 4807 1237 1146 4808 1266 1175 4809 1238 1147 4810 1239 1148 4811 1266 1175 4812 1265 1174 4813 1238 1147 4814 1267 1176 4815 1239 1148 4816 1240 1149 4817 1267 1176 4818 1266 1175 4819 1239 1148 4820 1268 1177 4821 1240 1149 4822 1241 1150 4823 1268 1177 4824 1267 1176 4825 1240 1149 4826 1269 1178 4827 1241 1150 4828 1242 1151 4829 1269 1178 4830 1268 1177 4831 1241 1150 4832 1270 1179 4833 1242 1151 4834 1243 1152 4835 1270 1179 4836 1269 1178 4837 1242 1151 4838 1271 1180 4839 1243 1152 4840 1244 1153 4841 1271 1180 4842 1270 1179 4843 1243 1152 4844 1272 1181 4845 1273 1182 4846 1244 1153 4847 1274 1183 4848 1244 1153 4849 1273 1182 4850 1275 1184 4851 1272 1181 4852 1244 1153 4853 1246 1155 4854 1275 1184 4855 1244 1153 4856 1274 1183 4857 1271 1180 4858 1244 1153 4859 1276 1185 4860 1277 1186 4861 1278 1187 4862 1279 1188 4863 1274 1183 4864 1273 1182 4865 1280 1189 4866 1281 1190 4867 1277 1186 4868 1280 1189 4869 1277 1186 4870 1276 1185 4871 1276 1185 4872 1278 1187 4873 1282 1191 4874 1283 1192 4875 1282 1191 4876 1284 1193 4877 1276 1185 4878 1282 1191 4879 1283 1192 4880 1283 1192 4881 1284 1193 4882 1285 1194 4883 1286 1195 4884 1285 1194 4885 1287 1196 4886 1283 1192 4887 1285 1194 4888 1286 1195 4889 1286 1195 4890 1287 1196 4891 1288 1197 4892 1289 1198 4893 1288 1197 4894 1290 1199 4895 1286 1195 4896 1288 1197 4897 1289 1198 4898 1291 1200 4899 1290 1199 4900 1292 1201 4901 1289 1198 4902 1290 1199 4903 1291 1200 4904 1291 1200 4905 1292 1201 4906 1293 1202 4907 1294 1203 4908 1293 1202 4909 1295 1204 4910 1291 1200 4911 1293 1202 4912 1294 1203 4913 1294 1203 4914 1295 1204 4915 1296 1205 4916 1297 1206 4917 1298 1206 4918 1299 1206 4919 1300 1207 4920 1298 1207 4921 1297 1207 4922 1294 1203 4923 1296 1205 4924 1301 1208 4925 1302 896 4926 1303 896 4927 1304 896 4928 595 524 4929 1256 1165 4930 614 543 4931 1305 1209 4932 1256 1165 4933 595 524 4934 1302 896 4935 1304 896 4936 1306 896 4937 1263 1172 4938 1307 1210 4939 1259 1168 4940 1308 1211 4941 1261 1170 4942 1309 1212 4943 1260 1169 4944 1261 1170 4945 1308 1211 4946 1310 1213 4947 1307 1210 4948 1263 1172 4949 1310 1213 4950 1311 1214 4951 1307 1210 4952 1312 1215 4953 1309 1212 4954 1313 1216 4955 1308 1211 4956 1309 1212 4957 1312 1215 4958 1314 1217 4959 1263 1172 4960 1262 1171 4961 1314 1217 4962 1310 1213 4963 1263 1172 4964 1315 1218 4965 1262 1171 4966 1264 1173 4967 1315 1218 4968 1314 1217 4969 1262 1171 4970 1316 1219 4971 1264 1173 4972 1265 1174 4973 1316 1219 4974 1315 1218 4975 1264 1173 4976 1317 1220 4977 1265 1174 4978 1266 1175 4979 1317 1220 4980 1316 1219 4981 1265 1174 4982 1318 1221 4983 1266 1175 4984 1267 1176 4985 1318 1221 4986 1317 1220 4987 1266 1175 4988 1319 1222 4989 1267 1176 4990 1268 1177 4991 1319 1222 4992 1318 1221 4993 1267 1176 4994 1320 1223 4995 1268 1177 4996 1269 1178 4997 1320 1223 4998 1319 1222 4999 1268 1177 5000 1321 1224 5001 1269 1178 5002 1270 1179 5003 1321 1224 5004 1320 1223 5005 1269 1178 5006 1322 1225 5007 1270 1179 5008 1271 1180 5009 1322 1225 5010 1321 1224 5011 1270 1179 5012 1323 1226 5013 1271 1180 5014 1274 1183 5015 1323 1226 5016 1322 1225 5017 1271 1180 5018 1324 1227 5019 1325 1228 5020 1274 1183 5021 1326 1229 5022 1274 1183 5023 1325 1228 5024 1327 1230 5025 1324 1227 5026 1274 1183 5027 1328 1231 5028 1327 1230 5029 1274 1183 5030 1279 1188 5031 1328 1231 5032 1274 1183 5033 1326 1229 5034 1323 1226 5035 1274 1183 5036 1329 1232 5037 1330 1233 5038 1325 1228 5039 1331 1234 5040 1325 1228 5041 1330 1233 5042 1324 1227 5043 1329 1232 5044 1325 1228 5045 1331 1234 5046 1326 1229 5047 1325 1228 5048 1332 1235 5049 595 524 5050 1330 1233 5051 576 505 5052 1330 1233 5053 595 524 5054 1329 1232 5055 1332 1235 5056 1330 1233 5057 576 505 5058 1331 1234 5059 1330 1233 5060 1332 1235 5061 1305 1209 5062 595 524 5063 1302 896 5064 1306 896 5065 1333 896 5066 1334 1236 5067 1335 1236 5068 1336 1236 5069 1337 896 5070 1302 896 5071 1333 896 5072 1338 896 5073 1337 896 5074 1333 896 5075 1339 896 5076 1338 896 5077 1333 896 5078 1334 1237 5079 1336 1237 5080 1340 1237 5081 1341 1238 5082 1342 1239 5083 1343 1240 5084 1344 1241 5085 1343 1240 5086 1345 1242 5087 1341 1238 5088 1343 1240 5089 1344 1241 5090 1280 1189 5091 1345 1242 5092 1281 1190 5093 1344 1241 5094 1345 1242 5095 1280 1189 5096 1310 1213 5097 1346 1243 5098 1311 1214 5099 1347 1244 5100 1313 1216 5101 1348 1245 5102 1312 1215 5103 1313 1216 5104 1347 1244 5105 1349 1246 5106 1346 1243 5107 1310 1213 5108 1349 1246 5109 1350 1247 5110 1346 1243 5111 1347 1244 5112 1348 1245 5113 1351 1248 5114 1352 1249 5115 1310 1213 5116 1314 1217 5117 1352 1249 5118 1349 1246 5119 1310 1213 5120 1353 1250 5121 1314 1217 5122 1315 1218 5123 1353 1250 5124 1352 1249 5125 1314 1217 5126 1354 1251 5127 1315 1218 5128 1316 1219 5129 1354 1251 5130 1353 1250 5131 1315 1218 5132 1355 1252 5133 1316 1219 5134 1317 1220 5135 1355 1252 5136 1354 1251 5137 1316 1219 5138 1356 1253 5139 1317 1220 5140 1318 1221 5141 1356 1253 5142 1355 1252 5143 1317 1220 5144 1357 1254 5145 1318 1221 5146 1319 1222 5147 1357 1254 5148 1356 1253 5149 1318 1221 5150 1358 1255 5151 1319 1222 5152 1320 1223 5153 1358 1255 5154 1357 1254 5155 1319 1222 5156 1359 1256 5157 1320 1223 5158 1321 1224 5159 1359 1256 5160 1358 1255 5161 1320 1223 5162 1360 1257 5163 1321 1224 5164 1322 1225 5165 1361 1258 5166 1359 1256 5167 1321 1224 5168 1362 1259 5169 1361 1258 5170 1321 1224 5171 1363 1260 5172 1362 1259 5173 1321 1224 5174 1360 1257 5175 1363 1260 5176 1321 1224 5177 1364 1261 5178 1322 1225 5179 1323 1226 5180 1365 1262 5181 1360 1257 5182 1322 1225 5183 1366 1263 5184 1365 1262 5185 1322 1225 5186 1367 1264 5187 1366 1263 5188 1322 1225 5189 1368 1265 5190 1367 1264 5191 1322 1225 5192 1369 1266 5193 1368 1265 5194 1322 1225 5195 1364 1261 5196 1369 1266 5197 1322 1225 5198 1370 1267 5199 1323 1226 5200 1326 1229 5201 1370 1267 5202 1364 1261 5203 1323 1226 5204 1371 1268 5205 1326 1229 5206 1331 1234 5207 1372 1269 5208 1370 1267 5209 1326 1229 5210 1371 1268 5211 1372 1269 5212 1326 1229 5213 1373 1270 5214 1331 1234 5215 576 505 5216 1373 1270 5217 1371 1268 5218 1331 1234 5219 557 486 5220 1373 1270 5221 576 505 5222 1349 1246 5223 1374 1271 5224 1350 1247 5225 1375 1272 5226 1351 1248 5227 1376 1273 5228 1347 1244 5229 1351 1248 5230 1375 1272 5231 1377 1274 5232 1374 1271 5233 1349 1246 5234 1377 1274 5235 1378 1275 5236 1374 1271 5237 1379 1276 5238 1376 1273 5239 1380 1277 5240 1381 1278 5241 1375 1272 5242 1376 1273 5243 1382 1279 5244 1381 1278 5245 1376 1273 5246 1383 1280 5247 1382 1279 5248 1376 1273 5249 1384 1281 5250 1383 1280 5251 1376 1273 5252 1379 1276 5253 1384 1281 5254 1376 1273 5255 1385 1282 5256 1349 1246 5257 1352 1249 5258 1385 1282 5259 1377 1274 5260 1349 1246 5261 1386 1283 5262 1352 1249 5263 1353 1250 5264 1387 1284 5265 1385 1282 5266 1352 1249 5267 1386 1283 5268 1387 1284 5269 1352 1249 5270 1388 1285 5271 1353 1250 5272 1354 1251 5273 1389 896 5274 1390 896 5275 1391 896 5276 1392 1286 5277 1386 1283 5278 1353 1250 5279 1388 1285 5280 1392 1286 5281 1353 1250 5282 1393 1287 5283 1354 1251 5284 1355 1252 5285 1394 1288 5286 1388 1285 5287 1354 1251 5288 1395 1289 5289 1394 1288 5290 1354 1251 5291 1396 1290 5292 1395 1289 5293 1354 1251 5294 1397 1291 5295 1396 1290 5296 1354 1251 5297 1398 1292 5298 1397 1291 5299 1354 1251 5300 1399 1293 5301 1398 1292 5302 1354 1251 5303 1400 896 5304 1401 896 5305 1389 896 5306 1393 1287 5307 1399 1293 5308 1354 1251 5309 1402 1294 5310 1355 1252 5311 1356 1253 5312 1402 1294 5313 1393 1287 5314 1355 1252 5315 1403 1295 5316 1356 1253 5317 1357 1254 5318 1403 1295 5319 1402 1294 5320 1356 1253 5321 1404 1296 5322 1357 1254 5323 1358 1255 5324 1404 1296 5325 1403 1295 5326 1357 1254 5327 1405 1297 5328 1358 1255 5329 1359 1256 5330 1405 1297 5331 1404 1296 5332 1358 1255 5333 1406 1298 5334 1407 1299 5335 1359 1256 5336 1408 1300 5337 1359 1256 5338 1407 1299 5339 1409 1301 5340 1406 1298 5341 1359 1256 5342 1410 1302 5343 1409 1301 5344 1359 1256 5345 1411 1303 5346 1410 1302 5347 1359 1256 5348 1412 1304 5349 1411 1303 5350 1359 1256 5351 1361 1258 5352 1412 1304 5353 1359 1256 5354 1408 1300 5355 1405 1297 5356 1359 1256 5357 1413 1305 5358 1414 1305 5359 1415 1305 5360 1416 1306 5361 1408 1300 5362 1407 1299 5363 1417 1307 5364 1416 1306 5365 1407 1299 5366 1413 1308 5367 1418 1308 5368 1414 1308 5369 1419 1309 5370 1420 1310 5371 1421 1311 5372 1422 1312 5373 1421 1311 5374 1423 1313 5375 1424 1314 5376 1419 1309 5377 1421 1311 5378 1422 1312 5379 1424 1314 5380 1421 1311 5381 1422 1312 5382 1423 1313 5383 1425 1315 5384 1426 1316 5385 1425 1315 5386 1427 1317 5387 1426 1316 5388 1422 1312 5389 1425 1315 5390 1426 1316 5391 1427 1317 5392 1428 1318 5393 1429 1319 5394 1428 1318 5395 1430 1320 5396 1429 1319 5397 1426 1316 5398 1428 1318 5399 1429 1319 5400 1430 1320 5401 1431 1321 5402 1432 1322 5403 1431 1321 5404 1433 1323 5405 1432 1322 5406 1429 1319 5407 1431 1321 5408 1432 1322 5409 1433 1323 5410 1434 1324 5411 1435 1325 5412 1434 1324 5413 1436 1326 5414 1435 1325 5415 1432 1322 5416 1434 1324 5417 1437 1327 5418 1436 1326 5419 1438 1328 5420 1437 1327 5421 1435 1325 5422 1436 1326 5423 1437 1327 5424 1438 1328 5425 1439 1329 5426 1440 1330 5427 1439 1329 5428 1441 1331 5429 1440 1330 5430 1437 1327 5431 1439 1329 5432 1440 1330 5433 1441 1331 5434 1442 1332 5435 1443 1333 5436 1444 1333 5437 1445 1333 5438 1446 1334 5439 1444 1334 5440 1443 1334 5441 1447 1335 5442 1444 1335 5443 1446 1335 5444 1448 1336 5445 1444 1336 5446 1447 1336 5447 1449 1337 5448 1440 1330 5449 1442 1332 5450 1450 1338 5451 1371 1268 5452 1373 1270 5453 537 466 5454 1373 1270 5455 557 486 5456 537 466 5457 1451 1339 5458 1373 1270 5459 1450 1338 5460 1373 1270 5461 1451 1339 5462 1377 1274 5463 1452 1340 5464 1378 1275 5465 1453 1341 5466 1380 1277 5467 1454 1342 5468 1453 1341 5469 1379 1276 5470 1380 1277 5471 1377 1274 5472 1455 1343 5473 1452 1340 5474 1456 1344 5475 1454 1342 5476 1457 1345 5477 1458 1346 5478 1453 1341 5479 1454 1342 5480 1456 1344 5481 1458 1346 5482 1454 1342 5483 1459 1347 5484 1455 1343 5485 1377 1274 5486 1460 1348 5487 1461 1349 5488 1455 1343 5489 1456 1344 5490 1457 1345 5491 1462 1350 5492 1459 1347 5493 1460 1348 5494 1455 1343 5495 1463 1351 5496 1377 1274 5497 1385 1282 5498 1463 1351 5499 1459 1347 5500 1377 1274 5501 1464 1352 5502 1385 1282 5503 1387 1284 5504 1464 1352 5505 1463 1351 5506 1385 1282 5507 1465 1353 5508 1387 1284 5509 1386 1283 5510 1466 1354 5511 1464 1352 5512 1387 1284 5513 1467 1355 5514 1466 1354 5515 1387 1284 5516 1468 1356 5517 1467 1355 5518 1387 1284 5519 1465 1353 5520 1468 1356 5521 1387 1284 5522 1391 896 5523 1390 896 5524 1469 896 5525 1470 1357 5526 1471 1358 5527 1472 1359 5528 1473 1360 5529 1472 1359 5530 1474 1361 5531 1473 1360 5532 1470 1357 5533 1472 1359 5534 1473 1360 5535 1474 1361 5536 1475 1362 5537 1476 1363 5538 1475 1362 5539 1477 1364 5540 1476 1363 5541 1473 1360 5542 1475 1362 5543 1476 1363 5544 1477 1364 5545 1478 1365 5546 1479 1366 5547 1478 1365 5548 1480 1367 5549 1479 1366 5550 1476 1363 5551 1478 1365 5552 1481 1368 5553 1480 1367 5554 1482 1369 5555 1481 1368 5556 1479 1366 5557 1480 1367 5558 1481 1368 5559 1482 1369 5560 1483 1370 5561 1484 1371 5562 1483 1370 5563 1485 1372 5564 1484 1371 5565 1481 1368 5566 1483 1370 5567 1389 896 5568 1401 896 5569 1390 896 5570 1486 1373 5571 1399 1293 5572 1393 1287 5573 1484 1371 5574 1485 1372 5575 1487 1374 5576 1488 1375 5577 1393 1287 5578 1402 1294 5579 1489 1376 5580 1393 1287 5581 1488 1375 5582 1490 1377 5583 1393 1287 5584 1489 1376 5585 1491 1378 5586 1486 1373 5587 1393 1287 5588 1490 1377 5589 1491 1378 5590 1393 1287 5591 1492 1379 5592 1402 1294 5593 1403 1295 5594 1488 1375 5595 1402 1294 5596 1492 1379 5597 1493 1380 5598 1403 1295 5599 1404 1296 5600 1492 1379 5601 1403 1295 5602 1493 1380 5603 1494 1381 5604 1404 1296 5605 1405 1297 5606 1493 1380 5607 1404 1296 5608 1494 1381 5609 1495 1382 5610 1405 1297 5611 1408 1300 5612 1494 1381 5613 1405 1297 5614 1495 1382 5615 1496 1383 5616 1408 1300 5617 1416 1306 5618 1495 1382 5619 1408 1300 5620 1496 1383 5621 1417 1307 5622 1497 1384 5623 1416 1306 5624 1498 1385 5625 1416 1306 5626 1497 1384 5627 1496 1383 5628 1416 1306 5629 1498 1385 5630 1499 1386 5631 1500 1387 5632 1497 1384 5633 1501 1388 5634 1497 1384 5635 1500 1387 5636 1502 1389 5637 1499 1386 5638 1497 1384 5639 1417 1307 5640 1502 1389 5641 1497 1384 5642 1498 1385 5643 1497 1384 5644 1501 1388 5645 1450 1338 5646 1451 1339 5647 1500 1387 5648 1503 1390 5649 1500 1387 5650 1451 1339 5651 1504 1391 5652 1450 1338 5653 1500 1387 5654 1499 1386 5655 1504 1391 5656 1500 1387 5657 1501 1388 5658 1500 1387 5659 1503 1390 5660 514 443 5661 1451 1339 5662 537 466 5663 1503 1390 5664 1451 1339 5665 514 443 5666 1505 896 5667 1506 896 5668 1507 896 5669 1508 896 5670 1506 896 5671 1505 896 5672 1509 896 5673 1506 896 5674 1508 896 5675 1510 896 5676 1506 896 5677 1509 896 5678 1511 896 5679 1506 896 5680 1510 896 5681 1505 896 5682 1507 896 5683 1512 896 5684 1413 1392 5685 1513 1392 5686 1514 1392 5687 1413 1393 5688 1514 1393 5689 1418 1393 5690 1460 1348 5691 1515 1394 5692 1461 1349 5693 1516 1395 5694 1462 1350 5695 1517 1396 5696 1516 1395 5697 1456 1344 5698 1462 1350 5699 1460 1348 5700 1518 1397 5701 1515 1394 5702 1519 1398 5703 1517 1396 5704 1520 1399 5705 1516 1395 5706 1517 1396 5707 1519 1398 5708 1460 1348 5709 1521 1400 5710 1518 1397 5711 1519 1398 5712 1520 1399 5713 1522 1401 5714 464 393 5715 1521 1400 5716 1460 1348 5717 463 392 5718 1523 1402 5719 1521 1400 5720 1519 1398 5721 1522 1401 5722 1524 1403 5723 464 393 5724 463 392 5725 1521 1400 5726 465 394 5727 1460 1348 5728 1459 1347 5729 465 394 5730 464 393 5731 1460 1348 5732 466 395 5733 1459 1347 5734 1463 1351 5735 466 395 5736 465 394 5737 1459 1347 5738 467 396 5739 1463 1351 5740 1464 1352 5741 467 396 5742 466 395 5743 1463 1351 5744 468 397 5745 1464 1352 5746 1466 1354 5747 468 397 5748 467 396 5749 1464 1352 5750 1525 1404 5751 1526 1404 5752 1527 1404 5753 1528 1405 5754 468 397 5755 1466 1354 5756 1529 308 5757 1528 1405 5758 1466 1354 5759 1525 1404 5760 1530 1404 5761 1526 1404 5762 1531 1406 5763 1532 1407 5764 1533 1408 5765 1470 1357 5766 1533 1408 5767 1471 1358 5768 1470 1357 5769 1531 1406 5770 1533 1408 5771 463 392 5772 1534 1409 5773 1523 1402 5774 1535 1410 5775 1524 1403 5776 1536 1411 5777 1519 1398 5778 1524 1403 5779 1535 1410 5780 463 392 5781 1537 1412 5782 1534 1409 5783 1535 1410 5784 1536 1411 5785 1538 1413 5786 462 391 5787 1539 1414 5788 1537 1412 5789 1535 1410 5790 1538 1413 5791 1540 1415 5792 463 392 5793 462 391 5794 1537 1412 5795 461 390 5796 1541 1416 5797 1539 1414 5798 329 303 5799 1540 1415 5800 1542 1417 5801 462 391 5802 461 390 5803 1539 1414 5804 1535 1410 5805 1540 1415 5806 329 303 5807 460 389 5808 1543 1418 5809 1541 1416 5810 329 303 5811 1542 1417 5812 1544 1419 5813 461 390 5814 460 389 5815 1541 1416 5816 431 360 5817 483 412 5818 1543 1418 5819 329 303 5820 1544 1419 5821 516 445 5822 460 389 5823 431 360 5824 1543 1418 5825 1528 1405 5826 469 398 5827 468 397 5828 1545 1420 5829 470 399 5830 469 398 5831 1546 1421 5832 1545 1420 5833 469 398 5834 1528 1405 5835 1546 1421 5836 469 398 5837 1547 1422 5838 471 400 5839 470 399 5840 1545 1420 5841 1547 1422 5842 470 399 5843 1548 1423 5844 472 401 5845 471 400 5846 1547 1422 5847 1548 1423 5848 471 400 5849 1488 1375 5850 473 402 5851 472 401 5852 1548 1423 5853 1488 1375 5854 472 401 5855 1492 1379 5856 474 403 5857 473 402 5858 1488 1375 5859 1492 1379 5860 473 402 5861 1493 1380 5862 475 404 5863 474 403 5864 1492 1379 5865 1493 1380 5866 474 403 5867 1494 1381 5868 476 405 5869 475 404 5870 1493 1380 5871 1494 1381 5872 475 404 5873 1495 1382 5874 477 406 5875 476 405 5876 1494 1381 5877 1495 1382 5878 476 405 5879 1496 1383 5880 478 407 5881 477 406 5882 1495 1382 5883 1496 1383 5884 477 406 5885 1498 1385 5886 479 408 5887 478 407 5888 1496 1383 5889 1498 1385 5890 478 407 5891 1501 1388 5892 480 409 5893 479 408 5894 1498 1385 5895 1501 1388 5896 479 408 5897 1503 1390 5898 458 387 5899 480 409 5900 1501 1388 5901 1503 1390 5902 480 409 5903 1503 1390 5904 514 443 5905 458 387 5906 1549 1424 5907 1489 1376 5908 1488 1375 5909 1548 1423 5910 1549 1424 5911 1488 1375 5912 1550 308 5913 1551 308 5914 1552 308 5915 1553 308 5916 1551 308 5917 1550 308 5918 1554 896 5919 1555 896 5920 1556 896 5921 1557 896 5922 1555 896 5923 1554 896 5924 1558 308 5925 1553 308 5926 1550 308 5927 1559 896 5928 1555 896 5929 1557 896 5930 1560 896 5931 1556 896 5932 1561 896 5933 1554 896 5934 1556 896 5935 1560 896 5936 1525 1425 5937 1562 1425 5938 1530 1425 5939 1563 1426 5940 1487 1374 5941 1564 1427 5942 1563 1426 5943 1484 1371 5944 1487 1374 5945 1563 1426 5946 1564 1427 5947 1565 1428 5948 1566 1429 5949 1563 1426 5950 1565 1428 5951 1064 983 5952 1065 984 5953 1567 1430 5954 1568 1431 5955 1569 1432 5956 1570 1433 5957 1064 983 5958 1567 1430 5959 1571 1434 5960 1572 1435 5961 1570 1433 5962 1573 1436 5963 1572 1435 5964 1568 1431 5965 1570 1433 5966 1574 1437 5967 1573 1436 5968 1202 1112 5969 1574 1437 5970 1572 1435 5971 1573 1436 5972 1199 1109 5973 1574 1437 5974 1202 1112 5975 3 3 5976 1575 1438 5977 1576 1439 5978 1577 896 5979 1578 896 5980 1579 896 5981 13 13 5982 3 3 5983 1576 1439 5984 1580 1440 5985 10 10 5986 1581 1441 5987 1582 896 5988 1578 896 5989 1577 896 5990 1580 1440 5991 1581 1441 5992 1583 1442 5993 3 3 5994 1584 1443 5995 1575 1438 5996 1577 896 5997 1579 896 5998 1585 896 5999 1586 1444 6000 1587 1445 6001 1584 1443 6002 1588 1446 6003 1589 1446 6004 1590 1446 6005 3 3 6006 1586 1444 6007 1584 1443 6008 1591 1447 6009 1592 1448 6010 1587 1445 6011 1588 1449 6012 1590 1449 6013 1593 1449 6014 1586 1444 6015 1591 1447 6016 1587 1445 6017 1591 1447 6018 1594 1450 6019 1592 1448 6020 1595 1451 6021 1596 1452 6022 1597 1453 6023 1591 1447 6024 1598 1454 6025 1594 1450 6026 1599 1455 6027 1597 1453 6028 1600 1456 6029 1595 1451 6030 1597 1453 6031 1599 1455 6032 1591 1447 6033 1601 1457 6034 1598 1454 6035 1602 1458 6036 1600 1456 6037 1603 1459 6038 1599 1455 6039 1600 1456 6040 1602 1458 6041 1591 1447 6042 1604 1460 6043 1601 1457 6044 1602 1458 6045 1603 1459 6046 1605 1461 6047 1591 1447 6048 872 801 6049 1604 1460 6050 1606 1462 6051 1607 1463 6052 874 803 6053 1602 1458 6054 1605 1461 6055 1608 1464 6056 1609 1465 6057 1608 1464 6058 1605 1461 6059 1591 1447 6060 871 800 6061 872 801 6062 1610 1466 6063 874 803 6064 873 802 6065 1611 1467 6066 1606 1462 6067 874 803 6068 1612 1468 6069 1611 1467 6070 874 803 6071 1613 1469 6072 1612 1468 6073 874 803 6074 1614 1470 6075 1613 1469 6076 874 803 6077 1615 1471 6078 1614 1470 6079 874 803 6080 1616 1472 6081 1615 1471 6082 874 803 6083 1617 1473 6084 1616 1472 6085 874 803 6086 1618 1474 6087 1617 1473 6088 874 803 6089 1610 1466 6090 1618 1474 6091 874 803 6092 1619 1475 6093 1620 1476 6094 765 694 6095 1621 1477 6096 1622 1478 6097 765 694 6098 1619 1475 6099 765 694 6100 1622 1478 6101 768 697 6102 1621 1477 6103 765 694 6104 1623 1479 6105 786 715 6106 1620 1476 6107 1624 24 6108 120 24 6109 1625 24 6110 1626 1480 6111 1623 1479 6112 1620 1476 6113 1627 1481 6114 1626 1480 6115 1620 1476 6116 1628 1482 6117 1627 1481 6118 1620 1476 6119 1619 1475 6120 1628 1482 6121 1620 1476 6122 1624 24 6123 111 24 6124 120 24 6125 1629 24 6126 1625 24 6127 1630 24 6128 1631 1483 6129 788 717 6130 786 715 6131 1632 1484 6132 1631 1483 6133 786 715 6134 1623 1479 6135 1632 1484 6136 786 715 6137 1629 1485 6138 1624 1485 6139 1625 1485 6140 1633 1486 6141 1630 1486 6142 1634 1486 6143 1635 24 6144 1629 24 6145 1630 24 6146 1633 1487 6147 1635 1487 6148 1630 1487 6149 1636 24 6150 1634 24 6151 1637 24 6152 1636 1488 6153 1633 1488 6154 1634 1488 6155 1638 24 6156 1637 24 6157 1639 24 6158 1638 24 6159 1636 24 6160 1637 24 6161 1640 24 6162 1639 24 6163 1641 24 6164 1640 1489 6165 1638 1489 6166 1639 1489 6167 1642 1490 6168 1641 1490 6169 1643 1490 6170 1642 1491 6171 1640 1491 6172 1641 1491 6173 1644 24 6174 1643 24 6175 1645 24 6176 1644 24 6177 1642 24 6178 1643 24 6179 1646 1492 6180 1645 1492 6181 1647 1492 6182 1648 24 6183 1644 24 6184 1645 24 6185 1646 24 6186 1648 24 6187 1645 24 6188 1649 24 6189 1647 24 6190 1650 24 6191 1651 24 6192 1646 24 6193 1647 24 6194 1649 24 6195 1651 24 6196 1647 24 6197 1652 1493 6198 1650 1493 6199 1653 1493 6200 1652 1494 6201 1649 1494 6202 1650 1494 6203 1652 24 6204 1653 24 6205 1654 24 6206 1655 24 6207 1654 24 6208 1656 24 6209 1655 24 6210 1652 24 6211 1654 24 6212 1657 24 6213 1656 24 6214 1658 24 6215 1657 24 6216 1655 24 6217 1656 24 6218 1659 1495 6219 1658 1495 6220 1660 1495 6221 1659 1496 6222 1657 1496 6223 1658 1496 6224 1661 1497 6225 1660 1497 6226 1662 1497 6227 1661 1498 6228 1659 1498 6229 1660 1498 6230 1663 1499 6231 1662 1499 6232 1664 1499 6233 1663 1500 6234 1661 1500 6235 1662 1500 6236 1665 24 6237 1664 24 6238 1666 24 6239 1665 24 6240 1663 24 6241 1664 24 6242 28 1501 6243 1666 1501 6244 22 1501 6245 1667 1502 6246 1665 1502 6247 1666 1502 6248 28 1503 6249 1667 1503 6250 1666 1503 6251 1580 1440 6252 408 337 6253 10 10 6254 1668 896 6255 1669 896 6256 1670 896 6257 1671 1504 6258 1672 1504 6259 1673 1504 6260 1674 1505 6261 1673 1505 6262 1672 1505 6263 1675 896 6264 1670 896 6265 1676 896 6266 1677 896 6267 1668 896 6268 1670 896 6269 1678 896 6270 1677 896 6271 1670 896 6272 1679 896 6273 1678 896 6274 1670 896 6275 1675 896 6276 1679 896 6277 1670 896 6278 1680 1506 6279 1681 1506 6280 1682 1506 6281 1683 896 6282 1675 896 6283 1676 896 6284 1684 896 6285 1683 896 6286 1676 896 6287 1685 896 6288 1684 896 6289 1676 896 6290 1686 896 6291 1685 896 6292 1676 896 6293 1680 1507 6294 1682 1507 6295 1687 1507 6296 1688 1508 6297 1689 1509 6298 1690 1510 6299 1691 1511 6300 1690 1510 6301 1692 1512 6302 1688 1508 6303 1690 1510 6304 1691 1511 6305 1693 1513 6306 1692 1512 6307 1694 1514 6308 1691 1511 6309 1692 1512 6310 1693 1513 6311 1693 1513 6312 1694 1514 6313 1695 1515 6314 1696 1516 6315 1695 1515 6316 1697 1517 6317 1693 1513 6318 1695 1515 6319 1696 1516 6320 1696 1516 6321 1697 1517 6322 1698 1518 6323 1699 1519 6324 1698 1518 6325 1700 1520 6326 1696 1516 6327 1698 1518 6328 1699 1519 6329 1701 1521 6330 1700 1520 6331 1702 1522 6332 1699 1519 6333 1700 1520 6334 1701 1521 6335 1701 1521 6336 1702 1522 6337 1703 1523 6338 1704 1524 6339 1703 1523 6340 1705 1525 6341 1701 1521 6342 1703 1523 6343 1704 1524 6344 1706 1526 6345 1705 1525 6346 1707 1527 6347 1704 1524 6348 1705 1525 6349 1706 1526 6350 1708 1528 6351 1707 1527 6352 1709 1529 6353 1706 1526 6354 1707 1527 6355 1708 1528 6356 1708 1528 6357 1709 1529 6358 1710 1530 6359 1708 1528 6360 1710 1530 6361 1711 1531 6362 1712 896 6363 1713 896 6364 1714 896 6365 1715 1532 6366 1716 1532 6367 1717 1532 6368 1718 896 6369 1712 896 6370 1714 896 6371 1719 896 6372 1718 896 6373 1714 896 6374 1577 896 6375 1719 896 6376 1714 896 6377 1582 896 6378 1577 896 6379 1714 896 6380 1580 1440 6381 1583 1442 6382 1720 1533 6383 1721 1534 6384 1580 1440 6385 1720 1533 6386 1722 1535 6387 1721 1534 6388 1720 1533 6389 1723 1536 6390 1716 1536 6391 1715 1536 6392 1722 1535 6393 1720 1533 6394 1724 1537 6395 1725 896 6396 1726 896 6397 1713 896 6398 1727 1538 6399 1728 1539 6400 1729 1540 6401 1712 896 6402 1725 896 6403 1713 896 6404 1730 896 6405 1731 896 6406 1726 896 6407 1732 1541 6408 1729 1540 6409 1733 1542 6410 1725 896 6411 1730 896 6412 1726 896 6413 1734 1543 6414 1729 1540 6415 1732 1541 6416 1727 1538 6417 1729 1540 6418 1734 1543 6419 1730 896 6420 1735 896 6421 1731 896 6422 1736 1544 6423 1733 1542 6424 1737 1545 6425 1738 1546 6426 1733 1542 6427 1736 1544 6428 1732 1541 6429 1733 1542 6430 1738 1546 6431 1739 1547 6432 1737 1545 6433 1740 1548 6434 1736 1544 6435 1737 1545 6436 1739 1547 6437 1741 1549 6438 1740 1548 6439 1742 1550 6440 1743 1551 6441 1740 1548 6442 1741 1549 6443 1739 1547 6444 1740 1548 6445 1743 1551 6446 1609 1465 6447 1742 1550 6448 1608 1464 6449 1744 1552 6450 1742 1550 6451 1609 1465 6452 1741 1549 6453 1742 1550 6454 1744 1552 6455 1745 1553 6456 1746 1554 6457 1721 1534 6458 1747 1555 6459 1748 1555 6460 1721 1555 6461 1745 1553 6462 1721 1534 6463 1748 1556 6464 1722 1557 6465 1747 1557 6466 1721 1557 6467 1749 1558 6468 1750 1559 6469 1746 1554 6470 1745 1553 6471 1749 1558 6472 1746 1554 6473 1751 1560 6474 1752 1561 6475 1750 1559 6476 1753 1562 6477 1751 1560 6478 1750 1559 6479 1749 1558 6480 1753 1562 6481 1750 1559 6482 1610 1466 6483 873 802 6484 1752 1561 6485 397 308 6486 396 308 6487 1754 308 6488 1755 1563 6489 1610 1466 6490 1752 1561 6491 1756 1564 6492 1755 1563 6493 1752 1561 6494 1757 1565 6495 1756 1564 6496 1752 1561 6497 1751 1560 6498 1757 1565 6499 1752 1561 6500 1758 308 6501 1754 308 6502 1759 308 6503 1760 308 6504 397 308 6505 1754 308 6506 1758 308 6507 1760 308 6508 1754 308 6509 1761 308 6510 1759 308 6511 1762 308 6512 1761 1566 6513 1758 1566 6514 1759 1566 6515 1761 1567 6516 1762 1567 6517 1763 1567 6518 1764 308 6519 1763 308 6520 1765 308 6521 1764 1568 6522 1761 1568 6523 1763 1568 6524 1766 308 6525 1765 308 6526 1767 308 6527 1766 1569 6528 1764 1569 6529 1765 1569 6530 1768 308 6531 1767 308 6532 1769 308 6533 1770 308 6534 1766 308 6535 1767 308 6536 1768 1570 6537 1770 1570 6538 1767 1570 6539 1771 308 6540 1769 308 6541 1772 308 6542 1771 1571 6543 1768 1571 6544 1769 1571 6545 933 862 6546 1773 1572 6547 932 861 6548 1771 308 6549 1772 308 6550 1774 308 6551 933 862 6552 1775 1573 6553 1773 1572 6554 1776 308 6555 1774 308 6556 1777 308 6557 1776 1574 6558 1771 1574 6559 1774 1574 6560 1778 1575 6561 1779 1576 6562 1775 1573 6563 1776 1577 6564 1777 1577 6565 1780 1577 6566 933 862 6567 1778 1575 6568 1775 1573 6569 1778 1575 6570 1781 1578 6571 1779 1576 6572 1782 1579 6573 1780 1579 6574 1783 1579 6575 1782 308 6576 1776 308 6577 1780 308 6578 1784 1580 6579 1785 1581 6580 1781 1578 6581 1782 1582 6582 1783 1582 6583 1786 1582 6584 1778 1575 6585 1784 1580 6586 1781 1578 6587 1784 1580 6588 1787 1583 6589 1785 1581 6590 1788 308 6591 1786 308 6592 1789 308 6593 1788 1584 6594 1782 1584 6595 1786 1584 6596 1790 1585 6597 1791 1586 6598 1787 1583 6599 1792 308 6600 1789 308 6601 1793 308 6602 1784 1580 6603 1790 1585 6604 1787 1583 6605 1792 1587 6606 1788 1587 6607 1789 1587 6608 1790 1585 6609 1794 1588 6610 1791 1586 6611 1792 308 6612 1793 308 6613 1795 308 6614 1796 1589 6615 1797 1590 6616 1794 1588 6617 1798 308 6618 1795 308 6619 1799 308 6620 1790 1585 6621 1796 1589 6622 1794 1588 6623 1798 1591 6624 1792 1591 6625 1795 1591 6626 1796 1589 6627 1800 1592 6628 1797 1590 6629 1798 308 6630 1799 308 6631 1801 308 6632 1802 1593 6633 1803 1594 6634 1800 1592 6635 1804 308 6636 1801 308 6637 1805 308 6638 1796 1589 6639 1802 1593 6640 1800 1592 6641 1804 1595 6642 1798 1595 6643 1801 1595 6644 1806 1596 6645 1807 1597 6646 1803 1594 6647 1804 1598 6648 1805 1598 6649 1808 1598 6650 1809 1599 6651 1806 1596 6652 1803 1594 6653 1802 1593 6654 1809 1599 6655 1803 1594 6656 1810 1600 6657 1811 1601 6658 1807 1597 6659 1812 308 6660 1808 308 6661 1813 308 6662 1806 1596 6663 1810 1600 6664 1807 1597 6665 1812 1602 6666 1804 1602 6667 1808 1602 6668 1814 1603 6669 1815 1604 6670 1811 1601 6671 1812 308 6672 1813 308 6673 1816 308 6674 1810 1600 6675 1814 1603 6676 1811 1601 6677 1817 1605 6678 1818 1606 6679 1815 1604 6680 1819 308 6681 1816 308 6682 1820 308 6683 1814 1603 6684 1817 1605 6685 1815 1604 6686 1819 1607 6687 1812 1607 6688 1816 1607 6689 1821 1608 6690 1822 1609 6691 1818 1606 6692 1823 308 6693 1820 308 6694 1824 308 6695 1817 1605 6696 1821 1608 6697 1818 1606 6698 1823 308 6699 1819 308 6700 1820 308 6701 1825 1610 6702 1826 1611 6703 1822 1609 6704 1823 308 6705 1824 308 6706 1827 308 6707 1821 1608 6708 1825 1610 6709 1822 1609 6710 1828 1612 6711 1829 1613 6712 1826 1611 6713 1830 1614 6714 1827 1614 6715 1831 1614 6716 1825 1610 6717 1828 1612 6718 1826 1611 6719 1830 308 6720 1823 308 6721 1827 308 6722 1832 1615 6723 1833 1616 6724 1829 1613 6725 1834 308 6726 1831 308 6727 1835 308 6728 1828 1612 6729 1832 1615 6730 1829 1613 6731 1834 1617 6732 1830 1617 6733 1831 1617 6734 1836 1618 6735 1837 1619 6736 1833 1616 6737 1838 1620 6738 1835 1620 6739 343 1620 6740 1832 1615 6741 1839 1621 6742 1833 1616 6743 1840 1622 6744 1833 1616 6745 1839 1621 6746 1841 1623 6747 1836 1618 6748 1833 1616 6749 1842 1624 6750 1841 1623 6751 1833 1616 6752 1840 1622 6753 1842 1624 6754 1833 1616 6755 1838 1625 6756 1834 1625 6757 1835 1625 6758 1843 1626 6759 1844 1627 6760 1837 1619 6761 1845 1628 6762 1843 1626 6763 1837 1619 6764 1836 1618 6765 1845 1628 6766 1837 1619 6767 1846 308 6768 343 308 6769 345 308 6770 1846 1629 6771 1838 1629 6772 343 1629 6773 1847 1630 6774 1848 1631 6775 1844 1627 6776 1849 1632 6777 1847 1630 6778 1844 1627 6779 1843 1626 6780 1849 1632 6781 1844 1627 6782 1850 1633 6783 1851 1634 6784 1848 1631 6785 1847 1630 6786 1850 1633 6787 1848 1631 6788 1852 1635 6789 1853 1636 6790 1851 1634 6791 1854 1637 6792 1852 1635 6793 1851 1634 6794 1855 1638 6795 1856 1638 6796 1851 1638 6797 1857 1639 6798 1851 1634 6799 1856 1640 6800 1850 1641 6801 1855 1641 6802 1851 1641 6803 1858 1642 6804 1854 1637 6805 1851 1634 6806 1857 1639 6807 1858 1642 6808 1851 1634 6809 1859 1643 6810 324 298 6811 1853 1636 6812 1852 1635 6813 1859 1643 6814 1853 1636 6815 1859 1643 6816 331 305 6817 324 298 6818 1860 1644 6819 1535 1410 6820 1861 1645 6821 1862 1646 6822 1519 1398 6823 1535 1410 6824 1860 1644 6825 1862 1646 6826 1535 1410 6827 1863 1647 6828 1864 1648 6829 1852 1635 6830 1860 1644 6831 1861 1645 6832 1865 1649 6833 1863 1647 6834 1852 1635 6835 1854 1637 6836 1866 1650 6837 1867 1651 6838 1864 1648 6839 1868 1652 6840 1865 1649 6841 1869 1653 6842 1863 1647 6843 1866 1650 6844 1864 1648 6845 1868 1652 6846 1860 1644 6847 1865 1649 6848 1870 1654 6849 1871 1655 6850 1867 1651 6851 1872 1656 6852 1869 1653 6853 1873 1657 6854 1874 1658 6855 1870 1654 6856 1867 1651 6857 1875 1659 6858 1874 1658 6859 1867 1651 6860 1866 1650 6861 1875 1659 6862 1867 1651 6863 1872 1656 6864 1868 1652 6865 1869 1653 6866 1876 1660 6867 1839 1621 6868 1871 1655 6869 1877 1661 6870 1873 1657 6871 1375 1272 6872 1878 1662 6873 1876 1660 6874 1871 1655 6875 1879 1663 6876 1878 1662 6877 1871 1655 6878 1870 1654 6879 1879 1663 6880 1871 1655 6881 1880 1664 6882 1872 1656 6883 1873 1657 6884 1877 1661 6885 1880 1664 6886 1873 1657 6887 1881 1665 6888 1840 1622 6889 1839 1621 6890 1876 1660 6891 1881 1665 6892 1839 1621 6893 1882 1666 6894 1877 1661 6895 1375 1272 6896 1883 1667 6897 1882 1666 6898 1375 1272 6899 1884 1668 6900 1883 1667 6901 1375 1272 6902 1885 1669 6903 1884 1668 6904 1375 1272 6905 1381 1278 6906 1885 1669 6907 1375 1272 6908 1886 1670 6909 1887 1671 6910 1614 1470 6911 1615 1471 6912 1886 1670 6913 1614 1470 6914 1886 1670 6915 1888 1672 6916 1887 1671 6917 1886 1670 6918 1889 1673 6919 1888 1672 6920 1890 1674 6921 1891 1675 6922 1889 1673 6923 1886 1670 6924 1890 1674 6925 1889 1673 6926 1890 1674 6927 1892 1676 6928 1891 1675 6929 1893 1677 6930 1724 1537 6931 1892 1676 6932 1890 1674 6933 1893 1677 6934 1892 1676 6935 1894 1678 6936 1722 1535 6937 1724 1537 6938 1893 1677 6939 1894 1678 6940 1724 1537 6941 1895 896 6942 1896 896 6943 1897 896 6944 1898 1679 6945 1899 1679 6946 1900 1679 6947 1901 1680 6948 1900 1680 6949 1899 1680 6950 1902 1681 6951 1856 1640 6952 1903 1682 6953 1902 1681 6954 1857 1639 6955 1856 1640 6956 1904 896 6957 1905 896 6958 1896 896 6959 1895 896 6960 1904 896 6961 1896 896 6962 1906 896 6963 1897 896 6964 1907 896 6965 1908 896 6966 1895 896 6967 1897 896 6968 1909 896 6969 1908 896 6970 1897 896 6971 1906 896 6972 1909 896 6973 1897 896 6974 1910 1683 6975 1911 1683 6976 1912 1683 6977 1913 896 6978 1906 896 6979 1907 896 6980 1914 896 6981 1913 896 6982 1907 896 6983 1915 896 6984 1914 896 6985 1907 896 6986 1910 1684 6987 1912 1684 6988 1916 1684 6989 1917 1685 6990 1918 1686 6991 1919 1687 6992 1920 1688 6993 1919 1687 6994 1921 1689 6995 1917 1685 6996 1919 1687 6997 1920 1688 6998 1922 1690 6999 1921 1689 7000 1923 1691 7001 1920 1688 7002 1921 1689 7003 1922 1690 7004 1922 1690 7005 1923 1691 7006 1924 1692 7007 1925 1693 7008 1924 1692 7009 1926 1694 7010 1922 1690 7011 1924 1692 7012 1925 1693 7013 1925 1693 7014 1926 1694 7015 1927 1695 7016 1928 1696 7017 1927 1695 7018 1929 1697 7019 1925 1693 7020 1927 1695 7021 1928 1696 7022 1876 1660 7023 1930 1698 7024 1881 1665 7025 1928 1696 7026 1929 1697 7027 1931 1699 7028 1876 1660 7029 1932 1700 7030 1930 1698 7031 1933 1701 7032 1931 1699 7033 1934 1702 7034 1928 1696 7035 1931 1699 7036 1933 1701 7037 1935 1703 7038 1936 1704 7039 1932 1700 7040 1937 1705 7041 1934 1702 7042 1938 1706 7043 1876 1660 7044 1935 1703 7045 1932 1700 7046 1933 1701 7047 1934 1702 7048 1937 1705 7049 1939 1707 7050 1940 1708 7051 1936 1704 7052 1937 1705 7053 1938 1706 7054 1941 1709 7055 1942 1710 7056 1939 1707 7057 1936 1704 7058 1935 1711 7059 1942 1711 7060 1936 1711 7061 1943 1712 7062 1944 1713 7063 1940 1708 7064 1945 1714 7065 1941 1709 7066 1946 1715 7067 1939 1707 7068 1943 1712 7069 1940 1708 7070 1937 1705 7071 1941 1709 7072 1945 1714 7073 1947 1716 7074 1948 1717 7075 1944 1713 7076 1949 1718 7077 1946 1715 7078 1950 1719 7079 1951 1720 7080 1947 1716 7081 1944 1713 7082 1943 1712 7083 1951 1720 7084 1944 1713 7085 1945 1714 7086 1946 1715 7087 1949 1718 7088 1952 1721 7089 1903 1682 7090 1948 1717 7091 1947 1716 7092 1952 1721 7093 1948 1717 7094 1953 1722 7095 1950 1719 7096 1954 1723 7097 1949 1718 7098 1950 1719 7099 1953 1722 7100 1952 1721 7101 1902 1681 7102 1903 1682 7103 1955 896 7104 1956 896 7105 1957 896 7106 1958 1724 7107 1959 1724 7108 1960 1724 7109 1961 1725 7110 1960 1725 7111 1959 1725 7112 1962 896 7113 1957 896 7114 1963 896 7115 1964 896 7116 1955 896 7117 1957 896 7118 1965 896 7119 1964 896 7120 1957 896 7121 1966 896 7122 1965 896 7123 1957 896 7124 1962 896 7125 1966 896 7126 1957 896 7127 1967 1726 7128 1968 1726 7129 1969 1726 7130 1970 896 7131 1962 896 7132 1963 896 7133 1971 896 7134 1970 896 7135 1963 896 7136 1972 896 7137 1971 896 7138 1963 896 7139 1973 896 7140 1972 896 7141 1963 896 7142 1967 1727 7143 1969 1727 7144 1974 1727 7145 1975 1728 7146 1976 1729 7147 1977 1730 7148 1978 1731 7149 1977 1730 7150 1979 1732 7151 1980 1733 7152 1977 1730 7153 1978 1731 7154 1981 1734 7155 1977 1730 7156 1980 1733 7157 1975 1728 7158 1977 1730 7159 1981 1734 7160 1978 1731 7161 1979 1732 7162 1982 1735 7163 1983 1736 7164 1982 1735 7165 1984 1737 7166 1978 1731 7167 1982 1735 7168 1983 1736 7169 1985 1738 7170 1984 1737 7171 1986 1739 7172 1983 1736 7173 1984 1737 7174 1985 1738 7175 1985 1738 7176 1986 1739 7177 1987 1740 7178 1988 1741 7179 1987 1740 7180 1989 1742 7181 1985 1738 7182 1987 1740 7183 1988 1741 7184 1988 1741 7185 1989 1742 7186 1990 1743 7187 1991 1744 7188 1990 1743 7189 1992 1745 7190 1988 1741 7191 1990 1743 7192 1991 1744 7193 1991 1744 7194 1992 1745 7195 1993 1746 7196 1994 1747 7197 1993 1746 7198 1995 1748 7199 1991 1744 7200 1993 1746 7201 1994 1747 7202 1996 1749 7203 1995 1748 7204 1997 1750 7205 1994 1747 7206 1995 1748 7207 1996 1749 7208 1996 1749 7209 1997 1750 7210 1998 1751 7211 1996 1749 7212 1998 1751 7213 1999 1752 7214 2000 896 7215 2001 896 7216 2002 896 7217 2003 1753 7218 2004 1753 7219 2005 1753 7220 2006 1754 7221 2005 1754 7222 2004 1754 7223 2007 896 7224 2008 896 7225 2001 896 7226 2000 896 7227 2007 896 7228 2001 896 7229 2009 896 7230 2002 896 7231 2010 896 7232 2011 896 7233 2000 896 7234 2002 896 7235 2012 896 7236 2011 896 7237 2002 896 7238 2009 896 7239 2012 896 7240 2002 896 7241 2013 1755 7242 2014 1755 7243 2015 1755 7244 2016 896 7245 2009 896 7246 2010 896 7247 2017 896 7248 2016 896 7249 2010 896 7250 2018 896 7251 2017 896 7252 2010 896 7253 2013 1756 7254 2015 1756 7255 2019 1756 7256 2020 1757 7257 2021 1758 7258 2022 1759 7259 2023 1760 7260 2022 1759 7261 2024 1761 7262 2020 1757 7263 2022 1759 7264 2023 1760 7265 2025 1762 7266 2024 1761 7267 2026 1763 7268 2023 1760 7269 2024 1761 7270 2025 1762 7271 2025 1762 7272 2026 1763 7273 2027 1764 7274 2028 1765 7275 2027 1764 7276 2029 1766 7277 2025 1762 7278 2027 1764 7279 2028 1765 7280 2028 1765 7281 2029 1766 7282 2030 1767 7283 2031 1768 7284 2030 1767 7285 2032 1769 7286 2028 1765 7287 2030 1767 7288 2031 1768 7289 2031 1768 7290 2032 1769 7291 2033 1770 7292 2034 1771 7293 2033 1770 7294 2035 1772 7295 2031 1768 7296 2033 1770 7297 2034 1771 7298 2036 1773 7299 2035 1772 7300 2037 1774 7301 2034 1771 7302 2035 1772 7303 2036 1773 7304 2036 1773 7305 2037 1774 7306 2038 1775 7307 2039 1776 7308 2038 1775 7309 2040 1777 7310 2036 1773 7311 2038 1775 7312 2039 1776 7313 2041 1778 7314 2040 1777 7315 2042 1779 7316 2039 1776 7317 2040 1777 7318 2041 1778 7319 2043 1780 7320 2042 1779 7321 2044 1781 7322 2041 1778 7323 2042 1779 7324 2043 1780 7325 2045 1782 7326 2046 1783 7327 2047 1784 7328 2048 1785 7329 2049 1786 7330 2050 1787 7331 2048 1785 7332 2050 1787 7333 2051 1788 7334 2052 1789 7335 2047 1784 7336 2053 1790 7337 2054 1791 7338 2045 1782 7339 2047 1784 7340 2052 1789 7341 2054 1791 7342 2047 1784 7343 2055 1792 7344 2053 1790 7345 2056 1793 7346 2055 1792 7347 2052 1789 7348 2053 1790 7349 2057 1794 7350 2056 1793 7351 2058 1795 7352 2057 1794 7353 2055 1792 7354 2056 1793 7355 2059 1796 7356 2058 1795 7357 2060 1797 7358 2059 1796 7359 2057 1794 7360 2058 1795 7361 2061 1798 7362 2060 1797 7363 2062 1799 7364 2061 1798 7365 2059 1796 7366 2060 1797 7367 2061 1798 7368 2062 1799 7369 2063 1800 7370 2064 1801 7371 2063 1800 7372 2065 1802 7373 2064 1801 7374 2061 1798 7375 2063 1800 7376 2066 1803 7377 2065 1802 7378 2067 1804 7379 2066 1803 7380 2064 1801 7381 2065 1802 7382 2068 1805 7383 2067 1804 7384 2069 1806 7385 2068 1805 7386 2066 1803 7387 2067 1804 7388 2070 1807 7389 2069 1806 7390 2071 1808 7391 2070 1807 7392 2068 1805 7393 2069 1806 7394 2072 1809 7395 2071 1808 7396 2073 1810 7397 2072 1809 7398 2070 1807 7399 2071 1808 7400 2074 1811 7401 2073 1810 7402 2075 1812 7403 2074 1811 7404 2072 1809 7405 2073 1810 7406 2076 1813 7407 2075 1812 7408 2077 1814 7409 2076 1813 7410 2074 1811 7411 2075 1812 7412 2078 1815 7413 2077 1814 7414 2079 1816 7415 2078 1815 7416 2076 1813 7417 2077 1814 7418 2080 1817 7419 2079 1816 7420 2081 1818 7421 2080 1817 7422 2078 1815 7423 2079 1816 7424 2082 1819 7425 2081 1818 7426 2083 1820 7427 2084 1821 7428 2080 1817 7429 2081 1818 7430 2082 1819 7431 2084 1821 7432 2081 1818 7433 2085 1822 7434 2083 1820 7435 2086 1823 7436 2085 1822 7437 2082 1819 7438 2083 1820 7439 2087 1824 7440 2086 1823 7441 2088 1825 7442 2087 1824 7443 2085 1822 7444 2086 1823 7445 2089 1826 7446 2088 1825 7447 2090 1827 7448 2089 1826 7449 2087 1824 7450 2088 1825 7451 2091 1828 7452 2090 1827 7453 2092 1829 7454 2091 1828 7455 2089 1826 7456 2090 1827 7457 2091 1828 7458 2092 1829 7459 2093 1830 7460 2094 1831 7461 2095 1832 7462 2096 1833 7463 2097 1834 7464 2091 1828 7465 2093 1830 7466 2098 1835 7467 2096 1833 7468 2099 1836 7469 2100 1837 7470 2094 1831 7471 2096 1833 7472 2098 1835 7473 2100 1837 7474 2096 1833 7475 2101 1838 7476 2099 1836 7477 2102 1839 7478 2101 1838 7479 2098 1835 7480 2099 1836 7481 2103 1840 7482 2102 1839 7483 2104 1841 7484 2103 1840 7485 2101 1838 7486 2102 1839 7487 2105 1842 7488 2104 1841 7489 2106 1843 7490 2105 1842 7491 2103 1840 7492 2104 1841 7493 2107 1844 7494 2106 1843 7495 2108 1845 7496 2107 1844 7497 2105 1842 7498 2106 1843 7499 2107 1844 7500 2108 1845 7501 2109 1846 7502 2110 1847 7503 2109 1846 7504 2111 1848 7505 2110 1847 7506 2107 1844 7507 2109 1846 7508 2112 1849 7509 2111 1848 7510 2113 1850 7511 2112 1849 7512 2110 1847 7513 2111 1848 7514 2114 1851 7515 2113 1850 7516 2115 1852 7517 2114 1851 7518 2112 1849 7519 2113 1850 7520 2116 1853 7521 2115 1852 7522 2117 1854 7523 2116 1853 7524 2114 1851 7525 2115 1852 7526 2118 1855 7527 2117 1854 7528 2119 1856 7529 2118 1855 7530 2116 1853 7531 2117 1854 7532 2120 1857 7533 2119 1856 7534 2121 1858 7535 2120 1857 7536 2118 1855 7537 2119 1856 7538 2122 1859 7539 2121 1858 7540 2123 1860 7541 2122 1859 7542 2120 1857 7543 2121 1858 7544 2124 1861 7545 2123 1860 7546 2125 1862 7547 2124 1861 7548 2122 1859 7549 2123 1860 7550 2126 1863 7551 2125 1862 7552 2127 1864 7553 2126 1863 7554 2124 1861 7555 2125 1862 7556 2128 1865 7557 2127 1864 7558 2129 1866 7559 2130 1867 7560 2126 1863 7561 2127 1864 7562 2128 1865 7563 2130 1867 7564 2127 1864 7565 2131 1868 7566 2129 1866 7567 2132 1869 7568 2131 1868 7569 2128 1865 7570 2129 1866 7571 2133 1870 7572 2132 1869 7573 2134 1871 7574 2133 1870 7575 2131 1868 7576 2132 1869 7577 2135 1872 7578 2134 1871 7579 2136 1873 7580 2135 1872 7581 2133 1870 7582 2134 1871 7583 2048 1785 7584 2136 1873 7585 2049 1786 7586 2048 1785 7587 2135 1872 7588 2136 1873 7589 2137 1874 7590 2138 1874 7591 2139 1874 7592 2140 1404 7593 2141 1404 7594 2138 1404 7595 2140 1404 7596 2138 1404 7597 2137 1404 7598 2137 1404 7599 2139 1404 7600 2142 1404 7601 2137 1404 7602 2142 1404 7603 2143 1404 7604 2144 1404 7605 2143 1404 7606 2145 1404 7607 2144 1875 7608 2137 1875 7609 2143 1875 7610 2146 1404 7611 2145 1404 7612 2147 1404 7613 2146 1404 7614 2144 1404 7615 2145 1404 7616 2148 1404 7617 2147 1404 7618 2149 1404 7619 2150 1404 7620 2146 1404 7621 2147 1404 7622 2148 1876 7623 2150 1876 7624 2147 1876 7625 2151 1404 7626 2149 1404 7627 2152 1404 7628 2151 1877 7629 2148 1877 7630 2149 1877 7631 2153 1878 7632 2152 1878 7633 2154 1878 7634 2155 1404 7635 2151 1404 7636 2152 1404 7637 2153 1404 7638 2155 1404 7639 2152 1404 7640 2156 1879 7641 2154 1879 7642 2157 1879 7643 2156 1404 7644 2153 1404 7645 2154 1404 7646 2158 1404 7647 2157 1404 7648 2159 1404 7649 2158 1880 7650 2156 1880 7651 2157 1880 7652 2160 1404 7653 2159 1404 7654 2161 1404 7655 2160 1881 7656 2158 1881 7657 2159 1881 7658 2162 1404 7659 2161 1404 7660 2163 1404 7661 2162 1404 7662 2160 1404 7663 2161 1404 7664 2164 1404 7665 2163 1404 7666 2165 1404 7667 2164 1882 7668 2162 1882 7669 2163 1882 7670 2166 1404 7671 2165 1404 7672 2167 1404 7673 2166 1883 7674 2164 1883 7675 2165 1883 7676 2166 1404 7677 2167 1404 7678 2168 1404 7679 2169 1884 7680 2168 1884 7681 2170 1884 7682 2169 1404 7683 2166 1404 7684 2168 1404 7685 2169 1885 7686 2170 1885 7687 2171 1885 7688 2169 1404 7689 2171 1404 7690 2172 1404 7691 2173 1404 7692 2172 1404 7693 2174 1404 7694 2173 1886 7695 2169 1886 7696 2172 1886 7697 2175 1887 7698 2174 1887 7699 2176 1887 7700 2175 1404 7701 2173 1404 7702 2174 1404 7703 2175 1404 7704 2176 1404 7705 2177 1404 7706 2178 1404 7707 2177 1404 7708 2179 1404 7709 2178 1404 7710 2175 1404 7711 2177 1404 7712 2180 1888 7713 2179 1888 7714 2181 1888 7715 2180 1404 7716 2178 1404 7717 2179 1404 7718 2180 1404 7719 2181 1404 7720 2182 1404 7721 2180 1404 7722 2182 1404 7723 2183 1404 7724 2184 1404 7725 2183 1404 7726 2185 1404 7727 2184 1889 7728 2180 1889 7729 2183 1889 7730 2186 1404 7731 2185 1404 7732 2187 1404 7733 2186 1404 7734 2184 1404 7735 2185 1404 7736 2188 1404 7737 2187 1404 7738 2189 1404 7739 2190 1404 7740 2186 1404 7741 2187 1404 7742 2188 1890 7743 2190 1890 7744 2187 1890 7745 2191 1404 7746 2189 1404 7747 2192 1404 7748 2191 1891 7749 2188 1891 7750 2189 1891 7751 2193 1892 7752 2192 1892 7753 2194 1892 7754 2195 1404 7755 2191 1404 7756 2192 1404 7757 2193 1404 7758 2195 1404 7759 2192 1404 7760 2196 1893 7761 2194 1893 7762 2197 1893 7763 2196 1404 7764 2193 1404 7765 2194 1404 7766 2198 1404 7767 2197 1404 7768 2199 1404 7769 2198 1894 7770 2196 1894 7771 2197 1894 7772 2200 1404 7773 2199 1404 7774 2201 1404 7775 2200 1895 7776 2198 1895 7777 2199 1895 7778 2202 1404 7779 2201 1404 7780 2203 1404 7781 2202 1404 7782 2200 1404 7783 2201 1404 7784 2204 1404 7785 2203 1404 7786 2205 1404 7787 2204 1896 7788 2202 1896 7789 2203 1896 7790 2206 1404 7791 2205 1404 7792 2207 1404 7793 2206 1897 7794 2204 1897 7795 2205 1897 7796 2206 1404 7797 2207 1404 7798 2208 1404 7799 2209 1898 7800 2208 1898 7801 2210 1898 7802 2209 1404 7803 2206 1404 7804 2208 1404 7805 2209 1899 7806 2210 1899 7807 2211 1899 7808 2209 1404 7809 2211 1404 7810 2212 1404 7811 2213 1404 7812 2212 1404 7813 2214 1404 7814 2213 1900 7815 2209 1900 7816 2212 1900 7817 2215 1901 7818 2214 1901 7819 2216 1901 7820 2215 1404 7821 2213 1404 7822 2214 1404 7823 2215 1404 7824 2216 1404 7825 2141 1404 7826 2140 1404 7827 2215 1404 7828 2141 1404 7829 2217 1404 7830 2218 1404 7831 2219 1404 7832 2220 1902 7833 2221 1903 7834 2222 1904 7835 2223 1905 7836 2224 1906 7837 2225 1907 7838 2223 1905 7839 2225 1907 7840 2226 1908 7841 2227 1404 7842 2228 1404 7843 2218 1404 7844 2229 1909 7845 2222 1904 7846 2230 1910 7847 2217 1911 7848 2227 1911 7849 2218 1911 7850 2231 1912 7851 2220 1902 7852 2222 1904 7853 2229 1909 7854 2231 1912 7855 2222 1904 7856 2232 1913 7857 2137 1913 7858 2228 1913 7859 2233 1914 7860 2230 1910 7861 2234 1915 7862 2227 1916 7863 2232 1916 7864 2228 1916 7865 2233 1914 7866 2229 1909 7867 2230 1910 7868 2235 1917 7869 2234 1915 7870 2236 1918 7871 2232 1404 7872 2140 1404 7873 2137 1404 7874 2235 1917 7875 2233 1914 7876 2234 1915 7877 2235 1917 7878 2236 1918 7879 2237 1919 7880 2238 1920 7881 2237 1919 7882 2239 1921 7883 2238 1920 7884 2235 1917 7885 2237 1919 7886 2238 1920 7887 2239 1921 7888 2240 1922 7889 2241 1923 7890 2240 1922 7891 2242 1924 7892 2241 1923 7893 2238 1920 7894 2240 1922 7895 2241 1923 7896 2242 1924 7897 2243 1925 7898 2244 1926 7899 2243 1925 7900 2245 1927 7901 2244 1926 7902 2241 1923 7903 2243 1925 7904 2246 1928 7905 2245 1927 7906 2247 1929 7907 2246 1928 7908 2244 1926 7909 2245 1927 7910 2248 1930 7911 2247 1929 7912 2249 1931 7913 2248 1930 7914 2246 1928 7915 2247 1929 7916 2250 1932 7917 2249 1931 7918 2251 1933 7919 2250 1932 7920 2248 1930 7921 2249 1931 7922 2252 1934 7923 2251 1933 7924 2253 1935 7925 2252 1934 7926 2250 1932 7927 2251 1933 7928 2254 1936 7929 2253 1935 7930 2255 1937 7931 2254 1936 7932 2252 1934 7933 2253 1935 7934 2256 1938 7935 2255 1937 7936 2257 1939 7937 2256 1938 7938 2254 1936 7939 2255 1937 7940 2258 1940 7941 2257 1939 7942 2259 1941 7943 2258 1940 7944 2256 1938 7945 2257 1939 7946 2260 1942 7947 2259 1941 7948 2261 1943 7949 2260 1942 7950 2258 1940 7951 2259 1941 7952 2262 1944 7953 2261 1943 7954 2263 1945 7955 2262 1944 7956 2260 1942 7957 2261 1943 7958 2264 1946 7959 2263 1945 7960 2265 1947 7961 2264 1946 7962 2262 1944 7963 2263 1945 7964 2180 1404 7965 2266 1404 7966 2178 1404 7967 2267 1948 7968 2265 1947 7969 2268 1949 7970 2267 1948 7971 2264 1946 7972 2265 1947 7973 2269 1404 7974 2270 1404 7975 2266 1404 7976 2271 1950 7977 2268 1949 7978 2272 1951 7979 2180 1952 7980 2269 1952 7981 2266 1952 7982 2271 1950 7983 2267 1948 7984 2268 1949 7985 2273 1404 7986 2274 1404 7987 2270 1404 7988 2275 1953 7989 2272 1951 7990 2276 1954 7991 2269 1955 7992 2273 1955 7993 2270 1955 7994 2275 1953 7995 2271 1950 7996 2272 1951 7997 2273 1956 7998 2277 1956 7999 2274 1956 8000 2275 1953 8001 2276 1954 8002 2278 1957 8003 2279 1958 8004 2280 1959 8005 2281 1960 8006 2282 1961 8007 2275 1953 8008 2278 1957 8009 2283 1962 8010 2281 1960 8011 2284 1963 8012 2285 1964 8013 2279 1958 8014 2281 1960 8015 2283 1962 8016 2285 1964 8017 2281 1960 8018 2286 1965 8019 2284 1963 8020 2287 1966 8021 2286 1965 8022 2283 1962 8023 2284 1963 8024 2288 1967 8025 2287 1966 8026 2289 1968 8027 2288 1967 8028 2286 1965 8029 2287 1966 8030 2288 1967 8031 2289 1968 8032 2290 1969 8033 2291 1970 8034 2290 1969 8035 2292 1971 8036 2291 1970 8037 2288 1967 8038 2290 1969 8039 2291 1970 8040 2292 1971 8041 2293 1972 8042 2294 1973 8043 2293 1972 8044 2295 1974 8045 2294 1973 8046 2291 1970 8047 2293 1972 8048 2294 1973 8049 2295 1974 8050 2296 1975 8051 2297 1976 8052 2296 1975 8053 2298 1977 8054 2297 1976 8055 2294 1973 8056 2296 1975 8057 2299 1978 8058 2298 1977 8059 2300 1979 8060 2299 1978 8061 2297 1976 8062 2298 1977 8063 2301 1980 8064 2300 1979 8065 2302 1981 8066 2301 1980 8067 2299 1978 8068 2300 1979 8069 2303 1982 8070 2302 1981 8071 2304 1983 8072 2303 1982 8073 2301 1980 8074 2302 1981 8075 2305 1984 8076 2304 1983 8077 2306 1985 8078 2305 1984 8079 2303 1982 8080 2304 1983 8081 2307 1986 8082 2306 1985 8083 2308 1987 8084 2307 1986 8085 2305 1984 8086 2306 1985 8087 2309 1988 8088 2308 1987 8089 2310 1989 8090 2309 1988 8091 2307 1986 8092 2308 1987 8093 2311 1990 8094 2310 1989 8095 2312 1991 8096 2311 1990 8097 2309 1988 8098 2310 1989 8099 2313 1992 8100 2312 1991 8101 2314 1993 8102 2313 1992 8103 2311 1990 8104 2312 1991 8105 2315 1994 8106 2314 1993 8107 2316 1995 8108 2315 1994 8109 2313 1992 8110 2314 1993 8111 2317 1996 8112 2316 1995 8113 2318 1997 8114 2317 1996 8115 2315 1994 8116 2316 1995 8117 2319 1998 8118 2318 1997 8119 2320 1999 8120 2319 1998 8121 2317 1996 8122 2318 1997 8123 2321 2000 8124 2320 1999 8125 2322 2001 8126 2321 2000 8127 2319 1998 8128 2320 1999 8129 2223 1905 8130 2322 2001 8131 2224 1906 8132 2223 1905 8133 2321 2000 8134 2322 2001 8135 2323 308 8136 2324 308 8137 2325 308 8138 2326 308 8139 2325 308 8140 2327 308 8141 2323 2002 8142 2325 2002 8143 2326 2002 8144 2328 308 8145 2327 308 8146 2329 308 8147 2326 308 8148 2327 308 8149 2328 308 8150 2330 308 8151 2329 308 8152 2331 308 8153 2328 2003 8154 2329 2003 8155 2330 2003 8156 2330 308 8157 2331 308 8158 2332 308 8159 2333 2004 8160 2332 2004 8161 2334 2004 8162 2330 2005 8163 2332 2005 8164 2335 2005 8165 2333 2006 8166 2335 2006 8167 2332 2006 8168 2336 2007 8169 2334 2007 8170 2337 2007 8171 2338 308 8172 2333 308 8173 2334 308 8174 2339 2008 8175 2338 2008 8176 2334 2008 8177 2336 2009 8178 2339 2009 8179 2334 2009 8180 2340 308 8181 2337 308 8182 2341 308 8183 2342 308 8184 2336 308 8185 2337 308 8186 2340 2010 8187 2342 2010 8188 2337 2010 8189 2343 308 8190 2341 308 8191 2344 308 8192 2345 2011 8193 2340 2011 8194 2341 2011 8195 2343 308 8196 2345 308 8197 2341 308 8198 2346 2012 8199 2344 2012 8200 2347 2012 8201 2346 308 8202 2343 308 8203 2344 308 8204 2348 308 8205 2347 308 8206 2349 308 8207 2348 2013 8208 2346 2013 8209 2347 2013 8210 2350 308 8211 2349 308 8212 2351 308 8213 2352 2014 8214 2348 2014 8215 2349 2014 8216 2350 2015 8217 2352 2015 8218 2349 2015 8219 2353 308 8220 2351 308 8221 2354 308 8222 2353 2016 8223 2350 2016 8224 2351 2016 8225 2355 308 8226 2354 308 8227 2356 308 8228 2355 2017 8229 2353 2017 8230 2354 2017 8231 2357 308 8232 2356 308 8233 2358 308 8234 2357 308 8235 2355 308 8236 2356 308 8237 2359 308 8238 2358 308 8239 2360 308 8240 2361 308 8241 2357 308 8242 2358 308 8243 2359 308 8244 2361 308 8245 2358 308 8246 2362 308 8247 2360 308 8248 2363 308 8249 2364 2018 8250 2360 2018 8251 2362 2018 8252 2365 308 8253 2359 308 8254 2360 308 8255 2366 308 8256 2365 308 8257 2360 308 8258 2367 308 8259 2366 308 8260 2360 308 8261 2364 308 8262 2367 308 8263 2360 308 8264 2368 2019 8265 2363 2019 8266 2369 2019 8267 2370 308 8268 2363 308 8269 2368 308 8270 2362 2020 8271 2363 2020 8272 2370 2020 8273 2371 308 8274 2369 308 8275 2372 308 8276 2368 308 8277 2369 308 8278 2371 308 8279 2373 2021 8280 2372 2021 8281 2374 2021 8282 2371 308 8283 2372 308 8284 2373 308 8285 2373 308 8286 2374 308 8287 2375 308 8288 2364 2022 8289 2362 2022 8290 2376 2022 8291 2377 2023 8292 2376 2023 8293 2378 2023 8294 2379 308 8295 2364 308 8296 2376 308 8297 2380 2024 8298 2379 2024 8299 2376 2024 8300 2377 2025 8301 2380 2025 8302 2376 2025 8303 2381 308 8304 2378 308 8305 2382 308 8306 2383 308 8307 2377 308 8308 2378 308 8309 2381 2026 8310 2383 2026 8311 2378 2026 8312 2384 308 8313 2382 308 8314 2385 308 8315 2386 2027 8316 2381 2027 8317 2382 2027 8318 2384 308 8319 2386 308 8320 2382 308 8321 2387 2028 8322 2385 2028 8323 2388 2028 8324 2387 308 8325 2384 308 8326 2385 308 8327 2389 308 8328 2388 308 8329 2390 308 8330 2389 2029 8331 2387 2029 8332 2388 2029 8333 2391 308 8334 2390 308 8335 2392 308 8336 2393 2030 8337 2389 2030 8338 2390 2030 8339 2391 2031 8340 2393 2031 8341 2390 2031 8342 2394 308 8343 2392 308 8344 2395 308 8345 2394 2032 8346 2391 2032 8347 2392 2032 8348 2396 308 8349 2395 308 8350 2397 308 8351 2396 2033 8352 2394 2033 8353 2395 2033 8354 2398 308 8355 2397 308 8356 2399 308 8357 2398 308 8358 2396 308 8359 2397 308 8360 2400 308 8361 2399 308 8362 2335 308 8363 2401 308 8364 2398 308 8365 2399 308 8366 2400 308 8367 2401 308 8368 2399 308 8369 2402 308 8370 2335 308 8371 2333 308 8372 2403 308 8373 2400 308 8374 2335 308 8375 2404 308 8376 2403 308 8377 2335 308 8378 2402 308 8379 2404 308 8380 2335 308 8381 2405 2034 8382 2406 2035 8383 2407 2036 8384 2408 2037 8385 2409 2038 8386 2410 2039 8387 2408 2037 8388 2410 2039 8389 2411 2040 8390 2412 2041 8391 2407 2036 8392 2413 2042 8393 2414 2043 8394 2405 2034 8395 2407 2036 8396 2412 2041 8397 2414 2043 8398 2407 2036 8399 2415 2044 8400 2413 2042 8401 2416 2045 8402 2417 2046 8403 2412 2041 8404 2413 2042 8405 2415 2044 8406 2417 2046 8407 2413 2042 8408 2418 2047 8409 2416 2045 8410 2419 2048 8411 2418 2047 8412 2415 2044 8413 2416 2045 8414 2420 2049 8415 2419 2048 8416 2421 2050 8417 2420 2049 8418 2418 2047 8419 2419 2048 8420 2422 2051 8421 2421 2050 8422 2423 2052 8423 2422 2051 8424 2420 2049 8425 2421 2050 8426 2424 2053 8427 2423 2052 8428 2425 2054 8429 2424 2053 8430 2422 2051 8431 2423 2052 8432 2426 2055 8433 2425 2054 8434 2427 2056 8435 2426 2055 8436 2424 2053 8437 2425 2054 8438 2428 2057 8439 2427 2056 8440 2429 2058 8441 2428 2057 8442 2426 2055 8443 2427 2056 8444 2430 2059 8445 2429 2058 8446 2431 2060 8447 2430 2059 8448 2428 2057 8449 2429 2058 8450 2432 2061 8451 2431 2060 8452 2433 2062 8453 2432 2061 8454 2430 2059 8455 2431 2060 8456 2434 2063 8457 2433 2062 8458 2435 2064 8459 2434 2063 8460 2432 2061 8461 2433 2062 8462 2436 2065 8463 2435 2064 8464 2437 2066 8465 2436 2065 8466 2434 2063 8467 2435 2064 8468 2438 2067 8469 2437 2066 8470 2439 2068 8471 2438 2067 8472 2436 2065 8473 2437 2066 8474 2440 2069 8475 2439 2068 8476 2441 2070 8477 2440 2069 8478 2438 2067 8479 2439 2068 8480 2442 2071 8481 2441 2070 8482 2443 2072 8483 2442 2071 8484 2440 2069 8485 2441 2070 8486 2444 2073 8487 2443 2072 8488 2445 2074 8489 2444 2073 8490 2442 2071 8491 2443 2072 8492 2444 2073 8493 2445 2074 8494 2446 2075 8495 2447 2076 8496 2446 2075 8497 2448 2077 8498 2447 2076 8499 2444 2073 8500 2446 2075 8501 2447 2076 8502 2448 2077 8503 2449 2078 8504 2450 2079 8505 2451 2080 8506 2452 2081 8507 2453 2082 8508 2447 2076 8509 2449 2078 8510 2454 2083 8511 2452 2081 8512 2455 2084 8513 2456 2085 8514 2450 2079 8515 2452 2081 8516 2454 2083 8517 2456 2085 8518 2452 2081 8519 2457 2086 8520 2455 2084 8521 2458 2087 8522 2459 2088 8523 2454 2083 8524 2455 2084 8525 2457 2086 8526 2459 2088 8527 2455 2084 8528 2460 2089 8529 2458 2087 8530 2461 2090 8531 2460 2089 8532 2457 2086 8533 2458 2087 8534 2462 2091 8535 2461 2090 8536 2463 2092 8537 2462 2091 8538 2460 2089 8539 2461 2090 8540 2464 2093 8541 2463 2092 8542 2465 2094 8543 2464 2093 8544 2462 2091 8545 2463 2092 8546 2466 2095 8547 2465 2094 8548 2467 2096 8549 2466 2095 8550 2464 2093 8551 2465 2094 8552 2468 2097 8553 2467 2096 8554 2469 2098 8555 2468 2097 8556 2466 2095 8557 2467 2096 8558 2470 2099 8559 2469 2098 8560 2471 2100 8561 2470 2099 8562 2468 2097 8563 2469 2098 8564 2472 2101 8565 2471 2100 8566 2473 2102 8567 2472 2101 8568 2470 2099 8569 2471 2100 8570 2474 2103 8571 2473 2102 8572 2475 2104 8573 2474 2103 8574 2472 2101 8575 2473 2102 8576 2476 2105 8577 2475 2104 8578 2477 2106 8579 2476 2105 8580 2474 2103 8581 2475 2104 8582 2478 2107 8583 2477 2106 8584 2479 2108 8585 2478 2107 8586 2476 2105 8587 2477 2106 8588 2480 2109 8589 2479 2108 8590 2481 2110 8591 2480 2109 8592 2478 2107 8593 2479 2108 8594 2482 2111 8595 2481 2110 8596 2483 2112 8597 2482 2111 8598 2480 2109 8599 2481 2110 8600 2484 2113 8601 2483 2112 8602 2485 2114 8603 2484 2113 8604 2482 2111 8605 2483 2112 8606 2486 2115 8607 2485 2114 8608 2487 2116 8609 2486 2115 8610 2484 2113 8611 2485 2114 8612 2486 2115 8613 2487 2116 8614 2488 2117 8615 2408 2037 8616 2488 2117 8617 2409 2038 8618 2408 2037 8619 2486 2115 8620 2488 2117 8621 2489 2118 8622 2490 2118 8623 2491 2118 8624 2489 308 8625 2491 308 8626 2492 308 8627 2489 308 8628 2492 308 8629 2493 308 8630 2494 308 8631 2493 308 8632 2495 308 8633 2489 308 8634 2493 308 8635 2494 308 8636 2496 2119 8637 2495 2119 8638 2497 2119 8639 2494 2120 8640 2495 2120 8641 2496 2120 8642 2498 308 8643 2497 308 8644 2499 308 8645 2496 2121 8646 2497 2121 8647 2498 2121 8648 2500 308 8649 2499 308 8650 2501 308 8651 2498 308 8652 2499 308 8653 2500 308 8654 2502 308 8655 2501 308 8656 2503 308 8657 2500 2122 8658 2501 2122 8659 2502 2122 8660 2504 308 8661 2503 308 8662 2505 308 8663 2502 2123 8664 2503 2123 8665 2504 2123 8666 2506 308 8667 2505 308 8668 2507 308 8669 2504 2124 8670 2505 2124 8671 2506 2124 8672 2508 2125 8673 2507 2125 8674 2509 2125 8675 2506 2126 8676 2507 2126 8677 2508 2126 8678 2510 2127 8679 2509 2127 8680 2511 2127 8681 2508 2128 8682 2509 2128 8683 2510 2128 8684 2512 308 8685 2511 308 8686 2513 308 8687 2510 2129 8688 2511 2129 8689 2512 2129 8690 2514 308 8691 2513 308 8692 2515 308 8693 2512 2130 8694 2513 2130 8695 2514 2130 8696 2516 2131 8697 2515 2131 8698 2517 2131 8699 2514 2132 8700 2515 2132 8701 2516 2132 8702 2518 308 8703 2517 308 8704 2519 308 8705 2516 2133 8706 2517 2133 8707 2518 2133 8708 2520 2134 8709 2519 2134 8710 2521 2134 8711 2518 308 8712 2519 308 8713 2520 308 8714 2522 2135 8715 2521 2135 8716 2523 2135 8717 2520 2136 8718 2521 2136 8719 2522 2136 8720 2524 2137 8721 2523 2137 8722 2525 2137 8723 2522 308 8724 2523 308 8725 2524 308 8726 2526 308 8727 2525 308 8728 2527 308 8729 2528 308 8730 2525 308 8731 2526 308 8732 2524 308 8733 2525 308 8734 2528 308 8735 2529 896 8736 2530 896 8737 2531 896 8738 2532 2138 8739 2533 2138 8740 2534 2138 8741 2535 2139 8742 2534 2139 8743 2533 2139 8744 2529 896 8745 2531 896 8746 2536 896 8747 2537 2140 8748 2538 2140 8749 2539 2140 8750 2540 896 8751 2529 896 8752 2536 896 8753 2541 896 8754 2540 896 8755 2536 896 8756 2537 2141 8757 2539 2141 8758 2542 2141 8759 2543 2142 8760 2544 2143 8761 2545 2144 8762 2546 2145 8763 2545 2144 8764 2547 2146 8765 2543 2142 8766 2545 2144 8767 2546 2145 8768 2548 2147 8769 2547 2146 8770 2549 2148 8771 2546 2145 8772 2547 2146 8773 2548 2147 8774 2548 2147 8775 2549 2148 8776 2550 2149 8777 2551 2150 8778 2550 2149 8779 2552 2151 8780 2548 2147 8781 2550 2149 8782 2551 2150 8783 2551 2150 8784 2552 2151 8785 2553 2152 8786 2554 2153 8787 2553 2152 8788 2555 2154 8789 2551 2150 8790 2553 2152 8791 2554 2153 8792 2554 2153 8793 2555 2154 8794 2556 2155 8795 2557 2156 8796 2556 2155 8797 2558 2157 8798 2554 2153 8799 2556 2155 8800 2557 2156 8801 2557 2156 8802 2558 2157 8803 2559 2158 8804 2560 2159 8805 2559 2158 8806 2561 2160 8807 2557 2156 8808 2559 2158 8809 2560 2159 8810 2562 2161 8811 2561 2160 8812 2563 2162 8813 2560 2159 8814 2561 2160 8815 2562 2161 8816 2564 2163 8817 2563 2162 8818 2565 2164 8819 2562 2161 8820 2563 2162 8821 2564 2163 8822 2564 2163 8823 2565 2164 8824 2566 2165 8825 2564 2163 8826 2566 2165 8827 2567 2166 8828 2541 896 8829 2568 896 8830 2540 896 8831 2541 896 8832 2569 896 8833 2568 896 8834 2541 896 8835 2570 896 8836 2569 896 8837 2571 896 8838 2572 896 8839 2570 896 8840 2541 896 8841 2571 896 8842 2570 896 8843 2573 896 8844 2574 896 8845 2572 896 8846 2571 896 8847 2573 896 8848 2572 896 8849 2575 896 8850 2576 896 8851 1905 896 8852 1904 896 8853 2575 896 8854 1905 896 8855 2577 896 8856 2578 896 8857 1972 896 8858 1973 896 8859 2577 896 8860 1972 896 8861 2579 896 8862 2580 896 8863 2008 896 8864 2007 896 8865 2579 896 8866 2008 896 8867 2581 2167 8868 2582 2168 8869 2583 2169 8870 2584 2170 8871 2585 2171 8872 2586 2172 8873 2584 2170 8874 2586 2172 8875 2587 2173 8876 2588 2174 8877 2583 2169 8878 2589 2175 8879 2590 2176 8880 2581 2167 8881 2583 2169 8882 2588 2174 8883 2590 2176 8884 2583 2169 8885 2591 2177 8886 2589 2175 8887 2592 2178 8888 2591 2177 8889 2588 2174 8890 2589 2175 8891 2593 2179 8892 2592 2178 8893 2594 2180 8894 2593 2179 8895 2591 2177 8896 2592 2178 8897 2595 2181 8898 2594 2180 8899 2596 2182 8900 2595 2181 8901 2593 2179 8902 2594 2180 8903 2597 2183 8904 2596 2182 8905 2598 2184 8906 2597 2183 8907 2595 2181 8908 2596 2182 8909 2597 2183 8910 2598 2184 8911 2599 2185 8912 2600 2186 8913 2599 2185 8914 2601 2187 8915 2600 2186 8916 2597 2183 8917 2599 2185 8918 2602 2188 8919 2601 2187 8920 2603 2189 8921 2602 2188 8922 2600 2186 8923 2601 2187 8924 2604 2190 8925 2603 2189 8926 2605 2191 8927 2604 2190 8928 2602 2188 8929 2603 2189 8930 2606 2192 8931 2605 2191 8932 2607 2193 8933 2606 2192 8934 2604 2190 8935 2605 2191 8936 2608 2194 8937 2607 2193 8938 2609 2195 8939 2608 2194 8940 2606 2192 8941 2607 2193 8942 2610 2196 8943 2609 2195 8944 2611 2197 8945 2610 2196 8946 2608 2194 8947 2609 2195 8948 2612 2198 8949 2611 2197 8950 2613 2199 8951 2612 2198 8952 2610 2196 8953 2611 2197 8954 2614 2200 8955 2613 2199 8956 2615 2201 8957 2614 2200 8958 2612 2198 8959 2613 2199 8960 2616 2202 8961 2615 2201 8962 2617 2203 8963 2616 2202 8964 2614 2200 8965 2615 2201 8966 2618 2204 8967 2617 2203 8968 2619 2205 8969 2620 2206 8970 2616 2202 8971 2617 2203 8972 2618 2204 8973 2620 2206 8974 2617 2203 8975 2621 2207 8976 2619 2205 8977 2622 2208 8978 2621 2207 8979 2618 2204 8980 2619 2205 8981 2623 2209 8982 2622 2208 8983 2624 2210 8984 2623 2209 8985 2621 2207 8986 2622 2208 8987 2625 2211 8988 2624 2210 8989 2626 2212 8990 2625 2211 8991 2623 2209 8992 2624 2210 8993 2627 2213 8994 2626 2212 8995 2628 2214 8996 2627 2213 8997 2625 2211 8998 2626 2212 8999 2627 2213 9000 2628 2214 9001 2629 2215 9002 2630 2216 9003 2631 2217 9004 2632 2218 9005 2633 2219 9006 2627 2213 9007 2629 2215 9008 2634 2220 9009 2632 2218 9010 2635 2221 9011 2636 2222 9012 2630 2216 9013 2632 2218 9014 2634 2220 9015 2636 2222 9016 2632 2218 9017 2637 2223 9018 2635 2221 9019 2638 2224 9020 2637 2223 9021 2634 2220 9022 2635 2221 9023 2639 2225 9024 2638 2224 9025 2640 2226 9026 2639 2225 9027 2637 2223 9028 2638 2224 9029 2641 2227 9030 2640 2226 9031 2642 2228 9032 2641 2227 9033 2639 2225 9034 2640 2226 9035 2643 2229 9036 2642 2228 9037 2644 2230 9038 2643 2229 9039 2641 2227 9040 2642 2228 9041 2643 2229 9042 2644 2230 9043 2645 2231 9044 2646 2232 9045 2645 2231 9046 2647 2233 9047 2646 2232 9048 2643 2229 9049 2645 2231 9050 2648 2234 9051 2647 2233 9052 2649 2235 9053 2648 2234 9054 2646 2232 9055 2647 2233 9056 2650 2236 9057 2649 2235 9058 2651 2237 9059 2650 2236 9060 2648 2234 9061 2649 2235 9062 2652 2238 9063 2651 2237 9064 2653 2239 9065 2652 2238 9066 2650 2236 9067 2651 2237 9068 2654 2240 9069 2653 2239 9070 2655 2241 9071 2654 2240 9072 2652 2238 9073 2653 2239 9074 2656 2242 9075 2655 2241 9076 2657 2243 9077 2656 2242 9078 2654 2240 9079 2655 2241 9080 2658 2244 9081 2657 2243 9082 2659 2245 9083 2658 2244 9084 2656 2242 9085 2657 2243 9086 2660 2246 9087 2659 2245 9088 2661 2247 9089 2660 2246 9090 2658 2244 9091 2659 2245 9092 2662 2248 9093 2661 2247 9094 2663 2249 9095 2662 2248 9096 2660 2246 9097 2661 2247 9098 2664 2250 9099 2663 2249 9100 2665 2251 9101 2666 2252 9102 2662 2248 9103 2663 2249 9104 2664 2250 9105 2666 2252 9106 2663 2249 9107 2667 2253 9108 2665 2251 9109 2668 2254 9110 2667 2253 9111 2664 2250 9112 2665 2251 9113 2669 2255 9114 2668 2254 9115 2670 2256 9116 2669 2255 9117 2667 2253 9118 2668 2254 9119 2671 2257 9120 2670 2256 9121 2672 2258 9122 2671 2257 9123 2669 2255 9124 2670 2256 9125 2584 2170 9126 2672 2258 9127 2585 2171 9128 2584 2170 9129 2671 2257 9130 2672 2258 9131 2673 2259 9132 2674 2259 9133 2675 2259 9134 2676 24 9135 2674 24 9136 2673 24 9137 2677 2260 9138 2674 2260 9139 2676 2260 9140 2678 2261 9141 2675 2261 9142 2679 2261 9143 2673 2262 9144 2675 2262 9145 2678 2262 9146 2680 2263 9147 2679 2263 9148 2681 2263 9149 2678 24 9150 2679 24 9151 2680 24 9152 2682 2264 9153 2681 2264 9154 2683 2264 9155 2680 2265 9156 2681 2265 9157 2682 2265 9158 2684 2266 9159 2683 2266 9160 2685 2266 9161 2682 2267 9162 2683 2267 9163 2684 2267 9164 2686 2268 9165 2685 2268 9166 2687 2268 9167 2684 2269 9168 2685 2269 9169 2686 2269 9170 2688 2270 9171 2687 2270 9172 2689 2270 9173 2686 24 9174 2687 24 9175 2688 24 9176 2690 2271 9177 2689 2271 9178 2691 2271 9179 2692 24 9180 2689 24 9181 2690 24 9182 2688 2272 9183 2689 2272 9184 2692 2272 9185 2693 2273 9186 2691 2273 9187 2694 2273 9188 2690 24 9189 2691 24 9190 2693 24 9191 2695 2274 9192 2694 2274 9193 2696 2274 9194 2693 2275 9195 2694 2275 9196 2695 2275 9197 2695 2276 9198 2696 2276 9199 2697 2276 9200 2677 2277 9201 2676 2277 9202 2698 2277 9203 2699 2278 9204 2698 2278 9205 2700 2278 9206 2677 24 9207 2698 24 9208 2699 24 9209 2701 2279 9210 2700 2279 9211 2702 2279 9212 2699 2280 9213 2700 2280 9214 2701 2280 9215 2703 2281 9216 2702 2281 9217 2704 2281 9218 2701 2282 9219 2702 2282 9220 2703 2282 9221 2705 2283 9222 2704 2283 9223 2706 2283 9224 2703 2284 9225 2704 2284 9226 2705 2284 9227 2707 2285 9228 2706 2285 9229 2708 2285 9230 2705 24 9231 2706 24 9232 2707 24 9233 2709 2286 9234 2708 2286 9235 2710 2286 9236 2711 24 9237 2708 24 9238 2709 24 9239 2707 2287 9240 2708 2287 9241 2711 2287 9242 2712 2288 9243 2710 2288 9244 2713 2288 9245 2709 24 9246 2710 24 9247 2712 24 9248 2714 2289 9249 2713 2289 9250 2715 2289 9251 2712 2290 9252 2713 2290 9253 2714 2290 9254 2714 2291 9255 2715 2291 9256 2716 2291 9257 1686 896 9258 2717 896 9259 1685 896 9260 2718 896 9261 2719 896 9262 973 896 9263 972 896 9264 2718 896 9265 973 896 9266 2720 896 9267 2721 896 9268 2719 896 9269 2718 896 9270 2720 896 9271 2719 896 9272 2722 896 9273 2723 896 9274 2721 896 9275 2720 896 9276 2722 896 9277 2721 896 9278 2722 896 9279 2724 896 9280 2723 896 9281 1228 896 9282 2725 896 9283 1194 896 9284 1228 896 9285 2726 896 9286 2725 896 9287 2727 896 9288 2728 896 9289 2726 896 9290 1228 896 9291 2727 896 9292 2726 896 9293 2729 896 9294 2730 896 9295 2728 896 9296 2727 896 9297 2729 896 9298 2728 896 9299 2731 896 9300 2732 896 9301 2730 896 9302 2729 896 9303 2731 896 9304 2730 896 9305 1559 896 9306 1557 896 9307 2733 896 9308 2734 896 9309 2733 896 9310 2735 896 9311 2736 896 9312 2733 896 9313 2734 896 9314 1559 896 9315 2733 896 9316 2736 896 9317 2737 896 9318 2735 896 9319 2738 896 9320 2734 896 9321 2735 896 9322 2737 896 9323 2737 896 9324 2738 896 9325 2739 896 9326 1511 896 9327 1510 896 9328 2740 896 9329 2741 896 9330 2740 896 9331 2742 896 9332 1511 896 9333 2740 896 9334 2741 896 9335 2743 896 9336 2742 896 9337 2744 896 9338 2741 896 9339 2742 896 9340 2743 896 9341 1339 896 9342 2745 896 9343 1338 896 9344 1339 896 9345 2746 896 9346 2745 896 9347 2747 896 9348 2748 896 9349 2746 896 9350 1339 896 9351 2747 896 9352 2746 896 9353 2749 896 9354 2750 896 9355 2748 896 9356 2747 896 9357 2749 896 9358 2748 896 9359 2751 2292 9360 2752 2292 9361 2753 2292 9362 2754 896 9363 2752 896 9364 2751 896 9365 2755 2293 9366 2752 2293 9367 2754 2293 9368 2756 896 9369 2753 896 9370 2757 896 9371 2758 896 9372 2753 896 9373 2756 896 9374 2751 2294 9375 2753 2294 9376 2758 2294 9377 2759 896 9378 2757 896 9379 2760 896 9380 2756 2295 9381 2757 2295 9382 2759 2295 9383 2761 896 9384 2760 896 9385 2762 896 9386 2759 896 9387 2760 896 9388 2761 896 9389 2763 896 9390 2762 896 9391 2764 896 9392 2761 896 9393 2762 896 9394 2763 896 9395 2765 2296 9396 2754 2296 9397 2766 2296 9398 2755 896 9399 2754 896 9400 2765 896 9401 1400 896 9402 2766 896 9403 1401 896 9404 2765 896 9405 2766 896 9406 1400 896 9407 2767 358 9408 2768 358 9409 2769 358 9410 2770 2297 9411 2771 2297 9412 2772 2297 9413 2773 358 9414 2767 358 9415 2769 358 9416 2774 358 9417 2773 358 9418 2769 358 9419 2775 2298 9420 2776 2298 9421 2777 2299 9422 2775 2298 9423 2777 2299 9424 2778 2299 9425 2779 358 9426 2780 358 9427 2768 358 9428 2781 2300 9429 2782 2300 9430 2783 2301 9431 2767 358 9432 2779 358 9433 2768 358 9434 2784 2302 9435 2770 2302 9436 2772 2302 9437 2779 358 9438 2785 358 9439 2780 358 9440 2786 2301 9441 2783 2301 9442 2787 2303 9443 2786 2301 9444 2781 2300 9445 2783 2301 9446 2788 2303 9447 2787 2303 9448 2789 2304 9449 2786 2301 9450 2787 2303 9451 2788 2303 9452 2790 2304 9453 2789 2304 9454 2791 2305 9455 2790 2304 9456 2788 2303 9457 2789 2304 9458 2792 2306 9459 2793 2306 9460 2794 2306 9461 2790 2304 9462 2791 2305 9463 2795 2305 9464 2774 358 9465 2796 358 9466 2773 358 9467 2797 2307 9468 2798 2307 9469 2799 2308 9470 2792 2309 9471 2794 2309 9472 2800 2309 9473 2801 358 9474 2802 358 9475 2796 358 9476 2803 2308 9477 2799 2308 9478 2804 2310 9479 2774 358 9480 2801 358 9481 2796 358 9482 2803 2308 9483 2797 2307 9484 2799 2308 9485 2805 358 9486 2806 358 9487 2802 358 9488 2807 308 9489 2808 308 9490 2809 308 9491 2801 358 9492 2805 358 9493 2802 358 9494 2803 2308 9495 2804 2310 9496 2810 2310 9497 2811 358 9498 2812 358 9499 2806 358 9500 2813 2311 9501 2814 2311 9502 2815 2312 9503 2805 358 9504 2811 358 9505 2806 358 9506 2807 308 9507 2809 308 9508 2816 308 9509 2817 358 9510 2818 358 9511 2812 358 9512 2819 2312 9513 2815 2312 9514 2820 2313 9515 2811 358 9516 2817 358 9517 2812 358 9518 2819 2312 9519 2813 2311 9520 2815 2312 9521 2821 358 9522 2822 358 9523 2818 358 9524 2823 2314 9525 2824 2314 9526 2825 2314 9527 2817 358 9528 2821 358 9529 2818 358 9530 2819 2312 9531 2820 2313 9532 2826 2313 9533 2827 358 9534 2828 358 9535 2822 358 9536 2829 2315 9537 2830 2315 9538 2831 2316 9539 2821 358 9540 2827 358 9541 2822 358 9542 2823 2317 9543 2825 2317 9544 2832 2317 9545 2827 358 9546 2833 358 9547 2828 358 9548 2834 2316 9549 2831 2316 9550 2835 24 9551 2834 2316 9552 2829 2315 9553 2831 2316 9554 2836 24 9555 2835 24 9556 2837 2318 9557 2836 24 9558 2834 2316 9559 2835 24 9560 2838 2318 9561 2837 2318 9562 2839 2319 9563 2838 2318 9564 2836 24 9565 2837 2318 9566 2840 2320 9567 2841 2320 9568 2842 2320 9569 2838 2318 9570 2839 2319 9571 2843 2319 9572 2844 2321 9573 2845 2321 9574 2846 2322 9575 2840 2323 9576 2842 2323 9577 2847 2323 9578 2848 2322 9579 2846 2322 9580 2849 2324 9581 2848 2322 9582 2844 2321 9583 2846 2322 9584 2850 1404 9585 2851 1404 9586 2852 1404 9587 2848 2322 9588 2849 2324 9589 2853 2324 9590 2854 2325 9591 2855 2325 9592 2776 2298 9593 2850 1404 9594 2852 1404 9595 2856 1404 9596 2775 2298 9597 2854 2325 9598 2776 2298 9599 2857 896 9600 2858 896 9601 2859 896 9602 2860 896 9603 2861 896 9604 2858 896 9605 2857 2326 9606 2860 2326 9607 2858 2326 9608 2862 2327 9609 2863 2327 9610 2859 2327 9611 2864 896 9612 2859 896 9613 2863 896 9614 2865 896 9615 2862 896 9616 2859 896 9617 2866 896 9618 2857 896 9619 2859 896 9620 2864 896 9621 2866 896 9622 2859 896 9623 2860 2328 9624 2867 2328 9625 2861 2328 9626 2868 896 9627 2869 896 9628 2867 896 9629 2870 896 9630 2868 896 9631 2867 896 9632 2860 896 9633 2870 896 9634 2867 896 9635 2871 2329 9636 2872 2329 9637 2869 2329 9638 2868 2330 9639 2871 2330 9640 2869 2330 9641 2873 2331 9642 2874 2331 9643 2872 2331 9644 2875 2332 9645 2876 2332 9646 2874 2332 9647 2877 2333 9648 2875 2333 9649 2874 2333 9650 2873 2334 9651 2877 2334 9652 2874 2334 9653 2871 896 9654 2873 896 9655 2872 896 9656 2878 896 9657 2876 896 9658 2875 896 9659 2879 896 9660 2876 896 9661 2878 896 9662 2880 896 9663 2881 896 9664 2875 896 9665 2882 896 9666 2875 896 9667 2877 896 9668 2882 896 9669 2880 896 9670 2875 896 9671 2879 896 9672 2878 896 9673 2883 896 9674 2884 2335 9675 2885 2335 9676 2881 2335 9677 2880 896 9678 2884 896 9679 2881 896 9680 2884 2336 9681 2886 2336 9682 2885 2336 9683 2887 896 9684 2888 896 9685 2886 896 9686 2889 896 9687 2887 896 9688 2886 896 9689 2884 896 9690 2889 896 9691 2886 896 9692 2890 2337 9693 2891 2337 9694 2888 2337 9695 2887 896 9696 2890 896 9697 2888 896 9698 2892 2338 9699 2863 2338 9700 2891 2338 9701 2892 896 9702 2864 896 9703 2863 896 9704 2890 896 9705 2892 896 9706 2891 896 9707 2865 2339 9708 2893 2339 9709 2862 2339 9710 2865 896 9711 2894 896 9712 2893 896 9713 2895 2340 9714 2896 2341 9715 2897 2342 9716 2898 2343 9717 2899 2344 9718 2900 2345 9719 2898 2343 9720 2900 2345 9721 2901 2346 9722 2902 2347 9723 2897 2342 9724 2903 2348 9725 2904 2349 9726 2895 2340 9727 2897 2342 9728 2902 2347 9729 2904 2349 9730 2897 2342 9731 2905 2350 9732 2903 2348 9733 2906 2351 9734 2905 2350 9735 2902 2347 9736 2903 2348 9737 2907 2352 9738 2906 2351 9739 2908 2353 9740 2907 2352 9741 2905 2350 9742 2906 2351 9743 2909 2354 9744 2908 2353 9745 2910 2355 9746 2909 2354 9747 2907 2352 9748 2908 2353 9749 2911 2356 9750 2910 2355 9751 2912 2357 9752 2911 2356 9753 2909 2354 9754 2910 2355 9755 2913 2358 9756 2912 2357 9757 2914 2359 9758 2913 2358 9759 2911 2356 9760 2912 2357 9761 2913 2358 9762 2914 2359 9763 2915 2360 9764 2916 2361 9765 2917 2362 9766 2918 2363 9767 2919 2364 9768 2913 2358 9769 2915 2360 9770 2920 2365 9771 2918 2363 9772 2921 2366 9773 2922 2367 9774 2916 2361 9775 2918 2363 9776 2920 2365 9777 2922 2367 9778 2918 2363 9779 2923 2368 9780 2921 2366 9781 2924 2369 9782 2923 2368 9783 2920 2365 9784 2921 2366 9785 2925 2370 9786 2924 2369 9787 2926 2371 9788 2925 2370 9789 2923 2368 9790 2924 2369 9791 2927 2372 9792 2926 2371 9793 2928 2373 9794 2927 2372 9795 2925 2370 9796 2926 2371 9797 2929 2374 9798 2928 2373 9799 2930 2375 9800 2929 2374 9801 2927 2372 9802 2928 2373 9803 2898 2343 9804 2930 2375 9805 2899 2344 9806 2898 2343 9807 2929 2374 9808 2930 2375 9809 2931 2376 9810 2932 2376 9811 2933 2376 9812 2931 2377 9813 2933 2377 9814 2934 2377 9815 2935 896 9816 2934 896 9817 2936 896 9818 2935 896 9819 2931 896 9820 2934 896 9821 2937 896 9822 2936 896 9823 2938 896 9824 2939 896 9825 2935 896 9826 2936 896 9827 2937 896 9828 2939 896 9829 2936 896 9830 2940 896 9831 2938 896 9832 2941 896 9833 2942 896 9834 2937 896 9835 2938 896 9836 2940 896 9837 2942 896 9838 2938 896 9839 2943 896 9840 2941 896 9841 2944 896 9842 2945 896 9843 2940 896 9844 2941 896 9845 2943 896 9846 2945 896 9847 2941 896 9848 2946 896 9849 2944 896 9850 2947 896 9851 2946 896 9852 2943 896 9853 2944 896 9854 2948 2378 9855 2947 2378 9856 2949 2378 9857 2950 896 9858 2947 896 9859 2948 896 9860 2951 896 9861 2947 896 9862 2950 896 9863 2951 896 9864 2946 896 9865 2947 896 9866 2951 2379 9867 2950 2379 9868 2952 2379 9869 2953 896 9870 2952 896 9871 2954 896 9872 2955 896 9873 2951 896 9874 2952 896 9875 2953 896 9876 2955 896 9877 2952 896 9878 2956 896 9879 2954 896 9880 2957 896 9881 2958 896 9882 2953 896 9883 2954 896 9884 2956 896 9885 2958 896 9886 2954 896 9887 2959 896 9888 2957 896 9889 2960 896 9890 2961 896 9891 2956 896 9892 2957 896 9893 2959 896 9894 2961 896 9895 2957 896 9896 2962 896 9897 2960 896 9898 2931 896 9899 2962 896 9900 2959 896 9901 2960 896 9902 2962 896 9903 2931 896 9904 2935 896 9905 2963 2380 9906 2964 2381 9907 2965 2382 9908 2966 2383 9909 2967 2384 9910 2968 2385 9911 2966 2383 9912 2968 2385 9913 2969 2386 9914 2970 2387 9915 2965 2382 9916 2971 2388 9917 2970 2387 9918 2963 2380 9919 2965 2382 9920 2972 2389 9921 2971 2388 9922 2973 2390 9923 2972 2389 9924 2970 2387 9925 2971 2388 9926 2972 2389 9927 2973 2390 9928 2974 2391 9929 2975 2392 9930 2974 2391 9931 2976 2393 9932 2975 2392 9933 2972 2389 9934 2974 2391 9935 2977 2394 9936 2976 2393 9937 2978 2395 9938 2977 2394 9939 2975 2392 9940 2976 2393 9941 2979 2396 9942 2978 2395 9943 2980 2397 9944 2981 2398 9945 2977 2394 9946 2978 2395 9947 2979 2396 9948 2981 2398 9949 2978 2395 9950 2982 2399 9951 2980 2397 9952 2983 2400 9953 2982 2399 9954 2979 2396 9955 2980 2397 9956 2984 2401 9957 2985 2402 9958 2986 2403 9959 2987 2404 9960 2982 2399 9961 2983 2400 9962 2988 2405 9963 2986 2403 9964 2989 2406 9965 2988 2405 9966 2984 2401 9967 2986 2403 9968 2990 2407 9969 2989 2406 9970 2991 2408 9971 2990 2407 9972 2988 2405 9973 2989 2406 9974 2990 2407 9975 2991 2408 9976 2992 2409 9977 2993 2410 9978 2992 2409 9979 2994 2411 9980 2993 2410 9981 2990 2407 9982 2992 2409 9983 2995 2412 9984 2994 2411 9985 2996 2413 9986 2995 2412 9987 2993 2410 9988 2994 2411 9989 2997 2414 9990 2996 2413 9991 2967 2384 9992 2998 2415 9993 2995 2412 9994 2996 2413 9995 2997 2414 9996 2998 2415 9997 2996 2413 9998 2966 2383 9999 2997 2414 10000 2967 2384 10001 2999 896 10002 3000 896 10003 3001 896 10004 3002 2416 10005 3001 2416 10006 3003 2416 10007 2999 896 10008 3001 896 10009 3002 896 10010 3004 2417 10011 3003 2417 10012 3005 2417 10013 3002 896 10014 3003 896 10015 3004 896 10016 3006 896 10017 3005 896 10018 3007 896 10019 3008 896 10020 3005 896 10021 3006 896 10022 3004 2418 10023 3005 2418 10024 3008 2418 10025 3006 2419 10026 3007 2419 10027 3009 2419 10028 3010 2420 10029 3009 2420 10030 3011 2420 10031 3006 896 10032 3009 896 10033 3010 896 10034 3012 896 10035 3011 896 10036 3013 896 10037 3010 896 10038 3011 896 10039 3012 896 10040 3012 896 10041 3013 896 10042 3014 896 10043

-
-
-
-
- - - - - -4.37108e-11 -1.62919e-10 -9.99987e-4 0 -9.99987e-4 -2.98019e-11 4.37108e-11 0 -2.98019e-11 9.99987e-4 -1.62919e-10 -0.2604 0 0 0 1 - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl deleted file mode 100644 index 6b12b270c95d7c36209551d9a87d81f3a5333232..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 17884 zcmb81d3aPs*2WKtvZ#nG3L=sZbp}SAK@z~FZ#Vj>K_cp)jsh|e2>WUXK{iDMF>zzx zkzEBvwt%9!-8zb95S0L;IDjZ9IOsP91RPPB_f*~Les7yU=Hq#IQsmU{oLWv*omwup zJT!DjenGFijNbV}24&ndu-D+cUinwI{9~KzGMWt=-Xo($bNPS$$*bbBk4tFkvYf4v zJ9oV6FP&THmFC=K(v!a$@2O0GU#oDUN$bBY!IHak?kd$>(?A?;ztyByL6hduKjRYZ zbBDKPN$Z??z7iSVclBz-BPQKE9szNv-n`b%21}}a-__*ml2gx{Key2D0Qy#x+FEb~ zOP>8|yvbGd_PZh|ze#WF@OWm5=$m`I6-%ZD#5mMvMPQ?P&el>UhPP(P#VD1Qq%G>x z6!p+_9sEoYnqo;ujvP=DS=?eo4U z6-%^K>R0VhA1$q>^=HaP``qKE9!`Stn_P84@+e3Vno5@_t#x3Z7J0fyUMnrt*@fOl zmareQhlXviguRmeEk#5Z{JeoB>|^XbDMC{$VUJ;7ND+4|7}JU+-2dFODPqimF(oYF ze&&7>dAQ~+P1!o3!5^|>#sU8%$?O`a)X3AZ%2p)J+v(~l&kH+d$DCERY@BB^>z zX;P~dOSl!dej*=z{AHHfSlFc229|K0xU?d(du5bpJsuc!WIao`glt>n;r$aZYmH01 zIj=m`tRCzKNU*nj_84L-to;cFE1b_ z_wN+hxxC0LSTn$P^ty$qwAEAxHU@!s`{pOtJH4u_GTIV1ESesz`BTAfO2syoZ`~D{ zvFuT=_tyR>)wM*h#HCfQqpgkaI#)zzZO%0|rXFeJ?d#Of)RqaCwl;Qym>&@5=6@S$ zF>b7Pd;UP*(Y-qNOs1`k3%gWAp8`?qP@Pt+t1{XWv->oSoq6z<-;|1Ne3^f%r+>GU z_e9O-fH)%{SmM&E*U{F7=AI8q`(i(8Jq5K_2@@`DZL|c@9mLG)OETwo>fsF=cDWZh zJjmBJQ~LTJ`uVI0tIUC0Vv9gbIkluE>tZ@gJd1X!j`n({Wg?R$Y(x87+p)a4dZPB; zx9AhC2TNR9>%^Kw&WBGmgr_i}xg4Q-bp#y4NGP4z8#dGny?|heOEax$k-_lvCh&N* zp(E%mf9*9YVZx=Y4ILZj2gKgR#onv=H6j;m8t6MZ>$3jIbjrq-(lW2-&U3O@S7o#% z)W+%3GSo;!i9=Pol&Zwp;I!Hk83JNYKm>YAwN#GQvb(gkq4P)^zs&!nqI0IxtGX(q zEm0e-TW`^HGuyB(msT4y(dUb{?kfGz^!Yg;G6RAoF0FbUZEZ}per0TME|*rlfsgs> z#~4u{zU*8PFM=nsB=99)^*Y+xsEYA1vrp5+^pguS18+CEm|#sJ)j-Swq5Tnz313H) zqd&mdc4=$lauE3-qIFi5u&&BzOX$pik{KJU%ca$Zj$V|~?}NF^&Lw9B1WR06^*Y+x z_zL51_U2q;1HBYMyO^3Y;nLPdeLE)_f+epuJ{h^<`BDDPW&?buY0vw^P^u%aF*C5i z1m|*TTdLn<#Gd<8fw8gAu4<-KoXe%HjY~n)0uj6Kjdi+)KRtB3iG=qD^sKStebyv$ z8;EKkhJL%T73*R;Oz1j@F_O6O`4?NZeJ`;NW5kq-bFn>@nYGU7Qu@)NB2y~P#r8xZo67u= zfeqbrOhKu1&*A79Xe*bt{V@YJFasr47QdFox+uNnVVDwK5{EGFuwAvH- zD~PHAp|MXfdQkUEj{X?FlkP@Wi=C8u`01a#X^4 zU0Usl{0L$ih@%4@Y|WA`Q>yzvtR3br$;$JcrZ+CoRqa$jaLrX0=W=OVss)%8ssy8! zB`&RckL2I#{{w%w{$F3%m;vJKfMAJBt6oQ28+DL-QZQeAjapAa?N!2rOIsUCJP{E4 z6Sw;Xo1^~Y_YCwMJ*GqdWZK%moS4vARBO(<|EY_r`5oRJ=sWtJ*YlETYhyYH?UVNkyb`BZbyY@Nq8@ze#6r8OIlU@z zX|+*~QMLwaaEpZYxz0Qdf>n(rF3q&Hp|irr!RpMpTw3+&4AHjUGntEz4}=XJfBy^! zmbkR)b+olH0K_k;NXF<=i6d0+hp5L5XLN~NY3iZ#2*$dnJ;)N5X4=}&S^AnFzT#Xi zt$L@RXWz%#(iQCn#UKg-f+a4kdL3oNW*GwM?)kk$;20$c<^AcU%5)>G53?yi0Qj`;P9J+bfy2Ha-W@0K}ok zUMOK*mC=^?7UNIjYPI3?s>G$$hRQI)JiFUI1VVQd`dj^zlBD+MjJ1?8t5-f2$FSVg@yY9SfJ(ysL zwgB&`+)hU1b1D_@0XSCYh+Jd`5iH>t*F~JRR7+2E#i_Hc2TNQ8sJS?v6FHOmgC!ha zxk$#^0Fi86mbmyqbA?yuC#fDRajU2jZtb!*-a4^2Sr3-DHA-`ZSA$(-gC%Y?P$E3< zau2e^&5ugBS;>})36}8u5gzAEu!P5X`Y3Qrczm$uvroI+`g2@@CG5xSp(4K@pOiC068!X}e=bjDQUb*?`EN8#7~tHx$JirxBdX&5!nk z6AH+kEqIi!qf^)HL zk*=%y#PVR{s%9(VY@JIrWyl8a)CWgOJ6Q!O z{v+6n%tk#x_$lJzhIJFSt%=2+hK)^!x0im58W*MrPl*mUclT%iWv*v!{It7zETd_5 zY-p-fp7uxStg^`c$W>|yFGajRqC;$RcKyWYWfEUmG0H2eKGr|umDQzOr*J*CfOro? zM-VL08$TW*RJ*exJ^{qrd0~Qc=^fjrOGf$j7P%^H zJPzW2V51FgC=b6l+}t%^@yd6lZ_OF)_jzTI$F_0*0b(?W^FgpKro#kARN|o0&+jfmDy|1~0V@8+mi-w-=H zUl%*lH#@oyHAfGckqU43;O!o~U47U4ab`R7`(yBH^f^j&R=@1%2J|9JSg-b=j+^(< ziy}V{I~9$t-56apI44A~4W>nU<(5ZB?$3x_fO>E)u2Yz3wyNAOxO;K*EtHBSL5rI9 z370C~pl$q{t#xCoQ7R_5t(X?M20i$2cKz6eC>7`8z6ld=E?QyE7|Kv8mIP_zmEltT zxo;ygqMkyjn5d-B4K4B|yksP1IQ0_F#oo^LM6|7j-@Q1lZN-wH6@2xKaH(!=*f#$8 z*1Cz8Ql&E1+1vG&v|YTwx9>7`qjf7lyZ}O9Z{#!@YF=-Q?K9$yIyFc5m#&}SJki(_ zc^||95Np$HuwK?A@*;@CAhZX$9-NEol=R)W`Yub@kHa+&d^fJX%S7Onx*DX74;@hl z`)0>=L~$-2U2IRJ)!RK|jqX_-{bREgQJ%@z^O+WT2BoR{LEYFl4cdkXo)eiCY1FW8 ztR2>En-R4grD7sTn^m7_6Emm{ zjQ|{Ba`A`?6G0EgsRs?gy~e(PlhhOQqq+_rSSF$V;FkVP>qdjtjdKs8eUdQ)(;|I0 zZHWXu80TEjn~YJy1lHOFVuo0uEmg8VxZSvKj3*}46Tik-KxjPV*{kk6+;1S79eXOu`KJ7zlkkcIe`vzP=q}d#p)h8i;DJaVpJ*zDRL;SrcAz zAbM@TCYG3x>JL-i9UY^7pPVuN58JNy^%YwE>cjmQA{~*&AZ`S)5CluO9^q0UPBbS` zh!fp>WyS~EN+a(GyzpfnD`wOh0;4t_s^xzKC6-!U;`m^gsl z#6Zj?h?d;0$mC)=*iD#wb$C07u92c>+cbi6xqX}6u?TivXTe4-5W(Kbyn5jG3|vBy zZ(ySvht#)- zIf!u}5GRIgu->%($SseLwefC(XJ#ihlo z7qr#V{TYeFDH~=MHdrs0R%8`+5!iXf)?wb|8uFaz?sV*n#=*a9 z8;v09TRJEw;m*JH{U-MyYZ7@GHVy_hSQpb_;sdN78CVVSv3_v-xKn3cKX`P(U$B1s zY3;`NO4NfTTyxeW@r!eow3E{fNT!EjXeY@AQ3zew7A0@ht$}6UE+I*`VYw z2$tx(aE*}kojbn~$7|fchQ2sVC)`VNwvE?Rc=e)ws_)|Tr+W*o=}*2YFz>>7A1#s{ z+|LgM!4lpHYg#qwHx#&Cf{p6OHfHJ_VLFk@#kMB~FD&prBXr`$XIYw7+Mba;9T2rZ zu!O(O;L|UW3l`cpmThoX&)*pEDux*Se zw2|7Vk2fZ~YvA1kzje1SQk1v|1WT0Gn(OX`HHj<1_mehCPc@F?QZCGrA@ zPOWN`tVkm`7u&Wkm#g+0l$C`Zf`cSQLq& zH2NEzOZY1Ye%I%2N$uOgZqHfb&mdUB?-Tj!Dv{Q(;bZnu8|j3O4?S;S+al-2?P|~; zZ=_f+zlYSc(x?Ykjt7GELtk#OgiFGjQmw1+uvjn8yWu%;6JC*PTj_f;mask6Byt{R zxSV}8vh<}8f7Qk(2ppH4dQocHdrrfvNtB!L7LkomLT@gdmN*e&#y(E3sz^$ zqM^M3NBaCNp$NXqFs=J5`h_Lj2i!Lz?{=t&4#BBfd&Jbij@Q?F&Kt{PUTu5(X6E{R zxK~4|;k(VScYX$h?&vj^(t9?4C44TbX|<;(tk%Yi zDa9ptSN$8p8Z7coimu-va zcP!dg_?9KAWp?o=?^wdS32h@Kt_Hypj!Rh+)<48m-S*WenFjyjy$tVhcTsG56`=fI2Qy z=WV{uOl*QDzGOWyDdF*`X*Yr~*Ws<&b=cPqNxfAwF&yvocyEZ}d}dy^CH@M6XB?ha z!m-bB*ti@v9t6RBK4IfEQKT5e`5-bt@Or1C%e{x=n?{jI zAT9>64QH2ZgY~i|5q-5&55$)sSi*W)6aL=^+@*HJsq<~9Ij@6Sb9bJ|b;AGkftMUN R;r11;4MXRNtd}*3{0EBqy08EM diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae deleted file mode 100644 index 4c18808193..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae +++ /dev/null @@ -1,181 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T14:39:21 - 2019-01-15T14:39:21 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.31 0.33 0.33 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.973 0.71 0 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - - - - - - - 147.1821 586.3167 -51.70481 141.8451 593.5132 -51.54813 148.0296 587.1405 -51.83827 151.8905 591.4855 -51.78149 148.0296 587.1405 -51.83827 141.8451 593.5132 -51.54813 154.4627 579.7385 -52.16218 147.1821 586.3167 -51.70481 148.0296 587.1405 -51.83827 157.3284 581.1897 -52.17074 154.4627 579.7385 -52.16218 135.6829 599.8162 -51.26036 135.6829 599.8162 -51.26036 135.0501 599.1939 -51.18709 133.4308 600.8645 -51.12577 135.6829 599.8162 -51.26036 135.0501 599.1939 -51.18709 133.9128 601.5067 -51.18113 133.9128 601.5067 -51.18113 134.8133 598.9592 -51.11772 132.8595 599.439 -50.69397 134.8133 598.9592 -51.11772 140.1886 591.8713 -50.99227 134.0013 598.1451 -50.68305 134.0013 598.1451 -50.68305 146.3874 585.5314 -51.29747 144.1774 583.6867 -49.7794 134.0013 598.1451 -50.68305 140.1886 591.8713 -50.99227 134.6165 595.5949 -50.03851 131.8069 597.9547 -49.89383 134.0013 598.1451 -50.68305 134.6165 595.5949 -50.03851 132.8595 599.439 -50.69397 146.3874 585.5314 -51.29747 153.6216 578.911 -52.03116 146.3874 585.5314 -51.29747 152.7586 578.2153 -51.6268 155.6281 574.2968 -51.78174 146.3874 585.5314 -51.29747 152.7586 578.2153 -51.6268 144.1774 583.6867 -49.7794 159.2641 570.7716 -52.35687 162.8215 567.0674 -52.67032 165.2659 562.3912 -52.84667 172.9984 550.0427 -53.33465 165.2659 562.3912 -52.84667 162.8215 567.0674 -52.67032 164.1523 561.8378 -52.68573 166.9693 556.039 -52.89651 164.1523 561.8378 -52.68573 165.2659 562.3912 -52.84667 167.53 556.3164 -53.01939 166.6854 559.4944 -52.95425 166.6854 559.4944 -52.95425 160.2062 571.5173 -52.49746 162.6554 570.8572 -52.5591 160.2062 571.5173 -52.49746 158.3187 570.1608 -51.93267 155.6281 574.2968 -51.78174 163.1142 561.3106 -52.22069 164.5175 558.413 -52.31974 163.1142 561.3106 -52.22069 165.9166 555.5091 -52.41862 166.4283 555.7683 -52.69495 158.3187 570.1608 -51.93267 163.1142 561.3106 -52.22069 153.4136 572.1343 -50.17359 164.6611 550.312 -50.55076 163.1142 561.3106 -52.22069 164.5175 558.413 -52.31974 161.0109 559.1158 -50.62105 161.0109 559.1158 -50.62105 168.0995 556.595 -53.06182 168.0995 556.595 -53.06182 171.2369 548.7321 -53.34135 167.53 556.3164 -53.01939 168.0995 556.595 -53.06182 171.2369 548.7321 -53.34135 165.9166 555.5091 -52.41862 169.5452 546.6098 -52.83352 165.9166 555.5091 -52.41862 166.4283 555.7683 -52.69495 168.5294 547.8276 -52.4199 164.6611 550.312 -50.55076 165.9166 555.5091 -52.41862 168.5294 547.8276 -52.4199 170.2308 546.8281 -53.1365 166.9693 556.039 -52.89651 170.9542 547.0538 -53.32364 173.5952 507.5234 -54.38581 174.2601 503.0798 -54.69903 173.1549 497.0505 -54.85206 170.8541 471.9127 -55.5304 173.1549 497.0505 -54.85206 174.2601 503.0798 -54.69903 171.7653 497.3518 -54.6093 168.5805 476.1851 -55.36858 171.7653 497.3518 -54.6093 173.1549 497.0505 -54.85206 168.5805 476.1851 -55.36858 175.0395 508.9087 -54.54603 175.0395 508.9087 -54.54603 174.3966 517.6433 -54.14333 175.4834 514.5324 -54.39304 178.2054 513.6084 -54.46698 175.4834 514.5324 -54.39304 175.5904 519.9503 -54.24005 178.8611 517.616 -54.36388 175.5904 519.9503 -54.24005 174.2275 527.6387 -53.88474 175.4405 525.2023 -54.08731 179.3099 521.5034 -54.26061 175.4405 525.2023 -54.08731 175.0387 530.3076 -53.93437 179.5789 525.2778 -54.15742 175.0387 530.3076 -53.93437 173.1037 537.4588 -53.61153 173.558 539.9431 -53.6331 179.2601 532.3463 -53.94981 173.558 539.9431 -53.6331 179.5871 528.9169 -54.05355 176.257 542.774 -53.59931 178.6049 535.7296 -53.84166 177.5732 539.2233 -53.72379 174.7415 546.3803 -53.46977 172.2361 537.294 -53.35007 173.2317 527.5505 -53.54014 173.2888 517.6509 -53.70773 172.3947 507.6486 -53.85226 170.4954 497.6169 -53.97182 166.3603 472.2097 -55.25035 170.4954 497.6169 -53.97182 171.3751 507.7449 -53.02009 169.4566 497.8222 -52.9879 165.1294 472.457 -54.66093 169.4566 497.8222 -52.9879 171.4316 537.1356 -52.93074 172.3313 527.4636 -52.99239 172.3161 517.6491 -53.02165 169.9478 503.7025 -51.87728 168.7326 497.9518 -51.74511 164.1041 472.6525 -53.74756 168.7326 497.9518 -51.74511 169.3761 544.4937 -52.4235 171.2169 532.6634 -52.33491 170.3756 539.2626 -52.38768 171.6387 524.9704 -52.23549 171.4328 529.911 -52.30222 171.3465 514.6817 -52.0771 171.6403 520.768 -52.17933 171.6194 519.9016 -52.16589 170.8032 509.2817 -51.98393 170.7922 509.195 -51.9824 166.6344 501.5209 -45.94777 169.9478 503.7025 -51.87728 168.7326 497.9518 -51.74511 168.4406 496.6146 -51.78708 163.9953 490.058 -44.6771 168.7326 497.9518 -51.74511 168.4406 496.6146 -51.78708 163.9953 490.058 -44.6771 169.3761 544.4937 -52.4235 166.4565 535.6899 -48.41067 170.3756 539.2626 -52.38768 163.2963 545.3479 -48.49355 171.2169 532.6634 -52.33491 167.6005 523.8228 -47.38319 171.4328 529.911 -52.30222 171.6387 524.9704 -52.23549 171.6403 520.768 -52.17933 167.2904 511.7811 -46.03887 171.6194 519.9016 -52.16589 171.3465 514.6817 -52.0771 170.8032 509.2817 -51.98393 170.7922 509.195 -51.9824 147.9977 370.8482 -57.88861 147.8802 362.2853 -58.26272 145.5586 345.2029 -58.71044 146.6722 347.2275 -58.67202 145.5586 345.2029 -58.71044 147.8802 362.2853 -58.26272 144.4947 345.3371 -58.57054 144.3674 339.324 -58.85768 144.4947 345.3371 -58.57054 145.5586 345.2029 -58.71044 137.904 305.8088 -59.70278 144.3674 339.324 -58.85768 150.5246 379.9121 -57.80507 150.5246 379.9121 -57.80507 151.9789 396.2892 -57.21645 153.4917 398.0839 -57.33747 155.0872 388.7207 -57.63296 153.4917 398.0839 -57.33747 156.3956 421.6591 -56.55326 156.7821 416.8031 -56.85988 156.7821 416.8031 -56.85988 160.3944 436.0628 -56.37245 163.1481 430.284 -56.58572 160.3944 436.0628 -56.37245 161.2016 446.9597 -55.89827 164.327 455.856 -55.87538 164.327 455.856 -55.87538 160.0106 447.184 -55.3559 155.2463 421.8587 -56.0568 150.8733 396.4633 -56.76457 146.9375 370.9956 -57.47976 144.1478 345.3795 -58.47243 143.0155 339.6945 -58.62051 144.1478 345.3795 -58.47243 143.4817 345.4588 -58.20291 143.4817 345.4588 -58.20291 159.0014 447.3643 -54.5122 154.2565 422.0219 -55.28169 149.9064 396.6075 -56.05662 145.9969 371.119 -56.8371 142.8599 345.5298 -57.83806 141.7799 340.0235 -57.9988 142.8599 345.5298 -57.83806 142.571 345.5616 -57.62332 140.7599 340.2846 -57.04233 142.571 345.5616 -57.62332 160.0603 456.6887 -53.11503 164.2462 477.0548 -52.42534 156.2013 436.8481 -53.78924 152.6687 417.5324 -54.43879 146.5953 380.5044 -55.68289 149.4661 398.7487 -55.06816 144.045 362.8009 -56.28057 141.8051 345.6408 -56.8616 141.8051 345.6408 -56.8616 139.7875 377.2972 -46.64912 144.045 362.8009 -56.28057 141.8051 345.6408 -56.8616 139.5207 340.6835 -55.45215 141.8051 345.6408 -56.8616 140.7599 340.2846 -57.04233 140.6004 345.889 -55.33434 140.6004 345.889 -55.33434 161.0911 466.8387 -50.64106 164.2462 477.0548 -52.42534 160.0603 456.6887 -53.11503 156.2013 436.8481 -53.78924 153.8413 437.0227 -49.41643 152.6687 417.5324 -54.43879 146.7377 407.1754 -48.08734 149.4661 398.7487 -55.06816 146.5953 380.5044 -55.68289 141.058 334.2219 -58.74307 142.3414 333.6596 -58.98421 142.3414 333.6596 -58.98421 122.7934 293.4137 -59.556 141.058 334.2219 -58.74307 142.3414 333.6596 -58.98421 133.2809 313.2206 -59.4102 133.2809 313.2206 -59.4102 139.8839 334.7278 -58.11659 138.9169 335.1351 -57.15695 137.839 335.6145 -55.70791 138.9169 335.1351 -57.15695 131.3666 318.3132 -57.39713 138.9169 335.1351 -57.15695 139.8839 334.7278 -58.11659 125.0363 320.3262 -48.45126 138.9169 335.1351 -57.15695 131.3666 318.3132 -57.39713 137.839 335.6145 -55.70791 121.5477 293.9556 -58.8296 129.8333 314.9069 -57.44483 120.56 294.3742 -57.7254 124.1763 292.8011 -59.83487 124.1763 292.8011 -59.83487 119.7885 284.8053 -59.9868 122.7934 293.4137 -59.556 124.1763 292.8011 -59.83487 128.7824 264.4633 -60.72529 119.7885 284.8053 -59.9868 120.3433 302.0181 -52.90182 129.8333 314.9069 -57.44483 120.56 294.3742 -57.7254 117.8102 286.1043 -59.30879 120.56 294.3742 -57.7254 121.5477 293.9556 -58.8296 118.9 290.4598 -58.13595 118.5959 297.0349 -53.91913 120.56 294.3742 -57.7254 118.9 290.4598 -58.13595 120.3433 302.0181 -52.90182 118.7687 285.4836 -59.79577 100.5721 266.186 -60.13474 102.1089 267.2483 -60.14162 96.02827 262.1213 -60.22027 102.2963 267.0047 -60.18058 98.03209 265.3815 -60.07365 100.5721 266.186 -60.13474 96.02827 262.1213 -60.22027 101.103 265.699 -60.20662 128.2531 262.1374 -60.78252 96.02827 262.1213 -60.22027 101.103 265.699 -60.20662 74 271.301 -58.85924 98.03209 265.3815 -60.07365 96.02827 262.1213 -60.22027 74 262.1103 -59.83592 126.484 252.8308 -60.30329 74 262.1103 -59.83592 96.02827 262.1213 -60.22027 128.2531 262.1374 -60.78252 104.6728 270.2503 -59.94817 107.8586 272.8487 -59.96598 102.9414 268.4804 -60.04117 112.2894 279.2928 -59.26791 113.1565 279.0881 -59.68856 108.2695 272.401 -60.10156 111.667 278.44 -59.34709 108.3906 274.3378 -59.68344 108.186 274.1004 -59.70054 116.8875 286.4681 -58.57391 113.8282 278.5053 -59.97569 115.6302 284.2937 -58.79717 114.4789 282.4699 -58.97194 118.3663 289.3334 -58.25959 118.3663 289.3334 -58.25959 116.3608 291.51 -55.33208 116.8875 286.4681 -58.57391 115.6302 284.2937 -58.79717 113.5529 286.1064 -56.61441 114.4789 282.4699 -58.97194 112.2894 279.2928 -59.26791 110.2009 281.238 -57.5789 111.667 278.44 -59.34709 108.3906 274.3378 -59.68344 108.186 274.1004 -59.70054 105.7498 275.1887 -58.78062 104.6728 270.2503 -59.94817 102.9414 268.4804 -60.04117 99.80713 268.5841 -59.75295 102.6659 274.7716 -58.62486 105.7512 269.3789 -60.18261 109.991 273.1805 -60.14798 117.0051 280.9045 -60.04969 113.7681 277.0449 -60.10348 105.7512 269.3789 -60.18261 128.5193 263.3 -60.75394 109.991 273.1805 -60.14798 113.7681 277.0449 -60.10348 117.0051 280.9045 -60.04969 104.6403 280.6888 -56.88534 107.6876 281.9181 -56.68606 105.7718 286.3627 -54.55187 108.6713 288.4594 -53.76598 111.2763 288.1916 -54.56865 106.091 291.8146 -51.61164 108.6855 294.6445 -50.0622 111.3907 294.7669 -50.7171 105.6094 297.042 -48.03109 107.7987 300.3302 -45.65637 110.6077 300.8064 -46.11263 104.3362 302.0016 -43.77494 106.1317 305.4107 -40.64809 109.0463 306.1928 -40.86519 100.9576 308.8366 -35.96826 103.8321 309.8187 -35.13884 106.8545 310.8526 -35.0879 102.252 306.6863 -38.73141 97.94578 312.6266 -30.0976 101.0485 313.5175 -29.21953 104.1824 314.7463 -28.88302 99.53195 310.7973 -33.11986 96.17863 314.3472 -26.82267 97.91443 316.4868 -22.96849 101.1651 317.854 -22.33954 92.13552 317.3186 -19.5331 94.55517 318.7109 -16.46019 97.92856 320.1612 -15.54193 94.23913 315.9154 -23.31775 87.43457 319.4504 -11.15536 91.07698 320.1785 -9.764601 89.86763 318.5125 -15.47365 90.40032 320.3808 -8.379012 91.07698 320.1785 -9.764601 87.43457 319.4504 -11.15536 94.57913 321.6595 -8.569125 94.57913 321.6595 -8.569125 74 319.5466 -9.215085 87.43457 319.4504 -11.15536 89.86763 318.5125 -15.47365 87.05075 319.5746 -10.43833 87.05075 319.5746 -10.43833 74 317.4272 -18.19599 92.13552 317.3186 -19.5331 94.23913 315.9154 -23.31775 96.17863 314.3472 -26.82267 74 313.9562 -26.73733 97.94578 312.6266 -30.0976 99.53195 310.7973 -33.11986 74 309.2187 -34.63909 100.9576 308.8366 -35.96826 102.252 306.6863 -38.73141 74 303.327 -41.71799 104.3362 302.0016 -43.77494 105.6094 297.042 -48.03109 74 296.4193 -47.80942 106.091 291.8146 -51.61164 74 288.6561 -52.77069 105.7718 286.3627 -54.55187 104.6403 280.6888 -56.88534 74 280.2175 -56.48415 102.6659 274.7716 -58.62486 99.80713 268.5841 -59.75295 114.0125 292.6706 -53.18174 113.6885 298.8069 -49.04492 112.6571 304.4006 -44.28948 111.0262 309.3736 -39.01021 108.9142 313.6788 -33.29713 106.435 317.2898 -27.23118 103.6919 320.1926 -20.88459 100.7813 322.3758 -14.32703 97.78395 323.8331 -7.623662 94.01329 321.8245 -7.34283 97.78395 323.8331 -7.623662 116.2592 298.3331 -51.06222 115.3868 304.5847 -46.09148 113.8546 310.1668 -40.52394 111.7903 315.0183 -34.46133 109.32 319.1054 -27.99522 106.5576 322.4097 -21.20639 103.6092 324.916 -14.17249 100.5634 326.6137 -6.96619 97.31938 323.9871 -6.525541 100.5634 326.6137 -6.96619 117.9492 304.1825 -48.74486 116.5345 310.6071 -42.86675 114.4944 316.2239 -36.40189 111.9751 320.9854 -29.45577 109.1086 324.8645 -22.12004 106.0182 327.8388 -14.48173 102.8076 329.8898 -6.622463 100.1761 326.7796 -5.962963 102.8076 329.8898 -6.622463 119.2829 309.2303 -47.1708 118.4568 312.6174 -43.98402 116.2624 318.8771 -36.98008 117.4458 315.8406 -40.58421 113.6297 324.0159 -29.69225 114.9169 321.7186 -33.16708 110.0847 328.8605 -20.60647 113.4264 324.3474 -29.15506 111.8114 326.7275 -24.97146 106.377 332.2646 -11.42634 108.2681 330.7086 -16.09114 104.4319 333.5263 -6.603205 104.2523 333.644 -6.145844 104.4319 333.5263 -6.603205 102.464 330.0803 -5.677928 104.0875 333.7477 -5.681748 119.2829 309.2303 -47.1708 118.4568 312.6174 -43.98402 117.4458 315.8406 -40.58421 119.1202 322.2314 -39.20741 116.2624 318.8771 -36.98008 114.9169 321.7186 -33.16708 113.6297 324.0159 -29.69225 121.1775 343.6825 -29.77928 113.4264 324.3474 -29.15506 122.1814 343.1452 -31.57093 122.9678 342.7313 -32.94909 123.7842 342.3073 -34.35767 124.6325 341.8722 -35.79812 125.513 341.4261 -37.26944 126.4263 340.9688 -38.77067 120.2241 344.2027 -28.04314 111.8114 326.7275 -24.97146 118.4502 345.2036 -24.71389 110.0847 328.8605 -20.60647 119.3162 344.7093 -26.35575 116.1061 346.6198 -20.08871 108.2681 330.7086 -16.09114 116.8458 346.1582 -21.57902 117.6268 345.686 -23.12108 114.1263 347.9689 -15.92387 106.377 332.2646 -11.42634 114.7476 347.5234 -17.26177 115.4068 347.0751 -18.64865 111.5344 350.374 -9.82049 104.4319 333.5263 -6.603205 112.218 349.5962 -11.54942 112.9827 348.8746 -13.36506 113.5384 348.4207 -14.62415 110.5493 352.4901 -6.686539 104.4319 333.5263 -6.603205 104.2523 333.644 -6.145844 110.5346 352.3898 -6.721432 110.977 351.3055 -8.210206 110.5346 352.3898 -6.721432 74 252.885 -59.38658 74 271.301 -58.85924 74 262.1103 -59.83592 74 252.885 -59.38658 86.63513 319.7108 -9.588829 86.63513 319.7108 -9.588829 85.57209 320.0695 -6.858551 89.40941 320.6886 -5.657611 86.63513 319.7108 -9.588829 85.57209 320.0695 -6.858551 90.40032 320.3808 -8.379012 74 320.2604 0 85.45708 320.1087 -6.489296 85.45708 320.1087 -6.489296 84.76541 320.3463 -3.498599 88.80091 320.8785 -2.854199 84.76541 320.3463 -3.498599 84.73252 320.3578 -3.284728 84.73252 320.3578 -3.284728 84.4897 320.4435 0 88.58245 320.9403 0 84.4897 320.4435 0 74 320.235 1.742307 84.4897 320.4435 0 74 320.2604 0 84.55893 320.4191 1.751782 88.80207 320.8781 2.862216 84.4897 320.4435 0 84.55893 320.4191 1.751782 88.58245 320.9403 0 74 317.4 0 74 320.2604 0 74 319.5466 -9.215085 74 316.6148 9.428307 74 320.235 1.742307 74 316.6241 -9.373581 74 317.4272 -18.19599 74 314.3113 -18.50794 74 313.9562 -26.73733 74 310.5245 -27.13714 74 309.2187 -34.63909 74 305.4026 -34.9838 74 303.327 -41.71799 74 299.0168 -41.92382 74 296.4193 -47.80942 74 283.2396 -52.22257 74 288.6561 -52.77069 74 291.5526 -47.73216 74 274.319 -55.27311 74 280.2175 -56.48415 74 265.0384 -56.80979 74 243.8531 -57.52735 74 320.1589 3.483137 74 320.1589 3.483137 74 319.6776 8.327116 84.76554 320.3465 3.494072 74 319.6776 8.327116 84.7341 320.3576 3.289787 74 318.8127 13.08544 86.63505 319.7108 9.588647 74 318.8127 13.08544 85.45862 320.1065 6.509946 110 316.6148 -9.428307 110 316.6241 9.373581 110 317.4 0 74 314.2817 18.59349 74 317.5593 17.77374 89.92848 318.488 15.56974 74 317.5593 17.77374 86.97251 319.6001 10.28472 87.43457 319.4504 11.15536 74 315.928 22.35795 92.24659 317.2567 19.71825 74 315.928 22.35795 74 310.4753 27.22747 74 313.9327 26.78267 94.38862 315.8047 23.58644 74 313.9327 26.78267 74 311.581 31.04283 96.35285 314.189 27.14535 74 311.581 31.04283 74 305.3457 35.05654 74 308.9127 35.06959 99.76937 310.4836 33.59988 74 308.9127 35.06959 98.14414 312.4176 30.46409 74 298.974 41.96307 74 305.9239 38.87071 101.2271 308.4236 36.52563 74 305.9239 38.87071 74 302.6316 42.42091 102.504 306.2308 39.27611 74 302.6316 42.42091 74 291.5473 47.73582 74 299.0349 45.72173 104.5141 301.4682 44.27994 74 299.0349 45.72173 74 295.1938 48.70882 105.7116 296.4107 48.50841 74 295.1938 48.70882 74 283.2843 52.20334 74 291.1036 51.38469 74 291.1036 51.38469 74 286.8281 53.71015 106.0953 291.1454 52.01316 74 286.8281 53.71015 74 274.4084 55.25072 74 282.3655 55.68323 105.6813 285.7073 54.85723 74 282.3655 55.68323 74 265.1531 56.80035 74 277.7762 57.28282 104.4852 280.1208 57.0819 74 277.7762 57.28282 74 244.2717 57.64558 74 273.0647 58.50398 102.4925 274.3397 58.72595 74 273.0647 58.50398 74 255.7616 56.80979 74 248.9798 58.76075 74 268.2845 59.33881 74 268.2845 59.33881 74 253.7706 59.49101 74 263.4502 59.78145 99.68023 268.3403 59.78361 74 263.4502 59.78145 74 258.603 59.83331 96.02826 262.1213 60.22027 74 258.603 59.83331 128.249 262.1374 60.78245 74 253.7706 59.49101 126.4879 253.0824 60.3344 74 248.9798 58.76075 125.0955 244.2028 58.55326 74 244.2717 57.64558 74 239.6597 56.1523 74 239.6597 56.1523 74 246.4811 55.27311 74 235.1944 54.29383 124.0571 235.6645 55.46878 74 235.1944 54.29383 74 237.5604 52.22257 74 230.8794 52.0746 74 230.8794 52.0746 74 229.2474 47.73216 74 226.7692 49.51859 123.2887 227.635 51.12199 74 226.7692 49.51859 74 222.8622 46.62725 74 222.8622 46.62725 74 221.7832 41.92382 74 219.216 43.43968 122.6917 220.3196 45.59934 74 219.216 43.43968 74 215.8264 39.95335 74 215.8264 39.95335 74 215.3974 34.9838 74 212.7494 36.23196 122.17 213.9074 39.02651 74 212.7494 36.23196 74 209.9841 32.27398 74 209.9841 32.27398 74 210.2755 27.13714 74 207.5485 28.10411 121.6883 208.5652 31.57165 74 207.5485 28.10411 74 205.439 23.71424 74 205.439 23.71424 74 206.4887 18.50794 74 203.6942 19.17467 121.3255 204.4163 23.42362 74 203.6942 19.17467 74 202.3215 14.49043 121.1867 201.5327 14.73729 74 202.3215 14.49043 74 204.1759 9.373581 74 201.3339 9.718449 74 201.3339 9.718449 74 200.7415 4.893649 121.199 199.9812 5.670078 74 200.7415 4.893649 74 203.4 0 74 200.5396 0 121.206 199.7251 1.073406 74 200.5396 0 74 204.1852 -9.428307 74 200.565 -1.742307 74 200.565 -1.742307 74 200.6411 -3.483137 74 200.6411 -3.483137 74 201.8884 -12.63455 121.2172 199.8183 -3.531095 74 201.8884 -12.63455 74 206.5183 -18.59349 74 204.5234 -21.47105 121.1897 201.0881 -12.83183 74 204.5234 -21.47105 121.1868 200.2742 -8.212285 74 210.3247 -27.22747 74 208.4804 -29.79117 121.2877 203.7551 -21.77414 74 208.4804 -29.79117 121.2212 202.2514 -17.35966 74 215.4543 -35.05654 74 213.6632 -37.40055 121.6128 207.7612 -30.20948 74 213.6632 -37.40055 121.4191 205.5951 -26.06664 74 221.826 -41.96307 74 219.9491 -44.12306 122.0851 213.0321 -37.95697 74 219.9491 -44.12306 121.8344 210.2441 -34.18056 74 229.2527 -47.73582 74 227.1912 -49.80265 122.604 219.4432 -44.81178 74 227.1912 -49.80265 122.3475 216.1047 -41.50831 74 237.5157 -52.20334 74 235.2212 -54.30639 123.2015 226.8246 -50.59164 74 235.2212 -54.30639 122.8829 223.0249 -47.84601 74 255.6469 -56.80035 123.9924 234.9757 -55.15524 74 243.8531 -57.52735 74 246.3916 -55.25072 123.563 230.8188 -53.03334 125.0663 243.6983 -58.41084 110 203.4 0 74 203.4 0 74 204.1759 9.373581 110 204.1759 -9.373581 74 204.1852 -9.428307 74 203.4 0 110 203.4 0 110 204.1852 9.428307 74 206.4887 18.50794 110 206.5183 18.59349 74 210.2755 27.13714 110 210.3247 27.22747 74 215.3974 34.9838 110 215.4543 35.05654 74 221.7832 41.92382 110 221.826 41.96307 74 229.2474 47.73216 110 229.2527 47.73582 74 237.5604 52.22257 110 246.3916 55.25072 74 246.4811 55.27311 110 237.5157 52.20334 110 255.6469 56.80035 74 255.7616 56.80979 110 265.0384 56.80979 74 265.1531 56.80035 110 274.319 55.27311 74 274.4084 55.25072 110 283.2396 52.22257 74 283.2843 52.20334 74 291.5473 47.73582 110 291.5526 47.73216 74 298.974 41.96307 110 299.0168 41.92382 74 305.3457 35.05654 110 305.4026 34.9838 74 310.4753 27.22747 110 310.5245 27.13714 74 314.2817 18.59349 110 314.3113 18.50794 74 316.6148 9.428307 110 316.6241 9.373581 74 317.4 0 110 317.4 0 74 317.4 0 74 316.6241 -9.373581 110 317.4 0 110 316.6148 -9.428307 74 314.3113 -18.50794 110 314.2817 -18.59349 74 310.5245 -27.13714 110 310.4753 -27.22747 74 305.4026 -34.9838 110 305.3457 -35.05654 74 299.0168 -41.92382 110 298.974 -41.96307 74 291.5526 -47.73216 110 291.5473 -47.73582 74 283.2396 -52.22257 110 274.4084 -55.25072 74 274.319 -55.27311 110 283.2843 -52.20334 110 265.1531 -56.80035 74 265.0384 -56.80979 110 255.7616 -56.80979 74 255.6469 -56.80035 110 246.4811 -55.27311 74 246.3916 -55.25072 110 237.5604 -52.22257 74 237.5157 -52.20334 74 229.2527 -47.73582 110 229.2474 -47.73216 74 221.826 -41.96307 110 221.7832 -41.92382 74 215.4543 -35.05654 110 215.3974 -34.9838 74 210.3247 -27.22747 110 210.2755 -27.13714 74 206.5183 -18.59349 110 206.4887 -18.50794 84.7341 320.3576 3.289787 89.41407 320.6871 5.673157 84.76554 320.3465 3.494072 85.45862 320.1065 6.509946 110 314.2817 -18.59349 110 314.3113 18.50794 90.40033 320.3808 8.379034 86.63505 319.7108 9.588647 91.07701 320.1785 9.764589 86.63505 319.7108 9.588647 86.97251 319.6001 10.28472 90.40033 320.3808 8.379034 87.43457 319.4504 11.15536 91.07701 320.1785 9.764589 87.43457 319.4504 11.15536 89.92848 318.488 15.56974 94.55227 318.7122 16.45559 92.24659 317.2567 19.71825 94.38862 315.8047 23.58644 97.90721 316.4928 22.95389 96.35285 314.189 27.14535 101.0357 313.5312 29.19467 98.14414 312.4176 30.46409 99.76937 310.4836 33.59988 103.8183 309.8407 35.10761 101.2271 308.4236 36.52563 102.504 306.2308 39.27611 106.1178 305.4436 40.61151 104.5141 301.4682 44.27994 107.7877 300.3761 45.61631 105.7116 296.4107 48.50841 108.6815 294.7035 50.0222 106.0953 291.1454 52.01316 108.6765 288.5307 53.7286 105.6813 285.7073 54.85723 107.7059 282.0015 56.6545 104.4852 280.1208 57.0819 105.7828 275.2829 58.75719 102.4925 274.3397 58.72595 102.9891 268.5362 60.03713 99.68023 268.3403 59.78361 96.58053 262.6059 60.21524 96.02826 262.1213 60.22027 110 310.4753 -27.22747 110 310.5245 27.13714 97.3738 263.2861 60.20641 97.45468 263.357 60.20529 97.87651 263.732 60.19865 98.44198 264.2419 60.18793 99.13787 264.8717 60.17274 99.93679 265.6062 60.15193 100.8656 266.476 60.12306 101.4574 267.0398 60.10194 101.9742 267.5385 60.08173 102.6678 268.2176 60.05197 128.5181 263.2998 60.75393 96.02826 262.1213 60.22027 128.249 262.1374 60.78245 96.96992 262.7546 60.21861 110 305.3457 -35.05654 110 305.4026 34.9838 96.88724 262.806 60.215 96.02826 262.1213 60.22027 96.96992 262.7546 60.21861 96.70634 262.7042 60.21442 96.58053 262.6059 60.21524 129.6118 261.815 60.6164 128.249 262.1374 60.78245 126.4879 253.0824 60.3344 128.5181 263.2998 60.75393 128.249 262.1374 60.78245 129.6118 261.815 60.6164 126.4433 244.1812 58.37969 125.0955 244.2028 58.55326 127.8409 252.9016 60.14357 125.3992 235.8737 55.39252 124.0571 235.6645 55.46878 124.6229 228.1184 51.25273 123.2887 227.635 51.12199 124.0114 221.0509 46.04731 122.6917 220.3196 45.59934 123.481 214.8315 39.90142 122.17 213.9074 39.02651 122.9784 209.5894 32.96654 121.6883 208.5652 31.57165 122.5566 205.393 25.35414 121.3255 204.4163 23.42362 122.338 202.3162 17.19005 121.1867 201.5327 14.73729 122.29 200.4432 8.672803 121.199 199.9812 5.670078 121.206 199.7251 1.073406 122.303 199.8158 0.005465984 121.2172 199.8183 -3.531095 121.1868 200.2742 -8.212285 122.3015 200.4403 -8.655743 121.1897 201.0881 -12.83183 122.3416 202.3096 -17.16872 121.2212 202.2514 -17.35966 121.2877 203.7551 -21.77414 122.5593 205.3839 -25.33296 121.4191 205.5951 -26.06664 121.6128 207.7612 -30.20948 122.9728 209.5758 -32.94645 121.8344 210.2441 -34.18056 122.0851 213.0321 -37.95697 123.4713 214.813 -39.87993 122.3475 216.1047 -41.50831 122.604 219.4432 -44.81178 123.9879 221.0283 -46.02692 122.8829 223.0249 -47.84601 123.2015 226.8246 -50.59164 124.6053 228.1009 -51.24126 123.563 230.8188 -53.03334 123.9924 234.9757 -55.15524 125.4115 235.8686 -55.39023 125.0663 243.6983 -58.41084 126.4862 244.184 -58.38125 126.484 252.8308 -60.30329 127.8804 252.9022 -60.14422 128.2531 262.1374 -60.78252 130.1483 264.1517 -60.55881 128.2531 262.1374 -60.78252 128.5193 263.3 -60.75394 129.6163 261.819 -60.61502 129.6163 261.819 -60.61502 93.18964 322.0723 4.96096 92.68201 322.225 2.499225 92.50154 322.2723 0 96.6286 324.2044 4.403673 96.20971 324.3409 2.21635 99.5867 326.9953 4.024808 99.23437 327.1367 2.025759 96.06967 324.3874 0 101.9412 330.3274 3.839929 101.628 330.4926 1.935426 99.12419 327.1936 0 103.4028 334.1868 2.868255 103.2813 334.2694 1.940771 101.5302 330.5617 0 103.5851 334.0661 3.848743 108.5547 350.8091 1.585274 103.2813 334.2694 1.940771 103.4028 334.1868 2.868255 103.1797 334.3393 0 103.1797 334.3393 0 108.8226 350.8756 3.15175 103.5851 334.0661 3.848743 104.085 333.7485 5.682728 109.0939 351.0652 4.022743 104.085 333.7485 5.682728 108.9399 350.9356 3.585469 100.1761 326.7796 5.96298 102.464 330.0803 5.677945 97.31939 323.9871 6.525559 94.01332 321.8245 7.342851 104.2338 333.656 6.095947 104.085 333.7485 5.682728 102.464 330.0803 5.677945 107.0321 342.8895 5.707075 104.085 333.7485 5.682728 110.0661 352.2416 5.7785 110.164 352.3941 5.90829 109.7733 351.8569 5.343812 107.0321 342.8895 5.707075 109.2862 351.2665 4.464313 109.5137 351.5326 4.906021 104.2338 333.656 6.095947 102.8076 329.8898 6.622468 100.1761 326.7796 5.96298 104.4319 333.5263 6.603207 100.5634 326.6137 6.966196 97.31939 323.9871 6.525559 97.78395 323.8331 7.623665 94.01332 321.8245 7.342851 94.57915 321.6595 8.569121 92.50154 322.2723 0 92.68103 322.2253 -2.492198 96.06967 324.3874 0 99.23371 327.137 -2.019999 99.12419 327.1936 0 96.20891 324.3411 -2.210086 101.6274 330.493 -1.929889 101.5302 330.5617 0 103.1797 334.3393 0 103.2863 334.2656 -1.988729 108.5549 350.809 -1.586725 103.2863 334.2656 -1.988729 108.465 350.7871 -9.69e-4 94.01329 321.8245 -7.34283 96.62548 324.2054 -4.391651 97.31938 323.9871 -6.525541 93.18581 322.0735 -4.947367 99.58414 326.9963 -4.013919 100.1761 326.7796 -5.962963 101.9389 330.3287 -3.829689 102.464 330.0803 -5.677928 103.5932 334.0606 -3.886435 104.0875 333.7477 -5.681748 109.773 351.8563 -5.343484 104.0875 333.7477 -5.681748 103.5932 334.0606 -3.886435 110.3509 352.6057 -6.185422 104.0875 333.7477 -5.681748 107.0318 342.8896 -5.707177 110.0629 352.2426 -5.779816 110.1457 352.3677 -5.884371 107.0318 342.8896 -5.707177 110.2215 352.4698 -5.987438 103.4393 334.1628 -3.090584 108.94 350.9357 -3.585777 103.4393 334.1628 -3.090584 109.5133 351.5319 -4.905634 109.286 351.2661 -4.464278 109.094 351.0652 -4.023076 108.8226 350.8756 -3.15177 110.5456 352.6433 -6.578977 110 299.0168 41.92382 110.4576 352.6611 -6.381585 110.0629 352.2426 -5.779816 110.3491 353.2406 -5.735692 110.1457 352.3677 -5.884371 110.0629 352.2426 -5.779816 110.152 352.6683 -5.681579 110.0629 352.2426 -5.779816 109.773 351.8563 -5.343484 110.152 352.6683 -5.681579 111.0758 353.3021 -7.211934 110.5346 352.3898 -6.721432 110.5493 352.4901 -6.686539 110.8108 352.8443 -6.96391 111.3602 351.7477 -8.67147 110.5346 352.3898 -6.721432 110.8108 352.8443 -6.96391 110.977 351.3055 -8.210206 110 298.974 -41.96307 111.0256 353.407 -7.051347 110.9674 353.4841 -6.89061 110.5456 352.6433 -6.578977 110 283.2843 -52.20334 110 291.5526 47.73216 110 291.5473 -47.73582 110.9029 353.5314 -6.734655 110.6931 353.0963 -6.580119 110.5456 352.6433 -6.578977 110.4576 352.6611 -6.381585 110.6931 353.0963 -6.580119 110.6576 353.5238 -6.238432 110.3509 352.6057 -6.185422 110.8337 353.5511 -6.585107 110.7504 353.5541 -6.414313 110.5589 353.4603 -6.065168 110.2215 352.4698 -5.987438 110.4557 353.365 -5.896948 110.0661 352.2416 5.7785 109.9655 352.6959 5.183135 109.7733 351.8569 5.343812 110.0661 352.2416 5.7785 110.152 352.6683 5.681578 110.0661 352.2416 5.7785 110.164 352.3941 5.90829 110.152 352.6683 5.681578 109.7152 352.3532 -4.771897 109.5133 351.5319 -4.905634 110.2416 353.0938 -5.583175 109.9632 352.6929 -5.179328 109.4969 352.0714 -4.360017 109.286 351.2661 -4.464278 109.3123 351.857 -3.947366 109.094 351.0652 -4.023076 109.1651 351.7195 -3.537776 108.94 350.9357 -3.585777 108.8226 350.8756 -3.15177 108.9366 351.2662 -3.14153 108.8226 350.8756 -3.15177 108.5549 350.809 -1.586725 108.9366 351.2662 -3.14153 109.0538 351.6558 -3.130634 108.465 350.7871 -9.69e-4 108.703 351.5699 0 108.5547 350.8091 1.585274 108.8226 350.8756 3.15175 108.9366 351.2662 3.141521 108.8226 350.8756 3.15175 108.9399 350.9356 3.585469 108.9366 351.2662 3.141521 109.1668 351.7215 3.542412 109.0939 351.0652 4.022743 109.0538 351.6558 3.130626 109.3153 351.8605 3.954563 109.2862 351.2665 4.464313 109.5006 352.076 4.367617 109.5137 351.5326 4.906021 109.7188 352.3579 4.778213 110.5566 352.5632 6.65388 104.4319 333.5263 6.603207 110.5345 352.3895 6.72144 106.3885 332.2547 11.45554 110.5345 352.3895 6.72144 104.4319 333.5263 6.603207 111.0294 353.3995 7.063343 110.5566 352.5632 6.65388 110.5345 352.3895 6.72144 110.9239 351.3999 8.05247 110.8107 352.8439 6.96387 110.5345 352.3895 6.72144 110.9239 351.3999 8.05247 110.8107 352.8439 6.96387 110.4111 352.6452 6.291219 110.5449 352.6439 6.577274 110 274.4084 -55.25072 110 283.2396 52.22257 106.0205 327.8363 14.48867 106.3885 332.2547 11.45554 104.4319 333.5263 6.603207 102.8076 329.8898 6.622468 110.2558 352.5116 6.036361 110.4621 353.372 5.906848 110.2558 352.5116 6.036361 110.2416 353.0938 5.583174 110.3533 353.246 5.741737 110.4111 352.6452 6.291219 110.6639 353.5277 6.249513 110.5449 352.6439 6.577274 110.6912 353.0925 6.578598 110.9731 353.4772 6.906038 110.5449 352.6439 6.577274 110.9072 353.5288 6.744768 110.8337 353.5513 6.585051 110.6912 353.0925 6.578598 111.4124 350.5408 9.492228 111.4936 351.5705 9.029276 111.4124 350.5408 9.492228 112.0113 349.815 11.03912 112.0113 349.815 11.03912 112.68 349.1436 12.65987 112.3941 350.6996 11.22295 112.68 349.1436 12.65987 108.2888 330.6885 16.14306 113.4178 348.5155 14.35437 113.3942 350.0263 13.43649 113.4178 348.5155 14.35437 114.2179 347.9008 16.12354 114.4531 349.4539 15.64866 114.2179 347.9008 16.12354 115.0841 347.2908 17.97419 115.5535 348.9369 17.85282 115.0841 347.2908 17.97419 110.1119 328.8298 20.67453 116.0176 346.6758 19.90836 116.0176 346.6758 19.90836 117.0302 346.0441 21.94665 116.6863 348.4525 20.04538 117.0302 346.0441 21.94665 111.8419 326.6861 25.04942 118.1242 345.3934 24.08683 117.8476 347.9899 22.22541 118.1242 345.3934 24.08683 118.8949 344.948 25.56124 119.0343 347.5399 24.39231 118.8949 344.948 25.56124 113.5332 324.1746 29.43671 119.7005 344.4931 27.07427 120.2441 347.096 26.5456 119.7005 344.4931 27.07427 120.5431 344.0266 28.62841 120.5431 344.0266 28.62841 121.4223 343.549 30.22045 121.4758 346.6557 28.68489 121.4223 343.549 30.22045 118.997 322.271 39.00466 122.3427 343.0579 31.85637 122.7288 346.2168 30.80981 122.3427 343.0579 31.85637 123.3101 342.5505 33.54366 124.0022 345.7778 32.92007 123.3101 342.5505 33.54366 124.3242 342.0272 35.27857 125.2956 345.3382 35.01551 124.3242 342.0272 35.27857 125.3847 341.4888 37.05754 125.3847 341.4888 37.05754 126.4921 340.9351 38.87838 126.6088 344.897 37.09596 126.4921 340.9351 38.87838 127.6488 340.3653 40.74189 127.9414 344.4537 39.16123 127.6488 340.3653 40.74189 124.9702 320.3474 48.35301 128.8567 339.7781 42.6484 129.293 344.0076 41.21117 128.8567 339.7781 42.6484 130.1169 339.1735 44.59606 130.6632 343.5578 43.24559 130.1169 339.1735 44.59606 131.0983 338.7079 46.08485 132.0517 343.1039 45.26432 131.0983 338.7079 46.08485 132.1119 338.2314 47.59766 133.4584 342.6455 47.26726 132.1119 338.2314 47.59766 133.1577 337.744 49.1331 133.1577 337.744 49.1331 131.3665 318.3131 57.39713 134.2374 337.2455 50.69192 134.883 342.1826 49.2543 134.2374 337.2455 50.69192 135.3528 336.7355 52.27475 136.3255 341.715 51.22537 135.3528 336.7355 52.27475 136.5041 336.2139 53.88052 137.7858 341.2428 53.18036 136.5041 336.2139 53.88052 137.692 335.6805 55.50824 139.2637 340.7659 55.11919 137.692 335.6805 55.50824 138.9169 335.1351 57.15715 138.9169 335.1351 57.15715 120.61 294.3535 57.80041 138.9169 335.1351 57.15715 131.3665 318.3131 57.39713 140.7599 340.2839 57.04258 141.7803 340.023 57.9992 140.7599 340.2839 57.04258 138.9169 335.1351 57.15715 139.8844 334.7275 58.117 121.5469 293.956 58.82896 139.8844 334.7275 58.117 120.3469 301.9743 52.93262 129.8333 314.9069 57.44483 129.8333 314.9069 57.44483 120.56 294.3743 57.72541 119.297 309.1636 47.23015 114.9479 321.6585 33.25259 118.4764 312.5463 44.05452 117.4704 315.7701 40.66286 116.2909 318.8104 37.06379 111.9767 320.9818 29.46196 113.5332 324.1746 29.43671 111.8419 326.6861 25.04942 114.9479 321.6585 33.25259 109.1118 324.8612 22.12753 110.1119 328.8298 20.67453 108.2888 330.6885 16.14306 120.56 294.3743 57.72541 118.5966 297.0234 53.9268 120.56 294.3743 57.72541 120.3469 301.9743 52.93262 120.049 293.0682 57.86926 120.61 294.3535 57.80041 120.56 294.3743 57.72541 120.049 293.0682 57.86926 117.9506 304.1734 48.75226 119.297 309.1636 47.23015 116.5365 310.5995 42.87437 118.4764 312.5463 44.05452 117.4704 315.7701 40.66286 114.497 316.2181 36.4092 116.2909 318.8104 37.06379 141.8054 345.6408 56.86187 141.8054 345.6408 56.86187 140.5925 345.891 55.3242 144.0459 362.8073 56.28039 140.5925 345.891 55.3242 141.8054 345.6408 56.86187 142.5709 345.5615 57.62332 145.997 371.1189 56.83715 141.8054 345.6408 56.86187 142.5709 345.5615 57.62332 144.0459 362.8073 56.28039 139.4196 346.1306 53.81512 138.2858 346.3597 52.33514 137.1909 346.5784 50.88531 135.7906 346.854 49.00115 134.4541 347.1132 47.17043 131.9637 347.5856 43.67092 132.9928 347.3921 45.13122 133.1789 347.3569 45.39314 130.8018 347.8016 41.99718 129.6927 348.0052 40.37422 127.618 348.3808 37.26832 128.633 348.1976 38.79955 126.648 348.5545 35.78371 125.268 348.8005 33.63377 123.9745 349.0303 31.57679 124.736 348.8951 32.79285 122.757 349.2466 29.60158 121.6112 349.4509 27.70665 120.5285 349.6464 25.8818 118.5309 350.0182 22.42049 119.5035 349.835 24.12163 117.6033 350.202 20.76632 116.7179 350.3881 19.15614 117.1377 350.2981 19.92367 115.0689 350.7842 16.06045 115.8723 350.5814 17.58589 114.3157 350.9992 14.5949 112.9338 351.5171 11.77864 113.6066 351.2408 13.17347 111.8057 352.2357 9.245554 112.3313 351.8466 10.46549 111.0757 353.3019 7.211991 111.0757 353.3019 7.211991 123.7592 374.6646 20.33613 111.0757 353.3019 7.211991 111.8057 352.2357 9.245554 111.0294 353.3995 7.063343 112.3313 351.8466 10.46549 117.1377 350.2981 19.92367 112.9338 351.5171 11.77864 115.8723 350.5814 17.58589 113.6066 351.2408 13.17347 116.7179 350.3881 19.15614 115.0689 350.7842 16.06045 114.3157 350.9992 14.5949 118.5309 350.0182 22.42049 117.6033 350.202 20.76632 119.5035 349.835 24.12163 120.5285 349.6464 25.8818 121.6112 349.4509 27.70665 122.757 349.2466 29.60158 123.9745 349.0303 31.57679 124.736 348.8951 32.79285 126.648 348.5545 35.78371 125.268 348.8005 33.63377 127.618 348.3808 37.26832 128.633 348.1976 38.79955 129.6927 348.0052 40.37422 131.3688 375.6854 33.70275 130.8018 347.8016 41.99718 131.9637 347.5856 43.67092 132.9928 347.3921 45.13122 133.1789 347.3569 45.39314 139.7854 377.2149 46.67034 134.4541 347.1132 47.17043 135.7906 346.854 49.00115 137.1909 346.5784 50.88531 138.2858 346.3597 52.33514 139.4196 346.1306 53.81512 144.4946 345.337 58.57052 144.3688 339.3236 58.85772 145.5585 345.2028 58.71045 146.6721 347.2275 58.67202 145.5585 345.2028 58.71045 144.3688 339.3236 58.85772 147.8803 362.2859 58.26271 144.4946 345.337 58.57052 145.5585 345.2028 58.71045 147.8803 362.2859 58.26271 144.1478 345.3794 58.47244 143.0164 339.694 58.62085 142.3414 333.6596 58.98421 137.904 305.8088 59.70278 142.3414 333.6596 58.98421 143.4817 345.4587 58.20293 141.0574 334.2221 58.74288 142.8599 345.5297 57.83806 146.9375 370.9955 57.4798 142.8599 345.5297 57.83806 143.4817 345.4587 58.20293 147.9978 370.8481 57.88864 144.1478 345.3794 58.47244 133.2809 313.2206 59.4102 142.3414 333.6596 58.98421 141.0574 334.2221 58.74288 133.2809 313.2206 59.4102 124.1763 292.8011 59.83487 122.7929 293.4139 59.5558 110 274.319 55.27311 110 265.1531 -56.80035 110 265.0384 56.80979 166.3609 472.2095 55.25054 168.5806 476.1858 55.36856 173.1549 497.0505 54.85206 178.2055 513.6084 54.46698 173.1549 497.0505 54.85206 168.5806 476.1858 55.36856 171.766 497.3516 54.60955 174.26 503.0787 54.69906 171.766 497.3516 54.60955 173.1549 497.0505 54.85206 174.26 503.0787 54.69906 164.3272 455.8572 55.87535 170.8541 471.9127 55.5304 164.3272 455.8572 55.87535 161.2021 446.9596 55.89841 160.3947 436.0644 56.37241 160.3947 436.0644 56.37241 156.3959 421.659 56.55335 156.7824 416.8048 56.85984 163.1481 430.284 56.58572 156.7824 416.8048 56.85984 151.9791 396.289 57.21651 153.492 398.0855 57.33743 153.492 398.0855 57.33743 150.5248 379.9133 57.80504 155.0871 388.7207 57.63296 150.5248 379.9133 57.80504 150.8735 396.4632 56.76467 155.2466 421.8587 56.05695 160.011 447.1838 55.35612 165.1299 472.4569 54.66123 170.4959 497.6167 53.97222 173.399 506.0709 54.41917 170.4959 497.6167 53.97222 164.1044 472.6524 53.7479 169.4569 497.8221 52.98835 172.1869 506.2147 53.87122 169.4569 497.8221 52.98835 149.9065 396.6074 56.05672 154.2567 422.0218 55.28186 159.0016 447.3642 54.51245 164.2475 477.0611 52.42507 168.3509 496.2026 51.80006 168.7324 497.9516 51.74466 171.1627 506.326 53.01771 168.7324 497.9516 51.74466 146.5969 380.5155 55.68253 149.4683 398.7625 55.06765 156.2039 436.8619 53.78875 152.6712 417.5472 54.43826 160.0624 456.6997 53.11461 164.0247 490.1041 44.72381 168.3509 496.2026 51.80006 168.7324 497.9516 51.74466 169.948 503.7039 51.87721 166.6361 501.5234 45.95058 168.7324 497.9516 51.74466 169.948 503.7039 51.87721 164.0247 490.1041 44.72381 146.5969 380.5155 55.68253 149.4683 398.7625 55.06765 146.7149 407.0116 48.10616 152.6712 417.5472 54.43826 153.797 436.7776 49.4334 156.2039 436.8619 53.78875 160.0624 456.6997 53.11461 161.0246 466.5125 50.65669 164.2475 477.0611 52.42507 159.288 482.8614 36.91776 170.5533 548.4019 53.28125 171.2375 548.7301 53.34142 168.0995 556.595 53.06182 172.9983 550.0427 53.33465 168.0995 556.595 53.06182 171.2375 548.7301 53.34142 167.5299 556.3164 53.01937 164.1524 561.8379 52.68492 167.5299 556.3164 53.01937 168.0995 556.595 53.06182 166.6854 559.4943 52.95426 162.6549 570.858 52.55907 166.6854 559.4943 52.95426 172.6011 540.2249 53.53088 173.5587 539.9397 53.63321 174.7145 546.4393 53.46762 173.5587 539.9397 53.63321 173.8647 531.8702 53.76949 175.0391 530.3038 53.93449 177.5261 539.3657 53.71889 175.0391 530.3038 53.93449 176.2141 542.8803 53.59553 174.4167 523.3727 53.99752 175.4407 525.1987 54.08742 179.5793 529.0911 54.04843 175.4407 525.1987 54.08742 178.5632 535.8959 53.83618 179.2341 532.5231 53.9443 175.5904 519.947 54.24014 179.3227 521.6325 54.25714 175.5904 519.947 54.24014 179.5843 525.4379 54.15293 174.2691 514.7611 54.2145 175.4833 514.5297 54.39311 178.8717 517.6911 54.36192 175.4833 514.5297 54.39311 175.0393 508.9067 54.54608 175.0393 508.9067 54.54608 173.1327 514.8001 53.75165 173.3707 523.323 53.61487 172.9218 531.747 53.46156 171.7731 540.0413 53.2916 169.8518 548.1684 53.10395 166.9693 556.0391 52.89651 166.9693 556.0391 52.89651 169.1853 547.9423 52.81647 166.4284 555.7684 52.69499 166.4284 555.7684 52.69499 172.1437 514.825 53.02455 172.4362 523.2709 53.00893 172.0597 531.6279 52.97018 171.0001 539.8648 52.90684 168.5286 547.8304 52.41991 165.9167 555.5092 52.41864 164.5174 558.4131 52.31973 165.9167 555.5092 52.41864 163.1142 561.3107 52.22074 170.7922 509.1944 51.98234 171.6197 519.9062 52.16606 170.8036 509.2846 51.98394 171.3469 514.6856 52.0772 171.6385 524.9754 52.23556 171.6403 520.7675 52.17942 171.2168 532.6635 52.33491 171.4324 529.916 52.30224 169.376 544.494 52.42348 170.3748 539.267 52.38773 164.6562 550.2944 50.54376 168.5286 547.8304 52.41991 165.9167 555.5092 52.41864 163.1142 561.3107 52.22074 165.9167 555.5092 52.41864 164.5174 558.4131 52.31973 164.6562 550.2944 50.54376 170.7922 509.1944 51.98234 167.292 511.7838 46.04125 170.8036 509.2846 51.98394 171.3469 514.6856 52.0772 171.6197 519.9062 52.16606 171.6403 520.7675 52.17942 167.6018 523.8251 47.38499 171.6385 524.9754 52.23556 171.4324 529.916 52.30224 171.2168 532.6635 52.33491 166.4567 535.691 48.41112 170.3748 539.267 52.38773 169.376 544.494 52.42348 163.2871 545.3167 48.47967 161.8168 540.5763 46.21861 165.2659 562.3909 52.84667 165.2659 562.3909 52.84667 162.8202 567.0697 52.67023 164.1524 561.8379 52.68492 165.2659 562.3909 52.84667 162.8202 567.0697 52.67023 160.5555 568.6147 52.43857 163.1142 561.3107 52.22074 158.3195 570.1597 51.93275 153.3019 572.0261 50.08963 163.1142 561.3107 52.22074 158.3195 570.1597 51.93275 161.0086 559.1134 50.61926 161.0086 559.1134 50.61926 152.0888 580.8278 51.9498 154.4604 579.7416 52.16205 148.0295 587.1405 51.83827 157.3284 581.1897 52.17074 148.0295 587.1405 51.83827 154.4604 579.7416 52.16205 147.182 586.3167 51.7048 134.8133 598.9592 51.11772 147.182 586.3167 51.7048 148.0295 587.1405 51.83827 141.867 593.4888 51.5492 151.8901 591.4863 51.78147 141.867 593.4888 51.5492 156.5378 574.9403 52.19377 160.204 571.5211 52.49731 160.204 571.5211 52.49731 155.6287 574.2962 51.78184 152.7599 578.2138 51.62692 146.3873 585.5314 51.29741 140.2549 591.8026 50.9951 146.3873 585.5314 51.29741 134.0013 598.1451 50.68305 152.7599 578.2138 51.62692 146.3873 585.5314 51.29741 155.6287 574.2962 51.78184 144.1758 583.6853 49.77828 134.0013 598.1451 50.68305 146.3873 585.5314 51.29741 140.2549 591.8026 50.9951 144.1758 583.6853 49.77828 135.6829 599.8162 51.26036 140.7409 611.8579 51.0045 135.6829 599.8162 51.26036 133.1687 602.1738 51.14907 134.8133 598.9592 51.11772 135.6829 599.8162 51.26036 133.1687 602.1738 51.14907 131.5618 602.2122 51.02228 134.0013 598.1451 50.68305 131.645 600.7431 50.71829 131.8065 597.9566 49.89427 134.0013 598.1451 50.68305 131.645 600.7431 50.71829 132.6506 593.6193 48.6554 134.9257 593.6296 49.46018 134.9257 593.6296 49.46018 119.1336 609.8837 50.66552 119.7207 609.8464 50.68941 115.2703 611.8452 50.56008 119.5332 610.1948 50.6817 117.1636 610.4385 50.61376 119.1336 609.8837 50.66552 115.2703 611.8452 50.56008 115.2703 611.8452 50.56008 119.5332 610.1948 50.6817 78.5 608.9732 49.91852 117.1636 610.4385 50.61376 115.2703 611.8452 50.56008 78.5 613.4347 49.84507 138.7921 615.8198 50.70246 140.7409 611.8579 51.0045 122.7147 607.8389 50.73527 123.9713 607.6068 50.80988 123.4579 608.4023 50.80147 126.0319 605.6458 50.77231 127.9405 605.0765 50.92054 127.0504 606.4672 50.91951 124.939 606.409 50.76372 130.2421 602.1396 50.74643 130.2931 604.3908 51.03549 129.0185 603.2642 50.76527 130.2421 602.1396 50.74643 129.1733 598.8491 49.63616 129.0185 603.2642 50.76527 127.385 602.7887 50.37024 126.0319 605.6458 50.77231 124.939 606.409 50.76372 121.9553 606.1175 50.51622 122.7147 607.8389 50.73527 124.4046 603.1265 50.21614 118.9087 609.0128 50.62524 123.4579 608.4023 50.80147 127.0504 606.4672 50.91951 130.2931 604.3908 51.03549 126.2537 599.9367 49.68259 127.4652 596.4736 48.84715 130.1616 594.7393 48.51872 127.8962 592.8582 47.6764 130.3263 590.6307 47.01794 127.533 589.1442 46.13349 129.7663 586.6801 45.17837 132.7772 589.3378 47.05366 126.4853 585.5353 44.27186 128.6415 582.9792 43.05879 132.2838 585.2465 45.13525 124.8235 582.0162 42.06745 127.1019 579.5585 40.70761 131.3067 581.4178 42.95297 125.7251 583.7717 43.21847 122.5726 578.5219 39.43481 125.266 576.4224 38.16274 129.9687 577.8713 40.54899 123.774 580.2745 40.81544 121.4774 574.3645 35.7929 123.2199 573.5654 35.45221 128.3696 574.6078 37.95738 119.7156 575.0375 36.27345 121.2197 576.7714 37.92153 118.6558 570.7945 31.84792 123.2199 573.5654 35.45221 121.4774 574.3645 35.7929 124.9272 572.6475 35.25468 120.9163 569.6375 31.31516 124.9272 572.6475 35.25468 119.7156 575.0375 36.27345 78.5 571.7433 31.61563 119.7156 575.0375 36.27345 121.2197 576.7714 37.92153 116.3443 571.7053 32.60404 116.3443 571.7053 32.60404 78.5 577.6932 37.73798 122.5726 578.5219 39.43481 123.774 580.2745 40.81544 124.8235 582.0162 42.06745 125.7251 583.7717 43.21847 78.5 584.6002 42.75815 126.4853 585.5353 44.27186 127.533 589.1442 46.13349 78.5 592.2657 46.52997 127.8962 592.8582 47.6764 127.4652 596.4736 48.84715 126.2537 599.9367 49.68259 78.5 600.4689 48.94146 124.4046 603.1265 50.21614 121.9553 606.1175 50.51622 118.9087 609.0128 50.62524 135.1815 588.6961 47.71107 134.7836 583.8903 45.57441 133.7784 579.2586 43.02811 134.3468 581.5752 44.3612 132.1284 574.4915 39.82436 133.064 576.9384 41.55553 126.5816 571.6195 35.20318 130.9869 571.9301 37.81912 123.0939 568.2579 31.02131 126.5816 571.6195 35.20318 128.1647 570.4938 35.29719 125.1521 566.6788 30.97128 128.1647 570.4938 35.29719 142.049 581.8507 48.18965 135.1815 588.6961 47.71107 140.0076 580.0281 46.53654 134.7836 583.8903 45.57441 138.0488 578.2212 44.82304 134.3468 581.5752 44.3612 136.1766 576.4271 43.05395 133.7784 579.2586 43.02811 133.064 576.9384 41.55553 134.4013 574.637 41.23545 132.1284 574.4915 39.82436 132.7261 572.8475 39.37314 130.9869 571.9301 37.81912 129.6642 569.2796 35.53549 131.1472 571.0619 37.47154 129.6642 569.2796 35.53549 128.3637 566.9689 33.33068 129.6642 569.2796 35.53549 136.211 557.1171 33.97536 138.1851 558.7699 36.24005 129.6642 569.2796 35.53549 131.1472 571.0619 37.47154 128.3637 566.9689 33.33068 127.0522 564.9207 31.15779 78.5 617.8348 49.38235 78.5 608.9732 49.91852 78.5 613.4347 49.84507 78.5 600.4689 48.94146 78.5 617.8348 49.38235 136.9802 619.7331 50.09773 78.5 622.1904 48.52596 78.5 622.1904 48.52596 133.7673 627.3227 48.00833 78.5 626.451 47.28908 78.5 626.451 47.28908 78.5 630.5824 45.67768 78.5 610.4229 46.99877 78.5 630.5824 45.67768 131.1066 634.4725 44.79914 78.5 634.5541 43.70889 78.5 626.4625 44.16893 78.5 634.5541 43.70889 78.5 618.568 46.28363 128.9701 641.0275 40.55387 78.5 638.3334 41.39453 78.5 638.3334 41.39453 78.5 641.8932 38.75652 78.5 633.8741 40.71679 78.5 641.8932 38.75652 127.313 646.8435 35.37791 78.5 645.2034 35.812 78.5 640.5817 36.02696 78.5 645.2034 35.812 78.5 648.2413 32.58721 78.5 648.2413 32.58721 126.0749 651.7964 29.39153 78.5 650.9799 29.10419 78.5 646.3702 30.25212 78.5 650.9799 29.10419 78.5 653.4012 25.39265 78.5 653.4012 25.39265 125.1906 655.7803 22.72857 78.5 655.4826 21.4788 78.5 651.0531 23.5842 78.5 655.4826 21.4788 124.6028 658.7102 15.52574 78.5 657.2113 17.39518 78.5 657.2113 17.39518 78.5 658.5694 13.17166 78.5 654.5388 16.14717 78.5 658.5694 13.17166 124.2663 660.5187 7.901792 78.5 659.5498 8.842516 78.5 659.5498 8.842516 78.5 660.138 4.457489 78.5 656.6793 8.199214 78.5 660.138 4.457489 124.1562 661.1359 0 78.5 660.3389 0 78.5 660.3389 0 124.2661 660.5195 -7.896456 78.5 659.6052 -8.528938 78.5 657.4 0 78.5 659.6052 -8.528938 124.6021 658.7137 -15.51457 78.5 657.429 -16.79783 78.5 654.5664 -16.07196 78.5 657.429 -16.79783 78.5 656.6873 -8.154454 125.1889 655.7884 -22.71232 78.5 653.8776 -24.56804 78.5 651.1028 -23.49881 78.5 653.8776 -24.56804 126.0716 651.8102 -29.372 78.5 649.0567 -31.61563 78.5 646.4336 -30.17697 78.5 649.0567 -31.61563 127.3078 646.8629 -35.35772 78.5 643.1068 -37.73798 78.5 640.6393 -35.97861 78.5 643.1068 -37.73798 128.963 641.0512 -40.53584 78.5 636.1998 -42.75815 78.5 633.9048 -40.69878 78.5 636.1998 -42.75815 131.098 634.4974 -44.78562 78.5 628.5343 -46.52997 78.5 626.4565 -44.17075 78.5 628.5343 -46.52997 133.7588 627.3443 -48.00055 78.5 620.3311 -48.94146 78.5 610.3771 -46.99877 78.5 620.3311 -48.94146 78.5 618.5329 -46.28967 115.2705 611.8453 -50.56008 78.5 611.8269 -49.91852 78.5 602.9652 -49.38235 78.5 611.8269 -49.91852 140.7409 611.858 -51.00449 138.7887 615.8271 -50.70162 136.9742 619.7464 -50.09514 78.5 594.349 -47.28908 118.7483 609.1484 -50.62597 78.5 611.8269 -49.91852 115.2705 611.8453 -50.56008 124.0568 603.6107 -50.27778 78.5 602.9652 -49.38235 121.671 606.4177 -50.5358 117.2875 611.0849 -50.61704 115.2705 611.8453 -50.56008 140.7409 611.858 -51.00449 117.2439 610.8673 -50.61784 118.7483 609.1484 -50.62597 115.2705 611.8453 -50.56008 117.5019 610.9129 -50.62501 117.2439 610.8673 -50.61784 115.2705 611.8453 -50.56008 117.2875 611.0849 -50.61704 142.0285 612.5706 -50.78311 140.7409 611.858 -51.00449 138.7887 615.8271 -50.70162 126.2759 606.9213 -50.893 128.3409 605.6928 -50.96418 124.3914 607.9334 -50.83117 122.6767 608.7795 -50.77705 121.1225 609.4939 -50.72948 119.7163 610.103 -50.68752 142.0285 612.5706 -50.78311 151.8905 591.4855 -51.78149 140.7409 611.858 -51.00449 138.3491 620.0554 -49.86093 136.9742 619.7464 -50.09514 135.1014 627.5009 -47.77825 133.7588 627.3443 -48.00055 132.3505 634.7138 -44.49734 131.098 634.4974 -44.78562 128.963 641.0512 -40.53584 130.115 641.4616 -40.04162 127.3078 646.8629 -35.35772 128.3884 647.5084 -34.47186 126.0716 651.8102 -29.372 127.1216 652.6332 -27.91795 125.1889 655.7884 -22.71232 126.2508 656.6492 -20.5526 124.6021 658.7137 -15.51457 125.713 659.4107 -12.58124 124.2661 660.5195 -7.896456 125.4574 660.8162 -4.235906 124.1562 661.1359 0 125.4574 660.8162 4.23553 124.2663 660.5187 7.901792 125.7129 659.4107 12.58088 124.6028 658.7102 15.52574 126.2508 656.6494 20.55225 125.1906 655.7803 22.72857 127.1216 652.6334 27.91764 126.0749 651.7964 29.39153 128.3883 647.5086 34.47159 127.313 646.8435 35.37791 130.1149 641.4619 40.0414 128.9701 641.0275 40.55387 131.1066 634.4725 44.79914 132.3504 634.7141 44.49716 133.7673 627.3227 48.00833 135.1012 627.5012 47.77812 136.9802 619.7331 50.09773 138.3489 620.0557 49.86088 138.7921 615.8198 50.70246 140.7409 611.8579 51.0045 152.9316 592.0364 51.64148 140.7409 611.8579 51.0045 151.8901 591.4863 51.78147 142.0285 612.5706 50.7831 142.0285 612.5706 50.7831 116.1409 571.5244 32.38267 114.4536 568.3213 28.19561 116.1409 571.5244 32.38267 112.8997 568.8838 28.82068 112.8997 568.8838 28.82068 78.5 566.9224 24.56804 108.6952 566.0571 24.09399 110.9778 565.2873 23.11461 112.8997 568.8838 28.82068 108.6952 566.0571 24.09399 114.4536 568.3213 28.19561 78.5 563.371 16.79783 108.2548 565.7937 23.58629 106.9211 563.0407 17.96873 108.2548 565.7937 23.58629 104.4406 563.7774 19.122 104.4406 563.7774 19.122 104.0042 563.5744 18.59887 103.3827 561.186 12.3453 104.0042 563.5744 18.59887 100.1948 562.0475 13.92465 100.1948 562.0475 13.92465 78.5 561.1948 8.528938 99.61602 561.8473 13.17115 102.3898 560.8727 10.95642 100.1948 562.0475 13.92465 99.61602 561.8473 13.17115 103.3827 561.186 12.3453 99.06661 561.655 12.40175 99.06661 561.655 12.40175 96.93304 560.8729 8.55534 99.94689 560.4176 7.700881 99.06661 561.655 12.40175 96.93304 560.8729 8.55534 102.3898 560.8727 10.95642 78.5 560.4611 0 96.87654 560.8514 8.424215 98.76642 559.9996 3.924756 96.87654 560.8514 8.424215 95.60169 560.3526 4.365003 95.60169 560.3526 4.365003 95.57309 560.3413 4.227624 98.99383 559.7287 3e-6 95.57309 560.3413 4.227624 95.14901 560.1705 10e-7 95.14901 560.1705 10e-7 78.5 561.2502 -8.842516 95.14901 560.1705 10e-7 78.5 560.4611 0 95.41001 560.2744 -3.29899 98.59183 559.9362 -2.950436 95.14901 560.1705 10e-7 95.41001 560.2744 -3.29899 98.99383 559.7287 3e-6 78.5 563.4 0 78.5 560.4611 0 78.5 561.1948 8.528938 78.5 564.1207 -8.199214 78.5 561.2502 -8.842516 78.5 566.2337 16.07196 78.5 563.371 16.79783 78.5 564.1127 8.154454 78.5 569.6973 23.49881 78.5 566.9224 24.56804 78.5 574.3664 30.17697 78.5 571.7433 31.61563 78.5 580.1607 35.97861 78.5 577.6932 37.73798 78.5 586.8952 40.69878 78.5 584.6002 42.75815 78.5 594.3435 44.17075 78.5 592.2657 46.52997 78.5 602.2671 46.28967 78.5 566.2612 -16.14717 78.5 563.5887 -17.39518 97.3918 561.0478 -9.554949 78.5 563.5887 -17.39518 95.61922 560.3598 -4.449745 96.16342 560.5751 -6.50106 96.96234 560.8843 -8.624381 78.5 569.7469 -23.5842 78.5 567.3988 -25.39265 106.5881 564.8574 -21.6559 78.5 567.3988 -25.39265 99.06665 561.655 -12.40181 99.61609 561.8473 -13.17119 100.1949 562.0475 -13.92463 78.5 574.4298 -30.25212 78.5 572.5587 -32.58721 112.8995 568.8836 -28.82038 78.5 572.5587 -32.58721 78.5 580.2183 -36.02696 78.5 578.9068 -38.75652 119.7156 575.0375 -36.27345 78.5 578.9068 -38.75652 116.1619 571.5431 -32.40568 116.3444 571.7055 -32.6043 78.5 586.9259 -40.71679 78.5 586.2459 -43.70889 122.7797 578.8086 -39.6695 78.5 586.2459 -43.70889 121.3381 576.9173 -38.05316 78.5 602.2321 -46.28363 126.7613 586.2964 -44.69626 78.5 594.349 -47.28908 78.5 594.3375 -44.16893 124.0394 580.6923 -41.12624 125.1163 582.5513 -42.42966 126.0208 584.4182 -43.61623 127.238 597.3388 -49.08148 127.3241 588.1755 -45.67068 127.6945 590.0641 -46.54939 127.862 593.8004 -48.01192 125.9218 600.6184 -49.81539 110 657.4 0 78.5 657.4 0 78.5 656.6873 -8.154454 110 656.6873 8.154454 78.5 656.6793 8.199214 78.5 657.4 0 110 657.4 0 110 656.6793 -8.199214 78.5 654.5664 -16.07196 110 654.5388 -16.14717 78.5 651.1028 -23.49881 110 651.0531 -23.5842 78.5 646.4336 -30.17697 110 646.3702 -30.25212 78.5 640.6393 -35.97861 110 640.5817 -36.02696 78.5 633.9048 -40.69878 110 633.8741 -40.71679 78.5 626.4565 -44.17075 110 618.568 -46.28363 78.5 618.5329 -46.28967 110 626.4625 -44.16893 110 610.4229 -46.99877 78.5 610.3771 -46.99877 110 602.2671 -46.28967 78.5 602.2321 -46.28363 110 594.3435 -44.17075 78.5 594.3375 -44.16893 78.5 586.9259 -40.71679 110 586.8952 -40.69878 78.5 580.2183 -36.02696 110 580.1607 -35.97861 78.5 574.4298 -30.25212 110 574.3664 -30.17697 78.5 569.7469 -23.5842 110 569.6973 -23.49881 78.5 566.2612 -16.14717 110 566.2337 -16.07196 78.5 564.1207 -8.199214 110 564.1127 -8.154454 78.5 563.4 0 110 563.4 0 78.5 563.4 0 78.5 564.1127 8.154454 110 563.4 0 110 564.1207 8.199214 78.5 566.2337 16.07196 110 566.2612 16.14717 78.5 569.6973 23.49881 110 569.7469 23.5842 78.5 574.3664 30.17697 110 574.4298 30.25212 78.5 580.1607 35.97861 110 580.2183 36.02696 78.5 586.8952 40.69878 110 586.9259 40.71679 78.5 594.3435 44.17075 110 602.2321 46.28363 78.5 602.2671 46.28967 110 594.3375 44.16893 110 610.3771 46.99877 78.5 610.4229 46.99877 110 618.5329 46.28967 78.5 618.568 46.28363 110 626.4565 44.17075 78.5 626.4625 44.16893 78.5 633.8741 40.71679 110 633.9048 40.69878 78.5 640.5817 36.02696 110 640.6393 35.97861 78.5 646.3702 30.25212 110 646.4336 30.17697 78.5 651.0531 23.5842 110 651.1028 23.49881 78.5 654.5388 16.14717 110 654.5664 16.07196 99.26033 560.1768 -5.837806 95.61922 560.3598 -4.449745 96.16342 560.5751 -6.50106 100.3539 560.557 -8.596796 96.96234 560.8843 -8.624381 97.3918 561.0478 -9.554949 102.3898 560.8727 -10.95643 99.06665 561.655 -12.40181 103.3827 561.186 -12.34529 99.06665 561.655 -12.40181 99.61609 561.8473 -13.17119 102.3898 560.8727 -10.95643 100.1949 562.0475 -13.92463 108.9461 564.0877 -20.56344 100.1949 562.0475 -13.92463 106.5881 564.8574 -21.6559 103.3827 561.186 -12.34529 114.4533 568.3211 -28.19537 112.8995 568.8836 -28.82038 118.6555 570.794 -31.84755 112.8995 568.8836 -28.82038 116.1619 571.5431 -32.40568 114.4533 568.3211 -28.19537 116.3444 571.7055 -32.6043 121.4773 574.3646 -35.79299 119.7156 575.0375 -36.27345 121.4773 574.3646 -35.79299 119.7156 575.0375 -36.27345 121.3381 576.9173 -38.05316 125.2661 576.4223 -38.16285 122.7797 578.8086 -39.6695 123.2196 573.5657 -35.45232 127.1014 579.5584 -40.70759 124.0394 580.6923 -41.12624 125.1163 582.5513 -42.42966 128.6435 582.9823 -43.0604 126.0208 584.4182 -43.61623 126.7613 586.2964 -44.69626 129.7668 586.6841 -45.18038 127.3241 588.1755 -45.67068 127.6945 590.0641 -46.54939 130.3264 590.6347 -47.01959 127.862 593.8004 -48.01192 130.1609 594.7438 -48.5202 127.238 597.3388 -49.08148 129.1707 598.855 -49.63746 125.9218 600.6184 -49.81539 127.3832 602.794 -50.37115 124.0568 603.6107 -50.27778 124.9392 606.4075 -50.76353 121.671 606.4177 -50.5358 122.7411 607.8225 -50.73566 120.9819 608.8649 -50.7051 119.1491 609.877 -50.66594 110.6863 554.1456 -6.153379 111.1912 554.8843 -8.090171 113.3827 551.9147 -7.739598 113.6942 552.0335 -8.312893 113.3827 551.9147 -7.739598 111.1912 554.8843 -8.090171 112.5726 551.6276 -5.963892 118.7353 541.8316 -5.381076 112.5726 551.6276 -5.963892 113.3827 551.9147 -7.739598 116.7397 546.8134 -7.757017 113.6942 552.0335 -8.312893 116.7397 546.8134 -7.757017 113.3827 551.9147 -7.739598 108.4645 556.3466 -6.524834 108.5642 557.4264 -8.760393 111.8506 555.1072 -9.20232 108.5642 557.4264 -8.760393 113.9768 552.1536 -8.809001 105.9595 558.1774 -7.065448 105.5944 559.447 -9.727527 109.3155 557.6549 -9.941179 105.5944 559.447 -9.727527 103.2334 559.5925 -7.761888 106.4591 559.7053 -11.00136 102.2726 559.2841 -5.265081 105.1203 557.9187 -4.789512 107.7305 556.1154 -4.42329 110.0369 553.9204 -4.1757 112.3583 551.546 -5.366928 112.3583 551.546 -5.366928 111.9811 551.3902 -4.056224 111.9811 551.3902 -4.056224 101.6873 559.0886 -2.65909 104.6107 557.754 -2.417872 107.286 555.9667 -2.233075 109.6438 553.7734 -2.109467 111.721 551.2752 -2.758919 117.8801 541.895 -2.768899 111.721 551.2752 -2.758919 111.6226 551.2316 -2.055087 111.6226 551.2316 -2.055087 102.6918 558.5502 2e-6 106.0961 556.6774 2e-6 109.0713 554.185 2e-6 111.5029 551.1741 2e-6 117.5859 541.9093 -0.0215469 111.5029 551.1741 2e-6 109.7462 553.8125 2.806405 109.0713 554.185 2e-6 111.5029 551.1741 2e-6 117.872 541.8955 2.730965 111.7159 551.2728 2.726644 111.7159 551.2728 2.726644 101.84 559.1402 3.53784 102.6918 558.5502 2e-6 104.7435 557.7975 3.21726 106.0961 556.6774 2e-6 107.4017 556.0061 2.971343 120.1153 541.6721 -7.778103 120.1153 541.6721 -7.778103 122.3464 535.7144 -4.803707 118.7353 541.8316 -5.381076 120.1153 541.6721 -7.778103 120.1806 541.6594 -7.864698 120.242 541.654 -7.951237 120.1153 541.6721 -7.778103 120.1806 541.6594 -7.864698 121.9491 538.9362 -7.902199 121.8323 538.9238 -7.712584 121.8323 538.9238 -7.712584 118.7252 541.8323 5.358079 112.3499 551.5425 5.341565 110.4437 554.0641 5.510762 112.3499 551.5425 5.341565 116.7396 546.8135 7.757017 113.3827 551.9146 7.739622 111.1912 554.8843 8.090186 113.3827 551.9146 7.739622 120.1153 541.6721 7.778121 120.1806 541.6594 7.864728 113.3827 551.9146 7.739622 116.7396 546.8135 7.757017 120.242 541.654 7.951237 120.3997 541.6967 8.218363 113.6568 552.0183 8.245432 111.8506 555.1072 9.202322 113.3827 551.9146 7.739622 113.6568 552.0183 8.245432 111.1912 554.8843 8.090186 120.1153 541.6721 7.778121 121.8324 538.9238 7.71264 120.1153 541.6721 7.778121 118.7252 541.8323 5.358079 121.9491 538.9362 7.902199 120.1153 541.6721 7.778121 121.8324 538.9238 7.71264 120.242 541.654 7.951237 120.1806 541.6594 7.864728 122.3458 535.7131 4.799978 117.872 541.8955 2.730965 123.5104 536.151 7.67235 121.749 535.4329 1.613872 117.5859 541.9093 -0.0215469 121.751 535.4336 -1.634611 117.8801 541.895 -2.768899 120.2163 542.6206 -8.777219 117.0264 547.5346 -8.820595 120.0919 542.8812 -8.835422 117.4372 554.5147 -15.02437 120.0919 542.8812 -8.835422 117.0264 547.5346 -8.820595 124.8001 537.1064 -10.24172 120.2163 542.6206 -8.777219 120.0919 542.8812 -8.835422 119.9382 544.9479 -10.3257 122.5173 540.1406 -9.682824 120.0919 542.8812 -8.835422 119.9382 544.9479 -10.3257 122.5173 540.1406 -9.682824 113.9768 552.1536 -8.809001 113.9768 552.1536 -8.809001 120.504 541.833 -8.482464 120.4974 541.9274 -8.555276 120.463 542.0417 -8.607999 120.4279 542.1372 -8.643524 120.3781 542.26 -8.682888 120.3055 542.4264 -8.729269 111.8506 555.1072 -9.20232 117.4372 554.5147 -15.02437 113.9768 552.1536 -8.809001 120.242 541.654 -7.951237 120.395 541.6925 -8.207969 121.9491 538.9362 -7.902199 120.242 541.654 -7.951237 120.395 541.6925 -8.207969 123.7901 536.2987 -8.222597 120.504 541.833 -8.482464 123.6248 536.1984 -7.874366 122.2432 539.1483 -8.508129 120.504 541.833 -8.482464 120.4974 541.9274 -8.555276 122.2432 539.1483 -8.508129 124.3647 536.572 -9.235679 120.463 542.0417 -8.607999 123.9383 536.4362 -8.566074 124.1681 536.4835 -8.898372 120.4279 542.1372 -8.643524 124.5357 536.7075 -9.574007 120.3781 542.26 -8.682888 124.6809 536.8866 -9.910348 120.3055 542.4264 -8.729269 119.9687 547.1384 -12.11716 122.8188 542.3347 -11.7848 119.9687 547.1384 -12.11716 120.2056 549.525 -14.26402 123.5368 544.2259 -14.0821 120.2056 549.525 -14.26402 120.6255 551.9228 -16.56215 124.5365 545.9096 -16.45768 120.6255 551.9228 -16.56215 119.1744 555.9575 -18.04604 121.1829 554.0738 -18.74924 125.7376 547.4674 -18.86133 121.1829 554.0738 -18.74924 120.8883 557.5578 -20.97384 121.9425 556.2501 -21.08072 121.9425 556.2501 -21.08072 122.5977 557.8419 -22.82303 127.0863 548.9545 -21.26213 122.5977 557.8419 -22.82303 123.3708 559.5151 -24.67343 128.5484 550.411 -23.64291 123.3708 559.5151 -24.67343 124.2687 561.2742 -26.62472 130.1054 551.8609 -25.99463 124.2687 561.2742 -26.62472 117.4677 558.0633 -18.12041 124.2687 561.2742 -26.62472 120.8883 557.5578 -20.97384 131.7455 553.3195 -28.31096 125.4754 562.7521 -28.58107 123.0606 562.5604 -26.53309 125.4754 562.7521 -28.58107 124.2687 561.2742 -26.62472 123.0606 562.5604 -26.53309 119.1744 555.9575 -18.04604 151.2768 570.1245 -48.53383 142.0517 581.8531 -48.19173 158.9845 557.1276 -49.01092 149.1528 568.1881 -46.81325 140.0109 580.0313 -46.53939 157.0264 555.3497 -47.39955 147.0502 566.3195 -45.01543 138.0525 578.2247 -44.8264 155.1343 553.7712 -45.79566 144.9763 564.515 -43.14399 136.1801 576.4309 -43.05755 151.5937 551.0852 -42.65053 142.9379 562.7702 -41.20262 134.4043 574.6405 -41.23888 153.3249 552.3484 -44.20937 149.9234 549.9376 -41.10354 140.9405 561.0812 -39.19528 132.7284 572.8504 -39.37594 146.748 547.9545 -38.05085 138.9892 559.4437 -37.126 131.1486 571.0635 -37.47323 148.3053 548.8966 -39.56676 145.2529 547.1017 -36.56046 137.0888 557.8535 -34.99883 129.6626 569.2763 -35.53127 142.4606 545.6451 -33.68619 135.2444 556.3063 -32.81779 128.8309 567.7609 -34.11412 143.8203 546.3353 -35.10179 141.168 545.03 -32.31553 133.4611 554.7977 -30.58698 127.8827 566.1874 -32.529 138.7677 543.9705 -29.69543 139.9376 544.4715 -30.9838 127.0548 564.924 -31.16191 126.9136 564.718 -30.93009 137.6533 543.5137 -28.44486 135.5836 542.7184 -26.06041 133.6195 542.0167 -23.71524 130.1961 540.8516 -19.38315 131.8096 541.3991 -21.46988 128.7041 540.3095 -17.35126 127.3258 539.7155 -15.33519 126.1701 539.0427 -13.45399 124.8933 537.3678 -10.56913 125.3534 538.2713 -11.85714 124.8933 537.3678 -10.56913 141.5214 506.6333 -8.06471 124.8933 537.3678 -10.56913 125.3534 538.2713 -11.85714 124.8001 537.1064 -10.24172 126.1701 539.0427 -13.45399 127.3258 539.7155 -15.33519 145.2864 510.2185 -16.5437 128.7041 540.3095 -17.35126 130.1961 540.8516 -19.38315 131.8096 541.3991 -21.46988 133.6195 542.0167 -23.71524 149.2142 514.9315 -24.50076 135.5836 542.7184 -26.06041 137.6533 543.5137 -28.44486 138.7677 543.9705 -29.69543 139.9376 544.4715 -30.9838 141.168 545.03 -32.31553 153.1544 520.8908 -31.82075 142.4606 545.6451 -33.68619 143.8203 546.3353 -35.10179 145.2529 547.1017 -36.56046 146.748 547.9545 -38.05085 156.8872 527.9812 -38.26179 148.3053 548.8966 -39.56676 149.9234 549.9376 -41.10354 151.5937 551.0852 -42.65053 160.2692 536.1252 -43.78109 153.3249 552.3484 -44.20937 155.1343 553.7712 -45.79566 161.8298 540.6166 -46.23907 157.0264 555.3497 -47.39955 163.2963 545.3479 -48.49355 158.9845 557.1276 -49.01092 142.0517 581.8531 -48.19173 135.1864 590.0863 -48.25038 140.0109 580.0313 -46.53939 135.0057 592.9119 -49.23141 134.8223 584.1998 -45.72327 138.0525 578.2247 -44.8264 135.1319 587.1671 -47.08467 134.2608 581.1887 -44.14717 136.1801 576.4309 -43.05755 133.4362 578.134 -42.32442 134.4043 574.6405 -41.23888 132.3814 575.0996 -40.27448 132.7284 572.8504 -39.37594 131.1215 572.1521 -38.01985 131.1486 571.0635 -37.47323 129.6626 569.2763 -35.53127 125.1519 566.6782 -30.97086 129.6626 569.2763 -35.53127 128.8309 567.7609 -34.11412 128.369 574.607 -37.95673 131.1215 572.1521 -38.01985 129.6626 569.2763 -35.53127 128.1645 570.494 -35.29723 128.1645 570.494 -35.29723 127.8827 566.1874 -32.529 127.0548 564.924 -31.16191 126.9136 564.718 -30.93009 132.6509 593.617 -48.65469 135.0057 592.9119 -49.23141 135.1864 590.0863 -48.25038 132.7767 589.3366 -47.05311 135.1319 587.1671 -47.08467 132.2836 585.2463 -45.1351 134.8223 584.1998 -45.72327 134.2608 581.1887 -44.14717 131.3071 581.4177 -42.95249 133.4362 578.134 -42.32442 129.9671 577.8695 -40.54754 132.3814 575.0996 -40.27448 131.6596 600.7254 -50.71719 131.6596 600.7254 -50.71719 130.2444 602.137 -50.74616 131.7214 602.4273 -51.06499 130.2444 602.137 -50.74616 129.0458 603.2405 -50.76493 129.9216 603.8884 -51.00407 129.0458 603.2405 -50.76493 126.5812 571.6199 -35.20323 126.5812 571.6199 -35.20323 124.9269 572.6478 -35.25477 123.0936 568.2573 -31.0209 124.9269 572.6478 -35.25477 127.6041 604.4528 -50.77521 127.6041 604.4528 -50.77521 126.0626 605.6224 -50.77227 128.0344 605.2553 -50.94276 126.0626 605.6224 -50.77227 126.0639 606.5345 -50.88083 124.9392 606.4075 -50.76353 124.0159 607.7331 -50.81811 122.7411 607.8225 -50.73566 120.916 569.637 -31.31476 123.2196 573.5657 -35.45232 121.8991 608.858 -50.75453 120.9819 608.8649 -50.7051 119.7241 609.9155 -50.69014 119.1491 609.877 -50.66594 132.2153 602.9476 -51.1103 132.2153 602.9476 -51.1103 130.5994 604.1737 -51.04704 130.5994 604.1737 -51.04704 128.3409 605.6928 -50.96418 126.2759 606.9213 -50.893 124.3914 607.9334 -50.83117 122.6767 608.7795 -50.77705 121.1225 609.4939 -50.72948 119.7163 610.103 -50.68752 163.7024 571.3837 -52.42132 172.9984 550.0427 -53.33465 162.6554 570.8572 -52.5591 174.3064 550.6689 -53.12287 174.7415 546.3803 -53.46977 172.9984 550.0427 -53.33465 174.3064 550.6689 -53.12287 152.9315 592.0366 -51.64146 157.3284 581.1897 -52.17074 128.7824 264.4633 -60.72529 130.1483 264.1517 -60.55881 128.7824 264.4633 -60.72529 137.904 305.8088 -59.70278 141.0649 313.7784 -59.32577 146.6722 347.2275 -58.67202 151.4744 363.5154 -58.08203 155.0872 388.7207 -57.63296 161.3756 413.3598 -56.8263 163.1481 430.284 -56.58572 170.7665 463.3024 -55.55879 170.8541 471.9127 -55.5304 178.2054 513.6084 -54.46698 179.6486 513.3562 -54.2792 178.2054 513.6084 -54.46698 178.8611 517.616 -54.36388 179.6486 513.3562 -54.2792 180.624 520.0272 -54.10552 179.3099 521.5034 -54.26061 179.5789 525.2778 -54.15742 181.0804 526.4918 -53.92919 179.5871 528.9169 -54.05355 180.7165 532.5394 -53.75119 179.2601 532.3463 -53.94981 178.6049 535.7296 -53.84166 179.3549 538.4431 -53.55994 177.5732 539.2233 -53.72379 176.257 542.774 -53.59931 177.1025 544.5309 -53.34714 176.5055 551.6755 -51.5207 166.8339 572.8691 -49.46423 177.2065 551.9689 -50.2708 164.251 577.9165 -49.26804 177.2065 551.9689 -50.2708 166.8339 572.8691 -49.46423 179.3545 545.4199 -51.74967 176.5055 551.6755 -51.5207 177.2065 551.9689 -50.2708 166.3751 579.04 -42.93542 180.0807 545.6546 -50.50285 177.2065 551.9689 -50.2708 180.1872 545.4 -50.51172 184.223 547.07 -38.54461 180.0807 545.6546 -50.50285 166.5196 578.832 -42.84918 171.2187 572.9039 -38.6561 181.0969 553.8546 -38.36448 181.0969 553.8546 -38.36448 168.8866 575.6576 -41.0796 166.3052 572.637 -50.49342 164.251 577.9165 -49.26804 165.5792 572.2998 -51.36051 155.5155 593.3439 -49.69342 156.0372 593.5831 -48.65551 161.4916 583.2438 -49.06035 175.5111 551.2299 -52.50223 164.6957 571.8743 -52.01497 154.7964 592.9927 -50.56887 153.9191 592.5488 -51.23028 175.5111 551.2299 -52.50223 178.3362 545.0272 -52.72901 144.1806 613.713 -49.12994 144.8537 614.041 -47.84741 140.4887 620.8195 -48.24004 144.8537 614.041 -47.84741 144.1806 613.713 -49.12994 150.5523 603.7369 -48.25563 142.7282 617.9666 -47.51324 150.5523 603.7369 -48.25563 144.8537 614.041 -47.84741 142.7282 617.9666 -47.51324 143.211 613.2084 -50.14118 139.5121 620.5144 -49.20986 143.211 613.2084 -50.14118 162.1038 586.0386 -44.20133 156.0372 593.5831 -48.65551 161.4916 583.2438 -49.06035 140.7767 621.8076 -46.85733 138.9932 625.5721 -45.87087 137.3768 629.2387 -44.56545 137.1443 629.7883 -44.33964 152.0114 604.5595 -43.8332 154.4623 600.1329 -43.92152 164.2181 582.345 -43.90257 182.0652 512.9013 -52.69934 183.8219 519.5413 -51.27045 182.8258 512.7386 -51.44998 185.2274 512.3189 -45.37658 182.8258 512.7386 -51.44998 183.8219 519.5413 -51.27045 182.8107 512.6459 -51.45027 182.0652 512.9013 -52.69934 182.8258 512.7386 -51.44998 185.2274 512.3189 -45.37658 182.8107 512.6459 -51.45027 182.8258 512.7386 -51.44998 183.0592 519.7023 -52.52221 183.8555 519.8355 -51.2628 183.8555 519.8355 -51.2628 183.53 526.4088 -52.34244 184.3017 526.3343 -51.09211 188.3265 519.3201 -39.1394 184.3017 526.3343 -51.09211 184.3054 526.6326 -51.08407 184.3054 526.6326 -51.08407 183.1379 532.8378 -52.16124 183.9086 532.8824 -50.91156 188.7736 526.5771 -38.99782 183.9086 532.8824 -50.91156 182.5258 538.9916 -50.72674 188.3043 533.4923 -38.86124 182.5258 538.9916 -50.72674 182.4523 539.2322 -50.71894 181.6895 539.1097 -51.96658 182.4523 539.2322 -50.71894 186.7483 540.2479 -38.71454 180.1872 545.4 -50.51172 180.6343 538.8172 -52.94461 182.0444 532.7113 -53.139 182.4246 526.4537 -53.31998 181.9606 519.8559 -53.49868 180.975 513.1133 -53.67425 173.1655 462.826 -54.00699 180.975 513.1133 -53.67425 175.4358 470.9249 -52.55602 172.0807 463.048 -54.96514 175.4358 470.9249 -52.55602 173.9296 462.6512 -52.7745 167.7062 429.2745 -53.6532 163.7569 412.8621 -55.30213 173.9296 462.6512 -52.7745 159.6235 387.7008 -54.74167 153.8375 362.9969 -56.5852 162.6776 413.094 -56.24377 164.5111 412.6131 -54.09023 151.1865 346.1976 -55.8217 143.4095 313.2394 -57.85597 152.7642 363.2386 -57.51049 154.5818 362.6828 -55.39349 133.2475 263.39 -57.95711 132.4747 263.5925 -59.11532 142.3422 313.4907 -58.76507 142.3942 304.7586 -56.89356 144.142 312.8594 -56.68454 131.9392 261.2483 -59.17296 132.4747 263.5925 -59.11532 133.2475 263.39 -57.95711 131.4127 263.8536 -60.00743 131.4127 263.8536 -60.00743 144.142 312.8594 -56.68454 133.2475 263.39 -57.95711 142.3942 304.7586 -56.89356 134.6265 263.0755 -55.02589 132.9809 262.2131 -57.98686 133.2475 263.39 -57.95711 134.6265 263.0755 -55.02589 132.9809 262.2131 -57.98686 154.5818 362.6828 -55.39349 151.1865 346.1976 -55.8217 148.1987 312.0684 -47.2067 147.2892 309.9442 -48.40665 145.5154 304.1515 -49.83339 146.2955 307.0918 -49.40263 164.5111 412.6131 -54.09023 159.6235 387.7008 -54.74167 167.9624 411.9879 -45.65198 159.3421 361.7684 -43.64249 167.7062 429.2745 -53.6532 178.5072 461.8685 -40.74309 130.8795 261.5144 -60.0655 165.3794 360.6109 19.0055 159.5327 331.0264 19.55412 162.3594 338.8992 7.685924 148.7239 342.0973 7.685924 162.3594 338.8992 7.685924 159.5327 331.0264 19.55412 166.5984 360.3771 6.355204 162.7312 340.1766 5.304825 149.0745 343.5924 4.795983 162.7312 340.1766 5.304825 162.3594 338.8992 7.685924 148.7239 342.0973 7.685924 162.953 361.0761 31.47413 155.6894 323.5661 31.18036 155.6894 323.5661 31.18036 150.9001 316.5932 42.43747 150.9001 316.5932 42.43747 159.3423 361.7683 43.64189 149.6193 314.7272 44.9185 143.1673 318.407 42.43747 150.9001 316.5932 42.43747 149.6193 314.7272 44.9185 143.1673 318.407 42.43747 154.5819 362.6836 55.39369 148.4114 312.5102 46.89611 142.5713 315.8657 45.38776 148.4114 312.5102 46.89611 148.1986 312.0682 47.20684 148.1986 312.0682 47.20684 151.1866 346.1985 55.82187 144.1429 312.8636 56.68451 147.288 309.9411 48.40807 141.8389 312.7431 47.67559 147.288 309.9411 48.40807 143.4013 313.2019 57.85704 144.1429 312.8636 56.68451 151.1866 346.1985 55.82187 146.2949 307.0899 49.40311 145.5154 304.1515 49.83339 140.7726 283.4475 50.94654 135.9338 262.7761 52.05916 134.6269 263.0756 55.02532 133.2476 263.39 57.95693 132.4735 263.5928 59.11447 133.2476 263.39 57.95693 154.5819 362.6836 55.39369 164.5111 412.6139 54.09046 153.8309 362.9652 56.58614 164.5111 412.6139 54.09046 170.8217 411.4693 36.98854 167.9625 411.9878 45.65161 169.3968 390.1758 27.44999 173.1209 411.4455 28.2493 169.9813 393.8752 27.90511 169.6639 391.9974 27.76976 168.8453 378.7987 18.91822 169.0071 386.7027 26.25589 168.8047 383.5891 24.37974 168.7616 380.9096 21.88657 162.731 340.1757 -5.306997 166.5984 360.3771 -6.35584 169.5242 374.9269 -0.002903938 162.9667 340.9621 -2.706577 163.0472 341.2269 -0.002899885 162.9669 340.9629 2.702928 169.0298 377.2937 15.47472 169.3945 375.5145 7.835719 162.3594 338.8992 -7.685924 165.3793 360.6109 -19.00613 169.3948 375.5135 -7.828681 155.6894 323.5661 -31.18037 162.9528 361.0761 -31.47474 168.7615 380.9217 -21.90046 159.5327 331.0264 -19.55413 169.0298 377.2937 -15.47473 168.8451 378.8005 -18.92147 150.9001 316.5932 -42.43747 170.8217 411.4693 -36.98872 168.8059 383.6169 -24.40065 169.0106 386.7414 -26.27382 169.401 390.2073 -27.45707 169.6667 392.0161 -27.77282 169.9813 393.8752 -27.9051 173.1209 411.4455 -28.24927 148.4129 312.5132 -46.89389 149.6204 314.729 -44.91647 141.8389 312.7431 -47.67559 148.1987 312.0684 -47.2067 148.4129 312.5132 -46.89389 147.2892 309.9442 -48.40665 142.5713 315.8657 -45.38776 149.6204 314.729 -44.91647 150.9001 316.5932 -42.43747 143.1673 318.407 -42.43747 150.9001 316.5932 -42.43747 155.6894 323.5661 -31.18037 143.1673 318.407 -42.43747 159.5327 331.0264 -19.55413 162.3594 338.8992 -7.685924 148.7239 342.0973 -7.685924 162.3594 338.8992 -7.685924 162.731 340.1757 -5.306997 148.7239 342.0973 -7.685924 149.0745 343.5924 -4.796211 162.9667 340.9621 -2.706577 149.2545 344.3597 -1.630087 163.0472 341.2269 -0.002899885 149.2545 344.3598 1.629722 162.9669 340.9629 2.702928 141.0077 309.1994 49.18325 146.2949 307.0899 49.40311 145.5154 304.1515 49.83339 140.1205 305.4169 49.83339 145.5154 304.1515 49.83339 140.7726 283.4475 50.94654 140.1205 305.4169 49.83339 135.9338 262.7761 52.05916 135.6894 261.7295 52.1044 135.9338 262.7761 52.05916 134.6269 263.0756 55.02532 135.6894 261.7295 52.1044 130.4224 264.0687 52.05916 135.9338 262.7761 52.05916 130.4224 264.0687 52.05916 134.1155 260.8545 55.08932 133.2476 263.39 57.95693 135.4545 260.6966 52.12728 132.9783 262.2061 57.98685 132.4735 263.5928 59.11447 132.9783 262.2061 57.98685 133.2476 263.39 57.95693 167.7062 429.2754 53.65342 163.7531 412.8434 55.30274 167.7062 429.2754 53.65342 178.5074 461.8684 40.74235 173.9293 462.6504 52.7747 177.8632 438.3558 28.51972 173.8777 415.2987 27.71158 173.1209 411.4455 28.2493 169.9813 393.8752 27.90511 177.651 436.7327 27.96464 177.8632 438.3558 28.51972 170.0524 393.8763 27.26987 169.9813 393.8752 27.90511 169.6639 391.9974 27.76976 170.0524 393.8763 27.26987 169.5002 390.41 26.83971 169.3968 390.1758 27.44999 169.1181 387.1024 25.69883 169.0071 386.7027 26.25589 168.9095 384.1022 23.87414 168.8047 383.5891 24.37974 168.8542 381.5271 21.44541 168.7616 380.9096 21.88657 168.9238 379.4908 18.53393 168.8453 378.7987 18.91822 169.0913 378.0699 15.22799 169.0298 377.2937 15.47472 169.0913 378.0699 15.22799 169.0298 377.2937 15.47472 169.3945 375.5145 7.835719 169.4439 376.2711 7.692096 169.5242 374.9269 -0.002903938 169.4441 376.2702 -7.686034 169.3948 375.5135 -7.828681 169.5687 375.6875 0.004703998 169.0298 377.2937 -15.47473 169.0913 378.07 -15.22799 169.0298 377.2937 -15.47473 168.8451 378.8005 -18.92147 169.0913 378.07 -15.22799 168.9239 379.4899 -18.53252 168.7615 380.9217 -21.90046 168.8542 381.5253 -21.44341 168.8059 383.6169 -24.40065 168.9094 384.1001 -23.87265 169.0106 386.7414 -26.27382 169.118 387.1002 -25.69773 169.401 390.2073 -27.45707 169.4998 390.4069 -26.83894 169.6667 392.0161 -27.77282 169.9813 393.8752 -27.9051 170.0524 393.8763 -27.27005 169.9813 393.8752 -27.9051 173.1209 411.4455 -28.24927 170.0524 393.8763 -27.27005 177.8632 438.3557 -28.51969 173.8777 415.2988 -27.71194 177.8632 438.3557 -28.51969 181.9269 461.7002 -28.44472 173.9293 462.6504 52.7747 182.8108 512.6458 51.45027 173.1632 462.814 54.00743 182.8108 512.6458 51.45027 181.9269 461.7001 28.44474 187.3652 511.9454 39.05834 182.8258 512.7386 51.44998 185.2508 512.3148 45.31264 181.3834 458.1704 27.97901 181.9269 461.7001 28.44474 185.0248 479.6176 28.14456 185.0868 479.596 27.6903 185.0248 479.6176 28.14456 182.0651 512.901 52.69948 182.8258 512.7386 51.44998 183.8104 519.4428 51.27305 182.8258 512.7386 51.44998 185.2508 512.3148 45.31264 182.0651 512.901 52.69948 182.8258 512.7386 51.44998 183.8104 519.4428 51.27305 188.3265 519.3201 39.1395 187.3652 511.9454 39.05834 183.8552 519.8327 51.26292 186.5585 486.7821 26.58442 190.6412 511.373 26.26406 191.6215 518.9355 26.43464 190.6412 511.373 26.26406 185.7558 483.3937 27.69218 185.3808 481.554 27.99964 189.8232 496.0992 16.41859 192.6201 511.0272 13.19884 193.6376 518.7002 13.3212 192.6201 511.0272 13.19884 189.0916 494.5148 19.73408 188.2785 492.4139 22.53555 187.4163 489.8098 24.83992 191.3236 498.8241 -0.00287497 193.2819 510.9116 -0.00286895 194.3193 518.6206 5e-5 193.2819 510.9116 -0.00286895 191.1468 498.5184 5.704702 190.6266 497.5934 11.27093 191.1459 498.517 -5.718338 193.2816 510.9116 -0.272887 193.2816 510.9116 -0.272887 193.2808 510.9118 -0.543032 193.2808 510.9118 -0.543032 190.6262 497.593 -11.2745 192.5786 511.0345 -13.60609 193.6376 518.7002 -13.3211 192.5786 511.0345 -13.60609 187.4273 489.8464 -24.81453 190.5866 511.3825 -26.53132 191.6215 518.9355 -26.43454 190.5866 511.3825 -26.53132 188.2915 492.4495 -22.49541 189.1034 494.5438 -19.68916 189.8232 496.0991 -16.4186 185.0248 479.6176 -28.14452 187.3248 511.9524 -39.18848 187.3248 511.9524 -39.18848 185.3762 481.5354 -28.0063 185.7501 483.3696 -27.70013 186.1461 485.1231 -27.22353 186.5627 486.7964 -26.57573 181.3834 458.1706 -27.98 181.9269 461.7002 -28.44472 185.0248 479.6176 -28.14452 185.0868 479.596 -27.69137 185.0248 479.6176 -28.14452 185.3762 481.5354 -28.0063 185.0868 479.596 -27.69137 185.7566 483.0888 -27.29599 185.7501 483.3696 -27.70013 186.1461 485.1231 -27.22353 186.529 486.3942 -26.24131 186.5627 486.7964 -26.57573 187.3664 489.3939 -24.53354 187.4273 489.8464 -24.81453 188.2158 491.9855 -22.23196 188.2915 492.4495 -22.49541 189.0155 494.0735 -19.43232 189.1034 494.5438 -19.68916 189.7137 495.5927 -16.21235 189.8232 496.0991 -16.4186 189.7137 495.5927 -16.21235 189.8232 496.0991 -16.4186 190.6262 497.593 -11.2745 190.6477 497.3438 -9.930324 191.1459 498.517 -5.718338 191.1317 498.2058 -3.334875 191.3236 498.8241 -0.00287497 191.1323 498.2067 3.319776 191.1468 498.5184 5.704702 190.6478 497.3439 9.927291 190.6266 497.5934 11.27093 189.8232 496.0992 16.41859 189.7137 495.5927 16.21236 189.8232 496.0992 16.41859 189.0916 494.5148 19.73408 189.7137 495.5927 16.21236 189.0156 494.0736 19.43194 188.2785 492.4139 22.53555 188.216 491.986 22.23081 187.4163 489.8098 24.83992 187.3664 489.3932 24.53312 186.5585 486.7821 26.58442 186.5291 486.3941 26.24009 185.7558 483.3937 27.69218 185.7565 483.0879 27.2951 185.3808 481.554 27.99964 185.0248 479.6176 28.14456 185.0868 479.596 27.6903 177.6511 436.7329 -27.96531 135.9337 262.7759 -52.05917 135.6923 261.7379 -52.10412 135.9337 262.7759 -52.05917 135.4587 260.7008 -52.12722 134.1214 260.8649 -55.08931 132.7125 261.0416 -58.01598 140.7725 283.4473 -50.94655 130.4224 264.0686 -52.05917 135.9337 262.7759 -52.05917 140.7725 283.4473 -50.94655 130.1107 262.7397 -52.11282 135.9337 262.7759 -52.05917 130.4224 264.0686 -52.05917 135.6923 261.7379 -52.10412 145.5154 304.1515 -49.83339 140.1205 305.4169 -49.83339 145.5154 304.1515 -49.83339 146.2955 307.0918 -49.40263 140.1205 305.4169 -49.83339 141.0077 309.1994 -49.18325 148.7239 342.0973 -7.685924 148.7239 342.0973 7.685924 143.1673 318.407 42.43747 149.0745 343.5924 -4.796211 149.0745 343.5924 4.795983 143.1673 318.407 -42.43747 142.5713 315.8657 45.38776 149.2545 344.3597 -1.630087 149.2545 344.3598 1.629722 142.5713 315.8657 -45.38776 140.1205 305.4169 49.83339 140.1205 305.4169 -49.83339 141.0077 309.1994 -49.18325 130.4224 264.0687 52.05916 130.4224 264.0686 -52.05917 141.0077 309.1994 49.18325 141.8389 312.7431 -47.67559 141.8389 312.7431 47.67559 130.1107 262.7397 52.11282 130.1107 262.7397 -52.11282 130.1107 262.7397 52.11282 129.7991 261.4111 52.13068 135.325 260.115 52.13068 129.7991 261.4111 52.13068 135.3896 260.4062 52.12983 135.4545 260.6966 52.12728 129.7991 261.4111 -52.13068 128.7519 256.9465 51.92697 133.7188 251.9276 51.45958 128.7519 256.9465 51.92697 127.7333 252.6035 -51.33979 127.7217 252.554 51.3307 127.7217 252.554 51.3307 128.7583 256.9737 -51.93012 126.7201 248.2837 -50.35484 126.7044 248.2167 50.33634 133.0495 247.8092 50.6098 126.7044 248.2167 50.33634 125.7271 244.0503 -48.98562 125.7085 243.971 48.95572 132.474 243.717 49.41178 125.7085 243.971 48.95572 124.769 239.9654 -47.24639 124.7491 239.8802 47.20563 131.9746 239.7042 47.87209 124.7491 239.8802 47.20563 123.8464 236.0317 -45.14372 123.8264 235.9465 45.09283 131.5621 235.7946 45.995 123.8264 235.9465 45.09283 122.9755 232.3188 -42.71715 122.9568 232.239 42.6599 131.2124 232.0579 43.80944 122.9568 232.239 42.6599 122.1548 228.8193 -39.96305 122.1385 228.75 39.90301 130.9371 228.53 41.34471 122.1385 228.75 39.90301 121.3911 225.5635 -36.90022 121.3781 225.5081 36.84383 130.6987 225.1947 38.58524 121.3781 225.5081 36.84383 120.6839 222.5483 -33.52634 120.675 222.5103 33.47986 130.4886 222.056 35.51883 120.675 222.5103 33.47986 120.0498 219.8447 -29.91198 120.0447 219.8231 29.88065 130.3029 219.1706 32.18438 120.0447 219.8231 29.88065 119.4886 217.4519 -26.05267 119.4871 217.4457 26.04219 130.1115 216.5848 28.6219 119.4871 217.4457 26.04219 119.0096 215.4101 22.02435 129.9399 214.3096 24.85331 119.0096 215.4101 22.02435 119.0084 215.4049 -22.01299 118.6129 213.7186 17.82632 129.8356 212.3583 20.92107 118.6129 213.7186 17.82632 118.6101 213.7068 -17.79204 118.3016 212.3912 13.50692 129.7946 210.7416 16.85197 118.3016 212.3912 13.50692 118.2982 212.377 -13.45304 118.077 211.4337 9.073374 129.792 209.4715 12.66442 118.077 211.4337 9.073374 118.0743 211.4221 -9.00459 117.941 210.8539 4.577673 129.8384 208.5523 8.376645 117.941 210.8539 4.577673 117.9394 210.8472 -4.49941 117.8953 210.6591 0.04063689 129.8812 208.0103 4.075517 117.8953 210.6591 0.04063689 129.8892 208.0341 -4.383086 117.9394 210.8472 -4.49941 129.8957 207.8433 -0.161536 129.8469 208.5942 -8.635335 118.0743 211.4221 -9.00459 129.7963 209.518 -12.84789 118.2982 212.377 -13.45304 129.7969 210.7747 -16.94731 118.6101 213.7068 -17.79204 129.8354 212.3565 -20.91703 119.0084 215.4049 -22.01299 129.9357 214.2557 -24.75467 119.4886 217.4519 -26.05267 130.1018 216.4604 -28.43318 120.0498 219.8447 -29.91198 130.2854 218.9703 -31.9292 120.6839 222.5483 -33.52634 130.461 221.7808 -35.22189 121.3911 225.5635 -36.90022 130.6618 224.8569 -38.27605 122.1548 228.8193 -39.96305 130.8932 228.1587 -41.05672 122.9755 232.3188 -42.71715 131.1665 231.6807 -43.56349 123.8464 236.0317 -45.14372 131.5239 235.4365 -45.80254 124.769 239.9654 -47.24639 131.9526 239.3929 -47.73811 125.7271 244.0503 -48.98562 132.468 243.4705 -49.32996 126.7201 248.2837 -50.35484 133.0607 247.6485 -50.57152 127.7333 252.6035 -51.33979 133.7386 251.8407 -51.44653 128.7583 256.9737 -51.93012 135.3296 260.1139 -52.13068 129.7991 261.4111 -52.13068 134.4982 256.0021 -51.96178 135.4587 260.7008 -52.12722 135.3944 260.4097 -52.1298 134.1214 260.8649 -55.08931 135.4587 260.7008 -52.12722 135.3944 260.4097 -52.1298 132.7125 261.0416 -58.01598 135.3296 260.1139 -52.13068 134.4982 256.0021 -51.96178 130.9856 252.6883 -57.5843 133.7386 251.8407 -51.44653 133.0607 247.6485 -50.57152 129.5455 244.1552 -55.83937 132.468 243.4705 -49.32996 128.8071 238.9385 -54.09314 131.9526 239.3929 -47.73811 129.4943 243.817 -55.74235 129.4423 243.4698 -55.64037 128.2631 234.5467 -52.18323 131.5239 235.4365 -45.80254 127.7932 230.3103 -49.92063 131.1665 231.6807 -43.56349 128.2512 234.4454 -52.13431 128.2395 234.3444 -52.085 127.4121 226.4772 -47.4543 130.8932 228.1587 -41.05672 127.2485 224.7514 -46.20344 130.6618 224.8569 -38.27605 127.3293 225.6095 -46.83724 126.6838 218.5796 -40.84441 130.461 221.7808 -35.22189 130.2854 218.9703 -31.9292 126.1575 213.2189 -34.67388 130.1018 216.4604 -28.43318 125.6517 208.7336 -27.75555 129.9357 214.2557 -24.75467 129.8354 212.3565 -20.91703 125.3208 205.5512 -21.0577 129.7969 210.7747 -16.94731 129.7963 209.518 -12.84789 125.1507 203.2636 -14.11682 129.8469 208.5942 -8.635335 125.0954 201.8883 -7.044929 129.8892 208.0341 -4.383086 129.8957 207.8433 -0.161536 125.0814 201.4376 0.01704895 129.8812 208.0103 4.075517 125.0862 201.8916 7.043741 129.8384 208.5523 8.376645 125.1444 203.2531 14.06396 129.792 209.4715 12.66442 129.7946 210.7416 16.85197 125.3154 205.5139 20.95629 129.8356 212.3583 20.92107 125.6431 208.6544 27.61153 129.9399 214.3096 24.85331 125.6561 208.768 27.81709 130.1115 216.5848 28.6219 126.2432 213.9794 35.66227 130.3029 219.1706 32.18438 125.6692 208.8824 28.02234 125.9471 211.2825 31.94316 126.543 216.9547 39.15246 130.4886 222.056 35.51883 126.8492 220.1918 42.39552 130.6987 225.1947 38.58524 127.1706 223.6719 45.37207 130.9371 228.53 41.34471 127.5184 227.3704 48.06593 131.2124 232.0579 43.80944 127.9066 231.2685 50.46771 131.5621 235.7946 45.995 128.3469 235.3212 52.55168 131.9746 239.7042 47.87209 128.8554 239.5026 54.30893 132.474 243.717 49.41178 129.4472 243.7794 55.7326 133.0495 247.8092 50.6098 130.1306 248.1143 56.81779 133.7188 251.9276 51.45958 130.9052 252.4677 57.55865 135.325 260.115 52.13068 135.3896 260.4062 52.12983 135.4545 260.6966 52.12728 134.1155 260.8545 55.08932 132.7056 261.0285 58.01602 132.7056 261.0285 58.01602 132.7056 261.0285 58.01602 130.1486 252.6385 58.70692 130.9052 252.4677 57.55865 132.7056 261.0285 58.01602 131.9338 261.2372 59.17397 131.9338 261.2372 59.17397 131.9392 261.2483 -59.17296 132.7125 261.0416 -58.01598 130.9856 252.6883 -57.5843 132.7125 261.0416 -58.01598 130.1903 252.6461 -58.70673 129.5455 244.1552 -55.83937 128.7856 244.2159 -56.98663 129.4943 243.817 -55.74235 129.4423 243.4698 -55.64037 128.8071 238.9385 -54.09314 127.6948 236.1642 -54.09151 128.2631 234.5467 -52.18323 128.2512 234.4454 -52.13431 128.2395 234.3444 -52.085 127.7932 230.3103 -49.92063 126.8624 228.614 -50.08031 127.4121 226.4772 -47.4543 127.3293 225.6095 -46.83724 127.2485 224.7514 -46.20344 126.2097 221.6981 -45.02363 126.6838 218.5796 -40.84441 125.6533 215.5864 -39.03352 126.1575 213.2189 -34.67388 125.1146 210.4206 -32.25635 125.6517 208.7336 -27.75555 124.6566 206.28 -24.83366 125.3208 205.5512 -21.0577 124.3876 203.2246 -16.88055 125.1507 203.2636 -14.11682 124.3005 201.3362 -8.532841 125.0954 201.8883 -7.044929 124.2833 200.6991 0.007544994 125.0814 201.4376 0.01704895 125.0862 201.8916 7.043741 124.2907 201.341 8.550171 125.1444 203.2531 14.06396 124.3853 203.2314 16.89774 125.3154 205.5139 20.95629 124.6548 206.2917 24.85595 125.6431 208.6544 27.61153 125.6561 208.768 27.81709 125.6692 208.8824 28.02234 125.1199 210.4319 32.27432 125.9471 211.2825 31.94316 126.2432 213.9794 35.66227 125.6632 215.6028 39.05213 126.543 216.9547 39.15246 126.8492 220.1918 42.39552 126.2331 221.7186 45.04209 127.1706 223.6719 45.37207 127.5184 227.3704 48.06593 126.8805 228.6354 50.09407 127.9066 231.2685 50.46771 128.3469 235.3212 52.55168 127.6834 236.1779 54.09777 128.8554 239.5026 54.30893 129.4472 243.7794 55.7326 128.7427 244.2177 56.98765 130.1306 248.1143 56.81779 129.1314 252.7361 -59.58673 130.8795 261.5144 -60.0655 127.7281 244.144 -57.8347 126.6411 235.9445 -54.87915 125.8168 228.2718 -50.78409 125.176 221.266 -45.63135 124.6339 215.0934 -39.54415 124.11 209.8859 -32.66979 123.6688 205.7176 -25.13347 123.4197 202.6542 -17.05753 123.3514 200.7779 -8.610383 123.3418 200.1484 0.006572902 123.3409 200.7816 8.627658 123.4169 202.6607 17.07679 123.6666 205.7279 25.15535 124.1155 209.8983 32.68881 124.6437 215.1109 39.5642 125.1995 221.2875 45.65079 125.8347 228.2914 50.79685 126.6293 235.9542 54.88356 127.6851 244.1437 57.83436 129.0906 252.7317 59.5863 130.8738 261.5066 60.06554 131.4126 263.8536 60.0075 130.8738 261.5066 60.06554 130.1478 264.1518 60.55745 128.7825 264.4632 60.72529 97.89824 263.3917 60.21661 128.7825 264.4632 60.72529 141.0567 313.741 59.32672 128.7825 264.4632 60.72529 130.1478 264.1518 60.55745 115.3549 278.8574 60.07938 137.904 305.8088 59.70278 98.81324 264.0327 60.21427 99.71492 264.6774 60.21158 100.6033 265.3259 60.20856 101.4783 265.9782 60.2052 102.3399 266.6343 60.20149 103.1883 267.2942 60.19744 104.0233 267.9579 60.19305 104.845 268.6254 60.18832 105.6534 269.2967 60.18325 106.5288 270.0409 60.17726 107.3904 270.792 60.17084 108.2373 271.549 60.16399 109.0684 272.3109 60.15673 109.8827 273.0768 60.14905 110.6791 273.8456 60.14099 111.4567 274.6165 60.13253 112.2143 275.3884 60.1237 112.9511 276.1604 60.1145 113.6658 276.9315 60.10494 114.5274 277.8943 60.09246 142.334 313.4533 58.76607 131.4126 263.8536 60.0075 163.7013 571.3861 52.42126 157.3284 581.1897 52.17074 162.6549 570.858 52.55907 174.3064 550.669 53.12287 172.9983 550.0427 53.33465 174.3064 550.669 53.12287 172.9983 550.0427 53.33465 174.7145 546.4393 53.46762 177.1106 544.5113 53.34785 176.2141 542.8803 53.59553 177.5261 539.3657 53.71889 179.3599 538.4271 53.56048 178.5632 535.8959 53.83618 179.2341 532.5231 53.9443 180.7188 532.5227 53.75171 179.5793 529.0911 54.04843 181.08 526.4833 53.92944 179.5843 525.4379 54.15293 179.3227 521.6325 54.25714 180.6233 520.0225 54.10566 178.8717 517.6911 54.36192 178.2055 513.6084 54.46698 179.6485 513.356 54.27924 178.2055 513.6084 54.46698 170.8541 471.9127 55.5304 179.6485 513.356 54.27924 170.7643 463.2911 55.5591 163.1481 430.284 56.58572 161.372 413.3416 56.82678 155.0871 388.7207 57.63296 151.4679 363.484 58.08284 146.6721 347.2275 58.67202 116.1505 279.822 60.0657 116.9162 280.7891 60.05143 117.654 281.7597 60.03657 118.3662 282.7351 60.02113 119.0548 283.7163 60.00511 119.7218 284.7044 59.98852 120.3662 285.6987 59.97135 120.9855 286.6982 59.95359 121.5799 287.7027 59.93526 122.1492 288.7122 59.91635 122.6935 289.7269 59.89685 123.2128 290.7466 59.87677 123.7071 291.7713 59.85611 124.1763 292.8011 59.83487 97.78306 263.4266 60.21291 97.89824 263.3917 60.21661 98.6568 264.0917 60.20829 98.81324 264.0327 60.21427 99.52873 264.7671 60.20298 99.71492 264.6774 60.21158 100.3968 265.452 60.19698 100.6033 265.3259 60.20856 101.2595 266.1453 60.19028 101.4783 265.9782 60.2052 102.1164 266.8474 60.18288 102.3399 266.6343 60.20149 102.9676 267.5591 60.17473 103.1883 267.2942 60.19744 104.0233 267.9579 60.19305 103.8131 268.2812 60.16582 104.845 268.6254 60.18832 104.6526 269.0141 60.15613 105.6534 269.2967 60.18325 105.4858 269.7584 60.14565 106.5288 270.0409 60.17726 106.3124 270.5146 60.13435 107.3904 270.792 60.17084 107.132 271.2831 60.12221 108.2373 271.549 60.16399 107.9442 272.0646 60.10921 109.0684 272.3109 60.15673 108.7489 272.8596 60.09533 109.8827 273.0768 60.14905 109.5456 273.6689 60.08054 110.6791 273.8456 60.14099 110.334 274.4929 60.06482 111.4567 274.6165 60.13253 111.1135 275.3321 60.04816 112.2143 275.3884 60.1237 111.8836 276.187 60.03053 112.9511 276.1604 60.1145 112.6435 277.0579 60.01192 113.6658 276.9315 60.10494 113.3926 277.9452 59.99231 114.5274 277.8943 60.09246 114.1302 278.8492 59.97167 115.3549 278.8574 60.07938 114.8558 279.7704 59.95 116.1505 279.822 60.0657 115.5686 280.709 59.92728 116.9162 280.7891 60.05143 116.2679 281.6655 59.90348 117.654 281.7597 60.03657 116.9529 282.6399 59.87859 118.3662 282.7351 60.02113 117.6227 283.6325 59.8526 119.0548 283.7163 60.00511 118.2764 284.6435 59.82548 119.7218 284.7044 59.98852 118.9133 285.6731 59.79723 120.3662 285.6987 59.97135 119.5325 286.7214 59.76782 120.9855 286.6982 59.95359 120.1331 287.7886 59.73725 121.5799 287.7027 59.93526 120.7141 288.8746 59.7055 122.1492 288.7122 59.91635 121.2745 289.979 59.67257 122.6935 289.7269 59.89685 121.8131 291.1017 59.63843 123.2128 290.7466 59.87677 122.3291 292.2425 59.6031 123.7071 291.7713 59.85611 124.1763 292.8011 59.83487 122.7929 293.4139 59.5558 144.1806 613.713 49.12994 150.5523 603.7368 48.25563 144.8537 614.041 47.84741 152.0114 604.5595 43.8332 144.8537 614.041 47.84741 150.5523 603.7368 48.25563 142.7289 617.9652 47.51362 144.1806 613.713 49.12994 144.8537 614.041 47.84741 142.7289 617.9652 47.51362 156.0368 593.5839 48.65548 164.2026 582.3703 43.90727 156.0368 593.5839 48.65548 162.1038 586.0386 44.20133 154.4623 600.1329 43.92152 155.5156 593.3437 49.69347 161.4916 583.2438 49.06035 166.3742 579.0411 42.93588 161.4916 583.2438 49.06035 154.7965 592.9926 50.56891 166.3041 572.6394 50.49336 166.8334 572.8699 49.46419 164.251 577.9165 49.26804 143.211 613.2084 50.14118 153.9191 592.5487 51.23032 165.5782 572.3022 51.36046 164.6946 571.8767 52.01491 139.5119 620.5147 49.20981 143.211 613.2084 50.14118 140.4885 620.8198 48.23997 176.5055 551.6755 51.5207 177.2065 551.9689 50.2708 179.3628 545.3996 51.75041 177.2065 551.9689 50.2708 176.5055 551.6755 51.5207 181.0969 553.8546 38.36449 166.8334 572.8699 49.46419 177.2065 551.9689 50.2708 184.2229 547.07 38.54487 181.0969 553.8546 38.36449 177.2065 551.9689 50.2708 178.7092 548.7779 50.39107 178.7092 548.7779 50.39107 175.511 551.2299 52.50223 178.3444 545.0072 52.72974 175.511 551.2299 52.50223 164.251 577.9165 49.26804 140.7767 621.8076 -46.85733 137.2383 627.8955 -46.22619 138.9932 625.5721 -45.87087 137.3768 629.2387 -44.56545 134.4937 634.7561 -43.05211 137.1443 629.7883 -44.33964 134.6446 636.1583 -41.06157 135.9309 632.7675 -42.96383 135.9309 632.7675 -42.96383 138.6098 630.7319 -39.21366 140.161 627.0417 -40.91883 146.6318 614.1234 -43.64167 143.209 620.5344 -42.90381 134.6446 636.1583 -41.06157 132.2714 641.1787 -38.74078 133.5082 639.3922 -38.87458 133.5082 639.3922 -38.87458 132.5112 642.4612 -36.39892 137.5396 633.4479 -37.66285 132.5112 642.4612 -36.39892 130.5624 646.937 -33.35136 131.6497 645.3276 -33.66073 131.6497 645.3276 -33.66073 130.9108 647.9857 -30.65422 135.4479 639.283 -33.33993 130.9108 647.9857 -30.65422 129.3147 651.8192 -27.00988 130.2894 650.3947 -27.41702 133.8033 644.4712 -27.98234 130.2894 650.3947 -27.41702 129.773 652.5478 -23.94338 129.773 652.5478 -23.94338 128.4613 655.6464 -19.88366 129.3552 654.4079 -20.28384 132.589 648.7422 -21.7977 129.3552 654.4079 -20.28384 129.0261 655.9661 -16.43661 129.0261 655.9661 -16.43661 127.9368 658.2784 -12.17156 128.7785 657.1955 -12.46049 131.7471 651.9782 -14.8394 128.7785 657.1955 -12.46049 128.6071 658.0855 -8.364795 128.6071 658.0855 -8.364795 127.6884 659.6182 -4.097973 128.5053 658.6244 -4.203634 131.2661 653.9467 -7.497923 128.5053 658.6244 -4.203634 128.4725 658.8038 -0.001616895 128.4725 658.8038 -0.001616895 127.6884 659.6182 4.097492 128.5053 658.6246 4.200415 131.1106 654.6039 7.8e-5 128.5053 658.6246 4.200415 127.9368 658.2785 12.1711 128.607 658.086 8.361636 131.2607 653.9692 7.369343 128.607 658.086 8.361636 128.7784 657.1963 12.45741 128.7784 657.1963 12.45741 128.4613 655.6466 19.88322 129.0259 655.9672 16.43358 131.7286 652.0523 14.63422 129.0259 655.9672 16.43358 129.3549 654.4093 20.28085 129.3549 654.4093 20.28085 129.3146 651.8195 27.00948 129.7726 652.5496 23.94034 132.5544 648.8706 21.57272 129.7726 652.5496 23.94034 130.2889 650.3969 27.4139 130.2889 650.3969 27.4139 130.5623 646.9373 33.35102 130.9102 647.988 30.65138 133.7524 644.642 27.77298 130.9102 647.988 30.65138 131.6492 645.3298 33.65845 135.3853 639.4697 33.17555 131.6492 645.3298 33.65845 132.2713 641.179 38.7405 132.5106 642.4631 36.3972 132.5106 642.4631 36.3972 133.5076 639.3937 38.87341 137.4745 633.6186 37.55643 133.5076 639.3937 38.87341 134.4935 634.7565 43.05188 134.6441 636.1596 41.06082 138.6084 630.7348 39.21209 134.6441 636.1596 41.06082 135.9304 632.7686 42.96331 135.9304 632.7686 42.96331 137.2381 627.8959 46.22603 137.1443 629.7884 44.33963 137.1443 629.7884 44.33963 137.3766 629.2393 44.5652 137.3766 629.2393 44.5652 146.6318 614.1234 43.64167 140.1031 627.174 40.8652 143.1741 620.6042 42.88915 138.9937 625.5711 45.87108 138.9937 625.5711 45.87108 140.7776 621.8057 46.8578 140.7776 621.8057 46.8578 136.2537 627.7846 47.13966 133.5002 634.8302 43.89337 131.2684 641.4246 39.49308 129.5497 647.337 33.99746 128.293 652.3506 27.53321 127.4321 656.2813 20.26943 126.9022 658.985 12.40796 126.651 660.3614 4.177354 126.651 660.3614 -4.177754 126.9022 658.9849 -12.40835 127.4322 656.2811 -20.2698 128.2931 652.3504 -27.53354 129.5498 647.3367 -33.99774 131.2685 641.4243 -39.49331 133.5004 634.8298 -43.89356 136.2539 627.7842 -47.13979 158.3315 583.913 44.20133 162.1038 586.0386 44.20133 164.2026 582.3703 43.90727 142.5916 611.8469 43.64167 154.4623 600.1329 43.92152 162.1038 586.0386 44.20133 158.3315 583.913 44.20133 160.4487 580.1557 43.89316 166.3742 579.0411 42.93588 166.4954 578.8665 42.86375 166.4954 578.8665 42.86375 152.0114 604.5595 43.8332 146.6318 614.1234 43.64167 168.863 575.6873 41.10057 162.4992 576.5166 42.83259 168.863 575.6873 41.10057 171.2033 572.921 38.67455 164.4272 573.0949 41.05356 171.2033 572.921 38.67455 172.3499 571.6901 37.2059 166.1709 570.0004 38.61319 172.3499 571.6901 37.2059 183.9261 555.2258 26.09408 173.4692 570.582 35.57449 173.4692 570.582 35.57449 179.9611 563.6656 24.69684 167.6809 567.3205 35.57449 173.4692 570.582 35.57449 179.9611 563.6656 24.69684 167.6809 567.3205 35.57449 185.6661 556.0692 13.57591 185.6661 556.0692 13.57591 187.1929 548.3034 26.02262 185.6661 556.0692 13.57591 183.9261 555.2258 26.09408 186.3608 555.0039 12.07742 189.009 549.0576 13.11036 186.3608 555.0039 12.07742 135.3536 624.6921 40.80042 138.6084 630.7348 39.21209 140.1031 627.174 40.8652 132.0294 630.5918 37.53371 137.4745 633.6186 37.55643 138.9079 618.3844 42.85827 143.1741 620.6042 42.88915 146.6318 614.1234 43.64167 142.5916 611.8469 43.64167 135.3538 624.6918 -40.80059 138.6098 630.7319 -39.21366 137.5396 633.4479 -37.66285 140.161 627.0417 -40.91883 132.0296 630.5913 -37.53402 135.4479 639.283 -33.33993 129.032 635.9111 -33.15777 133.8033 644.4712 -27.98234 126.4478 640.4975 -27.80087 132.589 648.7422 -21.7977 124.352 644.2169 -21.6192 131.7471 651.9782 -14.8394 122.8067 646.9594 -14.79147 131.2661 653.9467 -7.497923 121.8586 648.6419 -7.516479 131.1106 654.6039 7.8e-5 121.5384 649.2102 0 131.2607 653.9692 7.369343 121.8586 648.642 7.516211 131.7286 652.0523 14.63422 122.8066 646.9596 14.79102 132.5544 648.8706 21.57272 124.3519 644.2171 21.61866 133.7524 644.642 27.77298 126.4476 640.4979 27.80035 135.3853 639.4697 33.17555 129.0318 635.9116 33.15733 158.3315 583.913 -44.20133 152.0114 604.5595 -43.8332 146.6318 614.1234 -43.64167 154.4623 600.1329 -43.92152 142.5916 611.8469 -43.64167 146.6318 614.1234 -43.64167 143.209 620.5344 -42.90381 142.5916 611.8469 -43.64167 138.908 618.3842 -42.85832 160.4487 580.1557 -43.89316 166.3751 579.04 -42.93542 164.2181 582.345 -43.90257 162.4992 576.5166 -42.83259 166.5196 578.832 -42.84918 162.1038 586.0386 -44.20133 162.1038 586.0386 -44.20133 158.3315 583.913 -44.20133 173.4698 570.5823 -35.57449 183.9261 555.2258 -26.09408 183.9261 555.2258 -26.09408 172.3583 571.6813 -37.19436 179.9613 563.6653 -24.69651 185.6663 556.0693 -13.57591 187.193 548.3034 -26.02234 185.6663 556.0693 -13.57591 178.0647 548.8922 -10.59914 185.6663 556.0693 -13.57591 179.9613 563.6653 -24.69651 186.3608 555.0039 -12.07741 189.009 549.0576 -13.11007 186.3608 555.0039 -12.07741 173.4698 570.5823 -35.57449 167.6809 567.3205 -35.57449 173.4698 570.5823 -35.57449 172.3583 571.6813 -37.19436 167.6809 567.3205 -35.57449 166.1709 570.0004 -38.61319 171.2187 572.9039 -38.6561 164.4272 573.0949 -41.05356 168.8866 575.6576 -41.0796 158.3315 583.913 -44.20133 158.3315 583.913 44.20133 160.4487 580.1557 43.89316 142.5916 611.8469 -43.64167 142.5916 611.8469 43.64167 160.4487 580.1557 -43.89316 162.4992 576.5166 42.83259 162.4992 576.5166 -42.83259 164.4272 573.0949 41.05356 164.4272 573.0949 -41.05356 166.1709 570.0004 38.61319 166.1709 570.0004 -38.61319 167.6809 567.3205 35.57449 167.6809 567.3205 -35.57449 178.0647 548.8922 10.59914 187.0239 553.9404 10.59914 178.0647 548.8922 10.59914 138.908 618.3842 -42.85832 138.9079 618.3844 42.85827 135.3538 624.6918 -40.80059 135.3536 624.6921 40.80042 132.0296 630.5913 -37.53402 132.0294 630.5918 37.53371 129.032 635.9111 -33.15777 129.0318 635.9116 33.15733 126.4478 640.4975 -27.80087 126.4476 640.4979 27.80035 124.352 644.2169 -21.6192 124.3519 644.2171 21.61866 122.8067 646.9594 -14.79147 122.8066 646.9596 14.79102 121.8586 648.6419 -7.516479 121.8586 648.642 7.516211 121.5384 649.2102 0 178.0647 548.8922 -10.59914 187.0237 553.9403 -10.59914 179.1045 547.0468 -7.405182 187.0237 553.9403 -10.59914 178.0647 548.8922 -10.59914 187.0237 553.9403 -10.59914 188.129 552.1275 -7.397813 188.129 552.1275 -7.397813 179.1045 547.0468 7.405182 179.1045 547.0468 -7.405182 187.0239 553.9404 10.59914 188.129 552.1276 7.398019 178.0647 548.8922 10.59914 187.0239 553.9404 10.59914 188.129 552.1276 7.398019 189.623 549.3126 1.44e-4 188.8155 551.0028 3.800323 179.7522 545.8975 3.806247 188.8155 551.0028 3.800323 179.1045 547.0468 7.405182 189.0482 550.6215 2.08e-4 189.0482 550.6215 2.08e-4 188.8156 551.0026 -3.799961 179.972 545.5073 0 188.8156 551.0026 -3.799961 179.7522 545.8975 -3.806247 189.8571 541.1773 -26.14004 191.7583 541.7456 -13.17029 192.401 541.9378 1.58e-4 191.7582 541.7456 13.1706 189.857 541.1773 26.14035 180.1249 545.5491 50.5066 180.1883 545.3974 50.51189 186.7482 540.2479 38.71483 181.6947 539.093 51.96718 180.1883 545.3974 50.51189 180.1249 545.5491 50.5066 182.5003 539.0759 50.72386 182.5003 539.0759 50.72386 191.5427 533.9421 -26.24178 193.5235 534.2172 -13.22251 194.1932 534.3102 -1.34e-4 193.5235 534.2172 13.22224 191.5427 533.9421 26.24152 182.527 538.9879 50.72671 188.3044 533.4923 38.86099 183.1403 532.8201 52.16183 182.527 538.9879 50.72671 183.9081 532.8854 50.91166 183.9081 532.8854 50.91166 192.0663 526.531 -26.33639 194.0806 526.5027 -13.27087 194.7617 526.4932 1.3e-5 194.0806 526.5027 13.27089 192.0663 526.531 26.33642 188.7736 526.5771 38.99784 183.9361 532.6879 50.91719 183.5295 526.4 52.34276 183.9361 532.6879 50.91719 184.3054 526.6277 51.08412 184.3054 526.6277 51.08412 184.2991 526.1784 51.09623 184.2991 526.1784 51.09623 183.0584 519.6976 52.52244 183.8552 519.8327 51.26292 179.7522 545.8975 3.806247 179.7522 545.8975 -3.806247 179.972 545.5073 0 180.6394 538.8008 52.94518 182.0468 532.6939 53.13956 182.4241 526.445 53.32026 181.9598 519.8511 53.49885 180.9748 513.1129 53.67434 180.9748 513.1129 53.67434 172.0784 463.0363 54.96551 152.7576 363.207 57.51136 162.6739 413.0755 56.24431 97.73546 263.4947 60.20806 98.58457 264.1935 60.19943 99.43112 264.9023 60.18903 100.2732 265.62 60.17686 101.1091 266.3456 60.16293 101.9386 267.0793 60.14721 102.7618 267.822 60.12968 103.5786 268.5742 60.11031 104.3886 269.3364 60.08909 105.1916 270.1091 60.06602 105.9872 270.8926 60.04106 106.7751 271.6873 60.01422 107.555 272.4938 59.98547 108.3264 273.3126 59.95481 109.0892 274.1442 59.92222 109.8429 274.9892 59.88769 110.587 275.8479 59.85121 111.321 276.7207 59.8128 112.0442 277.6078 59.77245 112.7561 278.5096 59.73017 113.4559 279.4263 59.68595 114.1431 280.3583 59.63981 114.8171 281.3058 59.59174 115.4772 282.2691 59.54175 116.1226 283.2483 59.48985 116.7526 284.2436 59.43604 117.3663 285.2551 59.38034 117.9631 286.283 59.32274 118.5422 287.3275 59.26326 119.1026 288.3885 59.2019 119.6436 289.4659 59.13868 120.1642 290.5595 59.0736 120.6635 291.6691 59.00669 121.1405 292.7945 58.93794 121.5469 293.956 58.82896 97.3738 263.2861 60.20641 98.29032 264.0967 60.19166 97.45468 263.357 60.20529 99.13787 264.8717 60.17274 99.93679 265.6062 60.15193 100.7619 266.3583 60.12945 101.5728 267.1273 60.1015 102.3768 267.9043 60.06992 103.1738 268.6899 60.03469 103.9636 269.4845 59.99581 104.7361 270.3161 59.94446 105.52 271.1018 59.90715 106.2861 271.9253 59.85736 107.0437 272.759 59.80397 107.7622 273.6219 59.73214 108.5322 274.4595 59.6864 109.2626 275.327 59.62226 109.9831 276.2067 59.55461 110.6933 277.0987 59.48348 111.3926 278.0032 59.40893 112.0805 278.9206 59.33104 112.7564 279.8511 59.24984 113.4198 280.7949 59.16539 114.0702 281.7523 59.07776 114.7069 282.7236 58.98699 115.3292 283.7088 58.89316 115.9366 284.7081 58.79632 116.5283 285.7217 58.69656 117.1036 286.7498 58.59392 117.662 287.7926 58.48847 118.2025 288.85 58.38027 118.7245 289.922 58.2694 119.2271 291.0086 58.15592 119.7095 292.1094 58.0399 120.1708 293.2244 57.92139 110 255.7616 -56.80979 97.87651 263.732 60.19865 98.44198 264.2419 60.18793 110 255.6469 56.80035 110 246.4811 -55.27311 110 237.5604 -52.22257 110 246.3916 55.25072 100.8656 266.476 60.12306 101.9742 267.5385 60.08173 101.4574 267.0398 60.10194 102.6678 268.2176 60.05197 103.4366 268.9843 60.01535 102.9891 268.5362 60.03713 104.1266 269.6856 59.97914 110 229.2474 -47.73216 110 237.5157 52.20334 106.0198 271.6807 59.86279 105.3653 270.9786 59.90592 106.5453 272.2547 59.82585 107.132 272.9071 59.78213 108.1912 274.1173 59.69629 110 221.7832 -41.92382 110 221.826 41.96307 110 229.2527 47.73582 109.0604 275.1444 59.61899 108.4506 274.4205 59.67389 109.7682 276.0053 59.55128 110.5192 276.9454 59.47453 111.2274 277.8587 59.39733 111.8141 278.6371 59.32964 112.3051 279.3045 59.27029 112.8884 280.1179 59.19644 112.3808 279.4088 59.26092 113.4644 280.9447 59.11977 114.0968 281.8815 59.03108 115.1895 283.581 58.86577 114.6278 282.6937 58.95276 115.622 284.2853 58.79574 116.3911 285.5887 58.66407 115.7816 284.5502 58.76919 117.027 286.7212 58.54767 117.502 287.604 58.45581 117.9959 288.5597 58.35532 118.3558 289.2828 58.27864 119.0156 290.675 58.12953 118.5021 289.5837 58.24657 119.5326 291.8359 58.00387 103.4366 268.9843 60.01535 104.1266 269.6856 59.97914 104.7361 270.3161 59.94446 105.3653 270.9786 59.90592 106.0198 271.6807 59.86279 106.5453 272.2547 59.82585 107.132 272.9071 59.78213 107.7622 273.6219 59.73214 108.1912 274.1173 59.69629 110.2081 281.2723 57.56626 108.4506 274.4205 59.67389 109.0604 275.1444 59.61899 109.7682 276.0053 59.55128 110.5192 276.9454 59.47453 111.2274 277.8587 59.39733 111.8141 278.6371 59.32964 112.3051 279.3045 59.27029 113.5589 286.1458 56.59712 112.3808 279.4088 59.26092 112.8884 280.1179 59.19644 113.4644 280.9447 59.11977 114.0968 281.8815 59.03108 114.6278 282.6937 58.95276 115.1895 283.581 58.86577 115.622 284.2853 58.79574 116.3616 291.5393 55.31562 115.7816 284.5502 58.76919 116.3911 285.5887 58.66407 117.027 286.7212 58.54767 117.502 287.604 58.45581 117.9959 288.5597 58.35532 118.3558 289.2828 58.27864 118.5021 289.5837 58.24657 119.0156 290.675 58.12953 119.5326 291.8359 58.00387 116.2574 298.3574 51.04507 115.383 304.6037 46.07479 113.8499 310.1799 40.50921 111.7859 315.0267 34.44927 109.3159 319.1107 27.98619 106.5565 322.4111 21.20323 103.6091 324.9154 14.17383 100.5634 326.6137 6.966196 94.57915 321.6595 8.569121 97.92844 320.1609 15.54284 101.1635 317.8557 22.33567 104.1775 314.7518 28.87338 106.8497 310.8612 35.07564 109.0412 306.2062 40.85038 110.6037 300.8258 46.09599 111.3898 294.7919 50.70075 111.2789 288.2211 54.55361 97.78395 323.8331 7.623665 103.69 320.1944 20.88009 100.781 322.3756 14.32765 106.4299 317.2958 27.22035 108.9084 313.6884 33.28253 111.0202 309.3885 38.99261 112.6518 304.4216 44.26963 113.6851 298.8342 49.02401 114.0127 292.7045 53.16154 169.9905 393.9013 26.63747 174.0454 416.5027 27.14129 169.9905 393.9013 26.63747 169.4482 390.549 26.20628 168.8418 384.5766 23.33894 169.0675 387.4113 25.09697 168.7563 382.1387 21.00284 168.7913 380.2055 18.20705 168.8488 379.4397 16.63206 168.9325 378.8296 14.97311 169.2949 377.0207 7.575 168.9325 378.8296 14.97311 167.0729 384.1044 13.19409 168.8488 379.4397 16.63206 168.9325 378.8296 14.97311 168.0046 381.1903 12.83763 168.9325 378.8296 14.97311 169.2949 377.0207 7.575 168.0046 381.1903 12.83763 168.6688 394.1462 20.30819 169.9905 393.9013 26.63747 169.4482 390.549 26.20628 172.6146 415.5353 20.26457 174.0454 416.5027 27.14129 169.9905 393.9013 26.63747 168.6688 394.1462 20.30819 168.1955 391.5476 19.98609 169.0675 387.4113 25.09697 168.4276 392.8358 20.22779 167.7703 389.1058 19.03304 168.8418 384.5766 23.33894 167.9747 390.2963 19.58488 167.4261 386.9719 17.51789 168.7563 382.1387 21.00284 167.5863 387.9918 18.3413 167.1899 385.2797 15.54609 168.7913 380.2055 18.20705 169.4212 376.435 0.007477939 169.2953 377.0188 -7.562598 168.9325 378.8296 -14.97312 168.9325 378.8296 -14.97312 167.0396 383.5763 -5.235938 169.2953 377.0188 -7.562598 168.9325 378.8296 -14.97312 168.849 379.4382 -16.62885 168.0046 381.1903 -12.83764 168.9325 378.8296 -14.97312 168.849 379.4382 -16.62885 168.0046 381.1903 -12.83764 167.0385 383.5737 4.563882 169.4212 376.435 0.007477939 167.0826 383.5504 10.70187 167.0245 383.5981 -0.3832 168.7915 380.2028 -18.20246 168.7563 382.1353 -20.99894 168.7601 381.1041 -19.65665 168.8417 384.5747 -23.33751 168.7827 383.2983 -22.23323 169.0675 387.4117 -25.09704 168.9359 385.9494 -24.29519 169.7008 392.2082 -26.50967 169.2377 388.9475 -25.73466 169.4482 390.5491 -26.20623 169.9905 393.9013 -26.63743 169.9905 393.9013 -26.63743 168.4243 392.8179 -20.22566 169.7008 392.2082 -26.50967 169.9905 393.9013 -26.63743 174.0454 416.503 -27.14124 168.6688 394.1462 -20.30819 169.9905 393.9013 -26.63743 174.0454 416.503 -27.14124 168.6688 394.1462 -20.30819 167.0728 384.1019 -13.1872 168.7915 380.2028 -18.20246 167.0826 383.5504 -10.70187 167.0624 383.7501 -11.94885 167.1145 384.6085 -14.38568 168.7601 381.1041 -19.65665 167.1869 385.2561 -15.51026 168.7563 382.1353 -20.99894 167.2885 386.0284 -16.53857 168.7827 383.2983 -22.23323 167.4189 386.9239 -17.4737 168.8417 384.5747 -23.33751 167.579 387.9466 -18.30915 168.9359 385.9494 -24.29519 167.764 389.0689 -19.01286 169.0675 387.4117 -25.09704 167.9687 390.262 -19.5713 169.2377 388.9475 -25.73466 168.1902 391.5177 -19.97852 169.4482 390.5491 -26.20623 177.9001 438.3255 -27.42485 181.5722 459.3571 -27.46382 185.08 479.5862 -27.23261 185.08 479.5862 -27.23261 180.5141 458.3121 -20.17555 181.5722 459.3571 -27.46382 185.08 479.5862 -27.23261 185.4008 481.3431 -27.1233 184.4679 479.6997 -20.13058 185.08 479.5862 -27.23261 185.4008 481.3431 -27.1233 184.4679 479.6997 -20.13058 176.563 436.9239 -20.22028 177.9001 438.3255 -27.42485 172.6146 415.5353 -20.26457 185.7448 483.0532 -26.83948 186.4884 486.2579 -25.79085 186.1087 484.6951 -26.3907 187.6827 490.4311 -23.07304 186.8801 487.7388 -25.03274 187.2801 489.1325 -24.12601 188.4635 492.6828 -20.59437 188.0794 491.6187 -21.88762 189.1827 494.4448 -17.63132 188.8325 493.627 -19.17462 189.5067 495.1201 -16.00011 190.4225 496.8454 -9.82236 189.5067 495.1201 -16.00011 186.4752 489.8092 -11.73555 189.1827 494.4448 -17.63132 189.5067 495.1201 -16.00011 188.0256 492.5462 -13.23624 189.5067 495.1201 -16.00011 190.4225 496.8454 -9.82236 188.0256 492.5462 -13.23624 184.9369 482.2176 -19.80795 185.7448 483.0532 -26.83948 184.7035 480.9651 -20.04744 185.1666 483.4424 -19.41007 186.1087 484.6951 -26.3907 186.4884 486.2579 -25.79085 185.3884 484.6135 -18.85927 186.8801 487.7388 -25.03274 185.5995 485.7138 -18.16202 187.2801 489.1325 -24.12601 185.796 486.7199 -17.3287 187.6827 490.4311 -23.07304 185.9741 487.6074 -16.383 188.0794 491.6187 -21.88762 186.1328 488.3699 -15.33742 188.4635 492.6828 -20.59437 186.271 488.9998 -14.19801 188.8325 493.627 -19.17462 186.386 489.4837 -12.98573 190.919 497.7342 -3.301383 190.9195 497.7352 3.286555 190.423 496.8464 9.816722 189.5068 495.1202 16.00012 189.5068 495.1202 16.00012 186.5351 489.9821 6.326436 190.423 496.8464 9.816722 189.5068 495.1202 16.00012 188.8366 493.6369 19.1588 188.0256 492.546 13.23617 189.5068 495.1202 16.00012 188.8366 493.6369 19.1588 188.0256 492.546 13.23617 186.5307 489.9755 -5.02226 190.919 497.7342 -3.301383 186.5387 489.9789 -10.47796 186.5248 489.9665 -0.308484 190.9195 497.7352 3.286555 186.5277 489.9713 2.818029 188.0843 491.6326 21.87275 186.4891 486.2607 25.78905 187.2832 489.143 24.11813 185.7439 483.0487 26.84048 185.4001 481.3394 27.12366 185.0801 479.5862 27.23373 185.0801 479.5862 27.23373 184.9328 482.1951 19.8144 185.4001 481.3394 27.12366 185.0801 479.5862 27.23373 181.5722 459.3567 27.46384 184.4679 479.6997 20.13058 185.0801 479.5862 27.23373 181.5722 459.3567 27.46384 184.4679 479.6997 20.13058 186.1367 488.388 15.30931 188.0843 491.6326 21.87275 186.3852 489.4803 12.99633 186.5387 489.9789 10.47782 185.9744 487.6087 16.38173 187.2832 489.143 24.11813 185.5925 485.678 18.18754 186.4891 486.2607 25.78905 185.791 486.6943 17.35243 185.3811 484.5757 18.87966 185.7439 483.0487 26.84048 185.1605 483.4097 19.42317 177.9001 438.3251 27.42489 180.5141 458.3121 20.17555 177.9001 438.3251 27.42489 176.563 436.9239 20.22028 168.6206 394.1558 19.99723 184.4679 479.6997 20.13058 180.5141 458.3121 20.17555 168.6032 394.158 19.68498 184.4595 479.7015 19.99992 184.9042 482.1102 19.55355 184.4679 479.6997 20.13058 184.4595 479.7015 19.99992 184.9328 482.1951 19.8144 176.563 436.9239 20.22028 172.6146 415.5353 20.26457 168.6688 394.1462 20.30819 168.6206 394.1558 19.99723 168.6688 394.1462 20.30819 168.4276 392.8358 20.22779 168.2307 392.0493 19.76514 168.1955 391.5476 19.98609 167.9747 390.2963 19.58488 167.8688 390.0718 19.09556 167.7703 389.1058 19.03304 167.5478 388.2943 18.02928 167.5863 387.9918 18.3413 167.4261 386.9719 17.51789 167.2784 386.7696 16.60483 167.1899 385.2797 15.54609 167.073 385.5625 14.86862 167.0729 384.1044 13.19409 167.0826 383.5504 10.70187 166.9431 384.7367 12.87951 167.0826 383.5504 10.70187 166.8982 384.35 10.68884 166.8989 384.3496 -10.68885 166.8982 384.35 10.68884 167.0826 383.5504 10.70187 167.0385 383.5737 4.563882 168.6032 394.158 19.68498 168.1772 391.8594 19.37818 167.7775 389.7025 18.47792 167.4326 387.8418 17.04177 167.1669 386.4081 15.16941 166.9982 385.4981 12.99563 166.9365 385.165 10.67302 166.9223 385.0887 0.115271 166.9365 385.165 10.67302 166.9365 385.1649 -10.67326 168.6033 394.1582 -19.68497 168.6032 394.158 19.68498 168.1772 391.8594 19.37818 184.458 479.7027 19.86907 181.7077 464.8632 7.7298 184.458 479.7027 19.86907 170.8813 406.449 -9.600602 173.6769 421.5332 7.538402 173.9192 422.8403 6.984919 174.7811 427.4909 7.7298 173.4144 420.1165 7.7298 170.8813 406.449 7.7298 175.4809 431.2666 7.7298 176.0433 434.3007 7.7298 176.7072 437.8829 7.7298 178.4299 447.1776 7.7298 168.1758 391.8515 -19.37622 167.7775 389.7025 18.47792 167.7753 389.691 -18.47154 167.4326 387.8418 17.04177 167.4306 387.8311 -17.03148 167.1669 386.4081 15.16941 167.1656 386.4011 -15.15799 166.9982 385.4981 12.99563 166.9978 385.4956 -12.98757 166.9365 385.165 10.67302 166.9223 385.0887 0.115271 166.9365 385.1649 -10.67326 184.458 479.7027 19.86907 184.4581 479.7032 -19.86927 184.9042 482.1102 19.55355 181.8154 465.4443 -6.2688 166.9432 384.7367 -12.88127 166.9978 385.4956 -12.98757 166.9365 385.1649 -10.67326 166.8989 384.3496 -10.68885 184.9042 482.1104 -19.55359 185.3192 484.349 18.6183 185.3192 484.349 18.6183 185.3192 484.3492 -18.61814 185.6755 486.2715 17.12988 185.3811 484.5757 18.87966 185.6755 486.2715 17.12988 185.1605 483.4097 19.42317 185.9498 487.7519 -15.18744 185.9498 487.7518 15.18775 185.791 486.6943 17.35243 185.9498 487.7518 15.18775 185.6755 486.2716 -17.12959 185.5925 485.678 18.18754 186.1239 488.691 -12.91878 186.1239 488.691 12.91899 186.1367 488.388 15.30931 186.1239 488.691 12.91899 185.9744 487.6087 16.38173 186.1853 489.0225 -10.47169 186.1853 489.0224 10.47174 186.3852 489.4803 12.99633 186.1853 489.0224 10.47174 186.1887 489.0404 0.131875 186.3211 489.5158 -10.47522 186.1853 489.0224 10.47174 186.1887 489.0404 0.131875 186.3211 489.5156 10.47518 186.3211 489.5156 10.47518 186.1853 489.0225 -10.47169 186.3211 489.5158 -10.47522 186.1853 489.0225 -10.47169 186.1239 488.691 -12.91878 186.271 488.9998 -14.19801 185.9498 487.7519 -15.18744 186.5387 489.9789 -10.47796 186.4752 489.8092 -11.73555 186.386 489.4837 -12.98573 185.9741 487.6074 -16.383 185.6755 486.2716 -17.12959 186.1328 488.3699 -15.33742 185.5995 485.7138 -18.16202 185.3192 484.3492 -18.61814 185.796 486.7199 -17.3287 185.1666 483.4424 -19.41007 184.9042 482.1104 -19.55359 185.3884 484.6135 -18.85927 184.7035 480.9651 -20.04744 184.4581 479.7032 -19.86927 184.9369 482.2176 -19.80795 168.6206 394.1558 -19.9974 184.4581 479.7032 -19.86927 168.6033 394.1582 -19.68497 171.5393 409.9994 -9.600602 174.7811 427.4909 -9.600602 175.4809 431.2666 -9.600602 176.0433 434.3007 -9.600602 178.077 445.2738 -9.600602 178.394 446.9841 -9.600602 181.8154 465.4443 -9.600602 184.4596 479.7015 -20.00017 184.4596 479.7015 -20.00017 168.6206 394.1558 -19.9974 168.6033 394.1582 -19.68497 168.1758 391.8515 -19.37622 167.8689 390.072 -19.09587 167.7753 389.691 -18.47154 168.2308 392.0494 -19.76575 167.5478 388.2943 -18.0295 167.4306 387.8311 -17.03148 167.2784 386.7693 -16.60452 167.1656 386.4011 -15.15799 167.0731 385.5628 -14.86982 171.5393 409.9994 -3.3318 174.7811 427.4909 -9.600602 174.2865 424.8222 -0.571245 174.1269 423.9612 -1.710942 174.7781 424.731 -0.571502 174.1269 423.9612 -1.710942 174.2865 424.8222 -0.571245 174.6185 423.8698 -1.711179 174.7811 427.4909 7.7298 174.3874 425.3664 3.640013 174.7811 427.4909 -9.600602 175.9725 431.1755 -9.600602 175.4809 431.2666 -9.600602 175.4809 431.2666 7.7298 175.9725 431.1755 -9.600602 175.2727 427.3998 -9.600602 175.4809 431.2666 -9.600602 175.9725 431.1755 7.7298 175.4809 431.2666 7.7298 174.7811 427.4909 7.7298 174.879 425.2753 3.639833 174.9139 425.4635 2.199 174.3874 425.3664 3.640013 174.7781 424.7311 4.969245 178.9215 447.0865 4.398 178.4299 447.1776 4.398 180.7529 459.7118 4.398 178.9215 447.0865 7.7298 178.4299 447.1776 7.7298 178.4299 447.1776 4.398 178.9215 447.0865 4.398 181.2445 459.6207 4.398 180.7529 459.7118 4.398 178.394 446.9841 -6.2688 181.2445 459.6207 4.398 178.8856 446.893 -6.2688 178.394 446.9841 -6.2688 178.394 446.9841 -9.600602 178.8856 446.893 -6.2688 178.8856 446.893 -9.600602 178.394 446.9841 -9.600602 181.8154 465.4443 -9.600602 178.8856 446.893 -9.600602 182.307 465.3532 -9.600602 181.8154 465.4443 -9.600602 181.8154 465.4443 -6.2688 182.307 465.3532 -9.600602 176.7072 437.8829 7.7298 176.7072 437.8829 -6.2688 178.077 445.2738 -6.2688 176.0433 434.3007 -9.600602 175.4809 431.2666 7.7298 175.4809 431.2666 -9.600602 174.879 425.2753 0.757987 174.2865 424.8222 -0.571245 174.3874 425.3665 0.758167 174.7781 424.731 -0.571502 173.906 420.0253 -3.3318 173.4144 420.1165 -3.3318 173.677 421.5334 -3.14035 172.0309 409.9082 -3.3318 173.4144 420.1165 -3.3318 173.906 420.0253 -3.3318 174.7811 427.4909 -9.600602 174.3874 425.3665 0.758167 174.2865 424.8222 -0.571245 172.0309 409.9082 -9.600602 171.5393 409.9994 -9.600602 171.5393 409.9994 -3.3318 171.3729 406.3579 -9.600602 170.8813 406.449 -9.600602 171.5393 409.9994 -9.600602 172.0309 409.9082 -9.600602 178.394 446.9841 -6.2688 178.4299 447.1776 4.398 176.7072 437.8829 7.7298 178.4299 447.1776 7.7298 174.7781 424.7311 4.969245 174.3874 425.3664 3.640013 174.2865 424.8221 4.969502 173.4144 420.1165 0 171.5393 409.9994 4.398 171.5393 409.9994 0 173.4144 420.1165 4.398 173.4948 420.5507 0.04708188 173.4948 420.5507 4.350918 173.5689 420.9503 0.170127 173.5689 420.9503 4.227873 173.6376 421.3208 0.37357 173.6376 421.3208 4.02443 173.6977 421.6453 0.644106 173.6977 421.6453 3.753894 173.747 421.9113 0.974163 173.747 421.9113 3.423837 173.7841 422.1114 1.350976 173.7841 422.1114 3.047024 173.8065 422.2323 1.757344 173.8065 422.2323 2.640656 173.8151 422.2786 2.199 174.4109 422.7495 6.984769 174.1269 423.9609 6.109179 173.9192 422.8403 6.984919 174.6186 423.8701 6.108942 174.1686 421.4422 7.53835 173.6769 421.5332 7.538402 173.4144 420.1165 7.7298 173.906 420.0253 7.7298 173.4144 420.1165 7.7298 170.8813 406.449 7.7298 173.906 420.0253 7.7298 171.3729 406.3579 7.7298 170.8813 406.449 7.7298 170.8813 406.449 -9.600602 171.3729 406.3579 7.7298 171.3729 406.3579 -9.600602 175.2727 427.3998 -9.600602 174.7811 427.4909 -9.600602 175.4809 431.2666 -9.600602 175.2727 427.3998 7.7298 174.7811 427.4909 7.7298 174.7811 427.4909 -9.600602 175.2727 427.3998 -9.600602 167.0396 383.5763 -5.235938 167.0826 383.5504 -10.70187 166.8989 384.3496 -10.68885 167.0624 383.7501 -11.94885 166.8989 384.3496 -10.68885 167.0826 383.5504 -10.70187 167.0245 383.5981 -0.3832 167.0385 383.5737 4.563882 166.9432 384.7367 -12.88127 168.0046 381.1903 -12.83764 167.0826 383.5504 -10.70187 167.0396 383.5763 -5.235938 167.0728 384.1019 -13.1872 167.1145 384.6085 -14.38568 167.0731 385.5628 -14.86982 167.1869 385.2561 -15.51026 167.2885 386.0284 -16.53857 167.2784 386.7693 -16.60452 167.4189 386.9239 -17.4737 167.579 387.9466 -18.30915 167.5478 388.2943 -18.0295 167.764 389.0689 -19.01286 167.8689 390.072 -19.09587 167.9687 390.262 -19.5713 168.1902 391.5177 -19.97852 168.2308 392.0494 -19.76575 168.4243 392.8179 -20.22566 168.6688 394.1462 -20.30819 168.6206 394.1558 -19.9974 168.6206 394.1558 -19.9974 168.6688 394.1462 -20.30819 172.6146 415.5353 -20.26457 176.563 436.9239 -20.22028 180.5141 458.3121 -20.17555 184.4679 479.6997 -20.13058 184.4596 479.7015 -20.00017 184.7035 480.9651 -20.04744 184.4596 479.7015 -20.00017 184.4679 479.6997 -20.13058 186.3211 489.5156 10.47518 186.3211 489.5158 -10.47522 186.5387 489.9789 -10.47796 188.0256 492.5462 -13.23624 186.5387 489.9789 -10.47796 186.4752 489.8092 -11.73555 186.5307 489.9755 -5.02226 186.5351 489.9821 6.326436 186.5387 489.9789 10.47782 186.3852 489.4803 12.99633 186.3211 489.5156 10.47518 186.5387 489.9789 10.47782 186.5277 489.9713 2.818029 186.5248 489.9665 -0.308484 188.0256 492.546 13.23617 186.5387 489.9789 10.47782 186.5351 489.9821 6.326436 182.307 465.3532 -6.2688 181.8154 465.4443 -6.2688 179.3487 452.1355 -6.2688 171.3729 406.3579 7.7298 171.3729 406.3579 -9.600602 172.0309 409.9082 -9.600602 172.0309 409.9082 -3.3318 173.906 420.0253 4.398 173.906 420.0253 7.7298 172.0309 409.9082 0 172.0309 409.9082 4.398 174.1292 421.2297 4.02443 174.1686 421.4422 7.53835 174.0605 420.8592 4.227873 173.9865 420.4596 4.350918 173.906 420.0253 0 173.906 420.0253 -3.3318 174.1686 421.4421 -3.140402 174.1893 421.5542 0.644106 174.4108 422.7492 -2.586919 173.9865 420.4596 0.04708188 174.0605 420.8592 0.170127 174.1292 421.2297 0.37357 174.4109 422.7495 6.984769 174.6185 423.8698 -1.711179 174.2981 422.1412 2.640656 174.2386 421.8202 0.974163 174.2757 422.0202 1.350976 174.2981 422.1412 1.757344 174.3067 422.1875 2.199 174.6186 423.8701 6.108942 174.7781 424.731 -0.571502 174.7781 424.7311 4.969245 174.879 425.2753 0.757987 174.879 425.2753 3.639833 174.9139 425.4635 2.199 174.2757 422.0202 3.047024 174.2386 421.8202 3.423837 174.1893 421.5542 3.753894 171.5393 409.9994 4.398 172.0309 409.9082 4.398 172.0309 409.9082 0 173.4144 420.1165 4.398 173.906 420.0253 4.398 172.0309 409.9082 4.398 171.5393 409.9994 4.398 171.5393 409.9994 0 172.0309 409.9082 0 173.906 420.0253 0 171.5393 409.9994 0 173.4144 420.1165 0 173.906 420.0253 0 173.9865 420.4596 0.04708188 173.4144 420.1165 0 173.4948 420.5507 0.04708188 174.0605 420.8592 0.170127 173.5689 420.9503 0.170127 174.1292 421.2297 0.37357 173.6376 421.3208 0.37357 174.1893 421.5542 0.644106 173.6977 421.6453 0.644106 174.2386 421.8202 0.974163 173.747 421.9113 0.974163 174.2757 422.0202 1.350976 173.7841 422.1114 1.350976 174.2981 422.1412 1.757344 173.8065 422.2323 1.757344 174.3067 422.1875 2.199 173.8151 422.2786 2.199 174.2981 422.1412 2.640656 173.8065 422.2323 2.640656 174.2757 422.0202 3.047024 173.7841 422.1114 3.047024 174.2386 421.8202 3.423837 173.747 421.9113 3.423837 174.1893 421.5542 3.753894 173.6977 421.6453 3.753894 174.1292 421.2297 4.02443 173.6376 421.3208 4.02443 174.0605 420.8592 4.227873 173.5689 420.9503 4.227873 173.9865 420.4596 4.350918 173.4948 420.5507 4.350918 173.906 420.0253 4.398 173.4144 420.1165 4.398 115.993 567.6346 -27.66399 118.6555 570.794 -31.84755 120.916 569.637 -31.31476 114.4533 568.3211 -28.19537 118.9822 565.9119 -26.89754 123.0936 568.2573 -31.0209 117.5065 566.8297 -27.2301 120.4072 564.8883 -26.66989 125.1519 566.6782 -30.97086 121.77 563.7681 -26.54829 123.0606 562.5604 -26.53309 108.9461 564.0877 -20.56344 114.4533 568.3211 -28.19537 115.993 567.6346 -27.66399 111.2551 563.0012 -19.6484 117.5065 566.8297 -27.2301 118.9822 565.9119 -26.89754 113.4718 561.6182 -18.92751 120.4072 564.8883 -26.66989 115.5549 559.9614 -18.4157 121.77 563.7681 -26.54829 117.4677 558.0633 -18.12041 123.0606 562.5604 -26.53309 103.3827 561.186 -12.34529 106.4591 559.7053 -11.00136 109.3155 557.6549 -9.941179 111.8506 555.1072 -9.20232 123.7901 536.2987 -8.222597 122.2432 539.1483 -8.508129 123.9383 536.4362 -8.566074 141.5214 506.6333 -8.06471 123.9383 536.4362 -8.566074 124.1681 536.4835 -8.898372 123.7901 536.2987 -8.222597 123.9383 536.4362 -8.566074 141.5214 506.6333 -8.06471 124.3647 536.572 -9.235679 124.5357 536.7075 -9.574007 124.6809 536.8866 -9.910348 124.8001 537.1064 -10.24172 145.4696 499.8197 -9.201619 141.5214 506.6333 -8.06471 145.2864 510.2185 -16.5437 141.3924 506.487 -7.741603 145.4696 499.8197 -9.201619 141.3924 506.487 -7.741603 141.5214 506.6333 -8.06471 152.5168 508.2346 -24.96564 149.2142 514.9315 -24.50076 148.9042 503.5869 -17.35784 156.1893 513.799 -31.93395 153.1544 520.8908 -31.82075 159.8029 520.2748 -38.18756 156.8872 527.9812 -38.26179 163.2518 527.6049 -43.68167 160.2692 536.1252 -43.78109 166.4565 535.6899 -48.41067 161.8298 540.6166 -46.23907 163.2963 545.3479 -48.49355 141.2709 506.3385 -7.416421 141.2709 506.3385 -7.416421 123.6248 536.1984 -7.874366 141.0422 505.7369 -6.335302 123.6248 536.1984 -7.874366 141.2709 506.3385 -7.416421 145.2196 499.4637 -8.478413 141.0422 505.7369 -6.335302 141.2709 506.3385 -7.416421 145.2196 499.4637 -8.478413 123.5651 536.1705 -7.77547 121.8323 538.9238 -7.712584 123.6248 536.1984 -7.874366 123.5651 536.1705 -7.77547 121.9491 538.9362 -7.902199 150.3471 477.0908 -14.90921 150.7507 477.6445 -15.88967 150.1506 470.3296 -19.0209 154.4228 482.5574 -24.1649 150.1506 470.3296 -19.0209 150.7507 477.6445 -15.88967 149.9104 470.0209 -18.48197 144.2166 447.5814 -21.1855 149.9104 470.0209 -18.48197 150.1506 470.3296 -19.0209 151.2508 471.7543 -21.42986 151.2508 471.7543 -21.42986 149.8181 484.6406 -12.27648 150.1591 485.1284 -13.16222 154.113 490.325 -22.44476 150.1591 485.1284 -13.16222 148.0938 492.1642 -10.1139 148.3838 492.5827 -10.91401 151.9743 496.9908 -19.5519 148.3838 492.5827 -10.91401 144.8154 498.6332 -6.99114 148.0938 492.1642 -10.1139 147.4653 491.0985 -8.146356 149.8181 484.6406 -12.27648 149.1513 475.5271 -11.82195 150.3471 477.0908 -14.90921 148.9233 483.329 -9.77073 149.6711 469.718 -17.93948 148.1596 467.9143 -14.28653 149.6711 469.718 -17.93948 149.6711 469.718 -17.93948 148.1596 467.9143 -14.28653 151.9528 455.8706 -35.90971 161.0911 466.8387 -50.64106 153.8413 437.0227 -49.41643 159.2468 482.8015 -36.84574 163.9953 490.058 -44.6771 159.0583 482.5252 -36.51741 144.9603 429.172 -35.24451 146.7377 407.1754 -48.08734 138.0929 402.4429 -34.50053 139.7875 377.2972 -46.64912 133.2218 347.3463 -45.45401 132.9658 347.3948 -45.09379 131.353 375.6837 -33.67647 134.1692 347.1653 -46.77661 135.1508 346.976 -48.12942 136.1664 346.7784 -49.51065 137.2179 346.5715 -50.92166 138.3072 346.3542 -52.36348 139.4345 346.1268 -53.83471 140.6004 345.889 -55.33434 131.1901 343.3833 -44.01745 132.9658 347.3948 -45.09379 133.2218 347.3463 -45.45401 131.8465 347.6056 -43.50381 131.8465 347.6056 -43.50381 132.3431 343.0064 -45.68364 134.1692 347.1653 -46.77661 133.5087 342.6268 -47.33906 135.1508 346.976 -48.12942 134.6866 342.2444 -48.98363 136.1664 346.7784 -49.51065 135.8769 341.859 -50.61728 137.2179 346.5715 -50.92166 138.3072 346.3542 -52.36348 137.0794 341.4704 -52.23997 139.4345 346.1268 -53.83471 138.2941 341.0787 -53.85161 140.6004 345.889 -55.33434 139.5207 340.6835 -55.45215 162.4574 494.4964 -39.26535 163.9953 490.058 -44.6771 159.2468 482.8015 -36.84574 166.6344 501.5209 -45.94777 159.0583 482.5252 -36.51741 154.5944 476.2149 -28.2808 158.3548 488.1705 -31.98192 154.5944 476.2149 -28.2808 137.2841 423.3066 -20.95327 130.4609 399.0015 -20.66094 125.678 348.7298 -34.27653 124.7026 348.903 -32.73908 123.746 374.6672 -20.30914 126.7 348.5474 -35.86322 127.6703 348.3733 -37.34729 128.6849 348.1894 -38.87688 129.7434 347.996 -40.44884 130.7722 347.806 -41.95449 124.5409 345.5963 -33.79759 124.7026 348.903 -32.73908 125.678 348.7298 -34.27653 124.0221 349.0234 -31.65262 123.4789 345.9592 -32.0579 124.0221 349.0234 -31.65262 125.6165 345.2323 -35.52706 126.7 348.5474 -35.86322 127.6703 348.3733 -37.34729 126.7053 344.8668 -37.24618 128.6849 348.1894 -38.87688 127.8072 344.4993 -38.95484 129.7434 347.996 -40.44884 128.922 344.1296 -40.65298 130.7722 347.806 -41.95449 130.0497 343.7577 -42.34054 136.5414 437.3221 -6.496051 147.4998 467.1984 -12.54607 146.747 466.4441 -10.42038 145.458 465.3321 -6.327146 127.9337 409.7886 -6.593951 119.4333 382.0812 -6.622331 117.6231 350.199 -20.8015 117.116 350.3035 -19.88391 110.9029 353.5314 -6.734655 118.5557 350.0141 -22.46394 119.5333 349.8294 -24.17318 120.2142 349.7036 -25.34561 120.9187 349.576 -26.5433 121.6508 349.4445 -27.7725 122.4103 349.3091 -29.03167 123.1995 349.1692 -30.32358 116.4571 348.5487 -19.60675 117.116 350.3035 -19.88391 117.6231 350.199 -20.8015 110.9674 353.4841 -6.89061 111.0256 353.407 -7.051347 111.0758 353.3021 -7.211934 111.3914 352.7206 -8.168148 111.8088 352.2339 -9.252597 112.333 351.8462 -10.46878 112.9349 351.5173 -11.78062 116.4894 350.4396 -18.73466 116.4894 350.4396 -18.73466 117.4113 348.1615 -21.41338 118.5557 350.0141 -22.46394 118.3835 347.7846 -23.21102 119.5333 349.8294 -24.17318 119.3723 347.4144 -24.99953 120.2142 349.7036 -25.34561 120.9187 349.576 -26.5433 120.3769 347.0484 -26.77873 121.6508 349.4445 -27.7725 121.3966 346.6846 -28.54833 122.4103 349.3091 -29.03167 123.1995 349.1692 -30.32358 122.4307 346.3218 -30.3081 147.4998 467.1984 -12.54607 146.747 466.4441 -10.42038 148.0514 474.2868 -8.575824 145.458 465.3321 -6.327146 144.995 465.0053 -4.656908 145.458 465.3321 -6.327146 136.5414 437.3221 -6.496051 147.0757 473.3984 -5.202428 146.726 473.1499 -3.818984 147.0757 473.3984 -5.202428 145.458 465.3321 -6.327146 144.995 465.0053 -4.656908 135.5249 436.8092 -3.025954 127.9337 409.7886 -6.593951 110 229.2474 -47.73216 110 221.826 41.96307 110 229.2527 47.73582 144.5878 464.8291 -2.924179 126.697 408.9726 -3.093507 119.4333 382.0812 -6.622331 110.8337 353.5511 -6.585107 117.9326 380.7705 -3.127657 110.8337 353.5511 -6.585107 110.6931 353.0963 -6.580119 110.8337 353.5511 -6.585107 110.9029 353.5314 -6.734655 110.7504 353.5541 -6.414313 110.8108 352.8443 -6.96391 111.0758 353.3021 -7.211934 111.3914 352.7206 -8.168148 111.3602 351.7477 -8.67147 111.8088 352.2339 -9.252597 112.333 351.8462 -10.46878 112.0736 350.9663 -10.47298 112.9349 351.5173 -11.78062 115.8832 350.5798 -17.60583 113.6085 351.2409 -13.17702 112.8737 350.354 -12.30377 113.6085 351.2409 -13.17702 115.0766 350.7835 -16.07451 114.32 350.999 -14.60289 113.7236 349.8386 -14.13548 114.32 350.999 -14.60289 114.6099 349.3779 -15.9671 115.0766 350.7835 -16.07451 115.8832 350.5798 -17.60583 115.5223 348.9514 -17.79126 162.8251 503.6603 -38.99155 167.2904 511.7811 -46.03887 158.383 496.496 -31.09481 163.7564 515.7768 -41.59722 167.6005 523.8228 -47.38319 159.7894 508.5831 -34.98981 155.8186 502.3149 -27.6125 144.3892 498.092 -5.417509 143.9589 497.8401 -3.779235 140.3589 505.3188 -3.998863 140.1677 505.3716 -3.426729 140.3589 505.3188 -3.998863 143.9589 497.8401 -3.779235 140.7325 505.3944 -5.193562 122.3464 535.7144 -4.803707 140.7325 505.3944 -5.193562 140.3589 505.3188 -3.998863 140.1677 505.3716 -3.426729 146.3155 489.8796 -3.910681 143.783 497.8233 -3.092385 146.3155 489.8796 -3.910681 146.8663 490.3341 -6.069348 147.3641 481.6568 -4.389471 146.109 489.7893 -3.019197 147.3641 481.6568 -4.389471 148.098 482.3278 -7.131571 147.0992 481.4874 -3.263677 123.5104 536.151 -7.672266 123.5104 536.151 -7.672266 121.8323 538.9238 -7.712584 123.5104 536.151 -7.672266 122.3464 535.7144 -4.803707 139.995 505.459 -2.918808 121.751 535.4336 -1.634611 110 221.7832 -41.92382 110 215.4543 35.05654 139.5896 505.7034 1.230311 121.749 535.4329 1.613872 139.5608 505.7194 0.993617 139.5346 505.7366 -0.744963 139.5599 505.7198 -0.984627 140.359 505.3188 3.999053 122.3458 535.7131 4.799978 140.1869 505.3644 3.484556 110 215.3974 -34.9838 110 210.3247 27.22747 139.995 505.459 2.918806 141.0415 505.7357 6.332516 123.5104 536.151 7.67235 140.732 505.3942 5.192037 141.2709 506.3385 7.416425 123.5651 536.1705 7.775512 121.9491 538.9362 7.902199 123.5104 536.151 7.67235 123.5651 536.1705 7.775512 121.8324 538.9238 7.71264 123.6248 536.1984 7.874367 123.6248 536.1984 7.874367 141.3924 506.487 7.741588 123.6248 536.1984 7.874367 141.2709 506.3385 7.416425 123.7898 536.299 8.222576 121.9491 538.9362 7.902199 123.6248 536.1984 7.874367 123.7898 536.299 8.222576 144.8144 498.6314 6.987296 141.2709 506.3385 7.416425 141.0415 505.7357 6.332516 145.2196 499.4652 8.477823 141.3924 506.487 7.741588 141.2709 506.3385 7.416425 145.2196 499.4652 8.477823 144.3887 498.0915 5.415466 140.732 505.3942 5.192037 143.9589 497.8401 3.779438 140.359 505.3188 3.999053 143.7761 497.824 3.065602 140.359 505.3188 3.999053 140.1869 505.3644 3.484556 143.9589 497.8401 3.779438 110 206.4887 -18.50794 110 206.5183 18.59349 110 210.2755 -27.13714 143.5914 497.8851 2.363832 139.995 505.459 2.918806 143.3082 498.0431 0.787206 139.995 505.459 2.918806 139.5896 505.7034 1.230311 143.5914 497.8851 2.363832 139.5608 505.7194 0.993617 143.3096 498.0423 -0.803135 139.5346 505.7366 -0.744963 139.5599 505.7198 -0.984627 143.5914 497.8851 -2.363835 139.995 505.459 -2.918808 143.5914 497.8851 -2.363835 139.995 505.459 -2.918808 120.242 541.654 7.951237 120.3997 541.6967 8.218363 117.0266 547.5341 8.820644 113.9768 552.1536 8.809 113.6568 552.0183 8.245432 111.8506 555.1072 9.202322 113.6568 552.0183 8.245432 113.9768 552.1536 8.809 120.0919 542.8812 8.83542 120.2306 542.5894 8.769593 120.3319 542.3663 8.712802 120.4018 542.2027 8.665046 120.447 542.0875 8.626152 120.4919 541.9522 8.569451 120.5039 541.8329 8.482357 120.3997 541.6967 8.218363 119.9363 544.7519 10.16499 113.9768 552.1536 8.809 117.0266 547.5341 8.820644 115.7262 556.7609 15.18845 111.8506 555.1072 9.202322 113.9768 552.1536 8.809 117.0722 554.2337 14.38174 120.1665 549.194 13.96245 117.0722 554.2337 14.38174 119.9551 546.8261 11.85269 120.0919 542.8812 8.83542 122.5174 540.1405 9.682854 120.0919 542.8812 8.83542 120.2306 542.5894 8.769593 122.8477 542.4404 11.90196 119.9363 544.7519 10.16499 120.0919 542.8812 8.83542 122.5174 540.1405 9.682854 124.7906 537.0897 10.21605 120.3319 542.3663 8.712802 124.8934 537.3677 10.56913 124.665 536.8625 9.869955 120.4018 542.2027 8.665046 124.5153 536.6872 9.53053 120.447 542.0875 8.626152 124.3444 536.5601 9.198783 120.4919 541.9522 8.569451 120.5039 541.8329 8.482357 122.2431 539.1483 8.508049 120.5039 541.8329 8.482357 122.2431 539.1483 8.508049 123.9382 536.4362 8.566069 108.5642 557.4264 8.760399 111.1912 554.8843 8.090186 108.1904 556.2625 5.841384 111.1912 554.8843 8.090186 108.5642 557.4264 8.760399 110.4437 554.0641 5.510762 106.4591 559.7053 11.00136 105.5944 559.447 9.727533 105.6464 558.0828 6.325259 105.5944 559.447 9.727533 109.3155 557.6549 9.941182 103.3827 561.186 12.3453 102.3898 560.8727 10.95642 102.8754 559.4795 6.950337 102.3898 560.8727 10.95642 99.94689 560.4176 7.700881 109.3237 561.9395 16.96554 103.3827 561.186 12.3453 106.4591 559.7053 11.00136 106.9211 563.0407 17.96873 111.6222 560.5057 16.15767 109.3155 557.6549 9.941182 113.7706 558.7678 15.56136 98.76642 559.9996 3.924756 101.84 559.1402 3.53784 104.7435 557.7975 3.21726 107.4017 556.0061 2.971343 109.7462 553.8125 2.806405 110.9778 565.2873 23.11461 113.1941 564.2236 22.28977 115.3293 562.8956 21.65624 117.3475 561.3256 21.22474 117.4304 554.5123 15.01476 119.2147 559.5402 21.00246 120.5584 551.6173 16.25868 117.4304 554.5123 15.01476 120.5235 557.2025 20.35505 121.0911 553.7736 18.43388 120.5235 557.2025 20.35505 120.8799 557.5556 20.964 121.8433 555.9862 20.79578 120.8799 557.5556 20.964 115.9932 567.6347 27.66424 114.4536 568.3213 28.19561 117.5067 566.8298 27.23036 118.9824 565.9121 26.89781 121.7702 563.7683 26.54856 120.4074 564.8884 26.67016 123.0608 562.5605 26.53336 124.2688 561.2745 26.62497 123.3207 559.4008 24.55148 124.2688 561.2745 26.62497 122.5151 557.64 22.60541 125.1521 566.6788 30.97128 123.0608 562.5605 26.53336 124.2688 561.2745 26.62497 130.7027 552.4007 26.85662 124.2688 561.2745 26.62497 123.3207 559.4008 24.55148 125.4741 562.7508 28.57906 125.4741 562.7508 28.57906 118.6558 570.7945 31.84792 114.4536 568.3213 28.19561 115.9932 567.6347 27.66424 117.5067 566.8298 27.23036 120.9163 569.6375 31.31516 118.9824 565.9121 26.89781 123.0939 568.2579 31.02131 120.4074 564.8884 26.67016 121.7702 563.7683 26.54856 129.0329 550.8733 24.39397 122.5151 557.64 22.60541 127.4644 549.343 21.89669 121.8433 555.9862 20.79578 126.0149 547.787 19.37392 121.0911 553.7736 18.43388 124.7167 546.1666 16.84172 120.5584 551.6173 16.25868 120.1665 549.194 13.96245 123.6312 544.4129 14.33167 119.9551 546.8261 11.85269 142.049 581.8507 48.18965 151.0539 569.9171 48.35701 153.3019 572.0261 50.08963 161.0086 559.1134 50.61926 144.1758 583.6853 49.77828 140.0076 580.0281 46.53654 148.8206 567.889 46.53531 158.9805 557.1235 49.00757 138.0488 578.2212 44.82304 146.6128 565.9353 44.62865 157.0211 555.3445 47.39497 136.1766 576.4271 43.05395 144.4384 564.0509 42.64136 153.3184 552.3426 44.20326 155.1282 553.7656 45.7902 134.4013 574.637 41.23545 142.3045 562.2316 40.57782 151.587 551.0794 42.64404 132.7261 572.8475 39.37314 140.2181 560.473 38.44247 149.9168 549.932 41.09693 131.1472 571.0619 37.47154 138.1851 558.7699 36.24005 146.7421 547.9503 38.04477 148.299 548.8915 39.56027 145.2479 547.0982 36.55515 136.211 557.1171 33.97536 128.3637 566.9689 33.33068 134.3016 555.5092 31.6532 142.4579 545.6429 33.68295 143.8164 546.3327 35.0975 126.9118 564.7161 30.92742 132.4626 553.9408 29.27842 139.9369 544.47 30.98255 127.0522 564.9207 31.15779 141.1666 545.0279 32.31338 138.7673 543.97 29.69487 135.5829 542.7207 26.06097 137.653 543.5142 28.44483 133.6196 542.0175 23.71583 131.809 541.3986 21.46903 130.1947 540.8497 19.38048 127.319 539.7135 15.32565 128.7 540.3079 17.34551 126.1643 539.038 13.44349 125.351 538.2676 11.85134 124.8934 537.3677 10.56913 126.9118 564.7161 30.92742 127.0522 564.9207 31.15779 164.6562 550.2944 50.54376 161.0086 559.1134 50.61926 158.9805 557.1235 49.00757 163.2871 545.3167 48.47967 157.0211 555.3445 47.39497 161.8168 540.5763 46.21861 155.1282 553.7656 45.7902 153.3184 552.3426 44.20326 160.2526 536.0797 43.75447 151.587 551.0794 42.64404 149.9168 549.932 41.09693 148.299 548.8915 39.56027 156.8649 527.9329 38.22417 146.7421 547.9503 38.04477 145.2479 547.0982 36.55515 143.8164 546.3327 35.0975 142.4579 545.6429 33.68295 153.1313 520.8508 31.77911 141.1666 545.0279 32.31338 139.9369 544.47 30.98255 138.7673 543.97 29.69487 137.653 543.5142 28.44483 135.5829 542.7207 26.06097 149.197 514.9075 24.46695 133.6196 542.0175 23.71583 131.809 541.3986 21.46903 130.1947 540.8497 19.38048 128.7 540.3079 17.34551 145.279 510.2101 16.52748 127.319 539.7135 15.32565 126.1643 539.038 13.44349 125.351 538.2676 11.85134 124.8934 537.3677 10.56913 124.7906 537.0897 10.21605 166.4567 535.691 48.41112 161.8168 540.5763 46.21861 160.2526 536.0797 43.75447 163.2534 527.608 43.68398 156.8649 527.9329 38.22417 159.8055 520.2796 38.19189 153.1313 520.8508 31.77911 156.1932 513.8049 31.94093 149.197 514.9075 24.46695 152.5218 508.2414 24.97516 145.279 510.2101 16.52748 123.9382 536.4362 8.566069 141.5214 506.6333 8.06471 148.9106 503.5941 17.37219 141.5214 506.6333 8.06471 124.3444 536.5601 9.198783 124.5153 536.6872 9.53053 124.665 536.8625 9.869955 141.5214 506.6333 8.06471 123.9382 536.4362 8.566069 145.4697 499.8195 9.201579 145.4697 499.8195 9.201579 141.5214 506.6333 8.06471 123.9382 536.4362 8.566069 167.6018 523.8251 47.38499 163.7589 515.7813 41.60113 159.7933 508.589 34.99662 155.8235 502.3222 27.62199 151.9807 496.9989 19.56658 148.384 492.5826 10.91396 148.384 492.5826 10.91396 167.292 511.7838 46.04125 162.8284 503.6653 38.99724 158.3878 496.5032 31.10357 154.1196 490.3337 22.4594 150.1593 485.1282 13.16217 148.0937 492.1658 10.11334 150.1593 485.1282 13.16217 166.6361 501.5234 45.95058 162.4609 494.5018 39.27112 158.3599 488.1779 31.99154 154.4298 482.5668 24.18024 150.751 477.6441 15.88963 149.8186 484.6392 12.2768 150.751 477.6441 15.88963 164.0247 490.1041 44.72381 159.288 482.8614 36.91776 154.6261 476.2588 28.3422 159.0769 482.5517 36.55046 151.2676 471.7771 21.46487 150.1501 470.3294 19.02104 149.9104 470.0208 18.48189 150.1501 470.3294 19.02104 149.6714 469.7178 17.93934 150.3476 477.0892 14.9096 161.0246 466.5125 50.65669 159.288 482.8614 36.91776 159.0769 482.5517 36.55046 151.9702 455.8918 35.93915 154.6261 476.2588 28.3422 151.2676 471.7771 21.46487 144.2308 447.5961 21.21492 150.1501 470.3294 19.02104 149.9104 470.0208 18.48189 153.797 436.7776 49.4334 144.9771 429.1867 35.27295 146.7149 407.0116 48.10616 138.1092 402.451 34.52792 139.7854 377.2149 46.67034 131.3688 375.6854 33.70275 130.4744 399.0047 20.68878 123.7592 374.6646 20.33613 137.2979 423.3156 20.98192 119.4758 382.2192 6.621936 110.9731 353.4772 6.906038 111.0294 353.3995 7.063343 110.9072 353.5288 6.744768 110.8337 353.5513 6.585051 128.0145 410.0506 6.593294 136.6203 437.5771 6.495335 145.4579 465.3318 6.327086 146.9037 466.59 10.8836 147.6662 467.3745 12.99506 148.1411 467.8921 14.24089 149.6714 469.7178 17.93934 117.9271 380.7524 3.127661 110.8337 353.5513 6.585051 119.4758 382.2192 6.621936 110.6639 353.5277 6.249513 110.6912 353.0925 6.578598 110.8337 353.5513 6.585051 110.6639 353.5277 6.249513 126.6883 408.945 3.093571 128.0145 410.0506 6.593294 135.5174 436.7858 3.026023 136.6203 437.5771 6.495335 145.0268 465.0244 4.77973 145.4579 465.3318 6.327086 144.9911 465.003 4.641687 144.5878 464.8291 2.924202 148.0502 474.2854 8.571763 145.4579 465.3318 6.327086 146.9037 466.59 10.8836 145.0268 465.0244 4.77973 145.4579 465.3318 6.327086 147.0757 473.3982 5.20254 147.0757 473.3982 5.20254 149.1484 475.5234 11.81403 147.6662 467.3745 12.99506 148.1411 467.8921 14.24089 150.3476 477.0892 14.9096 149.6714 469.7178 17.93934 109.9655 352.6959 5.183135 110.152 352.6683 5.681578 110.2416 353.0938 5.583174 109.0538 351.6558 3.130626 110.2416 353.0938 5.583174 110.3533 353.246 5.741737 109.9655 352.6959 5.183135 110.4621 353.372 5.906848 108.703 351.5699 0 108.9366 351.2662 3.141521 109.0538 351.6558 3.130626 109.3153 351.8605 3.954563 109.1668 351.7215 3.542412 109.5006 352.076 4.367617 109.7188 352.3579 4.778213 117.9271 380.7524 3.127661 108.703 351.5699 0 109.0538 351.6558 3.130626 109.1651 351.7195 -3.537776 108.9366 351.2662 -3.14153 109.0538 351.6558 -3.130634 120.248 389.2991 0 109.0538 351.6558 -3.130634 109.1651 351.7195 -3.537776 109.0538 351.6558 -3.130634 117.9326 380.7705 -3.127657 110.3491 353.2406 -5.735692 110.152 352.6683 -5.681579 110.2416 353.0938 -5.583175 110.2416 353.0938 -5.583175 109.9632 352.6929 -5.179328 110.3491 353.2406 -5.735692 109.7152 352.3532 -4.771897 109.4969 352.0714 -4.360017 109.3123 351.857 -3.947366 110.6576 353.5238 -6.238432 110.5589 353.4603 -6.065168 110.4557 353.365 -5.896948 136.7897 336.0846 -54.27484 137.839 335.6145 -55.70791 135.7686 336.5455 -52.85848 134.7752 336.9975 -51.45931 133.8094 337.4405 -50.07822 132.6404 337.982 -48.37808 131.5116 338.5103 -46.70614 130.4211 339.0261 -45.0615 129.369 339.5295 -43.44611 128.3537 340.0207 -41.85977 127.3732 340.5004 -40.30125 125.513 341.4261 -37.26944 126.4263 340.9688 -38.77067 124.6325 341.8722 -35.79812 123.7842 342.3073 -34.35767 122.9678 342.7313 -32.94909 122.1814 343.1452 -31.57093 121.1775 343.6825 -29.77928 120.2241 344.2027 -28.04314 119.3162 344.7093 -26.35575 118.4502 345.2036 -24.71389 116.8458 346.1582 -21.57902 117.6268 345.686 -23.12108 116.1061 346.6198 -20.08871 115.4068 347.0751 -18.64865 114.1263 347.9689 -15.92387 114.7476 347.5234 -17.26177 113.5384 348.4207 -14.62415 112.9827 348.8746 -13.36506 112.218 349.5962 -11.54942 111.5344 350.374 -9.82049 110.977 351.3055 -8.210206 119.1202 322.2314 -39.20741 126.4263 340.9688 -38.77067 127.3732 340.5004 -40.30125 128.3537 340.0207 -41.85977 129.369 339.5295 -43.44611 130.4211 339.0261 -45.0615 131.5116 338.5103 -46.70614 132.6404 337.982 -48.37808 125.0363 320.3262 -48.45126 133.8094 337.4405 -50.07822 134.7752 336.9975 -51.45931 135.7686 336.5455 -52.85848 136.7897 336.0846 -54.27484 137.839 335.6145 -55.70791 146.4028 473.0145 -2.367131 144.5878 464.8291 -2.924179 144.2233 464.4843 -0.970817 144.5878 464.8291 -2.924179 135.5249 436.8092 -3.025954 144.2233 464.4843 -0.970817 146.4028 473.0145 -2.367131 144.5878 464.8291 -2.924179 132.0724 426.9425 0 126.697 408.9726 -3.093507 144.1773 464.4381 -0.003240883 110 204.1759 -9.373581 110 204.1852 9.428307 145.8997 489.792 -2.082171 145.8997 489.792 -2.082171 146.8463 481.4183 -2.083285 145.6995 489.8361 -0.703474 146.8463 481.4183 -2.083285 146.1647 472.8099 -0.804362 146.6606 481.3426 -0.703887 145.8997 489.7921 2.082169 145.8997 489.7921 2.082169 146.6596 481.3422 0.689913 146.8463 481.4184 2.083282 146.1011 489.7875 2.984643 146.8463 481.4184 2.083282 145.6985 489.8364 0.689507 146.1635 472.8088 0.78841 146.4028 473.0144 2.367135 146.7133 473.1427 3.765448 146.4028 473.0144 2.367135 147.0894 481.4829 3.220123 144.2242 464.4852 0.980046 144.5878 464.8291 2.924202 144.5878 464.8291 2.924202 110 203.4 0 135.5174 436.7858 3.026023 144.5878 464.8291 2.924202 144.2242 464.4852 0.980046 144.9911 465.003 4.641687 144.1773 464.4381 -0.003240883 146.3155 489.8795 3.910896 146.3155 489.8795 3.910896 147.3641 481.6567 4.389656 146.8657 490.3334 6.066706 147.3641 481.6567 4.389656 148.0971 482.3267 7.128251 148.0937 492.1658 10.11334 148.9211 483.326 9.764286 149.8186 484.6392 12.2768 147.4638 491.0961 8.141283 126.6883 408.945 3.093571 110 563.4 0 110 657.4 0 110 656.6793 -8.199214 110 564.1207 8.199214 110 656.6873 8.154454 110 566.2337 -16.07196 110 654.5388 -16.14717 110 564.1127 -8.154454 110 569.6973 -23.49881 110 651.0531 -23.5842 110 574.3664 -30.17697 110 646.3702 -30.25212 110 580.1607 -35.97861 110 640.5817 -36.02696 110 586.8952 -40.69878 110 633.8741 -40.71679 110 626.4625 -44.16893 110 594.3435 -44.17075 110 618.568 -46.28363 110 602.2671 -46.28967 110 610.4229 -46.99877 110 654.5664 16.07196 110 566.2612 16.14717 110 651.1028 23.49881 110 569.7469 23.5842 110 646.4336 30.17697 110 574.4298 30.25212 110 640.6393 35.97861 110 580.2183 36.02696 110 633.9048 40.69878 110 586.9259 40.71679 110 594.3375 44.16893 110 626.4565 44.17075 110 602.2321 46.28363 110 618.5329 46.28967 110 610.3771 46.99877 182.307 465.3532 -9.600602 181.8154 465.4443 -6.2688 182.307 465.3532 -6.2688 179.8404 452.0444 -6.2688 179.3487 452.1355 -6.2688 181.7077 464.8632 4.398 182.307 465.3532 -6.2688 179.3487 452.1355 -6.2688 179.8404 452.0444 -6.2688 182.1993 464.7721 4.398 181.7077 464.8632 4.398 181.7077 464.8632 7.7298 182.1993 464.7721 4.398 182.1993 464.7721 7.7298 181.7077 464.8632 7.7298 178.4299 447.1776 7.7298 182.1993 464.7721 7.7298 178.9215 447.0865 7.7298 174.7811 427.4909 -9.600602 173.4144 420.1165 -3.3318 171.5393 409.9994 -3.3318 174.7811 427.4909 -9.600602 173.9192 422.8406 -2.586769 173.677 421.5334 -3.14035 174.6186 423.8701 6.108942 174.2865 424.8221 4.969502 174.1269 423.9609 6.109179 174.7781 424.7311 4.969245 175.9725 431.1755 7.7298 175.2727 427.3998 7.7298 175.2727 427.3998 -9.600602 175.9725 431.1755 -9.600602 177.1988 437.7918 7.7298 176.5349 434.2096 7.7298 176.5349 434.2096 -9.600602 177.1988 437.7918 -6.2688 178.5686 445.1827 -6.2688 178.5686 445.1827 -9.600602 181.2445 459.6207 4.398 178.9215 447.0865 7.7298 178.9215 447.0865 4.398 182.1993 464.7721 4.398 182.1993 464.7721 7.7298 179.8404 452.0444 -6.2688 182.307 465.3532 -9.600602 182.307 465.3532 -6.2688 178.8856 446.893 -6.2688 178.8856 446.893 -9.600602 174.4108 422.7492 -2.586919 173.677 421.5334 -3.14035 173.9192 422.8406 -2.586769 174.1686 421.4421 -3.140402 173.906 420.0253 -3.3318 177.1988 437.7918 -6.2688 176.7072 437.8829 7.7298 177.1988 437.7918 7.7298 177.1988 437.7918 7.7298 176.0433 434.3007 7.7298 176.5349 434.2096 7.7298 174.6185 423.8698 -1.711179 173.9192 422.8406 -2.586769 174.1269 423.9612 -1.710942 174.4108 422.7492 -2.586919 174.7811 427.4909 7.7298 174.1269 423.9609 6.109179 174.2865 424.8221 4.969502 145.0012 302.6019 -49.51807 149.8266 315.2406 -43.76592 150.6033 316.326 -42.20819 143.7512 317.8309 -42.1369 150.6033 316.326 -42.20819 149.8266 315.2406 -43.76592 149.1818 301.7482 -37.55989 155.4163 323.364 -30.85339 146.5154 329.6161 -24.71984 155.4163 323.364 -30.85339 150.6033 316.326 -42.20819 143.7512 317.8309 -42.1369 149.0614 314.0002 -45.15019 143.175 315.3741 -45.01391 149.0614 314.0002 -45.15019 147.6048 311.0894 -47.38005 142.4648 312.3462 -47.24674 147.6048 311.0894 -47.38005 146.343 307.7585 -48.81966 142.0713 310.6687 -48.08299 146.343 307.7585 -48.81966 145.3559 304.1674 -49.43394 141.6576 308.905 -48.7186 145.3559 304.1674 -49.43394 140.7969 305.2351 -49.35218 145.3559 304.1674 -49.43394 145.0012 302.6019 -49.51807 140.7969 305.2351 -49.35218 137.2718 262.4734 -47.99499 140.6201 283.4799 -50.54616 140.6201 283.4799 -50.54616 152.1969 301.1326 -25.24167 141.9643 261.4628 -33.52045 138.103 262.2849 -45.79745 138.6487 262.1611 -44.2864 140.2254 261.8413 -39.57835 159.2352 330.8309 -19.22532 154.0177 300.7609 -12.68159 144.3336 260.864 -22.48724 142.0382 261.4458 -33.23557 143.5372 261.0682 -26.73712 162.6495 340.8083 -1.596364 154.6265 300.6366 -2e-6 145.7713 260.5469 -11.28538 162.5649 340.5264 -3.16919 162.3424 339.7742 -5.401347 162.0166 338.6431 -7.456562 144.713 260.7754 -20.14905 145.5661 260.5913 -13.47496 162.0166 338.6431 7.456562 154.0177 300.7609 12.68158 146.2507 260.4367 0 162.3423 339.7741 5.401597 162.5649 340.5264 3.169158 162.6495 340.8082 1.596745 162.6781 340.9027 3.83e-4 146.0799 260.4776 -6.747254 159.2358 330.8323 19.22326 152.1969 301.1326 25.24166 145.588 260.5873 13.25975 146.0796 260.4757 6.745868 155.4167 323.3647 30.85219 149.1818 301.7482 37.55988 143.6068 261.037 26.38061 145.5659 260.5923 13.47905 144.7163 260.7852 20.14185 145.3559 304.1674 49.43394 145.0012 302.6019 49.51806 140.3277 261.7811 39.22509 146.3437 307.7605 48.81906 147.6059 311.0921 47.3785 149.0624 314.0019 45.14844 149.8272 315.2416 43.76477 150.6033 316.3262 42.20796 143.5321 261.054 26.74673 142.0327 261.3942 33.21564 131.1031 263.9053 51.57476 145.0012 302.6019 49.51806 145.3559 304.1674 49.43394 140.2138 261.8069 39.5914 138.113 262.2835 45.77078 140.6203 283.4806 50.54612 140.6203 283.4806 50.54612 140.7969 305.2351 49.35218 145.3559 304.1674 49.43394 146.3437 307.7605 48.81906 140.7969 305.2351 49.35218 141.6576 308.905 48.7186 147.6059 311.0921 47.3785 142.4648 312.3462 47.24674 149.0624 314.0019 45.14844 142.0713 310.6687 48.08299 143.1749 315.374 45.01402 149.8272 315.2416 43.76477 150.6033 316.3262 42.20796 143.7515 317.8322 42.13536 150.6033 316.3262 42.20796 155.4167 323.3647 30.85219 143.7515 317.8322 42.13536 146.5154 329.6159 24.71972 159.2358 330.8323 19.22326 149.2878 341.4364 7.32731 162.0166 338.6431 7.456562 149.2878 341.4364 7.32731 162.0166 338.6431 7.456562 162.3423 339.7741 5.401597 149.6803 343.1098 3.835993 162.5649 340.5264 3.169158 162.6495 340.8082 1.596745 162.6781 340.9027 3.83e-4 149.815 343.6838 -1.08e-4 162.6495 340.8083 -1.596364 162.5649 340.5264 -3.16919 149.6803 343.1097 -3.836239 162.3424 339.7742 -5.401347 162.0166 338.6431 -7.456562 149.288 341.4372 -7.325833 162.0166 338.6431 -7.456562 159.2352 330.8309 -19.22532 149.288 341.4372 -7.325833 135.7848 262.8101 -51.65866 136.3306 253.554 -45.47358 135.7848 262.8101 -51.65866 137.2718 262.4734 -47.99499 135.7848 262.8101 -51.65866 131.1032 263.9058 -51.57474 131.0978 263.8828 -51.57598 131.1032 263.9058 -51.57474 135.7848 262.8101 -51.65866 135.7799 262.7892 -51.65979 135.7799 262.7892 -51.65979 138.103 262.2849 -45.79745 138.698 254.3178 -39.28681 138.6487 262.1611 -44.2864 140.2254 261.8413 -39.57835 142.0382 261.4458 -33.23557 141.9643 261.4628 -33.52045 140.7464 255.1684 -32.95159 143.5372 261.0682 -26.73712 142.475 256.0429 -26.49093 144.3336 260.864 -22.48724 143.903 257.018 -19.94035 144.713 260.7754 -20.14905 145.0238 258.0852 -13.32719 145.5661 260.5913 -13.47496 145.8105 259.223 -6.672296 145.7713 260.5469 -11.28538 146.0799 260.4776 -6.747254 146.2507 260.4367 0 145.8107 259.2227 6.658282 146.0796 260.4757 6.745868 145.5479 257.9764 -6.416636 145.3135 256.7742 -6.024756 145.1051 255.6315 -5.451318 144.9245 254.6225 -4.661861 144.7756 253.8214 -3.675826 144.6809 253.2503 -2.522285 144.6454 252.9145 -1.274216 144.6387 252.8061 -6.96e-4 144.6444 252.9164 1.274578 144.6812 253.2529 2.523802 144.7759 253.823 3.677192 144.9237 254.6206 4.666922 145.1039 255.6277 5.460591 145.3132 256.7729 6.027442 145.5486 257.9781 6.404082 145.0255 258.0883 13.29963 145.588 260.5873 13.25975 145.5659 260.5923 13.47905 143.9073 257.0279 19.89959 144.7163 260.7852 20.14185 142.478 256.0391 26.43447 143.6068 261.037 26.38061 143.5321 261.054 26.74673 140.7441 255.1259 32.87725 142.0327 261.3942 33.21564 138.7034 254.2994 39.20171 140.3277 261.7811 39.22509 140.2138 261.8069 39.5914 136.345 253.564 45.37801 138.113 262.2835 45.77078 135.7852 262.8117 51.65858 135.7799 262.7892 51.65979 135.7852 262.8117 51.65858 134.8289 258.531 51.70406 134.0048 254.3773 51.39474 135.7852 262.8117 51.65858 135.7799 262.7892 51.65979 135.7852 262.8117 51.65858 131.1031 263.9053 51.57476 146.5154 329.6159 24.71972 146.5154 329.6161 -24.71984 143.7512 317.8309 -42.1369 143.7515 317.8322 42.13536 143.175 315.3741 -45.01391 149.2878 341.4364 7.32731 149.288 341.4372 -7.325833 149.6803 343.1098 3.835993 149.6803 343.1097 -3.836239 143.1749 315.374 45.01402 142.4648 312.3462 -47.24674 142.4648 312.3462 47.24674 142.0713 310.6687 -48.08299 142.0713 310.6687 48.08299 141.6576 308.905 -48.7186 141.6576 308.905 48.7186 140.7969 305.2351 -49.35218 140.7969 305.2351 49.35218 131.1032 263.9058 -51.57474 131.1031 263.9053 51.57476 131.0978 263.8828 -51.57598 149.815 343.6838 -1.08e-4 131.0978 263.8828 51.57598 131.0978 263.8828 51.57598 130.0808 259.5468 -51.61579 130.0808 259.5467 51.61603 135.7799 262.7892 51.65979 131.0978 263.8828 51.57598 130.0808 259.5467 51.61603 129.108 255.3994 -51.29195 129.1125 255.4185 51.29483 134.0048 254.3773 51.39474 129.1125 255.4185 51.29483 134.8289 258.531 51.70406 128.2752 251.8487 50.72837 133.3691 250.7694 50.84247 128.2752 251.8487 50.72837 128.2649 251.8045 -50.719 127.5732 248.8558 50.04089 132.8911 247.7371 50.17081 127.5732 248.8558 50.04089 127.5584 248.7923 -50.02352 126.3733 243.7398 48.3915 132.1787 242.4829 48.54036 126.3733 243.7398 48.3915 125.6662 240.7251 -47.11708 124.9602 237.715 45.59931 131.4994 236.2356 45.7621 124.9602 237.715 45.59931 126.3486 243.6345 -48.35053 124.9146 237.5204 -45.4922 123.6845 232.2759 42.15123 131.0135 230.5512 42.30814 123.6845 232.2759 42.15123 123.642 232.0948 -42.01888 122.8036 228.5203 39.12992 130.7403 226.5796 39.25099 122.8036 228.5203 39.12992 122.769 228.3726 -38.99886 122.0469 225.294 36.00419 122.0469 225.294 36.00419 122.0227 225.1907 -35.89483 121.624 223.4912 33.99124 130.5384 223.1567 36.07633 121.624 223.4912 33.99124 121.6042 223.4064 -33.89151 121.1649 221.5337 31.53808 130.433 221.2783 34.06918 121.1649 221.5337 31.53808 121.1499 221.4697 -31.45235 120.6831 219.4796 28.58882 130.3169 219.2366 31.62102 120.6831 219.4796 28.58882 120.671 219.4279 -28.50856 120.2553 217.6555 25.54571 130.1854 217.0832 28.65757 120.2553 217.6555 25.54571 120.2479 217.6239 -25.48869 119.9242 216.244 22.80783 130.0698 215.1846 25.61627 119.9242 216.244 22.80783 119.9214 216.2319 -22.78279 119.6699 215.1598 20.38781 129.9683 212.5774 20.47811 119.6699 215.1598 20.38781 130 213.7198 22.90149 119.2691 213.4509 -15.66983 119.2638 213.4281 15.5954 119.2638 213.4281 15.5954 119.6678 215.1509 -20.36635 118.9463 212.0746 -10.19892 118.9359 212.0301 9.967663 129.9839 210.6965 15.56785 118.9359 212.0301 9.967663 118.7511 211.2422 -4.011783 118.7459 211.2203 3.711098 130.0862 209.1915 9.901047 118.7459 211.2203 3.711098 130.2005 208.3116 3.595074 118.7511 211.2422 -4.011783 130.203 208.3542 -4.154909 118.9463 212.0746 -10.19892 130.0894 209.2775 -10.32686 119.2691 213.4509 -15.66983 129.9861 210.7816 -15.82997 119.6678 215.1509 -20.36635 129.9666 212.609 -20.5483 119.9214 216.2319 -22.78279 129.9997 213.751 -22.96296 120.2479 217.6239 -25.48869 130.0728 215.2285 -25.69227 120.671 219.4279 -28.50856 130.189 217.1376 -28.73851 121.1499 221.4697 -31.45235 130.3184 219.296 -31.69608 121.6042 223.4064 -33.89151 130.4304 221.3413 -34.13855 122.0227 225.1907 -35.89483 130.5317 223.2186 -36.13655 122.769 228.3726 -38.99886 130.723 226.5567 -39.22849 123.642 232.0948 -42.01888 130.9935 230.4945 -42.26595 124.9146 237.5204 -45.4922 131.4973 236.2222 -45.75476 125.6662 240.7251 -47.11708 126.3486 243.6345 -48.35053 132.199 242.4439 -48.52818 127.5584 248.7923 -50.02352 132.9213 247.6833 -50.15948 128.2649 251.8045 -50.719 133.406 250.7684 -50.84386 129.108 255.3994 -51.29195 134.0461 254.4518 -51.40456 130.0808 259.5468 -51.61579 134.8609 258.6353 -51.70785 131.0978 263.8828 -51.57598 135.7799 262.7892 -51.65979 134.8609 258.6353 -51.70785 133.3691 250.7694 50.84247 132.8911 247.7371 50.17081 134.7605 244.9351 44.01772 132.1787 242.4829 48.54036 131.4994 236.2356 45.7621 133.3346 236.5924 41.56367 131.0135 230.5512 42.30814 132.1343 228.62 37.69954 130.7403 226.5796 39.25099 130.5384 223.1567 36.07633 130.433 221.2783 34.06918 131.194 221.5241 32.26934 130.3169 219.2366 31.62102 130.1854 217.0832 28.65757 130.5058 215.8805 25.45307 130.0698 215.1846 25.61627 130 213.7198 22.90149 129.9683 212.5774 20.47811 130.2436 211.8251 17.50713 129.9839 210.6965 15.56785 130.0862 209.1915 9.901047 130.3621 209.3755 8.868298 130.2005 208.3116 3.595074 130.4821 208.5538 0.002780914 130.203 208.3542 -4.154909 130.3684 209.359 -8.853302 130.0894 209.2775 -10.32686 129.9861 210.7816 -15.82997 130.2378 211.8031 -17.48563 129.9666 212.609 -20.5483 129.9997 213.751 -22.96296 130.0728 215.2285 -25.69227 130.5024 215.8614 -25.43057 130.189 217.1376 -28.73851 130.3184 219.296 -31.69608 131.206 221.5238 -32.22397 130.4304 221.3413 -34.13855 130.5317 223.2186 -36.13655 130.723 226.5567 -39.22849 132.151 228.6317 -37.62821 130.9935 230.4945 -42.26595 133.3372 236.5875 -41.54009 131.4973 236.2222 -45.75476 132.199 242.4439 -48.52818 134.744 244.9116 -44.10292 132.9213 247.6833 -50.15948 133.406 250.7684 -50.84386 134.0461 254.4518 -51.40456 137.3497 246.8538 37.96311 136.1605 239.6689 35.80343 135.2376 232.7741 32.47552 134.5806 226.5976 27.81373 134.1046 221.6856 21.94616 133.9563 218.1652 15.0907 134.1116 216.0427 7.635695 134.2349 215.3327 -0.01144099 134.1177 216.0329 -7.650109 133.9523 218.156 -15.09825 134.1035 221.6843 -21.95023 134.593 226.6176 -27.79408 135.2538 232.8084 -32.42861 136.1663 239.6903 -35.79309 137.3417 246.8598 -38.04285 144.5008 255.5932 -12.82294 144.06 253.1835 -12.04335 143.6984 250.8846 -10.90081 143.3974 248.8492 -9.324196 143.1496 247.2343 -7.35229 143.0144 246.0813 -5.047309 142.9992 245.3962 -2.550653 143.0097 245.1732 4.68e-4 142.9961 245.4012 2.554895 143.0147 246.0881 5.05362 143.1505 247.2395 7.358284 143.3956 248.8482 9.337038 143.6958 250.8801 10.92128 144.0598 253.1844 12.05006 144.5034 255.6001 12.79872 143.1313 253.2805 -19.20683 142.5 249.6717 -18.03688 142.0189 246.2144 -16.32853 141.6425 243.1361 -13.97363 141.3413 240.6917 -11.02077 141.2091 238.9465 -7.567609 141.248 237.9048 -3.824485 141.2889 237.5648 0.003594994 141.2428 237.9136 3.836278 141.2097 238.9586 7.58207 141.3428 240.7026 11.03446 141.6394 243.139 13.99673 142.0148 246.2128 16.36213 142.5003 249.6782 18.04897 143.1368 253.296 19.17158 141.4881 251.0563 -25.55771 140.6738 246.2563 -24.00514 140.0767 241.6443 -21.73806 139.6413 237.5103 -18.61793 139.306 234.2229 -14.69326 139.1909 231.8767 -10.09715 139.2911 230.4716 -5.109556 139.365 230.0107 -0.003621995 139.2852 230.4802 5.108242 139.1921 231.8864 10.10004 139.3069 234.2282 14.69721 139.6349 237.5022 18.63677 140.0684 241.6278 21.77377 140.6714 246.2493 24.01502 141.4929 251.0606 25.50619 139.573 248.935 -31.85196 138.5811 242.9447 -29.93968 137.8492 237.1849 -27.12327 137.3364 231.9993 -23.24808 136.9516 227.8696 -18.36167 136.8377 224.9205 -12.63092 136.9857 223.1487 -6.404463 137.0876 222.5639 -0.02342891 136.9803 223.1522 6.364987 136.8405 224.9183 12.59849 136.9512 227.8554 18.3349 137.3248 231.9618 23.24532 137.8342 237.1318 27.14798 138.5728 242.9011 29.93823 139.5736 248.9037 31.77859 174.7811 427.4909 7.7298 173.9192 422.8403 6.984919 174.1269 423.9609 6.109179 174.7811 427.4909 -9.600602 174.3874 425.3664 3.640013 174.4223 425.5547 2.199 176.0433 434.3007 7.7298 175.4809 431.2666 7.7298 176.0433 434.3007 -9.600602 178.394 446.9841 -9.600602 178.077 445.2738 -6.2688 178.077 445.2738 -9.600602 160.2247 589.1773 43.73743 170.3213 573.6862 39.02756 173.1198 570.7357 35.31607 168.1034 567.9967 35.2517 173.1198 570.7357 35.31607 170.3213 573.6862 39.02756 174.0316 569.8485 33.87501 173.2791 558.8113 22.736 174.0316 569.8485 33.87501 173.1198 570.7357 35.31607 168.1034 567.9967 35.2517 167.4424 577.2658 41.69601 163.9937 575.2901 41.60704 167.4424 577.2658 41.69601 166.2222 571.3352 38.89683 165.9793 579.3139 42.65538 162.7823 577.4401 42.56803 165.9793 579.3139 42.65538 164.5633 581.4627 43.32633 161.5275 579.667 43.24825 164.5633 581.4627 43.32633 161.9548 585.9467 43.80139 160.2445 581.9439 43.6408 161.9548 585.9467 43.80139 158.9453 584.2496 43.74131 161.9548 585.9467 43.80139 160.2247 589.1773 43.73743 158.9453 584.2496 43.74131 163.4744 590.9502 31.54599 154.3127 600.0407 43.52158 154.3127 600.0407 43.52158 176.2483 570.9912 22.73261 165.6584 592.1418 19.05017 152.032 611.5951 31.24382 148.8795 609.7938 43.3267 177.5831 571.6857 11.41045 166.7557 592.7405 6.370545 154.1504 612.8056 18.86532 178.0292 571.9179 -1.7e-4 166.7557 592.7405 -6.370545 155.2147 613.4137 6.308332 177.5831 571.6857 -11.41079 165.6584 592.1418 -19.05017 154.1505 612.8056 -18.86532 155.2147 613.4137 -6.308332 176.2483 570.9912 -22.73295 163.4744 590.9502 -31.54599 152.032 611.5951 -31.24382 164.5642 581.4612 -43.32596 160.2247 589.1773 -43.73743 154.3127 600.0407 -43.52158 165.9806 579.312 -42.65464 167.4439 577.2639 -41.6949 170.3221 573.6852 -39.0267 173.1196 570.7354 -35.31594 174.0297 569.8501 -33.87779 148.8795 609.7938 -43.3267 161.9548 585.9467 -43.80139 143.2054 612.1834 -43.17609 160.2247 589.1773 -43.73743 161.9548 585.9467 -43.80139 154.3127 600.0407 -43.52158 158.9453 584.2496 -43.74119 161.9548 585.9467 -43.80139 164.5642 581.4612 -43.32596 158.9453 584.2496 -43.74119 161.5275 579.667 -43.24825 165.9806 579.312 -42.65464 160.2445 581.9439 -43.64078 162.7823 577.4401 -42.56803 167.4439 577.2639 -41.6949 163.9937 575.2901 -41.60704 170.3221 573.6852 -39.0267 166.2222 571.3352 -38.89685 173.1196 570.7354 -35.31594 168.1034 567.9967 -35.25164 173.1196 570.7354 -35.31594 174.0297 569.8501 -33.87779 168.1034 567.9967 -35.25164 180.417 562.8212 -22.94507 180.417 562.8212 -22.94507 186.6588 554.0851 -10.34068 188.7099 550.89 1.71e-4 187.767 552.3364 -7.222344 188.4695 551.2553 -3.709324 186.6591 554.0852 10.34062 188.4695 551.2553 3.70939 187.767 552.3364 7.22222 180.4173 562.8208 22.94454 180.4173 562.8208 22.94454 148.8795 609.7938 43.3267 146.4817 614.0308 43.24172 146.4817 614.0308 43.24172 140.8398 632.4036 27.64757 144.5907 617.4699 42.99537 142.8036 620.955 42.38573 141.1256 624.468 41.40868 139.5652 627.981 40.05665 138.3137 630.9981 38.57965 142.4749 633.3811 16.67078 143.2955 633.8717 5.571019 142.475 633.3812 -16.66961 143.2955 633.8717 -5.569841 140.84 632.4038 -27.64641 138.3133 630.9993 -38.57901 148.8795 609.7938 -43.3267 139.5386 628.0433 -40.02911 141.1064 624.5096 -41.39482 142.7922 620.978 -42.38042 144.586 617.4786 -42.99449 146.4817 614.0308 -43.24172 146.4817 614.0308 -43.24172 143.2054 612.1834 43.17609 146.4817 614.0308 43.24172 144.5907 617.4699 42.99537 143.2054 612.1834 43.17609 139.3883 618.9577 42.32803 142.8036 620.955 42.38573 141.2861 615.5896 42.92958 137.5161 622.2803 41.37297 141.1256 624.468 41.40868 135.6934 625.515 40.07098 139.5652 627.981 40.05665 138.3137 630.9981 38.57965 136.9009 634.6583 36.3525 132.2665 631.5969 36.48891 136.9009 634.6583 36.3525 133.1763 646.0234 25.18455 135.7757 637.7974 34.00972 134.7811 640.767 31.35045 133.9164 643.5205 28.40144 131.6613 651.6557 14.3199 132.5559 648.2409 21.72462 132.0539 650.1234 18.09218 131.138 653.7938 5.242877 131.3714 652.8266 10.43008 131.3714 652.8266 -10.43007 131.0611 654.1171 1.68e-4 131.138 653.7939 -5.242698 132.042 650.169 -17.99273 131.6557 651.6771 -14.26027 133.8854 643.6229 -28.28104 132.537 648.3104 -21.60357 133.1506 646.113 -25.05761 132.2417 631.6409 -36.45676 138.3133 630.9993 -38.57901 139.5386 628.0433 -40.02911 134.7464 640.8743 -31.24493 135.7396 637.9019 -33.92404 136.866 634.7525 -36.28836 136.866 634.7525 -36.28836 135.6741 625.5494 -40.05495 141.1064 624.5096 -41.39482 137.5017 622.3059 -41.36413 142.7922 620.978 -42.38042 139.3796 618.9732 -42.32433 144.586 617.4786 -42.99449 141.2823 615.5965 -42.92884 146.4817 614.0308 -43.24172 143.2054 612.1834 -43.17609 135.7757 637.7974 34.00972 129.2093 637.0225 31.68661 134.7811 640.767 31.35045 133.9164 643.5205 28.40144 126.6261 641.6069 25.81874 133.1763 646.0234 25.18455 132.5559 648.2409 21.72462 124.609 645.1867 19.09125 132.0539 650.1234 18.09218 123.8348 646.5607 15.47455 131.6613 651.6557 14.3199 123.2249 647.6431 11.72591 131.3714 652.8266 10.43008 122.7855 648.423 7.879169 131.138 653.7938 5.242877 122.5201 648.8939 3.97086 131.0611 654.1171 1.68e-4 122.518 648.8977 -3.9227 131.138 653.7939 -5.242698 122.4302 649.0534 0.02361989 122.781 648.4309 -7.829839 131.3714 652.8266 -10.43007 123.218 647.6554 -11.67577 131.6557 651.6771 -14.26027 123.8256 646.5771 -15.42528 132.042 650.169 -17.99273 124.5976 645.207 -19.04384 132.537 648.3104 -21.60357 133.1506 646.113 -25.05761 126.6104 641.6349 -25.7756 133.8854 643.6229 -28.28104 134.7464 640.8743 -31.24493 129.1877 637.0608 -31.64572 135.7396 637.9019 -33.92404 173.2791 558.8113 -22.73593 186.6588 554.0851 -10.34068 178.4638 549.6099 -10.23505 186.6588 554.0851 -10.34068 187.767 552.3364 -7.222344 178.4638 549.6099 -10.23505 179.6228 547.5529 -6.483213 188.4695 551.2553 -3.709324 180.2268 546.4811 -2.221154 188.7099 550.89 1.71e-4 180.2268 546.4812 2.221496 188.4695 551.2553 3.70939 179.6228 547.553 6.483444 187.767 552.3364 7.22222 186.6591 554.0852 10.34062 178.464 549.6096 10.23453 186.6591 554.0852 10.34062 178.464 549.6096 10.23453 168.1034 567.9967 -35.25164 168.1034 567.9967 35.2517 166.2222 571.3352 38.89683 173.2791 558.8113 -22.73593 173.2791 558.8113 22.736 166.2222 571.3352 -38.89685 163.9937 575.2901 41.60704 163.9937 575.2901 -41.60704 162.7823 577.4401 42.56803 162.7823 577.4401 -42.56803 161.5275 579.667 43.24825 161.5275 579.667 -43.24825 160.2445 581.9439 43.6408 160.2445 581.9439 -43.64078 158.9453 584.2496 43.74131 158.9453 584.2496 -43.74119 143.2054 612.1834 43.17609 178.4638 549.6099 -10.23505 178.464 549.6096 10.23453 179.6228 547.5529 -6.483213 179.6228 547.553 6.483444 180.2268 546.4811 -2.221154 180.2268 546.4812 2.221496 143.2054 612.1834 -43.17609 141.2861 615.5896 42.92958 141.2823 615.5965 -42.92884 139.3883 618.9577 42.32803 139.3796 618.9732 -42.32433 137.5161 622.2803 41.37297 137.5017 622.3059 -41.36413 135.6934 625.515 40.07098 135.6741 625.5494 -40.05495 132.2665 631.5969 36.48891 132.2417 631.6409 -36.45676 129.2093 637.0225 31.68661 129.1877 637.0608 -31.64572 126.6261 641.6069 25.81874 126.6104 641.6349 -25.7756 124.609 645.1867 19.09125 124.5976 645.207 -19.04384 123.8348 646.5607 15.47455 123.8256 646.5771 -15.42528 123.2249 647.6431 11.72591 123.218 647.6554 -11.67577 122.7855 648.423 7.879169 122.781 648.4309 -7.829839 122.5201 648.8939 3.97086 122.518 648.8977 -3.9227 122.4302 649.0534 0.02361989 174.7811 427.4909 -9.600602 174.4223 425.5547 2.199 174.3874 425.3665 0.758167 178.5686 445.1827 -9.600602 178.077 445.2738 -9.600602 178.077 445.2738 -6.2688 178.5686 445.1827 -9.600602 176.5349 434.2096 -9.600602 178.077 445.2738 -9.600602 175.9725 431.1755 -9.600602 175.4809 431.2666 7.7298 175.9725 431.1755 7.7298 175.9725 431.1755 7.7298 174.7811 427.4909 7.7298 175.2727 427.3998 7.7298 176.5349 434.2096 -9.600602 176.0433 434.3007 -9.600602 178.077 445.2738 -9.600602 176.5349 434.2096 7.7298 176.0433 434.3007 7.7298 176.0433 434.3007 -9.600602 176.5349 434.2096 -9.600602 174.879 425.2753 0.757987 174.3874 425.3665 0.758167 174.4223 425.5547 2.199 174.7811 427.4909 -9.600602 174.1269 423.9612 -1.710942 173.9192 422.8406 -2.586769 178.394 446.9841 -6.2688 176.7072 437.8829 7.7298 178.077 445.2738 -6.2688 178.394 446.9841 -9.600602 178.5686 445.1827 -9.600602 178.077 445.2738 -6.2688 178.5686 445.1827 -6.2688 177.1988 437.7918 -6.2688 176.7072 437.8829 -6.2688 176.7072 437.8829 7.7298 178.5686 445.1827 -6.2688 176.7072 437.8829 -6.2688 177.1988 437.7918 -6.2688 177.1988 437.7918 7.7298 176.7072 437.8829 7.7298 176.0433 434.3007 7.7298 174.7811 427.4909 7.7298 174.2865 424.8221 4.969502 174.3874 425.3664 3.640013 181.7077 464.8632 4.398 179.3487 452.1355 -6.2688 181.8154 465.4443 -6.2688 178.394 446.9841 -6.2688 180.7529 459.7118 4.398 178.4299 447.1776 4.398 181.7077 464.8632 7.7298 181.7077 464.8632 4.398 181.8154 465.4443 -6.2688 178.5686 445.1827 -6.2688 178.077 445.2738 -6.2688 176.7072 437.8829 -6.2688 174.9139 425.4635 2.199 174.4223 425.5547 2.199 174.3874 425.3664 3.640013 174.879 425.2753 0.757987 174.7811 427.4909 -9.600602 173.677 421.5334 -3.14035 173.4144 420.1165 -3.3318 172.0309 409.9082 -3.3318 171.5393 409.9994 -3.3318 173.4144 420.1165 -3.3318 172.0309 409.9082 -3.3318 172.0309 409.9082 -9.600602 171.5393 409.9994 -3.3318 - - - - - - - - - - -0.1857989 -0.136694 -0.9730333 -0.1006511 -0.05298066 -0.9935103 -0.1030641 -0.0548129 -0.9931634 -0.0174508 0.02856689 -0.9994395 -0.110632 -0.04483264 -0.9928498 -0.1926987 -0.1247933 -0.9732903 -0.1076396 -0.05008125 -0.9929279 -0.01745086 0.02856832 -0.9994395 -0.01744973 0.02856761 -0.9994395 -0.08117955 -0.03634768 -0.9960365 -0.01745098 0.02856916 -0.9994395 -0.1240299 -0.07709145 -0.9892793 -0.1437436 -0.1146592 -0.9829502 -0.07666319 -0.03680562 -0.9963775 -0.1549742 -0.07983702 -0.9846873 -0.07013231 -0.0321058 -0.9970209 -0.01744419 0.0285713 -0.9994396 -0.2222076 -0.1725839 -0.9596034 -0.2294762 -0.2027411 -0.9519646 -0.2377715 -0.1168257 -0.96427 -0.2796159 -0.2285575 -0.9325108 -0.2748265 -0.224958 -0.9348072 -0.2614576 -0.2385988 -0.9352597 -0.2671992 -0.2177269 -0.9387224 -0.3645176 -0.3118726 -0.8774181 -0.3583244 -0.3072965 -0.8815739 -0.3512138 -0.3024747 -0.8860914 -0.3631799 -0.3109918 -0.8782851 -0.2470869 -0.2922865 -0.9238597 -0.3011981 -0.2916455 -0.9078671 -0.3096747 -0.3126046 -0.8979866 -0.2959714 -0.2820549 -0.912604 -0.3541112 -0.3036634 -0.8845303 -0.1989854 -0.1134705 -0.9734112 -0.2804391 -0.2024631 -0.9382764 -0.2920685 -0.187876 -0.9377626 -0.3888123 -0.2384145 -0.8899346 -0.3736732 -0.269085 -0.8876721 -0.03946119 0.01059007 -0.9991651 -0.389119 -0.2815085 -0.87712 -0.2176625 -0.09589111 -0.9713022 -0.1077007 -0.01931834 -0.9939957 -0.1250357 -0.031587 -0.9916493 -0.01744168 0.02856862 -0.9994397 -0.2310928 -0.09177178 -0.9685939 -0.2422942 -0.07635974 -0.9671932 -0.2403374 -0.08176052 -0.96724 -0.1301946 -0.02630746 -0.9911394 -0.1376697 -0.02310258 -0.9902088 -0.07400768 7.32447e-4 -0.9972574 -0.01747852 0.02856153 -0.9994392 -0.118659 -0.03705042 -0.9922436 -0.01745802 0.02856552 -0.9994395 -0.0174604 0.02856558 -0.9994394 -0.01745629 0.02856475 -0.9994395 -0.01745247 0.02856874 -0.9994395 -0.3191987 -0.1563185 -0.9347068 -0.3667194 -0.2312139 -0.9011421 -0.3382132 -0.153023 -0.928545 -0.3481371 -0.1362395 -0.9274909 -0.3466044 -0.1361148 -0.9280831 -0.4016284 -0.1500918 -0.9034197 -0.3577104 -0.1327261 -0.9243523 -0.0362873 0.01281803 -0.9992592 -0.4267198 -0.2185481 -0.8775802 -0.4124938 -0.251598 -0.8755269 -0.4887638 -0.2088118 -0.8470583 -0.458918 -0.1961167 -0.8665637 -0.467007 -0.196514 -0.8621409 -0.443103 -0.2298984 -0.866491 -0.4645628 -0.2018538 -0.8622276 -0.07458883 6.10384e-4 -0.9972142 -0.01743596 0.02857041 -0.9994398 -0.08313333 0.003540158 -0.9965322 -0.1325142 -0.01620566 -0.9910487 -0.07663255 0.004852473 -0.9970477 -0.01745581 0.02856737 -0.9994395 -0.4684939 -0.1963884 -0.8613623 -0.4473521 -0.1088013 -0.8877152 -0.4258387 -0.1318747 -0.8951371 -0.3629284 -0.1063882 -0.9257238 -0.5475704 -0.179146 -0.8173576 -0.5274944 -0.1739596 -0.8315575 -0.5175769 -0.1759132 -0.8373582 -0.5011562 -0.1375501 -0.8543551 -0.3067824 -0.06323647 -0.9496766 -0.2499819 -0.06149595 -0.9662957 -0.1647426 -0.01657187 -0.9861974 -0.27275 0.05728447 -0.960378 -0.1359016 0.04937988 -0.9894909 -0.1587274 0.05056935 -0.9860265 -0.01745837 0.02856856 -0.9994394 -0.2946649 0.07169008 -0.9529078 -0.158087 0.05896216 -0.9856632 -0.2964299 0.08792483 -0.9509987 -0.1592774 0.05929797 -0.9854514 -0.01745241 0.02856689 -0.9994396 -0.1446915 0.03763014 -0.9887611 -0.01746815 0.02856361 -0.9994394 -0.2486072 0.03152602 -0.9680912 -0.124792 0.03598183 -0.9915303 -0.01745241 0.02856588 -0.9994396 -0.01744866 0.02856689 -0.9994397 -0.1273242 0.02468961 -0.9915539 -0.01745116 0.02856564 -0.9994397 -0.01745223 0.02856749 -0.9994396 -0.2225776 0.01132267 -0.9748493 -0.1158187 0.02487277 -0.992959 -0.01745086 0.02856832 -0.9994395 -0.01745325 0.02856653 -0.9994395 -0.1124311 0.01553404 -0.9935382 -0.01745074 0.02856653 -0.9994397 -0.01745492 0.02856862 -0.9994395 -0.1970593 -0.004089474 -0.980383 -0.09738719 0.009064197 -0.9952054 -0.01745402 0.02856749 -0.9994395 -0.01745307 0.02856558 -0.9994395 -0.01745206 0.02856934 -0.9994395 -0.01745098 0.02856701 -0.9994396 -0.01745444 0.02856701 -0.9994395 -0.01745057 0.02856528 -0.9994397 -0.01745474 0.02856862 -0.9994394 -0.0174511 0.02856582 -0.9994397 -0.01745724 0.02856713 -0.9994394 -0.3675732 -0.03799635 -0.9292181 -0.4223501 -0.006531 -0.9064093 -0.4710976 0.0330525 -0.8814616 -0.5128142 0.08206611 -0.8545682 -0.5523971 0.110571 -0.8262152 -0.2862697 0.08438545 -0.9544259 -0.5502688 0.1394136 -0.8232668 -0.7204447 0.1012639 -0.6860796 -0.7657386 0.148234 -0.6258364 -0.5315203 0.133643 -0.8364365 -0.7582933 0.1793645 -0.6267533 -0.5240079 -0.0690335 -0.8489112 -0.6044221 -0.02529996 -0.7962625 -0.6679738 0.03170943 -0.7435089 -0.8501058 0.1591869 -0.5019759 -0.8443213 0.1666973 -0.509248 -0.7387425 0.1729205 -0.6514277 -0.8370356 0.193641 -0.5117371 -0.5789602 -0.1114277 -0.807706 -0.6950616 -0.06234949 -0.7162415 -0.6377998 -0.1225059 -0.7603972 -0.736789 -0.002716183 -0.6761173 -0.7069133 -0.06076347 -0.7046854 -0.7995813 0.07043904 -0.5964127 -0.7915818 -0.006470084 -0.611029 -0.7605327 0.01141405 -0.6491995 -0.8197848 0.07761108 -0.5673883 -0.8041936 0.09677791 -0.5864357 -0.8824949 0.1353223 -0.4504337 -0.8855069 0.1458194 -0.4411512 -0.8895164 0.1675511 -0.4250732 -0.7889429 0.1905902 -0.5841614 -0.9041542 0.2088106 -0.3726973 -0.9041947 0.2091181 -0.3724267 -0.9038752 0.2089316 -0.3733059 -0.8930137 0.1589119 -0.4210388 -0.5633583 -0.1652017 -0.8095281 -0.6438943 -0.1300728 -0.7539771 -0.6537275 -0.1153942 -0.7478801 -0.5516914 -0.1863488 -0.8129643 -0.6893315 -0.103093 -0.7170733 -0.7547349 -0.05575817 -0.6536561 -0.750342 -0.05960375 -0.6583575 -0.7652714 -0.02646023 -0.6431637 -0.7852603 -0.02191281 -0.6187778 -0.8347571 0.03418129 -0.5495566 -0.8267 0.01635819 -0.5624051 -0.8399185 0.04934948 -0.5404643 -0.8409265 0.08826154 -0.5339031 -0.8541107 0.0859726 -0.5129364 -0.2418347 0.06134372 -0.9683765 -0.1409055 0.04513734 -0.9889937 -0.1252497 0.04367256 -0.9911637 -0.01745361 0.02856761 -0.9994395 -0.1965105 0.05511695 -0.9789515 -0.1534184 0.06338769 -0.9861262 -0.1907741 0.06271648 -0.9796285 -0.1240002 0.04992967 -0.9910253 -0.0172984 0.02853763 -0.9994431 -0.01745826 0.02856749 -0.9994395 -0.1386189 0.04776275 -0.9891934 -0.01745218 0.02856564 -0.9994396 -0.253374 0.06720423 -0.9650312 -0.1380083 0.04953283 -0.9891917 -0.01745307 0.02856731 -0.9994395 -0.017452 0.02856689 -0.9994395 -0.2636532 0.07321494 -0.9618351 -0.1450873 0.05081409 -0.9881132 -0.01745724 0.02856707 -0.9994394 -0.1496953 0.05398797 -0.9872571 -0.0174542 0.02856713 -0.9994395 -0.01745164 0.02856677 -0.9994395 -0.2744587 0.07883095 -0.9583622 -0.1544554 0.05679535 -0.986366 -0.01745259 0.02856719 -0.9994396 -0.01744979 0.02856737 -0.9994397 -0.01745164 0.02856671 -0.9994396 -0.5130569 0.123816 -0.8493776 -0.494023 0.1131061 -0.8620606 -0.4744253 0.1021181 -0.8743526 -0.4542483 0.09097784 -0.8862175 -0.3148355 0.070957 -0.9464903 -0.2830333 0.09775233 -0.9541157 -0.3113913 0.08667558 -0.9463207 -0.4331551 0.08548349 -0.8972564 -0.4261366 0.1081287 -0.8981737 -0.7194043 0.1610206 -0.67567 -0.6945306 0.1475309 -0.7041746 -0.6689862 0.1304706 -0.7317342 -0.6481059 0.1169801 -0.7525121 -0.5413161 0.09900373 -0.8349702 -0.532314 0.1653524 -0.8302413 -0.5437512 0.1203961 -0.8305658 -0.6418796 0.1092587 -0.7589817 -0.6442574 0.1959018 -0.7392936 -0.6303448 0.1320873 -0.7649958 -0.7935607 0.1776829 -0.581971 -0.8126037 0.1915383 -0.550444 -0.7730752 0.163612 -0.6128507 -0.7602028 0.1503376 -0.6320527 -0.7135716 0.1304394 -0.6883322 -0.7449687 0.1471626 -0.650665 -0.6939503 0.1152718 -0.710736 -0.6945227 0.1146907 -0.7102706 -0.6880177 0.1581488 -0.7082518 -0.8145004 0.1463403 -0.5614034 -0.8211288 0.1283347 -0.5561274 -0.7775351 0.1476209 -0.611267 -0.7425705 0.2193743 -0.6328223 -0.7589659 0.1710938 -0.6282497 -0.7412953 0.222764 -0.6331331 -0.7635264 0.1536635 -0.6272282 -0.7597107 0.1717612 -0.6271665 -0.8817903 0.1964213 -0.4287943 -0.890069 0.2036562 -0.4078008 -0.8965986 0.1887013 -0.400628 -0.863238 0.1819865 -0.4708515 -0.8607045 0.1819254 -0.4754902 -0.8473014 0.1753321 -0.5013371 -0.8382415 0.1623623 -0.5205667 -0.8439085 0.1527776 -0.5142739 -0.8174526 0.1512523 -0.5557823 -0.2769011 0.1203679 -0.9533296 -0.1517129 0.07626843 -0.9854777 -0.01744592 0.02856677 -0.9994397 -0.2943588 0.1508265 -0.9437183 -0.2743394 0.141061 -0.9512306 -0.1477122 0.08572804 -0.985308 -0.1539973 0.08877885 -0.9840749 -0.0174542 0.02856689 -0.9994395 -0.5199552 0.2046005 -0.8293282 -0.6301849 0.2420149 -0.7377641 -0.7257525 0.2735458 -0.6312338 -0.7260822 0.2738792 -0.6307097 -0.6163706 0.2877067 -0.7330158 -0.6119459 0.2852044 -0.7376861 -0.5090693 0.2419605 -0.8260167 -0.7461963 0.3315309 -0.5773027 -0.7209606 0.3120307 -0.618751 -0.7328715 0.3353818 -0.5919616 -0.7154236 0.2994818 -0.6312525 -0.5433005 0.2588933 -0.7986232 -0.6227775 0.2911544 -0.7262075 -0.6492123 0.3041275 -0.6971585 -0.1579996 0.09088712 -0.9832475 -0.01745122 0.02856713 -0.9994396 -0.1224722 0.09708046 -0.9877125 -0.2805877 0.1687067 -0.9448855 -0.1527787 0.1025137 -0.9829292 -0.01745051 0.02856725 -0.9994395 -0.01745259 0.02856725 -0.9994395 -0.7436573 0.3389139 -0.5762909 -0.7408849 0.3416934 -0.5782174 -0.7416345 0.3428163 -0.5765894 -0.4125573 0.290542 -0.8633551 -0.6327255 0.3432807 -0.6941303 -0.5247094 0.2920342 -0.7996225 -0.6374598 0.3450224 -0.6889156 -0.6497923 0.3952895 -0.6492429 -0.6996994 0.3634152 -0.6151019 -0.6685521 0.3793222 -0.6396505 -0.7054749 0.3712929 -0.6036943 -0.2187021 0.1609289 -0.9624299 -0.08441472 0.1156964 -0.9896911 -0.09198588 0.1290061 -0.9873683 -0.0587489 0.08325564 -0.9947951 -0.05569761 0.07928901 -0.9952945 -0.05206584 0.08884155 -0.9946841 -0.07126259 0.1252818 -0.9895586 -0.04736548 0.07388657 -0.9961413 -0.03222846 0.04938042 -0.9982599 -0.01745158 0.02856713 -0.9994396 -0.0209974 0.1804008 -0.9833691 -0.02731418 0.0931735 -0.9952753 -0.03103828 0.07330769 -0.9968263 -0.01739585 0.1056571 -0.9942505 -0.01739567 -0.1163986 -0.9930503 -0.01745676 -0.04855543 -0.998668 -0.01739561 -0.04809731 -0.9986913 -0.1832662 0.2188818 -0.9583863 -0.1791447 0.2109451 -0.9609419 -0.09549319 0.1448115 -0.9848405 -0.3478533 0.3291453 -0.8778734 -0.2896854 0.2690546 -0.9185272 -0.1014744 0.1219219 -0.9873389 -0.3230772 0.3186824 -0.8911021 -0.2278251 0.2594735 -0.9384931 -0.2186395 0.2568496 -0.9413953 -0.4930908 0.3557565 -0.7939136 -0.1559831 0.1497877 -0.9763365 -0.5089623 0.3745574 -0.7750253 -0.4045066 0.338218 -0.8496958 -0.5402003 0.3427373 -0.7685799 -0.6072443 0.3922657 -0.6909284 -0.5325869 0.425099 -0.7318758 -0.5758436 0.3987384 -0.7137311 -0.4940761 0.3976048 -0.7731747 -0.4114026 0.4197039 -0.8090714 -0.4724434 0.3915665 -0.7896031 -0.373277 0.3708356 -0.8503795 -0.2823612 0.3824633 -0.8797693 -0.3627836 0.3545128 -0.8618056 -0.3417532 0.3549985 -0.8701614 -0.2351813 0.3105333 -0.9210098 -0.153083 0.2927377 -0.9438593 -0.2272485 0.2707083 -0.9354545 -0.1015063 0.2006931 -0.9743812 -0.08008122 0.1631533 -0.9833453 -0.08291953 0.248423 -0.965096 -0.0450772 0.06421291 -0.9969176 -0.06250274 0.07739597 -0.9950394 -0.09341782 0.09097629 -0.9914618 -0.08289098 0.0902462 -0.9924641 -0.01745307 0.02856636 -0.9994396 -0.01745259 0.02856492 -0.9994396 -0.01745432 0.02856463 -0.9994397 -0.0174514 0.02856767 -0.9994395 -0.01745307 0.02856701 -0.9994396 -0.01745313 0.02856665 -0.9994395 -0.01745349 0.02856671 -0.9994395 -0.07928794 0.3383014 -0.9376916 -0.1527193 0.3814014 -0.9117072 -0.0755341 0.4276911 -0.9007636 -0.1541215 0.4677053 -0.8703439 -0.2839537 0.4536729 -0.8447197 -0.0745877 0.5162546 -0.8531812 -0.1566852 0.5502904 -0.8201404 -0.2884045 0.5220885 -0.8026497 -0.07739657 0.6010141 -0.7954822 -0.1602841 0.6281052 -0.7614414 -0.2955837 0.5872914 -0.7534714 -0.08255523 0.680249 -0.7283173 -0.1656278 0.700325 -0.6943432 -0.3052223 0.6483799 -0.6974547 -0.08490473 0.7807454 -0.619054 -0.1642248 0.7678374 -0.6192384 -0.3170689 0.7046992 -0.6347176 -0.06998074 0.7592899 -0.6469789 -0.09012329 0.8444978 -0.5279217 -0.1702973 0.8256674 -0.5378404 -0.3307099 0.7556337 -0.5653748 -0.07114028 0.8296651 -0.5537102 -0.08594119 0.8806533 -0.4659014 -0.1770746 0.8763394 -0.4479665 -0.3457843 0.8006448 -0.4892863 -0.09476238 0.9290684 -0.357564 -0.1865358 0.9157105 -0.3559197 -0.3596068 0.8393062 -0.4077354 -0.1006823 0.902997 -0.4176834 -0.09399861 0.9609835 -0.2601442 -0.1819881 0.9379574 -0.2951546 -0.1000726 0.9536658 -0.2837375 -0.1978236 0.9512442 -0.2366437 -0.2100611 0.9475489 -0.2408851 -0.1026057 0.9710313 -0.2158017 -0.3590574 0.8636911 -0.3537166 -0.3831117 0.8747814 -0.2966194 -0.02694815 0.9876226 -0.1545172 -0.02368283 0.9768863 -0.2124435 -0.01992905 0.9639505 -0.2653343 -0.01858609 0.9842087 -0.1760338 -0.1018429 0.9713684 -0.2146422 -0.02295005 0.951604 -0.3064689 -0.01913571 0.9416172 -0.3361414 -0.03524959 0.9120645 -0.4085292 -0.02270632 0.89269 -0.4500989 -0.02008152 0.8951849 -0.4452425 -0.02392727 0.8593996 -0.5107444 -0.02017307 0.8325893 -0.5535234 -0.02270615 0.815591 -0.5781833 -0.01840311 0.7977133 -0.6027561 -0.01715153 0.7530217 -0.6577724 -0.020814 0.715794 -0.6980014 -0.01986801 0.6809768 -0.7320355 -0.01941013 0.6045839 -0.796305 -0.02014225 0.6026824 -0.797727 -0.0165416 0.5205118 -0.8536943 -0.02044767 0.4707543 -0.8820273 -0.01944047 0.4312012 -0.9020463 -0.02050852 0.3462959 -0.9379012 -0.02035611 0.3325037 -0.9428823 -0.01678562 0.249984 -0.9681044 -0.01757884 0.1575995 -0.9873467 -0.4170411 0.4688928 -0.7785989 -0.4252601 0.5158118 -0.7437016 -0.4357537 0.5608215 -0.7039873 -0.4482696 0.6034914 -0.6594336 -0.462638 0.6433107 -0.6100144 -0.478603 0.6797859 -0.5557252 -0.4961515 0.7123804 -0.4963346 -0.5152001 0.7401595 -0.4321259 -0.5205653 0.7562038 -0.3964439 -0.3752906 0.8802255 -0.2904481 -0.5444085 0.7671405 -0.3392863 -0.541298 0.4572771 -0.7056162 -0.5534998 0.4877 -0.6751197 -0.5687867 0.5165073 -0.6400797 -0.5867037 0.5433052 -0.6004984 -0.6067544 0.5676592 -0.5564281 -0.6285467 0.5892988 -0.5075984 -0.6513057 0.6084266 -0.4534511 -0.6612559 0.6173085 -0.4262288 -0.5403774 0.771257 -0.3363853 -0.6839308 0.6295765 -0.3686085 -0.6618114 0.4085316 -0.6285759 -0.6782262 0.4216216 -0.6018674 -0.6965634 0.4318729 -0.5729618 -0.7172981 0.4412804 -0.5392172 -0.7396582 0.4481104 -0.5020985 -0.7639576 0.4532717 -0.4592534 -0.7785533 0.4524826 -0.4348728 -0.6836326 0.6300407 -0.3683681 -0.7966174 0.4658176 -0.3852464 -0.720865 0.3722434 -0.584627 -0.7298964 0.3743175 -0.5719597 -0.7493164 0.3756958 -0.5453236 -0.7464181 0.3599483 -0.5597297 -0.7709673 0.3733676 -0.5159517 -0.7641691 0.3612552 -0.5343599 -0.7954531 0.3733112 -0.4773817 -0.788641 0.3444678 -0.5093008 -0.7829644 0.3656479 -0.503258 -0.8201264 0.369594 -0.4367985 -0.8044252 0.3700149 -0.4647464 -0.8238769 0.3702639 -0.4291056 -0.8372789 0.3729513 -0.3998392 -0.8275324 0.3718479 -0.4206178 -0.7995545 0.4618238 -0.3839681 -0.8446485 0.3736767 -0.3833208 -0.7627104 0.3313797 -0.5553921 -0.7653911 0.3347041 -0.5496814 -0.771652 0.3266184 -0.545778 -0.7832945 0.3227179 -0.5313218 -0.7878475 0.3230434 -0.5243466 -0.7855922 0.3385484 -0.5179092 -0.797441 0.3154484 -0.5143737 -0.7928909 0.3014084 -0.529601 -0.8122124 0.30791 -0.4954822 -0.7889462 0.3000016 -0.5362491 -0.7859377 0.2978396 -0.5418428 -0.7832462 0.2952738 -0.5471187 -0.7806517 0.2920691 -0.5525203 -0.7781414 0.2882513 -0.5580388 -0.7822868 0.2973746 -0.5473535 -0.799728 0.2987535 -0.520751 -0.8193705 0.3047919 -0.4855245 -0.8100931 0.2933779 -0.5076205 -0.8298212 0.2997305 -0.4707 -0.8034413 0.2955148 -0.5168686 -0.8226579 0.2882888 -0.4900239 -0.8414334 0.2940591 -0.4533424 -0.8163673 0.2910344 -0.498842 -0.8135119 0.2892581 -0.504508 -0.834056 0.282332 -0.4739613 -0.8530979 0.2866346 -0.4359641 -0.8280242 0.2854793 -0.4825741 -0.8256422 0.2839223 -0.4875479 -0.848244 0.2762271 -0.4518637 -0.8603706 0.2815714 -0.4248292 -0.8415122 0.280321 -0.46182 -0.8388642 0.2790415 -0.4673786 -0.8367186 0.2774209 -0.4721649 -0.8625733 0.2761101 -0.4239466 -0.8675889 0.278057 -0.4122787 -0.8746057 0.2803853 -0.3955365 -0.8598517 0.2754896 -0.4298377 -0.8499725 0.2721133 -0.4511111 -0.8500859 0.2721715 -0.4508623 -1 0 0 -0.01754868 -0.1254654 -0.9919429 -0.01742655 0.9876394 -0.1557711 -0.1062378 0.9723773 -0.2078368 -0.02884072 0.9923658 -0.1199103 -0.2136947 0.9655327 -0.1485975 -0.1125848 0.9799671 -0.1642841 -0.1099618 0.9818129 -0.1547644 -0.2185478 0.9575696 -0.187876 -0.02829122 0.9971835 -0.06946158 -0.05124163 0.9921772 -0.1138364 -0.1164895 0.9859346 -0.1198466 -0.03305184 0.9964691 -0.07718199 -0.2176041 0.9730838 -0.07587146 -0.1164304 0.9893074 -0.087834 -0.0232253 0.9986577 -0.04629796 -0.1204574 0.9913394 -0.05230903 -0.01742643 0.9994733 -0.02737569 -0.2186416 0.9750365 -0.03872919 -0.120428 0.9921123 -0.03479164 -0.01742613 0.9994242 0.02911472 -0.01742631 0.9997418 0.01458805 -0.01757872 0.9994242 0.02902317 -0.2163468 0.973454 0.07470971 -0.1153616 0.9930563 0.02304178 -0.1157893 0.9927548 0.03210604 -0.2176601 0.9752895 0.0378738 -1 -4.993e-6 0 -1 4.7112e-6 0 -1 -4.47617e-6 0 -1 -1.35659e-6 0 -1 7.126e-7 0 -1 3.18475e-7 0 -1 -1.06754e-5 0 -0.01745694 0.9973049 0.07126218 -0.02017313 0.9970287 0.07434451 -0.01925766 0.990231 0.1381 -0.01757913 0.998595 0.04999077 -0.01745206 0.9982235 0.05696737 -1 4.48083e-6 0 -0.0205391 0.9873139 0.1574465 -0.01998978 0.9755947 0.2186672 -0.01956284 0.9936178 0.1110903 -1 1.66362e-5 0 -0.01559537 0.9631932 0.2683573 -0.01992893 0.9546373 0.2971034 -1 -2.12839e-6 0 -0.02194291 0.9843196 0.1750247 -0.01699912 0.9786278 0.2049362 -0.01611405 0.9415444 0.3365035 -0.01940983 0.9273707 0.37364 -0.01696872 0.916311 0.4001078 -0.01843333 0.893927 0.4478333 -1 -4.46064e-6 0 -0.0182504 0.888229 0.4590384 -0.01855558 0.8553273 0.5177559 -0.01666349 0.8264625 0.5627453 -0.01901334 0.8103113 0.5856912 -0.0174874 0.85896 0.5117442 -0.01709097 0.7916793 0.6106979 -0.01818948 0.7598996 0.6497861 -0.01586991 0.7450022 0.6668733 -0.0180673 0.7055097 0.7084701 -0.01489305 0.6751022 0.7375738 -0.01855599 0.6453096 0.7636958 -0.01605308 0.5930498 0.8050058 -0.01712143 0.58033 0.8142015 -0.01684659 0.5135473 0.857896 -0.01644992 0.5099175 0.8600661 -0.01815891 0.4416747 0.8969916 -0.01559525 0.4232082 0.9058982 -0.01870822 0.3670544 0.9300114 -1 6.31214e-7 0 -0.01532083 0.3340068 0.9424462 -0.01867794 0.2900881 0.9568178 -0.01602274 0.2414702 0.9702759 -0.01702964 0.2105511 0.9774346 -0.01654118 0.1323295 0.9910679 -0.01678556 0.1473166 0.988947 -0.01812797 0.05154579 0.9985061 -0.01660203 0.03070163 0.9993907 -0.01586961 -0.03201395 0.9993615 -0.01641917 -0.04559534 0.9988251 -0.01553398 -0.1091653 0.9939022 -0.01568663 -0.1118515 0.9936012 -0.01751816 -0.1907774 0.981477 -0.01440495 -0.2610288 0.9652236 -0.01745676 -0.2695119 0.9628389 -0.01748764 -0.3461517 0.9380156 -0.01440513 -0.4034668 0.9148809 -0.01730436 -0.4215002 0.9066632 -1 -2.15091e-6 0 -0.01727402 -0.492554 0.8701105 -1 -2.23132e-6 0 -0.01458835 -0.536931 0.8435001 -0.01699918 -0.5625602 0.8265816 -1 2.12146e-6 0 -0.01696872 -0.6262563 0.7794327 -0.01492381 -0.6582044 0.7526913 -0.01651066 -0.6889315 0.7246385 -0.01651084 -0.7435373 0.6684907 -1 -4.45681e-6 0 -0.01535111 -0.7642921 0.6446874 -0.01586997 -0.7967054 0.6041594 -1 4.38086e-6 0 -0.01596164 -0.8413895 0.5401935 -0.01596134 -0.8529113 0.5218119 -0.01513755 -0.8839308 0.4673727 -1 2.13433e-6 0 -0.01535105 -0.9173105 0.3978766 -0.01532053 -0.921614 0.3878054 -0.0174877 -0.9472363 0.3200589 -0.01406943 -0.9699405 0.2429352 -0.01745671 -0.9701006 0.242075 -0.01745665 -0.9865471 0.1625425 -1 -2.12127e-6 0 -0.01553428 -0.9936754 0.111212 -0.01803654 -0.9964989 0.08163768 -0.01721251 -0.9996995 0.01745665 -0.01751774 -0.9997633 0.01290941 -1 2.12543e-6 0 -1 4.99288e-6 0 -0.01599186 -0.999432 -0.02966433 -1 1.06756e-5 0 -0.01635807 -0.9959225 -0.08871835 -0.02072221 -0.9979317 -0.06085431 -0.01770126 -0.9773234 -0.2110112 -0.02072232 -0.9766675 -0.2137547 -0.01770097 -0.9333008 -0.358659 -0.02142423 -0.990917 -0.132757 -0.02078342 -0.9321415 -0.3614974 -0.01770132 -0.8672136 -0.4976216 -1 -2.16613e-6 0 -0.02139377 -0.9586009 -0.2839485 -0.02078348 -0.8653382 -0.5007572 -0.01773148 -0.7806448 -0.6247234 -0.0213328 -0.9034552 -0.4281516 -0.02072221 -0.7778017 -0.6281681 -0.01779246 -0.6756578 -0.7370007 -0.02121078 -0.8266718 -0.5622845 -0.02063125 -0.6716755 -0.7405582 -0.01785379 -0.5546892 -0.831866 -0.02108901 -0.7300295 -0.6830903 -0.02056992 -0.549346 -0.8353418 -0.01785373 -0.4205546 -0.9070917 -1 -1.1609e-6 0 -0.02093631 -0.6158514 -0.7875842 -0.01733499 -0.3976985 -0.9173525 -0.01760953 -0.2763509 -0.9608954 -1 -5.9468e-7 0 -0.02081388 -0.4869596 -0.8731764 -0.01733475 -0.2686282 -0.963088 -9.15562e-5 0.9965589 -0.0828889 0 0.9965918 -0.08249235 3.05191e-5 0.9863775 -0.164498 -3.05191e-5 0.9863775 0.164498 1.22077e-4 0.9862294 0.1653838 9.15562e-5 0.9965589 0.0828889 0 0.9965918 0.08249235 -1.22077e-4 0.9862294 -0.1653838 1.22075e-4 0.94581 -0.3247207 -1.83112e-4 0.9453169 -0.3261534 1.52597e-4 0.8795385 -0.4758279 -1.83116e-4 0.8787119 -0.4773524 1.52595e-4 0.789344 -0.6139512 -1.22076e-4 0.7883949 -0.6151696 1.22077e-4 0.6773124 -0.7356956 -3.05193e-5 0.6766127 -0.736339 6.10393e-5 0.5465461 -0.8374291 3.05191e-5 0.5464754 -0.8374752 9.1557e-5 0.4008364 -0.9161497 -1.22077e-4 0.2458016 -0.9693202 1.83112e-4 0.2443017 -0.9696993 0 0.4016 -0.9158153 -1.83117e-4 0.08334851 -0.9965204 2.13631e-4 0.08142387 -0.9966796 -2.13631e-4 -0.08142387 -0.9966796 1.83117e-4 -0.08334851 -0.9965204 -1.83112e-4 -0.2443017 -0.9696993 1.22077e-4 -0.2458016 -0.9693202 -9.1557e-5 -0.4008364 -0.9161497 0 -0.4016 -0.9158153 -3.05191e-5 -0.5464754 -0.8374752 -6.10378e-5 -0.5465321 -0.8374381 6.10386e-5 -0.6766127 -0.736339 -1.22077e-4 -0.6773124 -0.7356956 1.22076e-4 -0.7883949 -0.6151696 -1.52595e-4 -0.789344 -0.6139512 1.83116e-4 -0.8787119 -0.4773524 -1.52597e-4 -0.8795385 -0.4758279 1.83112e-4 -0.9453169 -0.3261534 -1.22075e-4 -0.94581 -0.3247207 1.22077e-4 -0.9862294 -0.1653838 -3.05193e-5 -0.9863824 -0.1644682 9.15562e-5 -0.9965589 -0.0828889 -9.15562e-5 -0.9965589 0.0828889 0 -0.9965943 0.08246201 3.05193e-5 -0.9863824 0.1644682 0 -0.9965943 -0.08246201 -1.22077e-4 -0.9862294 0.1653838 1.22075e-4 -0.94581 0.3247207 -1.83112e-4 -0.9453169 0.3261534 1.52597e-4 -0.8795385 0.4758279 -1.83116e-4 -0.8787119 0.4773524 1.52595e-4 -0.789344 0.6139512 -1.22076e-4 -0.7883949 0.6151696 1.22077e-4 -0.6773124 0.7356956 -6.10386e-5 -0.6766127 0.736339 6.10378e-5 -0.5465321 0.8374381 3.05191e-5 -0.5464754 0.8374752 9.1557e-5 -0.4008364 0.9161497 -1.22077e-4 -0.2458016 0.9693202 1.83112e-4 -0.2443017 0.9696993 0 -0.4016 0.9158153 -1.83117e-4 -0.08334851 0.9965204 2.13631e-4 -0.08142387 0.9966796 -2.13631e-4 0.08142387 0.9966796 1.83117e-4 0.08334851 0.9965204 -1.83112e-4 0.2443017 0.9696993 1.22077e-4 0.2458016 0.9693202 -9.1557e-5 0.4008364 0.9161497 0 0.4016 0.9158153 -3.05191e-5 0.5464754 0.8374752 -6.10393e-5 0.5465461 0.8374291 3.05193e-5 0.6766127 0.736339 -1.22077e-4 0.6773124 0.7356956 1.22076e-4 0.7883949 0.6151696 -1.52595e-4 0.789344 0.6139512 1.83116e-4 0.8787119 0.4773524 -1.52597e-4 0.8795385 0.4758279 1.83112e-4 0.9453169 0.3261534 -1.22075e-4 0.94581 0.3247207 -0.1155764 0.9911128 0.0658605 -0.2116469 0.9660075 0.1484428 -0.1105706 0.9905573 0.08105862 -0.1194221 0.9837912 0.1337662 -1 -1.13172e-5 0 -0.2140918 0.9581182 0.1901953 -0.1190248 0.9780181 0.1712126 -0.2062157 0.9480978 0.2420448 -0.1105107 0.9724391 0.2053039 -0.1095938 0.9705655 0.214457 -0.1958693 0.952582 0.2328581 -0.1080972 0.9686024 0.2238851 -0.1774379 0.9377294 0.2986292 -0.0921691 0.9607867 0.2615222 -0.09958511 0.9537343 0.2836787 -0.1862571 0.9159954 0.355332 -0.07171911 0.9287781 0.3636313 -0.0944882 0.9080454 0.4080756 -0.1812518 0.8765643 0.4458508 -0.08630853 0.8788948 0.4691426 -0.1699636 0.8266842 0.5363819 -0.08993935 0.841255 0.5331051 -0.08145558 0.8200497 0.566466 -0.1637037 0.7688645 0.6181007 -0.08090633 0.7750649 0.6266807 -0.08066153 0.7469206 0.6600027 -0.1648982 0.7000315 0.6948127 -0.08462935 0.673342 0.7344717 -0.1600134 0.6281513 0.7614603 -0.07931983 0.5940293 0.8005234 -0.1564715 0.5503513 0.8201404 -0.07452809 0.5096724 0.8571346 -0.1541522 0.4679197 0.8702232 -0.07300132 0.4208564 0.9041851 -0.1527488 0.3821315 0.9113965 -0.07605403 0.3306155 0.9406961 -0.1526582 0.2935971 0.9436611 -0.08090686 0.2408284 0.9671896 -0.1022704 0.2017329 0.9740866 -0.08725363 0.1555855 0.9839614 -0.1057495 0.1313247 0.985683 -0.106727 0.1318446 0.9855082 -0.09817975 0.1273559 0.986986 -0.0976597 0.1271408 0.9870653 -0.09701949 0.1268669 0.9871637 -0.09442561 0.1259517 0.9875323 -0.09109884 0.1250663 0.9879572 -0.08820086 0.1248546 0.988247 -0.08566719 0.1254642 0.9883926 -0.08435451 0.1266233 0.9883577 -0.08365261 0.1280273 0.9882365 -0.08340972 0.1297078 0.9880378 -0.01745051 0.02856117 0.9994397 -0.0174517 0.02856773 0.9994396 -1 -2.72149e-6 0 -0.02630746 0.0420553 0.998769 -0.02227908 0.03576862 0.9991118 -0.02179032 0.03497433 0.9991506 -0.03390675 0.05026507 0.9981603 -0.01416075 0.02743643 0.9995233 0.2371934 -0.09650093 0.9666576 0.1044355 -0.06939989 0.9921073 0.1182301 -0.1468567 0.9820666 0.1205814 -0.003112912 0.9926986 0.1201229 -0.003448605 0.9927532 0.256089 -0.03460907 0.9660335 0.2457124 -0.2914306 0.9244964 0.1175609 -0.2855093 0.9511383 0.2479649 -0.1658084 0.9544743 0.2424479 -0.4123508 0.878172 0.1152696 -0.4232351 0.8986573 0.2366188 -0.5272573 0.8160952 0.1167041 -0.5551072 0.8235511 0.2262355 -0.6357057 0.7380351 0.1210102 -0.6750936 0.7277399 0.2127791 -0.7349609 0.6438615 0.1294918 -0.7780494 0.6147122 0.1978549 -0.8209009 0.5357006 0.1416099 -0.8602193 0.4898666 0.1828706 -0.8904565 0.4167081 0.1523237 -0.9208703 0.3588809 0.1679165 -0.942707 0.2882841 0.1615976 -0.9616201 0.2217503 0.1539692 -0.9766138 0.1500628 0.2266989 -0.97165 0.06711238 0.1341309 -0.9898223 0.04754853 0.2034117 -0.9790927 -0.001159727 0.2824856 -0.955281 -0.08740693 0.1117613 -0.9875404 -0.1107847 0.2071936 -0.9685516 -0.1377628 0.2038682 -0.9565633 -0.2083851 0.2172033 -0.936962 -0.2737243 0.09833335 -0.9529976 -0.2865768 0.2024306 -0.9176058 -0.3420841 0.2221484 -0.8896314 -0.3990066 0.1138677 -0.8935765 -0.4342295 0.1963322 -0.8611698 -0.4688716 0.2256327 -0.824675 -0.5186532 0.1389539 -0.8114751 -0.5676267 0.1856824 -0.7853658 -0.5905274 0.2303902 -0.7413139 -0.6303762 0.1753661 -0.7087892 -0.6832748 0.1739601 -0.6901639 -0.7024327 0.2369497 -0.6421508 -0.7290385 0.208779 -0.5929801 -0.7776798 0.1597667 -0.5788531 -0.7996273 0.2439744 -0.5325382 -0.810481 0.2384453 -0.4691999 -0.8502913 0.1388917 -0.4438065 -0.8852937 0.2349379 -0.4066398 -0.8828638 0.1200309 -0.3039075 -0.94511 0.2438473 -0.2850176 -0.9269863 0.1182631 -0.1540625 -0.9809581 0.2489135 -0.1603776 -0.9551551 0.1059938 -0.07281923 -0.9916968 0.2558458 -0.03460919 -0.966098 0.1209157 -0.00350964 -0.9926567 0.1205213 -0.003082454 -0.992706 0.255599 -0.03500556 -0.966149 0.2365847 -0.09851592 -0.9666036 -0.4012382 0.8972083 0.184459 -0.4124662 0.9062049 0.09308338 -0.4154561 0.9083697 0.04754871 -0.5734577 0.7910297 0.2131162 -0.5893005 0.8006783 0.1078863 -0.7229449 0.6504918 0.2328329 -0.7414634 0.6605876 0.1177124 -0.5936349 0.8029071 0.05420261 -0.8416324 0.4828468 0.2418964 -0.8625767 0.4909085 0.1223532 -0.7470188 0.6621449 0.05939036 -0.9030147 0.386409 0.1877567 -0.9109618 0.398273 0.1073659 -0.8682025 0.4923619 0.0616787 -0.8879623 0.3835679 0.2537689 -0.9471277 0.3046715 0.1006212 -0.946608 0.3040913 0.1070606 -0.9363067 0.301105 0.1807363 -0.9146715 0.3993791 0.06222939 -0.9523701 0.3049439 -7.01933e-4 -0.936032 0.3008914 0.1825064 -0.9204347 0.2952752 0.2561494 -0.8724375 0.3835111 0.302939 -0.9206441 0.2935038 0.25743 -0.9087954 0.2913651 0.2986592 -0.9273991 0.2979018 0.2262418 -0.711767 0.6409016 0.2874596 -0.8267316 0.4764335 0.2992091 -0.5654544 0.7810705 0.2649347 -0.3981234 0.8873162 0.2327396 -0.8380255 0.3676642 0.403158 -0.8435536 0.372244 0.3871068 -0.797869 0.4633152 0.3856738 -0.8881981 0.2854131 0.3600605 -0.8862449 0.2843772 0.3656496 -0.8961604 0.288069 0.3375098 -0.8807229 0.2825161 0.380147 -0.8953729 0.2876437 0.3399536 -0.8932752 0.2870664 0.345908 -0.9134506 0.2910041 0.2844728 -0.9047169 0.2898122 0.3122439 -0.8742921 0.2802911 0.3962957 -0.7960307 0.4681025 0.3836866 -0.6836326 0.6300407 0.3683681 -0.8342751 0.365621 0.4126818 -0.6839146 0.6295896 0.3686162 -0.5404101 0.77126 0.3363256 -0.5444014 0.7671609 0.3392513 -0.3752906 0.8802255 0.2904481 -0.3831083 0.8747735 0.2966472 -0.4150028 0.9085624 -0.04782384 -0.4124982 0.9060862 -0.09409081 -0.594093 0.8025413 -0.0545994 -0.7416914 0.6603257 -0.1177452 -0.7470403 0.6621369 -0.05920654 -0.589779 0.8002683 -0.1083118 -0.8626613 0.490874 -0.1218944 -0.8683672 0.4921246 -0.06125229 -0.9141498 0.4004765 -0.06283956 -0.9112592 0.3952482 -0.1156965 -0.9471098 0.3047366 -0.100592 -0.9462152 0.3035433 -0.1119747 -0.952055 0.3059272 -6.10389e-5 -0.3969619 0.8884415 -0.2304192 -0.5746472 0.7901743 -0.2130855 -0.5676862 0.7800076 -0.2632884 -0.400869 0.8975988 -0.183359 -0.7233383 0.6503056 -0.2321299 -0.7118607 0.6409341 -0.2871553 -0.842415 0.4816809 -0.2414966 -0.8269496 0.475612 -0.2999127 -0.8829243 0.3887247 -0.2633208 -0.870446 0.3850032 -0.3067513 -0.8974184 0.2874608 -0.334674 -0.9081324 0.2907269 -0.3012865 -0.919207 0.2946626 -0.2612136 -0.8761284 0.2809031 -0.3917811 -0.8822219 0.2829446 -0.3763337 -0.8888791 0.2852991 -0.3584668 -0.8853752 0.2840464 -0.368006 -0.8875237 0.2848035 -0.3621997 -0.8960433 0.2876433 -0.3381831 -0.8813315 0.2825461 -0.3787119 -0.9016852 0.3891788 -0.1884245 -0.9273397 0.2979939 -0.2263643 -0.9348666 0.3003097 -0.189311 -0.9044941 0.2881307 -0.3144381 -0.9129759 0.2925246 -0.2844371 -0.9205705 0.2957276 -0.2551376 -0.9359747 0.3011062 -0.1824461 -1 -2.6267e-6 0 -0.866234 0.2774525 -0.4155225 -1 2.1815e-6 0 -0.8705095 0.2790098 -0.4054219 -0.8953165 0.2874925 -0.34023 -0.8858782 0.2700941 -0.3771857 -0.8850294 0.2707368 -0.3787141 -0.8862708 0.2707642 -0.3757801 -0.8952174 0.2702163 -0.3543575 -0.8948158 0.2694213 -0.3559731 -0.9011373 0.2727797 -0.3369613 -0.8889071 0.2712256 -0.3691623 -0.8540805 0.2646017 -0.4478086 -0.8550885 0.2689662 -0.4432616 -0.8591523 0.2755293 -0.4312089 0.2284051 -0.5638715 -0.7936499 -0.8512378 0.2707957 -0.4495153 -0.8497413 0.2744576 -0.4501252 -0.8492 0.2757725 -0.450343 -0.8517864 0.2694221 -0.4493013 -0.8561015 0.2691512 -0.4411894 -0.8578092 0.2697916 -0.4374653 -0.8637196 0.2762279 -0.4215291 -1 -2.47598e-6 0 -0.8603097 0.2703403 -0.4321844 -0.8578834 0.2627668 -0.4415765 -0.8667826 0.2811756 -0.4118598 -0.8709693 0.2726014 -0.40878 -0.8762041 0.2843466 -0.3891188 -0.8726004 0.2698494 -0.407124 -0.8786231 0.2693337 -0.3943107 -0.8629591 0.2664931 -0.4292821 -0.8666071 0.2686955 -0.42047 -0.8778861 0.269546 -0.3958041 -0.8829531 0.2703397 -0.3838104 -0.8827776 0.2698232 -0.3845767 -0.8927496 0.2869727 0.3473398 -0.8998594 0.2687828 0.3435244 -0.900077 0.2735145 0.3391922 -0.8949229 0.2686935 0.3562539 -0.8860031 0.271804 0.375661 -0.8931806 0.2627109 0.3649814 -0.8891555 0.2664048 0.3720634 -0.8993686 0.260725 0.3509396 -0.9081231 0.2724735 -0.3179163 -0.9093526 0.2761995 -0.3111136 -0.8962888 0.271438 -0.3506965 -0.8999179 0.2715288 -0.3412039 -0.9169799 0.2754663 -0.288559 -0.9178561 0.278485 -0.2828187 -0.9249852 0.2782769 -0.2587749 -0.925526 0.2804411 -0.2544693 -0.9309078 0.2801604 -0.234352 -0.9323823 0.2816282 -0.2266027 -0.935173 0.2807167 -0.2159852 -0.9468243 0.285445 -0.1484754 -0.9479981 0.2805967 -0.1502172 -0.9043498 0.4225101 -0.06030625 -0.9347789 0.2785811 -0.2204111 -0.9411852 0.3145321 -0.1234506 -0.952002 0.3054622 -0.01962351 -0.9524328 0.3041815 -0.01858597 -0.897628 0.4242156 0.1196044 -0.9445281 0.3113839 0.1044355 -0.9334599 0.2843168 0.21867 -0.936089 0.2787331 0.2145814 -0.9323037 0.2814185 0.2271857 -0.9546343 0.281141 0.09814906 -0.9320504 0.2807748 0.2290146 -0.9255477 0.2803164 0.2545279 -0.9347362 0.2833079 0.2144876 -0.9248506 0.2782731 0.2592597 -0.9178476 0.2783299 0.2829992 -0.9168181 0.2754635 0.289075 -0.9093617 0.2760404 0.3112283 -0.9080135 0.2724773 0.3182259 -0.8625407 0.2763536 0.4238541 -0.8684271 0.2782751 0.4103627 -0.8608964 0.2758359 0.4275183 -0.8551858 0.2818472 0.4349938 -0.8491896 0.2801029 0.4476823 -0.8638564 0.2768124 0.4208648 -0.8573109 0.2639593 0.441977 -0.8607724 0.275988 0.42767 -0.8555088 0.2695439 0.4420983 -0.8446761 0.2810501 0.4555581 -0.8539601 0.2659145 0.4472601 -0.8485877 0.2744596 0.4522953 -0.8510169 0.2714953 0.4495115 -0.834513 0.2396356 0.4961482 -0.8726205 0.2796829 0.4003885 -0.8670305 0.2777891 0.4136317 -1 2.75483e-6 0 -0.7639247 0.453545 0.4590384 -0.8222247 0.367088 0.4349632 -0.82375 0.3678812 0.4313922 -0.7775431 0.4541594 0.4349322 -0.8793954 0.2820633 0.3835414 -0.8807776 0.2702455 0.3888422 -0.8811779 0.2697278 0.3882945 -0.8893094 0.2700676 0.3690425 -0.8870485 0.2702804 0.3742908 -0.8758084 0.2696368 0.4003198 -0.8728284 0.2714408 0.4055742 -0.8680807 0.2710692 0.4158816 -1 -2.5334e-6 0 -0.8550543 0.2775409 0.4380105 -0.8578608 0.2692393 0.4377046 -0.8637818 0.2758925 0.4216212 -0.8590825 0.2693006 0.4352636 -0.8619542 0.2706444 0.4287034 -0.5722367 0.1889754 -0.7980185 -1 1.68781e-6 0 -0.8445571 0.2809596 0.4558344 -0.8534311 0.2638055 0.4495131 -0.8485877 0.2711635 0.454279 -0.8422943 0.2805918 0.4602267 -0.8464581 0.2709826 0.4583417 -0.8394929 0.2833406 0.4636484 -0.8496856 0.261977 0.4576052 -0.8428147 0.2719554 0.4644392 -0.8430261 0.2896252 0.4532375 -0.8333473 0.2871517 0.4723095 -0.8455758 0.2603016 0.4660952 -0.8389754 0.2723237 0.4711263 -0.8300395 0.2864562 0.4785156 -0.8412687 0.2585913 0.4747606 -0.8350929 0.2725656 0.4778368 -0.8264601 0.289322 0.4829664 -0.8371661 0.2569393 0.4828407 -0.8313958 0.2727779 0.4841212 -0.8320194 0.2957633 0.4693271 -0.8196276 0.2923753 0.4926738 -0.8270807 0.2729977 0.4913347 -0.8154101 0.2949064 0.4981333 -0.832642 0.2551152 0.4915524 -0.8223748 0.2732704 0.4990221 -0.8214249 0.3005838 0.4846758 -0.8084829 0.2976228 0.5077167 -0.8279573 0.2537677 0.5000888 -0.8176558 0.2737523 0.5064571 -0.8048835 0.2999429 0.5120516 -0.8236778 0.2519345 0.5080196 -0.8135764 0.2743051 0.5126892 -0.8038132 0.3086096 0.508571 -0.7988418 0.3029037 0.5197126 -0.8189637 0.2498337 0.5166057 -0.8099118 0.2744264 0.5183948 -0.7952806 0.3022054 0.5255481 -0.8062556 0.27452 0.5240142 -0.7918605 0.305104 0.5290261 -0.8142182 0.24812 0.5248669 -0.8021577 0.2746392 0.5302041 -0.7802832 0.3185284 0.5382359 -0.7838914 0.3109624 0.5374166 -0.8093494 0.2463237 0.5331775 -0.7977979 0.2748849 0.5366161 -0.7789376 0.3121183 0.5439104 -0.8044959 0.2443091 0.5413867 -0.7932566 0.2751922 0.5431513 -0.774055 0.3125457 0.5505944 -0.7995775 0.2425376 0.5494101 -0.7889808 0.27513 0.549375 -0.7692947 0.3121798 0.5574312 -0.7842007 0.2749204 0.5562805 -0.7646577 0.3108987 0.5644825 -0.7942544 0.2408856 0.5577939 -0.7791821 0.2748546 0.5633208 -0.7603006 0.3141062 0.5685775 -0.7893816 0.2388745 0.5655226 -0.7739726 0.2747664 0.5704997 -0.7504383 0.3249692 0.5755324 -0.7505887 0.3198715 0.5781859 -0.7840394 0.2367377 0.5737923 -0.7685338 0.2746726 0.5778501 -0.7447268 0.3204199 0.5854172 -0.7786461 0.2350007 0.5817947 -0.7631285 0.2747628 0.5849277 -0.7399021 0.3200525 0.591702 -0.7734414 0.23289 0.5895343 -0.7582807 0.2749172 0.5911269 -0.7356089 0.3189887 0.5976002 -0.7679917 0.2306661 0.5974795 -0.7540342 0.2746714 0.5966475 -0.7316688 0.3208795 0.6014126 -0.7493674 0.2742452 0.6026924 -0.732586 0.3279912 0.5964392 -0.7236539 0.3253101 0.608686 -0.7623679 0.2288019 0.605347 -0.7444632 0.274035 0.6088344 -0.717958 0.3263085 0.6148651 -0.756685 0.2267857 0.6131853 -0.7393978 0.2739132 0.6150305 -0.7124666 0.3264925 0.6211231 -0.7509027 0.2248679 0.6209505 -0.734167 0.2738172 0.6213074 -0.7071542 0.3257896 0.6275303 -0.7453708 0.2228513 0.6282991 -0.7292008 0.2733626 0.627327 -0.704454 0.3251866 0.6308711 -0.726291 0.2730534 0.6308276 -0.6925522 0.3214941 0.6457656 -0.6119108 0.2880406 0.7366125 -0.9119791 0.4087456 -0.03494465 -0.7414689 0.2232494 0.6327587 -0.5324285 0.1656552 0.8301074 -0.6431307 0.197398 0.7398765 -0.6300593 0.241983 0.7378819 -0.5198876 0.2045674 0.8293787 -0.539921 0.2565777 0.8016566 -0.507837 0.2428401 0.8265169 -0.7436093 0.3389503 0.5763315 -0.7408527 0.3416621 0.5782771 -0.8513525 0.388077 0.3529804 -0.7416208 0.3428241 0.5766025 -0.7629294 0.3302528 0.5557623 -0.7862103 0.3377582 0.517487 -0.7738448 0.3240224 0.5442184 -0.7825735 0.3199939 0.534025 -0.7881765 0.3222472 0.5243421 -0.717715 0.4399007 0.5397894 -0.7661904 0.377617 0.5199596 -0.7806202 0.3734635 0.5011559 -0.7590847 0.3734689 0.5332087 -0.7401152 0.4478352 0.5016705 -0.7924625 0.3756307 0.4805254 -0.803893 0.3728164 0.4634264 -0.7359712 0.3404115 0.5852063 -0.64973 0.394892 0.6495469 -0.7091768 0.351094 0.611393 -0.7054415 0.371261 0.603753 -0.7147637 0.3574123 0.6011401 -0.6873597 0.3379727 0.6428928 -0.7314617 0.3505474 0.5848764 -0.7025839 0.3560987 0.6160923 -0.661807 0.4084983 0.6286022 -0.7207549 0.3722496 0.5847588 -0.67893 0.4193032 0.6026931 -0.7260442 0.373429 0.5774173 -0.7391492 0.3732827 0.5606412 -0.6971773 0.4302271 0.5734531 -0.7446793 0.3760936 0.5513679 -0.7589239 0.1710913 0.6283012 -0.684579 0.1475609 0.713847 -0.76182 0.1725249 0.6243922 -0.7982993 0.1434112 0.5849373 -0.7718685 0.1222916 0.62391 -0.7695874 0.1216519 0.6268463 -0.6377036 0.1424037 0.7570042 -0.6484168 0.1169812 0.7522441 -0.6944408 0.1149364 0.7103109 -0.6413411 0.1102066 0.7592998 -0.6928497 0.1149358 0.7118632 -0.7655256 0.1748778 0.6191837 -0.7694296 0.1780513 0.6134134 -0.7734743 0.1812525 0.6073592 -0.7779742 0.1847044 0.6005334 -0.7825682 0.1880885 0.5934725 -0.7913296 0.19343 0.5799849 -0.7890195 0.1912654 0.5838372 -0.7864534 0.1906239 0.5874977 -0.7950184 0.1969387 0.5737255 -0.7987171 0.2002362 0.5674123 -0.8057066 0.2048753 0.5557545 -0.802967 0.2024661 0.5605815 -0.8090932 0.2085373 0.5494363 -0.8126751 0.2121415 0.5427295 -0.817822 0.2161062 0.5333529 -0.8157636 0.2139437 0.537362 -0.8212592 0.2200401 0.5264177 -0.8249116 0.2236469 0.5191367 -0.8283872 0.2270336 0.5120845 -0.8346773 0.2323448 0.4993293 -0.8322458 0.2296313 0.5046152 -0.8372684 0.2353959 0.4935287 -0.8407738 0.2385687 0.485988 -0.8394025 0.2375316 0.4888579 -0.8454076 0.2437249 0.4752728 -0.843537 0.2413811 0.4797714 -0.8481284 0.2461983 0.4691105 -0.8524357 0.2507164 0.4587972 -0.850863 0.2490025 0.4626339 -0.8568734 0.2557467 0.4476177 -0.8567127 0.2507482 0.4507424 -0.8588743 0.2574609 0.4427741 -0.8601778 0.2600523 0.4387105 -0.851547 0.208904 0.4808606 -0.8658113 0.2464765 0.435454 -0.8636991 0.2415611 0.4423483 -0.8665233 0.2483934 0.4329412 -0.8568543 0.2386593 0.456993 -0.8386914 0.2348128 0.4913856 -0.7706431 0.4376468 0.463222 -0.6828937 0.5833101 0.4397791 -0.7493141 0.4799187 0.4562966 -0.6544627 0.6215626 0.4305098 -0.7003512 0.5592006 0.4436249 -0.7476027 0.4846782 0.4540673 -0.2946022 0.9176828 0.2665855 -0.3223399 0.9051275 0.2772026 -0.1634921 0.966212 0.1992608 -0.09161931 0.9829085 0.1596776 -0.03494435 0.9912295 0.1274477 0.02371317 0.9952524 0.09439498 0.05966514 0.9954779 0.07391768 -0.8245753 0.2095467 0.5255149 0.2159842 0.9760341 -0.02661269 0.2035321 0.978871 -0.01965433 0.2421377 0.9692531 -0.04379475 0.2429642 0.9690183 -0.04440557 -0.8046746 0.1887015 0.5629304 -0.8416867 0.1810089 0.5087231 -0.7973024 0.1869273 0.5739052 -0.7923631 0.1889732 0.5800429 -0.8018373 0.1661478 0.5739791 -0.7961847 0.146309 0.5870977 -0.8196024 0.1514379 0.5525563 -0.7934575 0.1412714 0.5920031 -0.7892075 0.1350189 0.5991007 -0.7847367 0.1299806 0.6060475 -0.7804915 0.1264705 0.6122405 -0.7763258 0.1239704 0.6180208 -0.2004786 0.05090546 0.9783747 -0.1545791 0.06610429 0.9857664 -0.1240305 0.04989904 0.991023 -0.01743859 0.02856618 0.9994398 -0.1352893 0.04504555 0.9897816 -0.195779 0.05270618 0.9792307 -0.1249457 0.04294055 0.991234 -0.01744496 0.02856737 0.9994397 -0.3052517 0.073673 0.9494177 -0.2813218 0.09918588 0.9544738 -0.1517722 0.07629805 0.9854663 -0.01744091 0.02856731 0.9994397 -0.01745808 0.02856564 0.9994395 -0.4261366 0.1081287 0.8981737 -0.2769011 0.1203679 0.9533296 -0.5357753 0.1294345 0.8343811 -0.4540929 0.09091621 0.8863036 -0.5426015 0.09860765 0.8341823 -0.4322414 0.0842936 0.8978096 -0.2415622 0.06131374 0.9684464 -0.3164787 0.06952154 0.9460487 -0.1432878 0.08438569 0.9860769 -0.1475304 0.08594244 0.9853166 -0.2743968 0.1412422 0.9511873 -0.0174542 0.02856689 0.9994395 -0.1579639 0.09030431 0.983307 -0.2947242 0.1507039 0.943624 -1 -2.10538e-6 0 -1 -2.3159e-7 0 -0.2859024 0.0842936 0.9545442 -0.1578748 0.05887115 0.9857027 -0.1591582 0.0593295 0.9854688 -0.01746165 0.02856814 0.9994394 -0.2959118 0.08832186 0.9511233 -0.1510382 0.04950171 0.9872878 -0.2945994 0.07721292 0.9524965 -0.1602843 0.05438435 0.9855716 -0.01743447 0.02856355 0.99944 -0.1544256 0.05679565 0.9863707 -0.01744991 0.02856761 0.9994395 -0.01745039 0.02856683 0.9994396 -0.2741255 0.07877063 0.9584626 -0.1496658 0.05395781 0.9872633 -0.01744824 0.02856469 0.9994397 -0.2633472 0.07315367 0.9619235 -0.1436516 0.05090522 0.9883183 -0.01745426 0.02856785 0.9994395 -0.0174551 0.02856767 0.9994395 -0.2530962 0.06711184 0.9651105 -0.1373955 0.0491352 0.9892968 -0.01744991 0.02856636 0.9994396 -0.1386189 0.04776275 0.9891934 -0.01745355 0.02856779 0.9994395 -0.01745343 0.02856707 0.9994396 -0.01745331 0.02856749 0.9994395 -0.01744705 0.0285663 0.9994397 -0.4742358 0.1020557 0.8744629 -0.4938247 0.1130111 0.8621866 -0.5128164 0.1237254 0.8495361 -0.5312482 0.1335521 0.8366236 -0.5497133 0.1405718 0.8234409 -0.2785789 0.06131297 0.9584543 -0.5515812 0.1204915 0.8253727 -0.7390435 0.1727975 0.6511188 -0.757024 0.1819848 0.6275318 -0.5194342 0.08957338 0.8498028 -0.7620368 0.1545498 0.62882 -0.669314 0.1303775 0.7314509 -0.694804 0.1475611 0.7038987 -0.7196851 0.161022 0.6753705 -0.817629 0.1899489 0.5435092 -0.8368579 0.1966331 0.5108859 -0.8376964 0.1988033 0.5086668 -0.7228784 0.1101744 0.6821352 -0.8439115 0.1673967 0.5096979 -0.7135117 0.1304396 0.6883943 -0.7467451 0.1462177 0.6488393 -0.7730752 0.163612 0.6128507 -0.7631361 0.1519557 0.6281185 -0.79351 0.1776852 0.5820396 -0.8334234 -0.04773229 0.5505697 -0.9044716 0.2075316 0.3726413 -0.9041506 0.2089928 0.3726043 -0.8355888 0.1582732 0.5260617 -0.882476 0.1353241 0.4504702 -0.8895049 0.1675489 0.4250982 -0.8855069 0.1458194 0.4411512 -0.8929873 0.1589737 0.4210713 -0.8140535 0.1428576 0.5629464 -0.8311891 0.1631248 0.5315215 -0.838089 0.1656584 0.5197733 -0.847306 0.1753026 0.5013398 -0.8618474 0.1794256 0.4743686 -0.8625752 0.1789973 0.4732062 -0.877 0.1945905 0.439324 -0.8852038 0.1986787 0.4206435 -0.8901774 0.2036225 0.4075809 -0.9070053 0.2070739 0.3666903 -0.1585761 -0.01901322 0.9871637 -0.08978664 0.003601193 0.9959546 -0.07687801 0.003662288 0.9970339 -0.01745402 0.02856689 0.9994395 -0.1324847 -0.01937979 0.9909956 -0.2400049 -0.07779407 0.9676496 -0.1306222 -0.01986795 0.9912332 -0.08606392 0.006805717 0.9962664 -0.1301032 -0.02670425 0.9911409 -0.01742267 0.02857017 0.99944 -0.01745265 0.02856612 0.9994395 -0.1865018 -0.009613454 0.9824077 -0.1039786 0.01031541 0.9945261 -0.01745671 0.02856594 0.9994395 -0.01745408 0.02856886 0.9994395 -0.2143052 0.002319395 0.9767641 -0.1158817 0.01812845 0.9930976 -0.0174483 0.02856767 0.9994396 -0.0174551 0.02856642 0.9994395 -0.01745301 0.02856498 0.9994397 -0.2360362 0.01937973 0.9715511 -0.1244245 0.02093577 0.9920082 -0.01744991 0.02856701 0.9994397 -0.01744997 0.0285682 0.9994396 -0.01744836 0.02856695 0.9994396 -0.0174517 0.02856916 0.9994395 -0.1273875 0.02719265 0.9914802 -0.0174492 0.02856564 0.9994397 -0.01745223 0.02856588 0.9994397 -0.01745104 0.02856886 0.9994395 -0.2565739 0.03802675 0.9657763 -0.1392571 0.03427255 0.989663 -0.01745283 0.02856594 0.9994395 -0.01745277 0.02856659 0.9994396 -0.1444178 0.03927844 0.988737 -0.01745092 0.02856761 0.9994395 -0.01745367 0.02856683 0.9994395 -0.01745647 0.02856814 0.9994394 -0.4850381 0.04565638 0.8733005 -0.4451807 0.008850455 0.8953971 -0.400658 -0.02142453 0.9159772 -0.3518886 -0.04620635 0.9349007 -0.2985689 -0.06683695 0.952045 -0.2480303 -0.06799697 0.966363 -0.2433295 -0.08295112 0.9663901 -0.432908 -0.1152082 0.8940458 -0.3595418 -0.1160935 0.9258791 -0.351453 -0.1368457 0.9261502 -0.6843973 0.04855632 0.7274907 -0.6326107 -0.00250256 0.7744659 -0.5750424 -0.04678589 0.8167848 -0.5054231 -0.08371323 0.8588012 -0.4917564 -0.1430436 0.8589029 -0.414325 -0.1407533 0.8991793 -0.4059976 -0.1658416 0.8987005 -0.4033074 -0.1636729 0.900308 -0.3528035 -0.1316909 0.926384 -0.8208089 0.09708094 0.5628927 -0.7672845 0.02594131 0.6407821 -0.8206278 0.09247279 0.5639317 -0.7679465 0.04977625 0.638577 -0.7216881 -0.02630752 0.6917183 -0.7286129 0.004699885 0.6849096 -0.6545081 -0.07474076 0.7523517 -0.672518 -0.04184162 0.738897 -0.5822214 -0.1232074 0.8036407 -0.5820879 -0.09259444 0.8078366 -0.5275844 -0.1739896 0.831494 -0.5014525 -0.1377003 0.8541569 -0.5176125 -0.175915 0.8373358 -0.4589744 -0.1960232 0.866555 -0.4677936 -0.1965722 0.861701 -0.04236024 0.01379454 0.9990072 -0.4629451 -0.1963602 0.8643637 -0.8541063 0.08566695 0.5129948 -0.8347571 0.03418129 0.5495566 -0.8409171 0.08783328 0.5339887 -0.8398969 0.0493195 0.5405005 -0.8265792 0.01614457 0.562589 -0.7852323 -0.02200442 0.6188103 -0.7547362 -0.05572777 0.6536571 -0.7652708 -0.02649068 0.6431632 -0.7503122 -0.05963432 0.6583886 -0.6893315 -0.103093 0.7170733 -0.6364127 -0.1350466 0.7594348 -0.6537103 -0.1154217 0.747891 -0.5669311 -0.1674302 0.8065707 -0.5514874 -0.2025274 0.8092246 -0.5614633 -0.1916306 0.8050073 -0.1304696 -0.02713155 0.9910811 -0.01748967 0.02855849 0.9994391 -0.1218934 -0.02911525 0.9921162 -0.2339907 -0.0879563 0.9682521 -0.1290328 -0.03006082 0.9911846 -0.01745659 0.02856594 0.9994395 -0.2165327 -0.08691829 0.9723985 -0.3370255 -0.1457911 0.9301391 -0.3247539 -0.1672447 0.9308943 -0.3958974 -0.244033 0.8852757 -0.4277309 -0.2171463 0.8774359 -0.4020351 -0.1980418 0.8939504 -0.4325527 -0.2223039 0.8737729 -0.4558403 -0.1959661 0.8682206 -0.185036 -0.1171925 0.975719 -0.1095035 -0.04266607 0.9930703 -0.1074572 -0.05154645 0.9928726 -0.01745152 0.02856701 0.9994395 -0.1918141 -0.1249462 0.9734454 -0.1914772 -0.142555 0.9710894 -0.1865335 -0.136482 0.9729224 -0.1031547 -0.05481237 0.9931541 -0.103947 -0.0557273 0.9930205 -0.01745378 0.02856713 0.9994395 -0.01745313 0.02856588 0.9994395 -0.2128088 -0.1101124 0.9708697 -0.1162773 -0.03500527 0.9925997 -0.01744902 0.02856719 0.9994397 -0.01745533 0.02856439 0.9994395 -0.01746094 0.02856653 0.9994395 -0.3020498 -0.1753031 0.9370352 -0.3090668 -0.1948643 0.9308629 -0.2808983 -0.2023724 0.9381586 -0.2711914 -0.2212624 0.9367488 -0.2675028 -0.2163217 0.9389608 -0.2744588 -0.2250483 0.9348935 -0.03952217 0.01052904 0.9991633 -0.37365 -0.2690597 0.8876895 -0.3877801 -0.2508698 0.8869561 -0.3787752 -0.273331 0.8842057 -0.3617169 -0.309315 0.8794801 -0.3533539 -0.3038819 0.8847581 -0.1218628 -0.07092642 0.9900097 -0.3641514 -0.3122998 0.8774181 -0.1056859 -0.05795478 0.9927093 -0.01745146 0.02856606 0.9994396 -0.08228051 -0.05221879 0.9952403 -0.1816501 -0.1486284 0.9720663 -0.1019027 -0.06180083 0.9928728 -0.01745164 0.02856659 0.9994396 -0.0174542 0.02856624 0.9994396 -0.1373682 -0.1285175 0.9821473 -0.2574622 -0.2326499 0.9378632 -0.210275 -0.2094815 0.9549356 -0.2459843 -0.2952727 0.9232041 -0.3025678 -0.3029341 0.9037056 -0.2757753 -0.2872506 0.9172977 -0.2580059 -0.3286874 0.908514 -0.3170631 -0.3228312 0.8917685 -0.3696475 -0.3151404 0.8740981 -0.0426352 -0.03177034 0.9985855 -0.03546321 -0.01699912 0.9992265 -0.03344833 -0.00979644 0.9993925 -0.02557462 0.008331537 0.9996382 -0.02649044 -7.93493e-4 0.9996488 -0.03726369 -0.03375399 0.9987353 -0.02499496 0.004486262 0.9996775 -0.01745343 0.02857106 0.9994395 -0.01986783 -0.04815894 0.9986422 -0.01767069 -0.007507741 0.9998157 -0.01751798 0.04074311 0.9990161 -0.0184642 0.06070309 0.9979851 -0.01721298 0.09528183 0.9953016 -0.01742625 0.0674467 0.9975708 -0.0751065 -0.09030479 0.9930781 -0.05997061 -0.05841416 0.9964895 -0.03549402 -0.01205515 0.9992973 -0.1178351 -0.1437765 0.9825698 -0.09241122 -0.09674489 0.9910099 -0.04788374 -0.02948099 0.9984178 -0.07892203 -0.1019638 0.9916526 -0.1865654 -0.2042973 0.9609662 -0.06308192 -0.04248189 0.9971038 -0.1349545 -0.1640084 0.977184 -0.2153707 -0.2574256 0.9419913 -0.1321464 -0.262248 0.9559097 -0.1769192 -0.2389035 0.9547904 -0.119452 -0.2124744 0.9698382 -0.1557078 -0.2095738 0.9653154 -0.07913655 -0.1474692 0.9858957 -0.06613457 -0.1144461 0.9912257 -0.06442534 -0.09274685 0.9936034 -0.06952273 -0.1685575 0.9832371 -0.0415672 -0.04544317 0.9981018 -0.01745218 0.02856713 0.9994396 -0.01745289 0.02856463 0.9994396 -0.01745325 0.02856773 0.9994395 -0.01745116 0.02856618 0.9994396 -0.07083499 -0.2226985 0.9723107 -0.07364267 -0.28218 0.9565309 -0.13822 -0.3160842 0.9386087 -0.07791507 -0.3447124 0.9354692 -0.1457299 -0.3705966 0.91729 -0.08301264 -0.4084711 0.9089886 -0.1540907 -0.4251304 0.8919194 -0.2725706 -0.3619015 0.8914777 -0.08356183 -0.467922 0.8798105 -0.160959 -0.4789401 0.8629651 -0.2888358 -0.3957453 0.8717567 -0.08749735 -0.534384 0.840701 -0.1706634 -0.5297218 0.8308243 -0.3074229 -0.4295315 0.8491137 -0.08850449 -0.4993792 0.8618511 -0.09494554 -0.5951877 0.797958 -0.1824734 -0.5789462 0.7946854 -0.3251217 -0.4623058 0.8249662 -0.09430468 -0.562105 0.8216719 -0.09461075 -0.6717975 0.7346679 -0.1954459 -0.6091052 0.7686299 -0.3446183 -0.4961137 0.7969375 -0.08325582 -0.6711437 0.7366375 -0.100133 -0.6274107 0.7722237 -0.1086795 -0.7148253 0.6908066 -0.2084467 -0.6494197 0.731303 -0.1245793 -0.6897034 0.7132947 -0.2678982 -0.5849936 0.765515 -0.2264503 -0.6360142 0.7377033 -0.2943552 -0.6021999 0.7420987 -0.0736429 -0.711007 0.6993181 -0.02060037 -0.7730801 0.6339739 -0.02642941 -0.6908274 0.7225366 -0.02050906 -0.6586707 0.7521518 -0.01822 -0.7422003 0.6699305 -0.06055039 -0.7496169 0.6590964 -0.01858639 -0.6547663 0.755603 -0.01840305 -0.6222864 0.7825733 -0.02163785 -0.5861142 0.8099395 -0.02673482 -0.5495904 0.8350064 -0.02096676 -0.5219117 0.8527418 -0.01950174 -0.5172092 0.8556368 -0.01849466 -0.4749103 0.8798399 -0.01806735 -0.4149698 0.9096559 -0.01959311 -0.3621985 0.9318951 -0.01760965 -0.3461509 0.9380136 -0.02139359 -0.2793992 0.9599367 -0.02185171 -0.2211421 0.9749968 -0.01956248 -0.1997453 0.9796526 -0.01837271 -0.1562293 0.98755 -0.02005112 -0.102514 0.9945296 -0.01739597 -0.04635876 0.9987733 -0.3348833 -0.3483726 0.8754941 -0.3575944 -0.3731288 0.8560965 -0.3810355 -0.4036809 0.8317775 -0.3722119 -0.3813067 0.8462054 -0.4054214 -0.434415 0.8043116 -0.3919304 -0.413935 0.8216134 -0.3665958 -0.5131486 0.7760709 -0.4262385 -0.4543167 0.7822512 -0.337756 -0.5680845 0.7504673 -0.3764542 -0.5476974 0.7472013 -0.4333734 -0.4836386 0.7604482 -0.4443936 -0.4922176 0.7484894 -0.4550396 -0.4826899 0.7482976 -0.3844218 -0.3278084 0.8629958 -0.3906713 -0.3301525 0.8592877 -0.4044396 -0.3423637 0.8480659 -0.4135676 -0.346486 0.8419675 -0.4234616 -0.3565623 0.8327926 -0.4296174 -0.358691 0.8287157 -0.4430814 -0.369499 0.8167922 -0.4434956 -0.3681758 0.8171648 -0.4566925 -0.3774336 0.8055905 -0.4618154 -0.3808787 0.8010355 -0.4736895 -0.3875946 0.7908152 -0.4819042 -0.3913831 0.7839564 -0.4904565 -0.3989575 0.7747809 -0.4703278 -0.429524 0.7709091 -0.5053044 -0.3994947 0.7648997 -0.5128426 -0.3989759 0.7601386 -0.5194483 -0.4384791 0.7334232 -0.4820207 -0.4474729 0.7532756 -0.5397715 -0.386471 0.7478549 -0.5368043 -0.3848791 0.7508058 -0.5393655 -0.3846943 0.7490628 -0.5314309 -0.3801167 0.7570288 -0.5520972 -0.3915953 0.7360991 -0.499535 -0.4500637 0.7402077 -1 2.19083e-6 0 -1 -5.77189e-7 0 -0.01825022 0.1488708 0.9886882 -0.01623612 0.1873258 0.9821637 -0.0174874 0.2364618 0.9714835 -0.01504582 0.3166955 0.948408 -0.01736557 0.3210651 0.9468979 -1 -6.07999e-7 0 -0.01773136 0.4040689 0.9145568 -0.01556479 0.4616034 0.8869498 -0.01590049 0.4847677 0.8744984 -1 1.10983e-6 0 -0.01608383 0.593241 0.8048642 -0.0159614 0.5580407 0.8296601 -1 -1.7964e-6 0 -0.01699888 0.6312181 0.775419 -1 1.4947e-6 0 -0.01510709 0.7113466 0.7026791 -0.016999 0.6962268 0.7176206 -1 1.24768e-6 0 -0.01764035 0.7578638 0.6521743 -1 -2.14143e-6 0 -0.01464933 0.811695 0.5838979 -0.01745682 0.8124139 0.5828199 -1 4.72699e-6 0 -0.01776242 0.8608679 0.5085185 -0.01525944 0.8923428 0.4511002 -0.01623612 0.9032132 0.4288851 -1 -4.71161e-6 0 -0.01550346 0.9510541 0.3086355 -0.01626694 0.9367685 0.3495715 -1 4.22423e-6 0 -0.01721286 0.9646547 0.2629545 -1 -2.51945e-6 0 -0.01467949 0.9875254 0.1567747 -0.01715165 0.9839331 0.1777122 -0.01763993 0.9958951 0.08877968 -0.01593106 0.9998727 -0.00100708 -0.01803648 0.9996382 -0.01995915 -0.01693797 0.9875907 -0.1561345 -0.01916623 0.9852008 -0.1703295 -0.0159918 0.9513324 -0.3077517 -0.02005118 0.9416424 -0.3360174 -1 -4.83442e-6 0 -1 5.0734e-6 0 -1 2.23485e-6 0 -0.01528996 0.8923733 -0.4510391 -0.02063053 0.8705117 -0.4917151 -1 -2.56727e-6 0 -0.0149241 0.8120375 -0.5834145 -0.02087485 0.7739273 -0.6329303 -1 -4.80171e-6 0 -1 6.48668e-7 0 -0.01486289 0.7119556 -0.7020673 -0.0207833 0.6547206 -0.7555853 -1 -2.38651e-6 0 -0.01510685 0.5942031 -0.8041732 -0.02035588 0.5163446 -0.856139 -1 1.29886e-6 0 -0.01559537 0.461361 -0.8870754 -0.01971548 0.3627837 -0.9316649 -1 2.35459e-6 0 -0.01629728 0.3165153 -0.9484474 -0.0184946 0.1981304 -0.9800013 -1 -1.32132e-6 0 -1 -4.21426e-7 0 -0.01736551 0.1141121 -0.9933162 -0.02346938 0.07028609 -0.9972508 -0.02221751 0.09128105 -0.9955773 -0.01748728 0.1870807 -0.9821889 -1 7.60086e-7 0 -0.02050882 -0.04449683 -0.998799 -0.01913571 -0.05945193 -0.9980478 -0.01742655 0.001922667 -0.9998463 -0.01986783 -0.1455452 -0.9891521 -0.01995944 -0.147987 -0.9887879 -0.02713167 -0.1032163 -0.9942888 -0.01745229 0.02856969 -0.9994395 -0.04675531 -0.03619569 -0.9982504 -0.04355061 -0.04159736 -0.998185 -0.04742705 -0.03680628 -0.9981964 -0.0242623 0.008484184 -0.9996697 -0.02795505 9.76598e-4 -0.9996088 -0.02539151 0.008850395 -0.9996384 -0.02035582 0.02093571 -0.9995736 0.2255661 0.2086891 -0.9516139 0.1006203 0.1247912 -0.9870678 0.1709386 0.2008475 -0.9645933 -0.01745569 0.02856999 -0.9994394 -0.01745182 0.02856683 -0.9994395 -0.01745182 0.02856427 -0.9994396 -0.01745104 0.02856141 -0.9994398 -0.0174542 0.02857804 -0.9994392 -0.01745122 0.02855986 -0.9994398 -0.01745253 0.02856987 -0.9994395 0.2412256 0.1697796 -0.9555025 0.08847516 0.0863083 -0.9923322 0.1143856 0.1002858 -0.9883616 0.231611 0.2974107 -0.9262306 0.106207 0.2612754 -0.9594036 0.2250527 0.4100025 -0.8838831 0.1083421 0.3858505 -0.9161776 0.2251443 0.5296704 -0.817777 0.1091984 0.5068968 -0.8550622 0.1101152 0.6187575 -0.7778264 0.2231254 0.6453578 -0.7305672 0.1242432 0.7190908 -0.6837192 0.218764 0.74898 -0.6254369 0.145455 0.807907 -0.5710772 0.2124738 0.8364667 -0.5051518 0.1663909 0.8811823 -0.4425291 0.2064302 0.9050397 -0.3718735 0.1823212 0.9356857 -0.3020783 0.2018863 0.9525129 -0.2279499 0.1914467 0.9694721 -0.1532062 0.1994448 0.9768983 -0.07675647 0.1942846 0.9809452 0 0.1995642 0.9768548 0.0769996 0.1915397 0.9694486 0.1532379 0.2022513 0.9523847 0.2281621 0.1825659 0.9356278 0.3021098 0.2069786 0.9048523 0.3720244 0.1667581 0.8810349 0.4426843 0.2132111 0.8362722 0.5051633 0.1461241 0.8076199 0.5713126 0.2197372 0.7489072 0.6251829 0.1251296 0.7186106 0.6840626 0.2241007 0.6441941 0.7312952 0.1159128 0.6148142 0.7801075 0.1111521 0.5094932 0.8532654 0.2251428 0.5315592 0.816551 0.1084664 0.3849733 0.9165319 0.2270982 0.4106446 0.8830614 0.1061779 0.2607907 0.9595388 0.234053 0.2970144 0.9257439 0.2761951 0.2150049 0.936744 0.1065108 0.1677926 0.9800516 0.1917228 0.1390157 0.971554 0.1128292 0.1011404 0.9884535 0.08865827 0.08505702 0.9924238 0.2413107 0.1706601 0.9553242 0.2060628 0.2224514 0.9529185 -0.01736569 -0.7751702 0.6315138 -0.04971516 -0.7829606 0.6200816 0.0696749 -0.8055799 0.5883761 -0.01721292 -0.8129153 0.5821275 -0.03671449 -0.7865089 0.6164867 -0.02087521 -0.8709297 0.4909642 -0.02157711 -0.8617736 0.506834 -0.07501709 -0.8586987 0.5069606 -0.07278805 -0.8325006 0.5492221 -0.05862611 -0.8660861 0.4964454 -0.07935082 -0.8310477 0.5505119 -0.02221816 -0.9409156 0.3379117 -0.0367757 -0.8791995 0.4750326 -0.08157747 -0.9068131 0.4135639 0.0272839 -0.9001859 0.4346504 -0.02292013 -0.9095726 0.4149125 -0.0635401 -0.9125732 0.4039468 -0.0180673 -0.9322683 0.3613162 -0.07681679 -0.9283326 0.3637276 -0.006592094 -0.9339477 0.357349 -0.01998972 -0.952366 0.3043017 -0.07175135 -0.9293801 0.3620834 -0.02105808 -0.9855192 0.1682512 -0.03076374 -0.9609398 0.2750425 -0.1038879 -0.9489082 0.2979606 -0.0896033 -0.9469999 0.3084845 -0.08640074 -0.9472652 0.308583 -0.1111191 -0.9494414 0.2936218 -0.02475106 -0.9688025 0.2465953 -0.09173917 -0.9487044 0.3025624 -0.02850508 -0.9818081 0.1877246 -0.1033388 -0.9754925 0.1942561 -0.106635 -0.9662767 0.2343894 -0.07464975 -0.9779854 0.1948646 -0.1270197 -0.9648244 0.2301735 -0.02035629 -0.9961785 0.084935 -0.0594511 -0.9828051 0.1748131 -0.1458513 -0.9852514 0.0894823 -0.04269665 -0.9847089 0.1688944 -0.03650045 -0.9923189 0.1181993 -0.08453744 -0.9901261 0.1118214 -0.02444547 -0.9972296 0.07025408 -0.2012146 -0.9774762 0.06366348 -0.07483166 -0.9937173 0.08322429 -0.01742655 -0.9989607 0.04211676 -0.1139888 -0.9921455 0.05151623 -0.0209667 -0.9840622 -0.1765843 -0.03756839 -0.9979889 -0.05105757 -0.01736527 -0.9958945 -0.08884066 -0.03961312 -0.997714 -0.05475032 -0.1713364 -0.9819649 -0.07993054 -0.1073343 -0.9931403 -0.04638844 -0.09497648 -0.9931941 -0.06741744 -0.2053329 -0.9772239 -0.05359166 -1 4.83423e-6 0 -1 -5.07351e-6 0 -1 -2.23489e-6 0 -1 2.56717e-6 0 -1 4.80173e-6 0 -1 -6.4866e-7 0 -1 2.38651e-6 0 -1 -1.29886e-6 0 -1 -2.35459e-6 0 -1 1.32132e-6 0 -1 4.21426e-7 0 -0.02743673 -0.9757607 -0.2171137 -0.02215683 -0.9375461 -0.3471545 -0.02743649 -0.9951307 -0.09466969 -0.02026444 -0.9909457 -0.1327263 -0.01751774 -0.9854215 -0.1692267 -0.01306241 -0.889589 -0.4565752 -0.02279788 -0.8606445 -0.5086958 -1 2.51941e-6 0 -0.03085452 -0.9683009 -0.2478738 -0.02551376 -0.9627187 -0.2692987 -0.015473 -0.9461437 -0.3233771 -0.0172435 -0.8163666 -0.5772767 -0.02227872 -0.7574156 -0.652553 -0.01889133 -0.6952261 -0.7185428 -0.02020341 -0.6295421 -0.7767038 -0.01785355 -0.7751214 -0.63156 -0.0170297 -0.7430832 -0.6689824 -1 2.40989e-6 0 -0.02365213 -0.6115692 -0.7908375 -0.01858592 -0.4835392 -0.8751255 -1 -1.24767e-6 0 -0.01797586 -0.6545784 -0.7557805 -0.02304202 -0.466762 -0.8840827 -0.01992905 -0.3221923 -0.9464645 -1 -2.26398e-6 0 -1 -1.24441e-6 0 -0.02438467 -0.5789762 -0.8149798 -0.02005106 -0.5438517 -0.8389418 -0.01782321 -0.5078102 -0.8612845 -0.01852512 -0.2643271 -0.9642552 -1 2.75889e-7 0 -0.02514731 -0.4348599 -0.900147 -0.02017343 -0.3906506 -0.920318 -0.01748722 -0.3298159 -0.9438833 -0.01907455 -0.2054561 -0.9784804 -9.15567e-5 -0.9961675 0.08746713 0 -0.9962048 0.08704048 3.05193e-5 -0.9848282 0.1735329 -3.05193e-5 -0.9848282 -0.1735329 1.22076e-4 -0.9846667 -0.1744469 9.15567e-5 -0.9961675 -0.08746713 0 -0.9962048 -0.08704048 -1.22076e-4 -0.9846667 0.1744469 1.22076e-4 -0.9397124 0.341966 -1.83116e-4 -0.939143 0.3435264 1.83116e-4 -0.8662018 0.4996943 -2.13633e-4 -0.8651824 0.5014573 2.13632e-4 -0.7664799 0.6422683 -1.83113e-4 -0.7651985 0.6437946 1.83116e-4 -0.6431964 0.7657012 -1.22077e-4 -0.6420347 0.7666756 1.22077e-4 -0.5001205 0.8659558 0 -0.4994679 0.8663325 6.1038e-5 -0.341721 0.9398014 -3.05189e-5 -0.1737748 0.9847854 9.1556e-5 -0.1731324 0.9848986 0 -0.3417847 0.9397783 -9.15583e-5 -4.27272e-4 1 9.15583e-5 4.27272e-4 1 -9.1556e-5 0.1731324 0.9848986 3.05189e-5 0.1737748 0.9847854 -6.1038e-5 0.341721 0.9398014 0 0.3417847 0.9397783 0 0.4994812 0.8663249 -1.22077e-4 0.5001205 0.8659558 1.22077e-4 0.6420347 0.7666756 -1.83116e-4 0.6431964 0.7657012 1.83113e-4 0.7651985 0.6437946 -2.13632e-4 0.7664799 0.6422683 2.13633e-4 0.8651824 0.5014573 -1.83116e-4 0.8662018 0.4996943 1.83116e-4 0.939143 0.3435264 -1.22076e-4 0.9397124 0.341966 1.22076e-4 0.9846667 0.1744469 -3.05193e-5 0.9848282 0.1735329 9.15567e-5 0.9961675 0.08746713 -9.15567e-5 0.9961675 -0.08746713 0 0.9962048 -0.08704048 3.05193e-5 0.9848282 -0.1735329 0 0.9962048 0.08704048 -1.22076e-4 0.9846667 -0.1744469 1.22076e-4 0.9397124 -0.341966 -1.83116e-4 0.939143 -0.3435264 1.83116e-4 0.8662018 -0.4996943 -2.13633e-4 0.8651824 -0.5014573 2.13632e-4 0.7664799 -0.6422683 -1.83113e-4 0.7651985 -0.6437946 1.83116e-4 0.6431964 -0.7657012 -1.22077e-4 0.6420347 -0.7666756 1.22077e-4 0.5001205 -0.8659558 0 0.4994812 -0.8663249 6.1038e-5 0.341721 -0.9398014 -3.05189e-5 0.1737748 -0.9847854 9.1556e-5 0.1731324 -0.9848986 0 0.3417847 -0.9397783 -9.15583e-5 4.27272e-4 -1 9.15583e-5 -4.27272e-4 -1 -9.1556e-5 -0.1731324 -0.9848986 3.05189e-5 -0.1737748 -0.9847854 -6.1038e-5 -0.341721 -0.9398014 0 -0.3417847 -0.9397783 0 -0.4994679 -0.8663325 -1.22077e-4 -0.5001205 -0.8659558 1.22077e-4 -0.6420347 -0.7666756 -1.83116e-4 -0.6431964 -0.7657012 1.83113e-4 -0.7651985 -0.6437946 -2.13632e-4 -0.7664799 -0.6422683 2.13633e-4 -0.8651824 -0.5014573 -1.83116e-4 -0.8662018 -0.4996943 1.83116e-4 -0.939143 -0.3435264 -1.22076e-4 -0.9397124 -0.341966 -0.1689218 -0.9725745 -0.1598882 -0.08853608 -0.9908655 -0.1017203 -0.09546279 -0.9839265 -0.1509155 -0.1573852 -0.9607613 -0.2284024 -0.0927155 -0.9771448 -0.1912906 -0.09665256 -0.9690588 -0.2271198 -0.1924506 -0.9412869 -0.2773841 -0.1087076 -0.9572193 -0.2681679 -0.1834193 -0.9223155 -0.3401345 -0.09912645 -0.9484159 -0.3011333 -0.09720194 -0.9447358 -0.313091 -0.1681004 -0.9289779 -0.3297613 -0.09454858 -0.9417322 -0.322802 -0.06909435 -0.8853172 -0.4598254 -0.07245266 -0.9225359 -0.3790491 -0.07895416 -0.8845491 -0.4597164 -0.06607443 -0.9259881 -0.3717259 -0.07724493 -0.8396535 -0.5376016 -0.08383756 -0.8353544 -0.543281 -0.1024538 -0.7165665 -0.6899535 -0.05874824 -0.7900043 -0.6102803 -0.07962554 -0.7523686 -0.6539124 -0.04901325 -0.7999606 -0.5980477 -0.06689816 -0.7286164 -0.6816473 -0.1199096 -0.6885724 -0.7151851 -0.07544207 -0.7026919 -0.7074833 -0.1209475 -0.6617473 -0.7399069 -0.04986846 -0.6635808 -0.7464407 -0.09778308 -0.6358038 -0.7656318 -0.1818003 -0.581047 -0.7933051 -0.09464067 -0.591161 -0.8009819 -0.1740521 -0.619086 -0.7657927 -0.1709071 -0.5292629 -0.8310666 -0.09189438 -0.5537469 -0.8275989 -0.08694988 -0.5272234 -0.8452665 -0.1614143 -0.4785358 -0.8631042 -0.08240157 -0.4870849 -0.8694587 -0.08102852 -0.4628849 -0.8827072 -0.1523838 -0.4256552 -0.8919624 -0.07553493 -0.4209204 -0.9039472 -0.07761079 -0.3916553 -0.916833 -0.1457874 -0.3702518 -0.9174201 -0.07812881 -0.3311929 -0.9403229 -0.1378231 -0.315809 -0.9387596 -0.07355177 -0.2708597 -0.9598048 -0.1313232 -0.2628601 -0.9558551 -0.0702247 -0.2139092 -0.9743262 -0.1236006 -0.2087477 -0.9701275 -0.06881988 -0.1618411 -0.9844142 -0.07825052 -0.1459721 -0.9861891 -0.06482309 -0.1083132 -0.9920012 -0.06338775 -0.08810806 -0.9940921 -0.04019385 -0.03802698 -0.9984681 -0.0406515 -0.03241133 -0.9986476 -0.6842456 -0.6343159 -0.3597936 -0.6504917 -0.6440216 -0.4026126 -0.7124089 -0.5681753 -0.4118866 -0.6702342 -0.5494693 -0.4988684 -0.6764005 -0.5561848 -0.4828467 -0.6092561 -0.6269268 -0.4855615 -0.7316123 -0.5679669 -0.3770372 -0.7841563 -0.5164433 -0.3440717 -0.7697028 -0.5072958 -0.3875676 -0.755687 -0.5000883 -0.4229052 -0.7631645 -0.5006073 -0.4086223 -0.7211903 -0.4727976 -0.5063073 -0.7321231 -0.4787229 -0.4845826 -0.727068 -0.4767768 -0.4940204 -0.5727028 -0.7451393 -0.3417295 -0.5170297 -0.7713175 -0.3711467 -0.6137235 -0.618973 -0.4901182 -0.4781125 -0.7552566 -0.4483258 -0.665777 -0.5450124 -0.5096101 -0.4454905 -0.8380911 -0.3148678 -0.3662275 -0.8707364 -0.3281703 -0.4859381 -0.7453269 -0.4564559 -0.3325335 -0.8538566 -0.400438 -0.3067464 -0.9095575 -0.2803779 -0.3459324 -0.845711 -0.4063295 -0.3208773 -0.9281452 -0.1886382 -0.4637072 -0.8600586 -0.2127791 -0.5947182 -0.7698957 -0.2314539 -0.7109755 -0.6595507 -0.2439401 -0.7525428 -0.5724489 -0.3255485 -0.792035 -0.5194373 -0.3207265 -0.7653233 -0.5950276 -0.2454027 -0.8091601 -0.5313423 -0.2508692 -0.3272547 -0.9401667 -0.09482234 -0.4758549 -0.8728177 -0.108404 -0.6123933 -0.7816208 -0.1185051 -0.7338956 -0.6670585 -0.1281807 -0.7788148 -0.6001259 -0.1824732 -0.8207126 -0.5437542 -0.1753917 -0.8223965 -0.5397902 -0.179696 -0.7796517 -0.6164944 -0.1099008 -0.8310895 -0.5459213 -0.106114 -0.3917723 -0.9177673 -0.06494438 -0.5616664 -0.8243104 -0.07101702 -0.7137684 -0.6968001 -0.07074201 -0.7764455 -0.6270527 -0.06274795 -0.8349127 -0.5503826 -3.05192e-5 -0.8359283 -0.5487401 0.01040709 -0.7481198 -0.6489626 0.1384356 -0.7100636 -0.6978558 0.09384703 -0.7805848 -0.6181626 0.09253364 -0.823194 -0.5404338 0.1740204 -0.8243286 -0.5409561 0.16688 -0.7772563 -0.6063808 0.1678541 -0.3330261 -0.9408782 0.06198459 -0.3900322 -0.917186 0.08151608 -0.4821361 -0.8732652 0.07037633 -0.5606437 -0.8230811 0.09064298 -0.6188945 -0.7816216 0.07770133 -0.7643855 -0.5002108 -0.4068218 -0.7332035 -0.4792802 -0.4823932 -0.8106504 -0.5169948 -0.2748862 -0.8004472 -0.5032551 -0.3256051 -0.7688359 -0.491906 -0.4085585 -0.7314013 -0.4783026 -0.4860851 -0.7344546 -0.4716501 -0.4879781 -0.7342345 -0.47247 -0.4875161 0.7599297 0.4060589 0.5075659 -0.7364855 -0.4716718 -0.4848865 -0.7707744 -0.4912142 -0.4057285 -0.7365682 -0.4717162 -0.4847177 -0.7858969 -0.5154979 0.3415086 -0.790355 -0.5184597 0.3264026 -0.7435648 -0.5853849 0.3231656 -0.7430887 -0.5856997 0.3236898 -0.7634955 -0.4997802 0.4090165 -0.7637842 -0.5012239 0.4067045 -0.7187466 -0.5730502 0.3937221 -0.7153808 -0.5748072 0.3972744 -0.7641654 -0.5008473 0.4064521 -0.7311839 -0.4785137 0.4862046 -0.728204 -0.476995 0.4921329 -0.7604766 -0.4990189 0.4155185 -0.7260785 -0.4751509 0.497033 -0.7235496 -0.473353 0.5024073 -0.7280694 -0.4769257 0.492399 -0.6669731 -0.5502361 0.5023815 -0.6789903 -0.5491008 0.4872995 -0.6827456 -0.5486746 0.4825089 -0.6651138 -0.5503906 0.5046722 -0.7330466 -0.479308 0.482604 -0.7689124 -0.4750385 0.4279162 -0.7693218 -0.490409 0.4094423 -0.8021596 -0.5018838 0.3235006 -0.7365573 -0.4717092 0.484741 -0.7341746 -0.4725623 0.4875168 -0.7366433 -0.4717667 0.4845542 -0.7344194 -0.4717082 0.4879751 0.7611185 0.4023652 -0.5087246 -0.8041436 -0.512535 0.3010998 -0.8376837 -0.5207751 0.1645581 -0.7747631 -0.4896212 0.4000166 -0.8380494 -0.5360342 0.101689 -0.8495815 -0.5274559 -0.001220703 -0.8379633 -0.5359767 -0.1026968 -0.8374076 -0.52053 -0.1667246 -0.6946158 -0.4564443 -0.5560284 -0.6468797 -0.4254648 -0.6328715 -0.69499 -0.4560528 -0.5558821 -0.6716924 -0.4568998 -0.5831569 -0.6928892 -0.4554763 -0.5589687 -0.6934207 -0.455434 -0.5583439 -0.7097252 -0.4381649 -0.5516355 -0.7194552 -0.4596773 -0.5206544 -0.7122647 -0.4492474 -0.5393105 -0.6892456 -0.4565061 -0.5626214 -0.7051187 -0.4389595 -0.5568863 -0.7017252 -0.450309 -0.5520902 -0.6949885 -0.4497343 -0.5610082 -0.643499 -0.3597002 -0.6756663 -0.713783 -0.4678899 -0.5211459 -0.6926967 -0.4559279 -0.558839 -0.7108177 -0.4661164 -0.5267577 -0.7047598 -0.4627084 -0.5377868 -0.7025198 -0.4613882 -0.5418366 -0.7007582 -0.4603561 -0.5449866 -0.6986554 -0.4590152 -0.548804 -0.696214 -0.4575199 -0.553138 -0.63928 -0.523247 -0.5635015 -0.6643137 -0.457759 -0.5908843 -0.6370533 -0.53277 -0.5570631 -0.7262942 -0.4754575 -0.4964241 -0.7184044 -0.4707061 -0.5121824 -0.7866577 -0.4858319 -0.3809686 -0.7275612 -0.4660677 -0.5034239 -0.7267867 -0.4603837 -0.5097334 -0.7373213 -0.4630423 -0.4918833 -0.7208908 -0.4526892 -0.5247753 -0.7421062 -0.4655407 -0.4822347 -0.8455225 -0.5300499 0.06433355 -0.7147064 -0.4579456 -0.5286594 -0.7222005 -0.4572654 -0.5189749 -0.656163 -0.4190592 -0.6275665 -0.7144996 -0.448031 -0.5373625 -0.7246239 -0.4577006 -0.5151993 -0.7097762 -0.4436826 -0.5471414 -0.7120442 -0.4459165 -0.5423573 -0.7233355 -0.4583678 -0.5164153 -0.7122915 -0.4462237 -0.5417798 -0.7216579 -0.4589788 -0.5182166 -0.7101863 -0.4441792 -0.5462055 -0.7189118 -0.4585825 -0.5223677 -0.6775885 -0.4590096 -0.5746166 -0.6969765 -0.4383533 -0.5675123 -0.6859679 -0.4488685 -0.5726826 -0.665798 -0.4590331 -0.5882192 -0.686994 -0.4336211 -0.5831056 -0.6754194 -0.4471971 -0.5863645 -0.6561405 -0.4569087 -0.6005948 -0.6755946 -0.4280261 -0.6003047 -0.6636385 -0.4447247 -0.6015015 -0.6478577 -0.4544892 -0.6113265 -0.6408466 -0.4549223 -0.6183537 -0.6630939 -0.4224183 -0.6179558 -0.6538158 -0.440333 -0.6153308 -0.6302635 -0.4460157 -0.6354824 -0.6257989 -0.4525712 -0.6352599 -0.6416703 -0.4352676 -0.6315073 -0.6287575 -0.4306876 -0.6474353 -0.6495152 -0.4156751 -0.6366665 -0.6300675 -0.4312048 -0.6458154 -0.6614171 -0.3815234 -0.6457301 -0.6361206 -0.4074675 -0.6552258 -0.6179215 -0.4265664 -0.6604653 -0.6648243 -0.3763594 -0.6452616 -0.6221314 -0.3987317 -0.6737697 -0.6041061 -0.4201641 -0.6771396 -0.6142873 -0.5085694 -0.603331 -0.5831362 -0.4869997 -0.650218 -0.6092879 -0.4543413 -0.6498787 -0.607638 -0.3891202 -0.6923594 -0.5899736 -0.4127465 -0.6939537 -0.5465373 -0.4648069 -0.6966 -0.5612806 -0.4371281 -0.7027682 -0.5499871 -0.4672494 -0.6922371 -0.5771849 -0.4958809 -0.6488142 -0.6175894 -0.5079944 -0.6004375 -0.4323679 -0.2666172 -0.8613787 -0.4093286 -0.2971691 -0.8626359 -0.4616276 -0.2433875 -0.8530314 -0.4517837 -0.2811173 -0.8466786 -0.4290677 -0.3120271 -0.8476675 -0.4791884 -0.256151 -0.8395029 -0.4708581 -0.2952782 -0.8313264 -0.4483847 -0.3261258 -0.8322218 -0.495655 -0.2680767 -0.826112 -0.4895556 -0.3089441 -0.8154072 -0.4672731 -0.3394604 -0.816347 -0.5249005 -0.2901464 -0.8001841 -0.5079274 -0.3220668 -0.7989259 -0.4856792 -0.3520365 -0.8001164 -0.5107995 -0.2793115 -0.8130614 -0.5382641 -0.3003988 -0.7874214 -0.5257803 -0.3348843 -0.7819257 -0.5035685 -0.3637595 -0.783644 -0.5630143 -0.3182825 -0.7627 -0.5429046 -0.3469414 -0.7647787 -0.5209978 -0.3747485 -0.7668931 -0.5514547 -0.3097106 -0.7745819 -0.5740337 -0.3274089 -0.7505257 -0.5598744 -0.3585394 -0.7469875 -0.5376653 -0.3847311 -0.7502654 -0.5944196 -0.3423628 -0.7276353 -0.5762042 -0.369375 -0.7290753 -0.5522128 -0.3925368 -0.7355107 -0.5850877 -0.3353473 -0.7383866 -0.603423 -0.3501452 -0.7164351 -0.5926562 -0.3794782 -0.7104611 -0.5638735 -0.3980929 -0.7235805 -0.6198999 -0.3627477 -0.6958004 -0.6121535 -0.3567996 -0.7056643 -0.5725705 -0.4027922 -0.714088 -0.5793167 -0.4067913 -0.7063378 -0.6286104 -0.3702322 -0.6839423 -0.6401642 -0.3795939 -0.6679059 -0.6526855 -0.3893346 -0.6499388 -0.6742644 -0.4054193 -0.6172542 -0.6642959 -0.3978878 -0.6327689 -0.6833918 -0.413142 -0.6019048 -0.6920531 -0.4201882 -0.5869451 -0.7000895 -0.4261149 -0.5729753 -0.7100681 -0.4325537 -0.5556085 -0.7067242 -0.4308341 -0.5611799 -0.7128028 -0.4349269 -0.5502279 -0.7381969 -0.4309607 -0.518978 -0.7129313 -0.4307802 -0.5533152 -0.7068769 -0.4286673 -0.562645 -0.7158365 -0.4320045 -0.5485893 -0.6989569 -0.4265401 -0.5740407 -0.7007158 -0.4142341 -0.5808678 -0.7259319 -0.4140552 -0.5491641 -0.6923953 -0.3977298 -0.6019966 -0.6814584 -0.3929319 -0.6174296 -0.668983 -0.3891821 -0.6332449 -0.6658427 -0.3758469 -0.6445096 -0.6927207 -0.3753839 -0.6158127 -0.6520712 -0.3573787 -0.6686431 -0.6378256 -0.3524689 -0.684795 -0.6264936 -0.3499611 -0.6964432 -0.6160026 -0.3485004 -0.7064619 -0.6190177 -0.3340614 -0.7107885 -0.6573852 -0.3367192 -0.6741402 -0.6079391 -0.3174589 -0.7277568 -0.595938 -0.313915 -0.7391316 -0.5822438 -0.3113256 -0.7510451 -0.5816419 -0.297169 -0.7572209 -0.6126981 -0.3018323 -0.7304097 -0.5673137 -0.2810781 -0.774048 -0.5512951 -0.2767156 -0.7870848 -0.5464105 -0.2638664 -0.7948649 -0.5670415 -0.2690548 -0.7785072 -0.5300347 -0.2482773 -0.8108154 -0.5170807 -0.2380164 -0.8221775 -0.5353928 -0.2448835 -0.8083233 -0.5022201 -0.2244974 -0.8350905 -0.5080794 -0.2271525 -0.8308172 -0.4812954 -0.2135157 -0.8501563 -0.384662 -0.3274693 -0.8630174 -0.3850028 -0.327199 -0.8629679 -0.4041618 -0.3423305 -0.8482118 -0.3700467 -0.3178586 -0.8729441 -0.414144 -0.347887 -0.8411061 -0.4234493 -0.356491 -0.8328295 -0.3974784 -0.3369899 -0.8534922 -0.4318721 -0.3594509 -0.8272132 -0.4424672 -0.3693737 -0.8171817 -0.4510388 -0.3715981 -0.8114671 -0.4616593 -0.3806316 -0.801243 -0.4708822 -0.3845126 -0.79399 -0.4833673 -0.389642 -0.783923 -0.4886428 -0.3986722 -0.7760726 -0.5106173 -0.3959261 -0.7632251 -0.5181244 -0.3940333 -0.7591344 -0.47168 -0.4911515 -0.7323172 -0.4954796 -0.4470762 -0.7447301 -0.5143447 -0.4211382 -0.7470557 -0.344139 -0.4967066 -0.7967754 -0.4190626 -0.449582 -0.7888363 -0.461153 -0.4577654 -0.7601243 -0.4536982 -0.4678591 -0.7584628 -0.4532405 -0.4879408 -0.7459806 -0.5022211 -0.4498809 -0.7384993 -0.5183054 -0.4675521 -0.716069 -0.584782 -0.3976982 -0.7070122 -0.2611824 -0.3275005 -0.9080349 -0.3153263 -0.3234139 -0.8921731 -0.3279543 -0.3393073 -0.8816556 -0.2755889 -0.3617448 -0.890613 -0.3420923 -0.3572605 -0.8691018 -0.2909991 -0.3951912 -0.8712884 -0.352163 -0.3714817 -0.8590592 -0.3673649 -0.390865 -0.8439595 -0.3082088 -0.4296734 -0.8487569 -0.3841535 -0.4106752 -0.8269051 -0.3250608 -0.4629468 -0.8246307 -0.4017859 -0.4305961 -0.8081802 -0.273149 -0.2873405 -0.9180551 -0.1966062 -0.1949582 -0.9609045 -0.1941637 -0.2549581 -0.9472576 -0.1217387 -0.1060522 -0.9868803 -0.1666325 -0.1789621 -0.9696424 -0.1725578 -0.2068008 -0.9630459 -0.09918671 -0.09466993 -0.9905552 -0.1394432 -0.1714276 -0.9752786 -0.3484975 -0.5223953 -0.7782369 -0.3764257 -0.5476698 -0.7472359 -0.2857213 -0.5686347 -0.7713741 -0.337729 -0.5680903 -0.7504749 -0.2943273 -0.6022052 -0.7421053 -0.1659047 -0.2124471 -0.962986 -0.1232373 -0.1452723 -0.9816866 -0.1548528 -0.2092374 -0.9655259 -0.08157813 -0.07672554 -0.9937093 -0.1026359 -0.1215577 -0.9872637 -0.06705069 -0.06216758 -0.995811 -0.08853441 -0.1056859 -0.9904506 -0.05310231 -0.04596096 -0.9975309 -0.06802725 -0.07574862 -0.9948037 -0.2264258 -0.6360005 -0.7377227 -0.2084175 -0.6494238 -0.7313076 -0.04208594 -0.02841335 -0.99871 -0.05325639 -0.05148625 -0.9972528 -0.03244125 -0.01010161 -0.9994227 -0.03994989 -0.02575838 -0.9988697 -0.06253325 -0.02749752 -0.997664 -0.01743537 0.0285719 -0.9994398 -0.05401808 -0.02462857 -0.9982362 -0.01748436 0.02855932 -0.9994392 -0.04471087 -0.0179454 -0.9988388 -0.01745754 0.02858161 -0.9994391 -0.03839254 -0.009827017 -0.9992144 -0.0335403 -0.002227842 -0.999435 -0.02896219 0.002349913 -0.9995778 -0.02584916 0.007873773 -0.9996349 -0.02368235 0.01306188 -0.9996343 0.1926053 0.1348329 -0.9719688 0.1148756 0.09235215 -0.9890777 0.08926838 0.08264571 -0.9925729 0.2494644 0.1496664 -0.9567484 0.1220149 0.09122127 -0.9883275 0.116187 0.0917716 -0.9889786 0.244458 0.1551285 -0.9571706 0.191294 0.139442 -0.9715774 0.1004076 0.08905452 -0.9909529 0.1203674 -0.002746701 -0.9927257 0.2565422 -0.03253316 -0.9659854 0.1204879 -0.002014219 -0.9927128 0.1257393 -0.002960324 -0.9920589 0.2582837 -0.03119057 -0.9655655 0.1295841 -0.002288877 -0.9915658 0.2607241 -0.02887099 -0.9649816 0.1317798 -0.001190185 -0.9912784 0.2638397 -0.02667391 -0.9641978 0.1324216 2.13632e-4 -0.9911935 0.2675934 -0.02450698 -0.9632203 0.1320575 0.001922667 -0.9912402 0.1294601 0.002349913 -0.9915819 0.2753098 -0.01620543 -0.961219 0.1297372 0.004272639 -0.9915393 0.1352888 0.006439387 -0.9907853 0.2716206 -0.02353024 -0.9621168 0.2780301 -0.004455804 -0.9605621 0.1346198 0.01574784 -0.9907723 0.1341292 0.02032536 -0.9907555 0.2815381 0.02542233 -0.9592133 0.1391983 0.03662312 -0.9895871 0.2795228 0.06988829 -0.9575921 0.1285174 0.04934996 -0.9904786 0.1346807 0.06402903 -0.9888182 0.2673767 0.1124013 -0.9570139 0.1251908 0.07822138 -0.9890443 0.124001 0.08228075 -0.9888648 0.2552341 0.1393517 -0.9567846 0.6819731 0.3614342 -0.6358287 0.7716958 0.4067227 -0.4889401 0.7580175 0.3962066 -0.5181022 0.8288423 0.4340755 -0.3529859 0.8367233 0.428311 -0.3412388 0.01812809 -0.02963364 0.9993965 0.7030475 0.3137406 -0.6381936 0.692824 0.3388279 -0.636546 0.7706136 0.369925 -0.5189511 0.8292168 0.4316078 -0.3551257 0.05237007 -0.01309251 0.998542 0.8508144 0.3994354 -0.3414183 0.8685263 0.3661434 -0.3340674 0.8797163 0.3723955 -0.2956702 0.7762968 0.3572626 -0.5193523 0.8309462 0.4285506 -0.3547856 0.8437933 0.4276037 -0.3242964 0.851229 0.4327864 -0.2968254 0.8650285 0.40639 -0.294233 0.8369805 0.4268372 -0.3424524 0.7130591 0.3833563 -0.5870133 0.7585856 0.4122536 -0.5045742 0.5676695 0.3183527 -0.7592121 0.7081143 0.3991345 -0.5824653 0.7649427 0.424863 -0.4841015 0.7263908 0.4047169 -0.5554825 0.4842763 0.2692086 -0.8324682 0.3904656 0.2329853 -0.8906484 0.564814 0.3298182 -0.7564424 0.3888487 0.2407987 -0.8892765 0.4923006 0.2546498 -0.8323423 0.5010419 0.2361614 -0.8325773 0.6739172 0.3947002 -0.6245377 0.7481588 0.4304492 -0.5049477 0.6573025 0.4454042 -0.6079216 0.7389237 0.4466136 -0.504508 0.6564015 0.4169498 -0.6287208 0.7221803 0.4208013 -0.5489827 0.8315815 0.4724645 -0.2919752 0.8135193 0.4623656 -0.3527102 0.8506146 0.4790067 -0.216812 0.731867 0.4424589 -0.5182672 0.478782 0.2961258 -0.8264849 0.4616676 0.3844229 -0.7994262 0.453274 0.3307996 -0.8277164 0.8205713 0.4453675 -0.3582046 0.8203105 0.4550803 -0.3463994 0.8220686 0.4426218 -0.3581748 0.828742 0.4716092 -0.301283 0.8298432 0.4718243 -0.2978963 0.8315758 0.4720035 -0.2927362 0.8136433 0.4824483 -0.3243891 0.8113289 0.4635904 -0.3561314 0.8160275 0.4518701 -0.360434 0.8239641 0.4394801 -0.3576879 0.7585833 -0.0940904 -0.644747 0.8444745 -0.09635001 -0.5268582 0.8426308 -0.1094718 -0.527247 0.9304199 -0.1144484 -0.3481673 0.9196919 -0.1248229 -0.3722715 0.9309697 -0.1043159 -0.3498766 0.838521 -0.1343464 -0.528047 0.7539535 -0.1166149 -0.6464944 0.8384261 -0.134468 -0.5281669 0.9242511 -0.1536349 -0.3495088 0.9158508 -0.1507343 -0.3721511 0.9161151 -0.1485963 -0.3723606 0.7616309 -0.0661956 -0.6446213 0.84674 -0.06210541 -0.5283694 0.9347673 -0.07794559 -0.3466046 0.765713 0.01263469 -0.6430585 0.8502236 -0.02050864 -0.5260222 0.950708 -0.08713269 -0.2975941 0.94362 -0.02139383 -0.3303387 0.8479477 0.03842377 -0.5286855 0.9409081 0.02475106 -0.3377564 0.7582696 0.1287892 -0.6390938 0.8411446 0.1353839 -0.5235905 0.9542225 0.008789598 -0.2989689 0.9274299 0.142496 -0.3457872 0.8173432 0.2315821 -0.5275604 0.9433964 0.1458797 -0.2978633 0.9031712 0.2752179 -0.3294497 0.01852518 -0.02652126 0.9994767 0.7298737 0.2414091 -0.6395359 0.804636 0.2866659 -0.5199843 0.9130595 0.2796736 -0.2968252 0.7873632 0.3257918 -0.5233727 0.522092 0.1838477 -0.8328385 0.5423533 0.1037646 -0.8337182 0.5482757 0.02075296 -0.8360402 0.5437571 -0.03650069 -0.8384486 0.5404058 -0.05710166 -0.8394647 0.747631 -0.1202154 -0.6531433 0.5363398 -0.0734896 -0.8407967 0.8240712 -0.1322383 -0.5508356 0.5313017 -0.07547295 -0.8438142 0.01818907 -0.02969461 0.9993936 0.9194598 -0.1574499 -0.3602822 0.8114448 -0.1381299 -0.567871 0.7410019 -0.1264708 -0.6594856 0.8326599 -0.1392903 -0.5359811 0.8030894 -0.1448759 -0.5779778 0.7343549 -0.1326063 -0.6656866 0.5257582 -0.08011347 -0.8468531 0.8261752 -0.1460631 -0.5441508 0.7992725 -0.152597 -0.5812725 0.7276455 -0.13865 -0.6717948 0.5202 -0.08466029 -0.8498381 0.8196323 -0.1527197 -0.5521592 0.8070594 -0.1633712 -0.5674197 0.7218451 -0.1419152 -0.6773478 0.5145848 -0.08908563 -0.8527991 0.7985029 -0.1613852 -0.5799553 0.8130127 -0.159282 -0.5600354 0.7201961 -0.1475611 -0.6778963 0.7204122 -0.1478974 -0.6775934 0.8052783 -0.1693202 -0.5682055 0.5095135 -0.09079378 -0.8556592 0.5086035 -0.09485381 -0.8557601 0.897926 -0.1778029 -0.4026353 0.8821045 -0.1830863 -0.4340175 0.01742643 -0.02954256 0.9994117 0.8873242 -0.1837884 -0.4229394 0.8806083 -0.1900141 -0.4340782 0.8806964 -0.1884874 -0.4345648 0.8857261 -0.1901341 -0.4234834 0.8045249 -0.1684677 -0.5695247 0.9080628 -0.1739584 -0.3809994 0.01767051 -0.0295729 0.9994065 0.9030077 -0.1721904 -0.3936086 0.9009448 -0.1659306 -0.4009557 0.8928588 -0.1825026 -0.4116989 0.897324 -0.1759734 -0.4047755 0.9090614 -0.1659969 -0.3821684 0.01782298 -0.02963382 0.9994019 0.9210604 -0.1675182 -0.3515472 0.9251108 -0.1774047 -0.3357048 0.01812803 -0.02969461 0.9993947 0.9361102 -0.1598587 -0.3132779 0.508449 -0.09488403 -0.8558485 0.9714447 -0.1870499 0.1459715 0.9672726 -0.1887912 0.1695336 0.9778575 -0.1901025 0.08749777 -0.1870489 -0.7975094 -0.5735778 0.9806527 -0.1891845 0.05029457 0.9808248 -0.1900123 0.04333716 -0.2101542 -0.9090101 -0.3599112 -0.2087808 -0.893842 -0.3968087 -0.1957513 -0.8525592 -0.4845868 -0.2016408 -0.8597279 -0.4692643 0.95252 -0.1837532 0.2427765 0.9480502 -0.1855875 0.258376 -0.1870524 -0.7975086 -0.573578 0.9285751 -0.1823518 0.3232586 -0.1870551 -0.7975091 -0.5735762 0.9250068 -0.1775302 0.3359249 0.9165928 -0.1763113 0.3588485 -0.165444 -0.7341063 -0.6585715 -0.1739881 -0.7417614 -0.6477022 -0.1633055 -0.69076 -0.7044019 -0.1870636 -0.7975091 -0.5735735 0.907956 -0.1739003 0.3812804 0.9118555 -0.1750281 0.3713282 -0.1445702 -0.6541217 -0.7424448 -0.1201542 -0.5734563 -0.810377 0.903196 -0.1723135 0.3931225 -0.107276 -0.5111407 -0.8527761 0.9051309 -0.1768267 0.386614 0.897114 -0.1780799 0.4043194 0.9009392 -0.1659352 0.4009668 -0.09888076 -0.4762147 -0.8737519 -0.09372478 -0.3863134 -0.9175935 0.727707 -0.1395046 0.6715512 0.8123924 -0.1611722 0.5603948 0.759099 -0.1398685 0.6357717 0.8973302 -0.1760051 0.4047477 0.8940204 -0.1813432 0.4096856 0.8866196 -0.1843068 0.4241894 0.8918249 -0.1843039 0.4131351 0.887375 -0.1836948 0.4228734 0.8818613 -0.1830255 0.4345368 0.7218815 -0.1417027 0.6773533 0.8066822 -0.1630333 0.568053 0.8189234 -0.1531151 0.5531006 0.9081375 -0.167674 0.3836298 0.7347754 -0.1329102 0.6651617 0.8258458 -0.147224 0.544338 0.9431395 -0.1713356 0.2848371 0.9210699 -0.1681609 0.3512151 0.9569201 -0.1819537 0.2262671 0.9522793 -0.1731638 0.2513531 0.9491842 -0.1749067 0.2616429 0.9547276 -0.178689 0.2378349 0.9708929 -0.1903149 0.1454218 0.9074588 -0.2248046 0.3549386 0.9579618 -0.1925445 0.2126871 0.9662902 -0.1862264 0.1777727 0.9820275 -0.1845211 -0.03967541 0.9805502 -0.1898597 -0.04974621 0.9822459 -0.1875987 0 0.9849753 -0.1699612 -0.03061068 0.9833883 -0.1814974 -0.002533078 0.9819881 -0.187724 0.02142453 0.9685748 -0.2105796 0.13236 0.9801414 -0.1873853 0.06488293 0.9778575 -0.1901025 -0.08749777 0.9710201 -0.1886984 -0.1466738 0.9796696 -0.1891891 -0.06674569 0.9481376 -0.1853121 -0.2582528 0.9523901 -0.1843375 -0.2428433 0.9649847 -0.1887303 -0.1821687 0.9672501 -0.1879687 -0.1705726 0.9753079 -0.1893422 -0.1136847 0.9714316 -0.184398 -0.1493923 0.9285751 -0.1823518 -0.3232586 0.9431445 -0.171306 -0.2848386 0.9618797 -0.1872059 -0.1993526 0.959424 -0.1829611 -0.2145481 0.9571315 -0.1806104 -0.2264497 0.9546954 -0.1786582 -0.2379871 0.9491767 -0.1749053 -0.2616713 0.9522867 -0.1731652 -0.2513245 0.9123166 -0.1780807 -0.3687354 0.917986 -0.1801241 -0.3533509 -0.09726566 -0.475555 0.8742923 -0.1163372 -0.5005066 0.8578805 -0.1325739 -0.57525 0.8071628 -0.09375321 -0.3864269 0.9175427 -0.1471329 -0.6562843 0.740029 -0.158974 -0.6954695 0.7007493 -0.166086 -0.7402762 0.6514651 -0.1870628 -0.7975059 0.5735782 -0.1710283 -0.7291594 0.6626281 -0.1870648 -0.7975039 0.5735803 -0.1870675 -0.7975042 0.573579 -0.1979489 -0.8593656 0.4714944 -0.1993832 -0.8501483 0.4873337 -0.2109487 -0.8938463 0.3956509 -0.1870494 -0.7975121 0.573574 -0.2086605 -0.909811 0.3587544 -0.2267855 -0.9527982 0.2018516 -0.2208061 -0.9676708 0.1218935 -0.232095 -0.9726932 1.83112e-4 -0.2208061 -0.9676708 -0.1218935 -0.2267862 -0.9528625 -0.2015471 -0.05411005 -0.2656978 -0.9625367 -0.04657268 -0.2183364 -0.9747617 -0.02380514 -0.1485685 -0.9886155 -0.01195234 -0.05095368 -0.9986296 -0.03766059 -0.1606833 -0.9862874 -0.01194959 -0.05095332 -0.9986296 0.890513 -0.1920558 0.4124333 0.8911596 -0.1902869 0.4118561 0.8854964 -0.1913886 0.4233988 -0.007416009 -0.03103756 -0.9994907 -0.008575737 -0.03866726 -0.9992154 -0.009582817 -0.04092532 -0.9991163 -0.01195025 -0.0509532 -0.9986295 0.8850439 -0.1917865 0.4241643 0.8806059 -0.1896778 0.4342296 0.8901137 -0.1931845 0.4127678 0.8802531 -0.1907728 0.4344654 0.7203446 -0.147835 0.6776788 0.8036328 -0.1709688 0.5700385 0.8054017 -0.1688322 0.568176 0.9121718 -0.1609302 0.3768873 0.7410616 -0.1270809 0.6593013 0.8008587 -0.1340715 0.5836524 0.9360716 -0.1594911 0.3135803 0.9193451 -0.1565303 0.3609751 0.9499592 -0.1651983 0.2651169 0.984302 -0.1744471 0.02679574 0.9780938 -0.1767337 0.1099894 0.9781532 -0.1769165 0.1091652 0.9840431 -0.173651 0.03878915 0.9773409 -0.1705707 0.1253415 0.9870132 -0.1602244 0.01153612 0.9787864 -0.1733194 0.1092593 0.978597 -0.1698697 0.1161559 0.9843562 -0.176155 0.00350964 0.9904168 -0.1378563 0.00839281 0.9821779 -0.1555272 0.1055364 0.9953722 -0.09607332 0.002014219 0.9860034 -0.135107 0.09769088 0.9988617 -0.04770141 -3.05192e-5 0.9897131 -0.1114568 0.08969646 0.9999898 -0.001648008 0.004211604 0.9926844 -0.08807718 0.08258378 0.9991381 0.03906458 0.0140388 0.9945929 -0.06799691 0.07849556 0.9974176 0.06619542 0.02786368 0.995543 -0.0543245 0.07709199 0.9973035 0.06625694 0.03155672 0.9963464 -0.05938953 0.06137323 0.9975068 -0.05755841 0.04083412 0.9977951 0.06286954 0.02127188 0.9982853 -0.05853593 -9.15578e-5 0.9977925 0.06286936 -0.02139389 0.9975154 -0.05725371 -0.0410481 0.9980753 0.06201535 3.05194e-5 0.9963982 -0.05914664 -0.06076413 0.9977504 0.06204462 -0.02539157 0.9955397 -0.05438536 -0.07709175 0.9945736 -0.06820923 -0.0785551 0.9973275 0.06601238 -0.03131234 0.9991332 0.03903388 -0.01446598 0.9926841 -0.08813822 -0.08252274 0.9999986 -0.00125128 -0.001220762 0.9896943 -0.1116988 -0.08960318 0.9988442 -0.04797524 0.002929747 0.9859488 -0.1355046 -0.09769147 0.9953914 -0.09589207 9.76622e-4 0.9821238 -0.1558287 -0.1055948 0.9905609 -0.1370311 -0.003418147 0.9772233 -0.1728299 -0.1231448 0.9790358 -0.1702684 -0.111793 0.9844115 -0.1758488 -0.003357052 0.9781486 -0.1769213 -0.1091986 0.978086 -0.1767379 -0.110053 0.9864435 -0.1640105 -0.005462944 0.9498007 -0.1650195 -0.2657952 0.9842725 -0.1746915 -0.02627694 0.9773133 -0.1705713 -0.1255556 0.9500965 -0.1618133 -0.2667082 0.8325645 -0.1382216 0.5364059 0.9297146 -0.1495759 0.3365382 0.7481809 -0.1199409 0.6525639 0.8383966 -0.1345292 0.5281981 0.9501273 -0.1617829 0.2666167 0.9446538 -0.1551279 0.2890757 0.9172307 -0.1550692 0.366935 0.9237944 -0.1551916 0.350028 0.9837 -0.171122 0.05524003 0.9775839 -0.1673355 0.127783 0.9502172 -0.159219 0.2678371 0.9834421 -0.1688917 0.06570726 0.9759145 -0.1663604 0.141121 0.7539752 -0.1171935 0.6463647 0.8385287 -0.1337983 0.5281739 0.9306387 -0.1050455 0.3505384 0.919731 -0.1252514 0.3720308 0.9305461 -0.1146588 0.3477607 0.758463 -0.09421271 0.6448705 0.8425909 -0.1098063 0.5272412 0.8439284 -0.09711337 0.5275926 0.9507008 -0.08700996 0.2976529 0.9491431 -0.1272645 0.2879779 0.9346328 -0.07871007 0.3467944 0.9601017 -0.1514055 0.2351195 0.9667221 -0.1534193 0.2047219 0.9747975 -0.09250211 0.2030103 0.9707788 -0.1306823 0.2012727 0.9569169 -0.1523193 0.2472022 0.9539908 -0.1555549 0.2563284 0.9791544 -0.1520172 0.1347126 0.9831358 -0.1528081 0.1004682 0.990303 -0.09402823 0.1022683 0.9860157 -0.1325451 0.1010187 0.9759209 -0.1507661 0.157633 0.9713339 -0.1562582 0.1791476 0.9675211 -0.1577234 0.197551 0.9882357 -0.1527476 0.00766021 0.9863303 -0.1633049 0.02200388 0.9955782 -0.09393626 3.96742e-4 0.9907602 -0.1333363 0.02481168 0.9893401 -0.1401745 0.03946125 0.9834741 -0.1584851 0.0875284 0.9876116 -0.147867 -0.05252408 0.985612 -0.1690143 -0.001831114 0.9910727 -0.1333068 -0.002075254 0.9865624 -0.16166 -0.02368283 0.9907872 -0.1323288 -0.02880954 0.9843456 -0.1545507 -0.0847221 0.9824056 -0.1539376 -0.1057482 0.9903476 -0.09375494 -0.1020867 0.9855723 -0.1326649 -0.1051065 0.9684382 -0.1540308 -0.1959643 0.9664137 -0.1551889 -0.2048433 0.9748245 -0.09247416 -0.2028939 0.9702494 -0.1304062 -0.2039867 0.9668515 -0.1136538 -0.2286506 0.9751124 -0.142951 -0.169472 0.9791042 -0.1560426 -0.1304068 0.9501486 -0.1589125 -0.2682622 0.9442703 -0.154947 -0.2904226 0.9488293 -0.1270497 -0.2891045 0.9257582 -0.144293 -0.3495016 0.9587887 -0.1556169 -0.2377134 0.9624688 -0.1568967 -0.2214438 0.9646091 -0.1574772 -0.2114956 0.9836969 -0.171091 -0.05539244 0.9779145 -0.1670905 -0.1255544 0.9758387 -0.1667547 -0.1411799 0.9812951 -0.1790526 -0.07071155 0.9754853 -0.168527 -0.1415175 0.9741452 -0.1701755 -0.1485984 0.9833641 -0.1693214 -0.06576919 0.9784982 -0.1942836 -0.06924748 0.9737834 -0.1791795 -0.1401452 0.9727825 -0.1820133 -0.1434072 0.9728776 -0.2218105 -0.06564587 0.9719625 -0.1935501 -0.1335197 0.9666002 -0.2499512 -0.05664336 0.9705292 -0.2076501 -0.1222889 0.9586668 -0.2795552 -0.05298119 0.9685963 -0.2223038 -0.1113655 0.9505661 -0.3059903 -0.05286008 0.9664596 -0.2363121 -0.1005616 0.9443079 -0.3243522 -0.05548286 0.9643448 -0.2471137 -0.0947315 0.9447283 -0.3236888 -0.0520966 0.9669341 -0.2419242 -0.08069229 0.9616912 -0.2662192 -0.06540268 0.9474605 -0.3177021 -0.03720253 0.9588726 -0.2819944 -0.03228896 0.9512336 -0.3081766 -0.01348918 0.9577389 -0.2876391 -3.05187e-5 0.9511626 -0.3083969 0.01345896 0.958801 -0.2822445 0.03222858 0.9473825 -0.3179203 0.03732514 0.9593903 -0.2742423 0.06604272 0.9670156 -0.2430509 0.07620519 0.9452211 -0.3219099 0.05413991 0.9643616 -0.2470492 0.09473013 0.9664557 -0.2362501 0.1007443 0.9454889 -0.3217043 0.05057048 0.9509499 -0.3045213 0.05441582 0.9686329 -0.222054 0.1115458 0.9589941 -0.2780879 0.0547508 0.9705581 -0.2074971 0.1223192 0.9669365 -0.2481507 0.05877977 0.9722827 -0.192546 0.1326367 0.973576 -0.2188798 0.06512683 0.9736945 -0.1800651 0.1396268 0.9784557 -0.1946169 0.06891089 0.9737859 -0.168132 0.1532079 0.9749509 -0.1706301 0.142675 0.9819717 -0.1767951 0.06689709 0.9840311 -0.1736848 -0.03894251 0.8918648 -0.1843059 -0.4130479 0.8909118 -0.1905914 -0.4122512 0.8913307 -0.1894299 -0.4118811 0.8905798 -0.1914772 -0.4125581 0.8852773 -0.1901056 -0.4244338 0.8804773 -0.1900732 -0.4343179 0.01181066 0.05096608 -0.9986306 -0.01195275 -0.05095309 0.9986296 -0.00564599 -0.02578854 0.9996516 -0.008942008 -0.04071229 0.999131 -0.008942127 -0.03821003 0.9992298 -0.007172048 -0.03140449 0.9994811 -0.01194918 -0.0509532 0.9986295 -0.02679556 -0.1551276 0.987531 -0.03201407 -0.1365405 0.9901171 -0.05398815 -0.2215683 0.9736493 -0.01195156 -0.05095332 0.9986295 -0.05139458 -0.2699131 0.9615121 0.9735788 -0.2283517 0 0.9735921 -0.2282952 0 0.9735898 -0.2283045 0 0.973578 -0.2283551 0 0.9735836 -0.2283306 0 0.9735713 -0.2283836 0 0.97358 -0.2283465 2.96893e-6 0.9735864 -0.2283189 0 0.9735763 -0.2283619 0 0.9735792 -0.2283499 3.31267e-7 0.9735792 -0.2283496 0 0.9735767 -0.2283605 0 0.9735784 -0.2283533 0 0.9735777 -0.2283562 0 0.973577 -0.2283592 0 0.97358 -0.2283467 0 0.9735795 -0.2283487 0 0.9735794 -0.228349 0 -0.005646049 -0.02539205 -0.9996617 0.9735796 -0.2283484 0 0.009796619 0.03732478 -0.9992552 -0.003601253 0.02804726 -0.9996002 7.01936e-4 -0.005615472 -0.999984 -0.002716183 -0.01422184 -0.9998952 0.9735771 -0.2283586 0 0.02594101 0.1418822 -0.9895436 -0.01522922 0.07773309 -0.9968579 0.973584 -0.2283295 0 0.973581 -0.2283421 -1.31755e-7 0.0430926 0.1690745 -0.9846608 0.9735811 -0.2283416 0 0.973577 -0.2283591 2.40253e-7 0.9735782 -0.2283543 -1.36042e-7 0.05273652 0.2352696 -0.9704985 0.06329691 0.2523331 -0.965568 0.9735801 -0.2283458 -1.33996e-7 0.9735759 -0.2283638 0 0.07031691 0.3124586 -0.9473252 0.08258521 0.3335456 -0.9391097 0.9735758 -0.2283644 -1.39432e-7 0.9735838 -0.2283304 -8.45532e-7 0.08771246 0.3880835 -0.9174409 0.1011716 0.4122246 -0.9054476 0.9735795 -0.2283486 0 0.9735755 -0.2283651 1.67319e-7 0.1047424 0.4609643 -0.8812157 0.1186912 0.4872782 -0.8651431 0.97358 -0.2283465 -8.00053e-7 0.9735785 -0.228353 -3.75225e-7 0.1208558 0.5303924 -0.8390935 0.1351386 0.5586218 -0.8183394 0.973577 -0.2283592 2.66204e-7 0.9735799 -0.2283467 7.45863e-7 0.1362397 0.5959572 -0.7913746 0.1507642 0.6258851 -0.7652047 0.973585 -0.2283251 -1.99034e-7 0.9735776 -0.2283565 0 0.1509497 0.6576051 -0.7380852 0.1653519 0.6881728 -0.7064538 0.9735738 -0.2283726 5.71773e-7 0.9735815 -0.2283402 -2.95637e-7 0.1647102 0.7151484 -0.6792888 0.1785374 0.74531 -0.6423686 0.9735803 -0.228345 1.33734e-7 0.9735764 -0.2283619 5.54478e-7 0.1771931 0.7679792 -0.615476 0.190351 0.797051 -0.5731284 0.9735813 -0.2283411 -1.64132e-7 0.9735811 -0.2283418 8.39474e-7 0.1884855 0.815499 -0.5472062 0.2007858 0.8426657 -0.4995994 0.9735825 -0.2283356 6.23368e-7 0.9735712 -0.2283837 7.00275e-7 0.1985269 0.8572825 -0.4750303 0.2096953 0.8818433 -0.4223509 0.9735831 -0.2283332 3.98986e-7 0.207164 0.8930209 -0.3994957 0.2170562 0.9143095 -0.3419428 0.9735711 -0.2283846 4.90415e-7 0.9735866 -0.2283179 -1.2582e-6 0.2143394 0.9223342 -0.3214939 0.2226996 0.9398736 -0.258926 0.9735746 -0.2283694 -8.43599e-7 0.9735758 -0.2283642 -2.59599e-6 0.2200127 0.9452092 -0.2411929 0.2267234 0.9582873 -0.1740176 0.973579 -0.2283509 -2.10059e-6 0.9735701 -0.228389 7.12184e-7 0.2241616 0.9614075 -0.1595224 0.2289227 0.969496 -0.08758944 0.9735968 -0.2282749 1.26692e-6 0.9735634 -0.2284174 -3.20571e-6 0.2269103 0.970816 -0.07764083 0.2291346 0.9733947 -3.96743e-4 0.973563 -0.228419 -2.49865e-6 0.227736 0.9701518 0.08331805 0.2281628 0.9698144 0.08603411 0.2284698 0.9735451 0.003418147 0.2247733 0.9604674 0.1642539 0.2262358 0.9586563 0.1726142 0.2203801 0.9442681 0.2445209 0.2224541 0.9402341 0.2578258 0.21461 0.9216758 0.3231969 0.2170537 0.9145737 0.341237 0.2074103 0.8930301 0.3993472 0.2098777 0.8819321 0.4220749 0.1988319 0.858258 0.4731375 0.201062 0.8424891 0.4997863 0.1890332 0.8177198 0.5436918 0.190563 0.7965865 0.5737035 0.1780171 0.7715808 0.6107152 0.1786301 0.7445209 0.6432574 0.1658732 0.720076 0.6737779 0.1652595 0.6871319 0.707488 0.152442 0.6636647 0.7323323 0.1503996 0.6245796 0.7663422 0.1379783 0.6026365 0.7859971 0.1344671 0.5571264 0.8194686 0.1227483 0.5372297 0.8344563 0.1177728 0.4858013 0.8660986 0.1065719 0.4673966 0.8776007 0.1001315 0.4107803 0.9062192 0.08942174 0.3937 0.9148793 0.08148509 0.3322274 0.939673 0.07165801 0.3169068 0.9457459 0.06232017 0.2512951 0.9659022 0.0536828 0.2382919 0.9697089 0.04232949 0.1684024 0.9848091 0.03549385 0.158517 0.9867182 0.02105814 0.08374434 0.9962648 0.005340814 0.01907438 0.9998039 0.003936946 0.01516813 0.9998772 0.01867765 0.07791531 0.996785 -0.003357052 -0.01452696 0.9998889 -0.001159667 -0.005707025 0.9999831 0.8025327 -0.4318466 -0.4116429 0.8902764 -0.1928815 -0.4125589 0.8867395 -0.196514 -0.4184201 0.8798166 -0.2083567 -0.4272122 0.8845648 -0.1944065 -0.4239709 0.8811773 -0.2049661 -0.4260463 0.877411 -0.2188568 -0.4269096 0.8776449 -0.2227607 -0.4244021 0.8740733 -0.2387831 -0.4230588 0.8731077 -0.244768 -0.4216297 0.8716432 -0.2599059 -0.4155565 0.868683 -0.2745555 -0.4123215 0.8687185 -0.2812615 -0.407701 0.872488 -0.2526699 -0.4182376 0.8711749 -0.2581022 -0.4176574 0.8670027 -0.2909135 -0.4045687 0.8658888 -0.303879 -0.3973591 0.8627663 -0.3204892 -0.3910511 0.8626617 -0.3275038 -0.3854296 0.8666282 -0.2960074 -0.4016655 0.8654203 -0.3017694 -0.3999788 0.8599891 -0.3405592 -0.3800505 0.8586012 -0.3535668 -0.3712069 0.8543236 -0.368275 -0.3667491 0.8513702 -0.3857962 -0.3554294 0.85813 -0.3518828 -0.3738869 0.844506 -0.4142111 -0.3394688 0.8465771 -0.4162844 -0.3316847 0.8388152 -0.450064 -0.3063194 0.8327641 -0.470568 -0.2916674 0.8306066 -0.4858328 -0.2721384 0.8227975 -0.5146452 -0.2411321 0.8260583 -0.5063716 -0.2474176 0.8197249 -0.5299111 -0.2173603 0.8132524 -0.5488317 -0.1934019 0.8136436 -0.5507811 -0.1860759 0.8088733 -0.5678044 -0.1527166 0.8048624 -0.5764234 -0.1411836 0.80397 -0.5846888 -0.1084961 0.7992863 -0.5964891 -0.0730924 0.798318 -0.599944 -0.05249279 0.7981199 -0.6024887 -0.003479242 0.7980695 -0.6025654 -4.88303e-4 0.8003286 -0.5972861 0.05218738 0.7987117 -0.5970425 0.07483243 0.8039532 -0.5852869 0.1053504 0.8055008 -0.5756281 0.1407864 0.8078104 -0.5696088 0.1516189 0.8120987 -0.5538105 0.1838201 0.8134675 -0.5492295 0.1913574 0.8196615 -0.5301843 0.2169324 0.8223683 -0.5222128 0.2258415 0.8261262 -0.5058264 0.2483048 0.8293216 -0.5070111 0.2348737 0.8325823 -0.4824405 0.2721358 0.8364933 -0.4611715 0.2959725 0.8412813 -0.4467342 0.304425 0.8346856 -0.4994563 0.2320419 0.8318932 -0.4887959 0.26274 0.8433069 -0.4292527 0.3233816 0.8483467 -0.4123471 0.3320811 0.8497435 -0.3974809 0.3463308 0.8543203 -0.3804202 0.3541433 0.8552311 -0.3669287 0.3659827 0.8593817 -0.3500213 0.3727579 0.8600473 -0.3381166 0.382094 0.86348 -0.3231984 0.3872277 0.8637106 -0.3126644 0.3952786 0.8665258 -0.2990251 0.3996462 0.8666408 -0.2891753 0.406585 0.8691411 -0.276753 0.4098801 0.8691318 -0.2691812 0.4149114 0.8716062 -0.2566384 0.4176593 0.8717865 -0.2510831 0.4206489 0.8746188 -0.2383548 0.4221718 0.8748795 -0.2353073 0.4233396 0.8785764 -0.2193084 0.4242729 0.8786672 -0.2179958 0.4247609 0.8773615 -0.196329 0.4378262 0.8758873 -0.1919932 0.4426741 0.8816554 -0.2077104 0.423722 0.8817221 -0.2136629 0.4206117 0.8794734 -0.1928817 0.435113 0.8764203 -0.2075306 0.4345326 0.8046717 -0.1707554 0.5686355 0.7091052 -0.2182707 0.6704683 0.7963932 -0.2240094 0.5617631 0.7996215 -0.1969679 0.5672823 0.707535 -0.1827816 0.682631 0.7203714 -0.1481394 0.6775838 0.7076511 -0.1814372 -0.6828694 0.7990889 -0.1945915 -0.5688507 0.7995676 -0.2202252 -0.5587421 0.8049182 -0.1702981 -0.5684235 0.7097552 -0.2177242 -0.6699581 0.7978936 -0.261763 -0.5429974 0.7044765 -0.2845617 -0.6501827 0.7940663 -0.2770183 -0.5410357 0.7864485 -0.2909087 -0.5448587 0.771612 -0.3084556 -0.5563004 0.6976035 -0.3594223 -0.6198105 0.7825112 -0.340197 -0.5214809 0.7773908 -0.3463345 -0.5250868 0.7549654 -0.37057 -0.5410224 0.7673346 -0.3726652 -0.5218412 0.6868394 -0.4348101 -0.5824019 0.7508345 -0.4265675 -0.5042695 0.7204612 -0.4539391 -0.5242853 0.7374064 -0.4470766 -0.5063145 0.6879004 -0.5065254 -0.5198317 0.7232443 -0.5177584 -0.4569947 0.6772288 -0.5802377 -0.4524218 0.7034007 -0.5921286 -0.3932061 0.6632823 -0.6473205 -0.3755435 0.6903766 -0.6493282 -0.3189875 0.6431621 -0.7044752 -0.3000955 0.6702657 -0.6993812 -0.2482138 0.6248525 -0.749646 -0.2181521 0.6540673 -0.7378743 -0.1665459 0.6052255 -0.7869061 -0.120337 0.6581208 -0.7495265 -0.07132387 0.5911889 -0.8065329 7.01943e-4 0.6791691 -0.7339812 9.76607e-4 0.6585463 -0.7490972 0.07190352 0.6051125 -0.7869179 0.1208271 0.6539056 -0.7381693 0.1658722 0.6251353 -0.7495337 0.2177276 0.6697156 -0.6999297 0.2481524 0.6422887 -0.7053731 0.2998568 0.6885074 -0.6539295 0.3135822 0.6745367 -0.6623595 0.3260067 0.6771584 -0.6589689 0.3274397 0.6434435 -0.6605955 0.3867741 0.7370161 -0.5848457 0.3387668 0.6967349 -0.5948601 0.4008766 0.659221 -0.5913456 0.4644761 0.7439677 -0.5156837 0.42495 0.7221158 -0.5140051 0.4629769 0.6745787 -0.5124881 0.5313189 0.7471704 -0.4424059 0.4959976 0.7499839 -0.4289197 0.5035397 0.6876725 -0.4326184 0.5830506 0.7497128 -0.370019 0.54865 0.7732104 -0.3509737 0.5281697 0.6971243 -0.3571686 0.6216498 0.7531252 -0.3025685 0.5841702 0.7881208 -0.2856571 0.5452206 0.7030621 -0.2878535 0.6502646 0.7519073 -0.2410424 0.6136237 0.4976513 -0.1986516 -0.8443226 0.4911481 -0.1456384 -0.858815 0.4934602 -0.3017709 -0.8157399 0.4876723 -0.4025532 -0.7746784 0.4798521 -0.5011545 -0.7201292 0.4698227 -0.5967548 -0.6505002 0.4589521 -0.6859867 -0.5646107 0.4477814 -0.7627727 -0.4665508 0.4348348 -0.8241354 -0.3629321 0.4216547 -0.8708684 -0.2525778 0.4100832 -0.9026593 -0.1305295 0.4056625 -0.9140226 7.62983e-4 0.4106077 -0.9023054 0.1313248 0.4222308 -0.8706165 0.252484 0.4355753 -0.8238757 0.3626335 0.4478349 -0.7628208 0.4664209 0.4592003 -0.6859926 0.5644019 0.4701796 -0.5966208 0.6503652 0.4802882 -0.5002786 0.7204476 0.4880296 -0.4012641 0.7751221 0.4933518 -0.3014741 0.8159151 0.4971896 -0.1999623 0.8442854 0.4914804 -0.1452711 0.8586869 0.5082901 -0.09527957 0.8558989 0.5081716 -0.09531074 0.8559659 0.2561466 -0.03454756 0.9660204 0.1211602 -0.002868771 0.9926288 -0.01745283 0.02857196 0.9994394 -0.01745283 0.02856838 0.9994395 0.258312 -0.03122079 0.965557 0.1216188 -0.002105772 0.9925746 0.2565435 -0.0323807 0.9659902 -0.01745241 0.02856707 0.9994395 0.1268356 -0.003357052 0.9919182 -0.01745188 0.0285564 0.9994399 -0.01745146 0.02858328 0.9994391 -0.0174539 0.02856111 0.9994397 -0.01745229 0.02855962 0.9994398 -0.01744985 0.02857011 0.9994395 -0.01745343 0.02856755 0.9994395 -0.01745259 0.02857053 0.9994395 -0.01745182 0.02856516 0.9994396 -0.01745408 0.02856552 0.9994396 -0.01745247 0.0285719 0.9994394 -0.01745152 0.02856242 0.9994397 -0.01745086 0.02856928 0.9994395 -0.01745188 0.02856212 0.9994397 -0.01745134 0.02857202 0.9994395 -0.01745355 0.02856165 0.9994397 -0.01745182 0.02857017 0.9994395 -0.0174508 0.02856606 0.9994397 -0.01745659 0.02856743 0.9994395 -0.0174573 0.02856612 0.9994395 -0.01744854 0.0285691 0.9994396 -0.01745319 0.02856773 0.9994395 0.5145624 -0.089087 0.8528125 0.5095551 -0.09067368 0.8556472 0.1926987 0.1341932 0.9720388 0.09924656 0.08981633 0.9910011 0.0900923 0.08176058 0.9925718 0.2437531 0.155554 0.9572813 0.1150556 0.09402823 0.9888989 0.2495217 0.1496642 0.9567339 0.1161265 0.09180247 0.9889828 0.1220447 0.09125119 0.988321 0.2552626 0.1393507 0.9567772 0.1230823 0.08249229 0.9889619 0.1254319 0.07852464 0.9889898 0.2674434 0.112068 0.9570344 0.1428269 0.06262409 0.9877645 0.1297662 0.05307227 0.9901233 0.2789753 0.07031601 0.9577205 0.1393508 0.03689771 0.9895554 0.2815383 0.02539181 0.959214 0.1333359 0.0209968 0.9908486 0.1349231 0.01590019 0.9907285 0.2779655 -0.004608333 0.9605801 0.1396853 0.003875911 0.9901884 0.1316274 0.006195306 0.99128 0.2716487 -0.02356058 0.9621081 0.1294301 0.002441465 0.9915856 0.1315357 0.001922667 0.9913096 0.2747301 -0.01510679 0.9614028 0.2675934 -0.02450698 0.9632203 0.1324216 2.13632e-4 0.9911935 0.2638681 -0.02667367 0.9641899 0.1317798 -0.001190185 0.9912784 0.2607524 -0.02890127 0.964973 0.1295841 -0.002288877 0.9915658 -0.01903629 0.02872794 0.999406 -0.0173425 0.02854955 0.999442 -0.01736378 0.02855932 0.9994414 -0.01738238 0.02854555 0.9994414 -0.0174753 0.02855539 0.9994395 -0.01744377 0.02854222 0.9994404 -0.01743459 0.02857643 0.9994397 -0.01745218 0.02858817 0.999439 -0.01740789 0.02856123 0.9994406 -0.01747435 0.02855336 0.9994396 -0.01745837 0.02857249 0.9994393 -0.01745027 0.02856975 0.9994395 -0.01744621 0.0285741 0.9994394 -0.01746523 0.0285657 0.9994394 -0.01745122 0.02856713 0.9994396 -0.02661281 0.04171985 0.9987749 -0.0215767 0.03506594 0.9991521 -1 7.80549e-6 0 -0.03131252 0.04834216 0.9983399 -0.02392679 0.03839278 0.9989763 -0.03622657 0.05490452 0.9978343 -0.0263071 0.04165798 0.9987856 -0.04132324 0.06149655 0.9972516 -0.0289011 0.04498445 0.9985696 -0.04657208 0.06796592 0.9966001 -0.03161746 0.04834175 0.9983304 -0.05197435 0.07437551 0.995875 -0.03445619 0.05163854 0.9980713 -0.05795633 0.08066278 0.9950551 -0.0375995 0.0542019 0.9978219 -0.03991895 0.05749797 0.9975473 -0.06372332 0.08719229 0.9941514 -0.04290938 0.0607323 0.9972314 -0.06976741 0.09326738 0.9931938 -0.04599183 0.06387591 0.9968975 -0.0759918 0.09915554 0.9921661 -0.0494402 0.06701898 0.9965261 -0.08237206 0.1049565 0.9910596 -0.05288946 0.07004112 0.996141 -0.08893245 0.1105399 0.9898849 -0.05642932 0.07294005 0.9957387 -0.09567749 0.1159422 0.9886371 -0.05994015 0.07565766 0.9953307 -0.1025761 0.1210099 0.9873372 -0.06341862 0.07815933 0.9949218 -0.1096237 0.1258597 0.9859727 -0.0669291 0.08047974 0.9945067 -0.1168284 0.130379 0.984557 -0.07037687 0.08258444 0.9940961 -0.1241531 0.1345908 0.9830928 -0.0738244 0.08450585 0.9936845 -0.1316577 0.1384938 0.9815731 -0.07724404 0.08621668 0.9932774 -0.1393203 0.1420671 0.9800035 -0.08081328 0.08771049 0.9928626 -0.1473168 0.1453025 0.9783583 -0.08508783 0.08926904 0.9923665 -0.1554935 0.1483521 0.9766338 -0.08951115 0.09060978 0.9918557 -0.1638871 0.1510996 0.9748385 -0.09405964 0.09186226 0.9913194 -0.1725228 0.1535096 0.9729701 -0.09869784 0.09299081 0.990763 -0.1813458 0.1555875 0.9710336 -0.1034285 0.09399813 0.9901853 -0.1903468 0.1572643 0.9690387 -0.1081581 0.09485203 0.9895984 -0.1994727 0.1585161 0.9669971 -0.1128305 0.09549546 0.9890146 -0.2086597 0.1593102 0.9649256 -0.1174059 0.0958901 0.9884437 -0.2179079 0.1596465 0.9628235 -0.1219523 0.09595048 0.9878872 -0.227248 0.1594642 0.9606922 -0.1265329 0.0957694 0.9873287 -0.2366771 0.1588224 0.9585194 -0.1311694 0.095371 0.9867619 -0.2462297 0.1577237 0.9562919 -0.135873 0.09482419 0.986178 -0.2558403 0.1561654 0.9540221 -0.1407213 0.09408885 0.9855683 -0.265609 0.1541222 0.9516818 -0.1456368 0.09317457 0.9849409 -0.2756214 0.1507662 0.9493695 -0.1499092 0.09024459 0.9845727 -0.1518936 0.09412091 0.9839054 -0.2892283 0.1590649 0.943952 0.6727439 0.3955647 0.6252554 0.7215083 0.4120419 0.5564596 0.7476182 0.4333969 0.5032239 0.8134261 0.4614796 0.3540828 0.8137713 0.4689927 0.3432525 0.8144899 0.4590356 0.3548134 0.7359094 0.4472588 0.5083277 0.6542465 0.4173236 0.630716 0.7415198 0.4442648 0.5027697 0.8146916 0.471376 0.337761 0.7623718 0.4292232 0.4843106 0.8005763 0.3917733 0.4534218 0.8234184 0.4563899 0.3371803 0.7990252 0.4237602 0.4265984 0.8160275 0.4518701 0.360434 0.7070697 0.401389 0.582185 0.7413953 0.4051077 0.534996 0.8288463 0.4294387 0.3586032 0.8235578 0.4459756 0.3505118 0.5647554 0.3299111 0.7564457 0.7126326 0.3852183 0.586312 0.7693527 0.4101139 0.489799 0.7133279 0.3877784 0.5837734 0.478782 0.2961258 0.8264849 0.3887835 0.2408266 0.8892975 0.5677219 0.3182868 0.7592005 0.3904969 0.2329248 0.8906505 0.4611498 0.384088 0.7998859 0.4495741 0.3356165 0.8277951 0.6561385 0.4452489 0.6092911 0.6820163 0.3605253 0.6362982 0.759291 0.3948899 0.517242 0.7036653 0.3110887 0.6388106 0.7664834 0.3698592 0.5250785 0.6928613 0.3387396 0.6365522 0.8508183 0.4344429 0.2955799 0.8378534 0.4392375 0.3241482 0.8366813 0.4283967 0.3412341 0.8798375 0.3723035 0.2954257 0.8649683 0.4064515 0.2943248 0.8484039 0.4080725 0.3371763 0.8510473 0.4016885 0.3381788 0.7444267 0.3681542 0.5570382 0.4842763 0.2692086 0.8324682 0.5010985 0.2360677 0.8325698 0.4923439 0.2545953 0.8323333 0.8299062 0.4341954 0.3503289 0.7341015 0.4706929 -0.4894315 0.6519544 0.4939252 -0.5753203 0.7305017 0.4770112 -0.4887 0.7258946 0.5028922 -0.4692297 0.6509802 0.542453 -0.5310082 0.7000607 0.5045515 -0.5053145 0.8155249 0.4900718 -0.3078132 0.8549051 0.4594672 -0.2408884 0.7333461 0.510037 -0.4495174 0.8131195 0.4883661 -0.3167574 0.8116108 0.4840732 -0.3270493 0.7528748 0.4339201 -0.4948667 0.8055505 0.4724349 -0.3576223 0.7243509 0.5371745 -0.4321568 0.6531748 0.58942 -0.4753386 0.736238 0.5402151 -0.4075799 0.8182859 0.4959401 -0.2906056 0.7236391 0.5722032 -0.3859144 0.8179687 0.4943763 -0.2941415 0.8255665 0.4978241 -0.2657279 0.6577791 0.6331501 -0.4079799 0.7422862 0.5693649 -0.35332 0.8260625 0.504543 -0.2511118 0.7246546 0.6063305 -0.327474 0.8223132 0.5017991 -0.2683261 0.8290165 0.5097274 -0.2300212 0.6633313 0.6716325 -0.3300023 0.7496436 0.595491 -0.2888339 0.8320133 0.5089985 -0.220623 0.8336412 0.5138575 -0.2024666 0.7265523 0.636977 -0.2576474 0.8361066 0.5180345 -0.1804606 0.6685268 0.7029221 -0.2428426 0.757853 0.6162133 -0.2143363 0.8388798 0.5165061 -0.1717618 0.8415889 0.5196756 -0.1471925 0.7286139 0.6614108 -0.1779265 0.8423461 0.5242384 -0.125009 0.6724404 0.7250869 -0.1485698 0.7652879 0.6300289 -0.1319019 0.8443766 0.5227341 -0.1173771 0.8481958 0.5224314 -0.08734655 0.730042 0.677336 -0.0908547 0.8466933 0.5280427 -0.06543308 0.6742345 0.7368297 -0.04989916 0.7694224 0.6371821 -0.04458868 0.8475241 0.5273755 -0.05981802 0.8530865 0.5211662 -0.02508628 0.7304521 0.6829639 0 0.8487133 0.5288398 -0.003784358 0.6757256 0.735238 0.05310338 0.7648783 0.6418544 0.0546298 0.8483385 0.5294448 -0.003204464 0.8483098 0.5286219 0.03048861 0.6730032 0.7242444 0.1501225 0.6780158 0.7304174 0.08237147 0.8485834 0.5258135 0.05853557 0.8457504 0.5297232 0.06402945 0.7596839 0.6343721 0.143013 0.8458813 0.5256391 0.09049057 0.668432 0.7026746 0.2438181 0.6912992 0.7002414 0.1782343 0.8447723 0.5223672 0.1161562 0.8424298 0.5241114 0.1249774 0.7517982 0.6195911 0.2256249 0.8412044 0.520202 0.1475304 0.6627953 0.6717681 0.3308025 0.7006967 0.6634629 0.262376 0.8387284 0.5169341 0.1712126 0.8369905 0.5164773 0.1808266 0.7438687 0.5974388 0.2995434 0.8347628 0.5130288 0.1999316 0.6569629 0.6334629 0.4088088 0.7071952 0.6232974 0.3337295 0.8321027 0.5096687 0.2187302 0.8291527 0.509614 0.229781 0.7373188 0.5698282 0.3628455 0.8248994 0.5009092 0.2619755 0.8254482 0.5055783 0.2510495 0.6522008 0.589758 0.4762561 0.7122219 0.582394 0.3918639 0.8220595 0.5001757 0.2721073 0.7326388 0.5394841 0.4149667 0.8182808 0.4941669 0.2936252 0.818207 0.4959783 0.2907627 0.6498697 0.5426872 0.5321277 0.7177279 0.5424848 0.4365514 0.8137348 0.4879723 0.3157827 0.8151434 0.4908745 0.3075443 0.7299931 0.5083613 0.4568141 0.814726 0.4841356 0.319115 0.6507571 0.4939809 0.5766264 0.7168711 0.5097051 0.4757065 0.8134853 0.4820789 0.3253331 0.7327378 0.4979224 0.4638628 0.8198921 0.4767673 0.31697 0.7528488 0.4338921 0.4949306 0.8116078 0.484285 0.3267428 0.8057069 0.4725593 0.3571051 0.7309577 0.4774069 0.4876307 0.818037 0.4753978 0.3237478 0.7344389 0.4704193 0.4891885 0.8159758 0.4732696 0.3319632 0.4546782 0.4710366 0.7559049 0.4524795 0.5557875 0.6973971 0.4534347 0.6364322 0.6239801 0.4567236 0.7102487 0.5356774 0.4612373 0.7741205 0.4335868 0.4657273 0.8252468 0.3194779 0.4693257 0.8610408 0.1958118 0.471302 0.8794912 0.06610375 0.4712808 0.879539 -0.06561672 0.4692946 0.8611618 -0.1953537 0.4656279 0.8254466 -0.3191064 0.4611452 0.7743638 -0.4332506 0.4567215 0.7104591 -0.5354003 0.4535234 0.6366419 -0.6237015 0.45266 0.5560284 -0.6970878 0.4550704 0.4713066 -0.7555006 -0.03372377 0.06174045 -0.9975224 -0.0340597 0.06045901 -0.9975895 -0.0765711 0.1351972 -0.9878557 0.008564651 -0.01520496 -0.9998478 0.008567392 -0.0152046 -0.9998477 -0.07663297 0.1394714 -0.9872564 -0.09775245 0.2963703 -0.9500575 0.825004 0.4119221 0.3868961 -0.1564732 0.3161205 -0.9357265 0.008564233 -0.01520639 -0.9998478 0.008567571 -0.01520448 -0.9998477 0.8346608 0.4235715 0.3520352 -0.1613861 0.2888043 -0.9436878 -0.2432686 0.4304429 -0.8692177 0.8444565 0.4330624 0.3151987 -0.2403697 0.4287957 -0.8708367 -0.30596 0.5422131 -0.7825557 0.8535317 0.4312369 0.2924354 -0.3097702 0.5563657 -0.771038 -0.3323226 0.6326307 -0.6995286 0.87421 0.4410572 0.2030413 0.8633063 0.3904365 0.3197838 -0.3385215 0.6388632 -0.6908379 0.8718783 0.4438742 0.206891 -0.3746001 0.6648193 -0.6462896 -0.3449902 0.6122783 -0.711405 0.8845275 0.4408141 0.1526247 -0.3746069 0.6648148 -0.6462903 0.9026639 0.3812448 0.1996255 0.8969882 0.4193025 0.1399913 0.8867328 0.4163722 0.2008463 -0.3746489 0.6648461 -0.6462336 0.9189282 0.3795652 0.1072438 0.9002509 0.420522 0.1127374 0.1798202 -0.29909 -0.9371285 0.2241008 -0.377367 -0.8985394 0.1650153 -0.2934386 -0.9416283 0.2619473 -0.4460397 -0.8558226 0.2619168 -0.4648702 -0.8457514 0.09351032 -0.1645892 -0.9819198 0.09189283 -0.1629412 -0.9823473 0.05157643 -0.08935856 -0.9946633 0.05096727 -0.09045934 -0.9945952 0.1805521 -0.3040636 0.9353857 0.2628023 -0.3752052 0.8889072 0.2646647 -0.4472931 0.8543311 0.1636433 -0.291335 0.9425204 0.252299 -0.4441708 0.8596845 0.3184058 -0.567869 0.7590406 0.320854 -0.566141 0.7593004 0.3779526 -0.6733501 0.6354144 0.3796929 -0.6711845 0.636667 0.4261938 -0.7585121 0.4929688 0.4272422 -0.7566999 0.4948428 0.4620007 -0.82106 0.3352847 0.4620054 -0.8196645 0.3386758 0.4837607 -0.8586593 0.1693513 0.4835401 -0.8582195 0.1721871 0.4909304 -0.8711985 7.62978e-4 0.4912043 -0.8710445 3.05191e-4 0.4837655 -0.8592171 -0.1664842 0.4842576 -0.8578199 -0.1721621 0.462603 -0.8224189 -0.3310977 0.4623096 -0.8192659 -0.3392244 0.428065 -0.7606652 -0.4880051 0.4267529 -0.7566372 -0.4953606 0.3809756 -0.6763134 -0.6304425 0.3785272 -0.671418 -0.6371147 0.3219761 -0.5715 -0.7547974 0.3194789 -0.566596 -0.7595408 0.008562207 -0.01520544 0.9998478 0.00856769 -0.01520377 0.9998478 0.05148601 -0.08813971 0.9947767 0.04959309 -0.08801633 0.9948838 0.09036755 -0.1617216 0.9826902 0.008567154 -0.01520478 0.9998477 0.09485399 -0.164499 0.981806 -0.07608437 0.1384046 0.987449 -0.137946 0.2475703 0.9589995 -0.07644933 0.1358998 0.9877686 -0.1604401 0.2908187 0.9432303 -0.1818333 0.3224047 0.9289736 -0.03411984 0.06183081 0.9975033 0.008566975 -0.01520472 0.9998478 -0.03497493 0.06207597 0.9974585 0.8565784 0.4376432 -0.2733897 0.8747709 0.4403916 -0.2020674 0.8867449 0.4162864 -0.2009711 0.8501654 0.4361153 -0.2949958 0.8718912 0.4438652 -0.2068563 0.8845167 0.4408239 -0.1526586 0.9026367 0.3812767 -0.1996873 0.8970035 0.4192792 -0.1399632 -0.3746043 0.6648185 0.646288 -0.374612 0.6648193 0.6462827 0.9189499 0.3794701 -0.1073954 0.9002807 0.4204911 -0.1126152 -0.3746041 0.6648212 0.6462853 -0.337696 0.6239974 0.7046905 -0.3598506 0.6386425 0.680179 -0.3435832 0.6161791 0.7087128 -0.374597 0.6648193 0.6462913 -0.3052799 0.5552597 0.773622 -0.3062024 0.5430949 0.7818492 -0.2405802 0.4285153 0.8709167 -0.2436656 0.4319999 0.8683336 0.8712071 0.4909156 0 0.8712143 0.490903 0 0.8712147 0.4909023 0 0.871214 0.4909034 0 0.8712081 0.4909139 0 0.8712188 0.490895 0 0.8712168 0.4908984 0 0.8712113 0.4909083 0 0.8712162 0.4908995 0 0.8712185 0.4908955 0 0.8712072 0.4909156 0 0.8712292 0.4908765 0 0.8712139 0.4909036 0 -0.3746551 0.6648185 -0.6462584 -0.3746031 0.6648166 -0.6462906 0.871212 0.4909071 0 0.8712141 0.4909032 7.59137e-7 0.8712095 0.4909116 -7.86805e-7 0.8712157 0.4909006 -8.83656e-7 0.8712074 0.4909153 1.29108e-6 0.8712079 0.4909142 -1.06524e-6 0.8712232 0.4908873 -6.18919e-7 0.8712255 0.4908831 -2.09802e-6 0.8712078 0.4909145 -9.91202e-7 0.8712105 0.4909099 -1.02851e-6 0.8712185 0.4908956 6.74547e-7 0.8712157 0.4909005 -8.96872e-7 0.8712109 0.490909 -7.58771e-7 0.8711984 0.4909314 -2.13673e-6 0.8712189 0.4908947 -9.05684e-7 0.8712091 0.4909121 -9.33743e-6 0.8712221 0.4908891 0 0.8712135 0.4909043 0 -0.3745992 0.6648121 0.6462973 -0.4379529 0.7773588 0.4515646 -0.4092343 0.726117 0.5525228 -0.4091094 0.7260509 0.5527021 0.9047306 0.4156969 -0.09305191 0.9197869 0.3868 -0.06616556 -0.4384025 0.7779242 0.4501523 0.8712147 0.4909022 0 0.8712151 0.4909016 0 0.9047199 0.415706 0.09311497 0.9254182 0.3738539 0.06192237 -0.409174 0.7260574 -0.5526459 -0.4091722 0.7261762 -0.5524909 -0.4383473 0.7779344 -0.4501887 0.9278852 0.3728266 -0.005432426 0.9747127 0.1854938 0.1246086 -0.4774682 0.8474489 -0.2320657 -0.477602 0.8476222 -0.2311558 -0.437988 0.7773364 -0.4515692 0.9195773 0.3925698 -0.01632779 -0.4908712 0.8712323 -3.05192e-5 0.9605036 0.2757114 -0.03763025 -0.4908712 0.8712323 0 -0.4776256 0.8476099 0.2311524 -0.4774413 0.8474553 0.232098 0.9370573 0.2859941 -0.2003271 0.9517332 0.2898689 -0.1008956 0.9566662 0.2911871 0 0.9517304 0.2898681 0.1009258 0.9370656 0.2859662 0.2003288 0.8591725 0.3800843 0.3425764 0.8707196 0.3524995 0.3429164 0.9130759 0.2796787 0.2967695 0.7312031 0.2413742 0.6380288 0.7081108 0.3150821 0.6319038 0.7787905 0.33443 0.5306995 0.8872185 0.3077843 0.3436747 0.8026866 0.2553545 0.5389698 0.9682279 0.1486905 -0.2010617 0.9834211 0.1504293 -0.1012628 0.9885282 0.1510366 0 0.9834135 0.1504586 0.1012925 0.9682279 0.1486905 0.2010617 0.9051319 0.2494926 0.3442236 0.9434006 0.1458498 0.2978646 0.7585917 0.1278765 0.6388944 0.6943059 0.2275187 0.6827698 0.927924 0.1682196 0.3326549 0.8290601 0.1386802 0.5416892 0.9793859 0.008423209 -0.2018223 0.9947887 0.008209526 -0.1016274 0.9999671 0.008118152 -3.05194e-5 0.9947825 0.008209466 0.1016877 0.9793859 0.008423209 0.2018223 0.9542428 0.008758962 0.2989047 0.9396332 0.1152415 0.322194 0.7650552 0.01303166 0.6438329 0.7016659 0.1140806 0.703314 0.9408522 0.02304214 0.3380329 0.8475868 0.03750842 0.5293297 0.9433797 -0.02295041 0.3309199 0.8488054 -0.02313369 0.5281991 0.7613645 -0.0659216 0.6449639 0.8464584 -0.06244289 0.5287809 0.8711717 0.4909787 0 0.871193 0.4909409 0 0.8712924 0.4907643 0 0.5221318 0.1836678 0.8328533 0.5423885 0.1035214 0.8337254 0.548277 0.02063095 0.8360423 0.5437565 -0.0365312 0.8384477 0.5403704 -0.05710113 0.8394876 0.5363121 -0.07364255 0.840801 0.5312798 -0.0754742 0.8438279 0.5201777 -0.0846616 0.8498516 0.5257582 -0.08011347 0.8468531 -0.03711074 0.05746674 0.9976575 -0.04660296 0.07089632 0.9963945 -0.05667436 0.08417224 0.9948383 -0.06702071 0.09714341 0.9930112 -0.07739591 0.1099596 0.9909182 -0.08841454 0.1227489 0.9884916 -0.09973704 0.135292 0.9857732 -0.1113935 0.1475276 0.9827651 -0.1234501 0.1600425 0.9793603 -0.1366626 0.1715454 0.9756514 -0.1483819 0.1822577 0.9719903 -0.1613564 0.1930356 0.9678333 -0.1747826 0.2041419 0.9632119 -0.1896479 0.2138499 0.9582808 -0.2024303 0.2226641 0.953647 -0.216841 0.2314904 0.948363 -0.2315171 0.2397572 0.9428236 -0.2465957 0.2474197 0.9370028 -0.2619435 0.2544053 0.9309477 -0.2776286 0.2607517 0.9246248 -0.2935917 0.2663689 0.9180694 -0.3098571 0.2712814 0.9112601 -0.3263446 0.2754381 0.9042307 -0.3431008 0.2787961 0.8969697 -0.360071 0.2813302 0.8894956 -0.3772515 0.2830379 0.8817999 -0.3946151 0.2838909 0.8738907 -0.4121273 0.2838259 0.8657909 -0.429744 0.282854 0.8575043 -0.44747 0.2809887 0.8490088 -0.4652442 0.2781882 0.8403328 -0.4830369 0.274434 0.8314815 -0.5008197 0.269698 0.8224614 -0.5172353 0.2598689 0.815436 -1 1.90909e-6 0 -0.5360696 0.2706747 0.7996029 -0.03592056 0.05441492 0.9978722 -0.06131184 0.08761888 0.9942655 -0.03988796 0.06131207 0.9973213 -0.06433463 0.09299224 0.9935862 -0.07727479 0.1093811 0.9909917 -0.1000713 0.1377926 0.9853929 -0.112891 0.153848 0.9816244 -0.1290646 0.1718217 0.9766369 -0.1434377 0.187293 0.9717752 -0.1588837 0.2035335 0.9660902 -0.1624251 0.2037485 0.9654557 -0.1920581 0.2340832 0.9530576 -0.2094236 0.2490376 0.9455803 -0.2259656 0.2631382 0.9379221 -0.2265107 0.256999 0.9394915 -0.2639326 0.2886229 0.9203459 -0.2807425 0.2990843 0.9119936 -0.3000678 0.3099561 0.9021566 -0.3201497 0.3203328 0.8915666 -0.3405364 0.3299767 0.8804262 -0.3604252 0.3384214 0.8692322 -0.3808252 0.3459717 0.8574823 -0.4020966 0.3527768 0.8449065 -0.4233287 0.3582623 0.8321304 -0.4468582 0.3615883 0.8182736 -0.4675325 0.3641009 0.8055085 -0.4876095 0.3641888 0.7934756 -0.5094612 0.3644632 0.7794972 -0.534423 0.3658956 0.7619137 -0.5535671 0.362422 0.7498092 -0.5758995 0.3603721 0.7338064 -0.5945448 0.354145 0.721871 -0.616008 0.3481068 0.7066513 -0.6379525 0.3408436 0.6905378 -0.6642874 0.3281151 0.6716121 -1 -1.83053e-6 0 0.152567 -0.1478365 0.9771735 -0.02499473 0.05273622 0.9982957 -1 9.5817e-7 0 -1 1.98151e-6 0 -1 -2.35653e-6 0 -0.1025142 0.1440508 0.984246 -0.1246086 0.1684948 0.9777947 -0.1184753 0.160256 0.9799396 -0.1418826 0.1874779 0.9719678 -0.1601046 0.2064635 0.9652665 -0.1541524 0.2003585 0.9675194 -0.1717327 0.2186715 0.9605679 -1 -2.25043e-6 0 -1 -3.29204e-7 0 -0.2261183 0.2671059 0.9367631 -0.2101845 0.2546203 0.9439232 -0.2410073 0.2786371 0.929665 -0.2506865 0.2856923 0.924952 -0.2986966 0.3236312 0.8977991 -1 3.11803e-6 0 -1 1.93436e-6 0 -0.3086132 0.3258262 0.8936416 -0.2882215 0.3132166 0.9048888 -0.3309783 0.3387301 0.8807471 -0.3520443 0.3494196 0.8683149 -0.3743774 0.3597283 0.8546562 -0.3969873 0.3689712 0.8403936 -0.4153097 0.374261 0.829124 -0.4332801 0.378071 0.8181264 -0.4295253 0.3849369 0.8169037 -0.4488751 0.3799019 0.8088176 -0.4705443 0.384114 0.7943831 -0.5104033 0.3945524 0.764079 -0.4859374 0.3909595 0.7816749 -0.5353138 0.3977009 0.7451666 -0.5558789 0.3954389 0.7311819 -0.5341275 0.3959032 0.7469728 -0.5777233 0.3921072 0.7158825 -0.6039213 0.3927564 0.6935573 -0.6281803 0.3897019 0.6734405 -0.6479558 0.3840246 0.657783 -0.6737164 0.3775559 0.6352619 -0.655655 0.3871731 0.6482387 -0.6946704 0.3688204 0.6175797 -0.2259937 0.2710704 0.9356536 -0.2267897 0.2713176 0.9353893 -0.2278544 0.271527 0.9350698 -0.2290158 0.2716816 0.9347411 -0.2301464 0.2716527 0.9344719 -0.2312749 0.2714383 0.9342554 -0.2323745 0.271012 0.9341064 -0.2332577 0.2702775 0.934099 -0.2360069 0.3090704 0.9212906 -0.2823635 0.3823748 0.879807 -0.3403798 0.3551205 0.8706497 -0.3449018 0.3555837 0.8686789 -0.3512451 0.3557314 0.8660728 -0.3581191 0.3550671 0.8635267 -0.3642176 0.3534138 0.8616521 -0.3689473 0.3510325 0.8606126 -0.3712048 0.3708691 0.8512716 -0.4111841 0.41976 0.8091534 -0.4464042 0.3954372 0.8027158 -0.4522611 0.3950991 0.7995979 -0.4621189 0.3937869 0.7945931 -0.4721669 0.3912903 0.7899053 -0.4810111 0.3876532 0.7863545 -0.4884049 0.3829903 0.7840786 -0.4933668 0.3959508 0.7744755 -0.532405 0.4250084 0.7320607 -0.5541076 0.4052346 0.7271518 -0.5659214 0.4021847 0.7197087 -0.5814337 0.3963308 0.7105327 -0.5940877 0.3894562 0.703835 -0.6041565 0.3820384 0.6993151 -0.611025 0.3867393 0.6907107 -0.6547048 0.3857668 0.6500353 -0.6681779 0.3795313 0.6399175 -0.6860147 0.3690404 0.6270512 -0.5413202 0.4573617 0.7055444 -0.553498 0.4877899 0.6750564 -0.5687931 0.5166047 0.6399953 -0.5867057 0.5433681 0.6004394 -0.606754 0.5677198 0.5563666 -0.6285451 0.5893278 0.5075666 -0.6516774 0.6077296 0.4538516 -0.6624563 0.6163108 0.4258081 -0.3561629 0.8616884 0.3614428 -0.3615345 0.8401725 0.4042313 -0.345781 0.8006677 0.4892511 -0.3306789 0.7556936 0.5653129 -0.3170394 0.7047931 0.6346281 -0.3052181 0.6485235 0.697323 -0.2955513 0.5874707 0.7533444 -0.2883797 0.5223124 0.8025129 -0.2840116 0.4538815 0.8445882 -0.5208452 0.7535256 0.4011478 -0.4961557 0.712417 0.4962778 -0.5175449 0.7396638 0.4301684 -0.478631 0.6798434 0.5556306 -0.4626457 0.6433824 0.609933 -0.4483304 0.6036132 0.6592807 -0.4357898 0.5610119 0.7038132 -0.4252865 0.5160204 0.7435419 -0.4170489 0.4691151 0.7784608 0.984158 -0.1441735 -0.103186 0.9821923 -0.1722796 -0.07495456 0.9794777 -0.1734091 -0.102727 0.9879547 -0.1117599 -0.1070294 0.9944928 0.0233165 -0.1021777 0.9928684 -0.04907423 -0.1086469 0.9919172 0.09329551 -0.08600151 0.9864808 0.1519869 -0.06128305 0.9772704 0.207924 -0.04135286 0.9801145 0.1970911 -0.02304172 0.9807517 0.1952592 2.74669e-4 0.9789782 0.2039563 -0.001892149 0.9549465 0.2793424 -0.1002251 0.9507908 0.297042 -0.08810847 0.9478614 0.3115692 -0.06695884 0.9410474 0.3363783 -0.03576803 0.9408183 0.3369635 -0.03628742 0.9449974 0.3266778 -0.01617515 0.9479511 0.3112635 -0.06711131 0.9633929 -0.1526255 -0.2204081 0.9695402 -0.1301347 -0.2075014 0.973639 -0.09350937 -0.2080461 0.9680591 -0.1747206 -0.1798173 0.9692776 -0.1740793 -0.1737741 0.9634088 -0.1763111 -0.2018864 0.9618762 -0.1778663 -0.2077447 0.9690436 -0.1046501 -0.2236137 0.9786081 -0.01123118 -0.2054268 0.9634436 -0.1501566 -0.2218776 0.9728956 -0.02188235 -0.2302074 0.9775034 0.0780074 -0.1959645 0.9692131 -0.07867717 -0.2333155 0.9734199 0.08517992 -0.2125989 0.9704843 0.1695959 -0.1714576 0.97166 0.0116887 -0.236094 0.9671133 0.1832354 -0.1763992 0.959531 0.2489775 -0.1315692 0.9810776 0.1936152 -6.10389e-5 0.9807575 0.1952298 -1.83114e-4 0.9789648 0.2040209 0.001892149 0.979092 0.2004207 0.03479206 0.9458764 0.3243868 0.009552419 0.9480248 0.3175851 0.01971554 0.9431017 0.3318038 0.021577 0.969088 0.2426306 0.04471117 0.9486353 0.3088566 0.06854659 0.9477267 0.3119923 0.06689691 0.9506105 0.2975007 0.0885055 0.9321023 0.3621655 0.004638791 0.9471184 0.3208434 -0.005157649 0.9477787 0.3189273 0.001098692 0.9439322 0.3295171 -0.0202648 0.9476753 0.3192285 0.002197325 0.9856466 0.1567158 0.06277787 0.9911538 0.09341752 0.09427207 0.9796379 0.1776831 0.09348046 0.9936462 0.02163815 0.1104492 0.985282 0.1106931 0.1302559 0.9920903 -0.05169963 0.1143862 0.9860857 0.04049813 0.1612296 0.9800947 -0.1387404 0.142006 0.9817382 -0.03466963 0.1870515 0.9877013 -0.1146311 0.1063297 0.9817501 -0.1602576 0.1023927 0.9796282 -0.1728289 0.102269 0.9665011 -0.1451476 0.2116786 0.969063 -0.1304678 0.2095114 0.9658357 -0.1514354 0.2103066 0.9821757 -0.1723736 0.07495564 0.9645099 -0.1702632 0.2018195 0.9636161 -0.1682223 0.2077143 0.968354 -0.1771048 0.1758534 0.9642441 -0.1645883 0.2077115 0.9544923 0.2780617 0.1078248 0.9569794 0.2628283 0.1229299 0.9403318 0.3370863 0.04635888 0.9426101 0.3290559 0.05664324 0.9620465 0.2283422 0.1494204 0.9632787 0.2230651 0.1494527 0.9678084 0.1745973 0.1812809 0.9688397 0.1799426 0.1702069 0.971748 0.1198167 0.2033465 0.973385 0.1344988 0.1855578 0.9740135 0.065921 0.2166848 0.9766542 0.08759093 0.1961488 0.9746733 0.01419115 0.2231827 0.9783933 0.04052984 0.2027409 0.9739598 -0.03314381 0.2242857 0.9784663 -0.005310237 0.2063382 0.9721897 -0.07513827 0.2218136 0.9768905 -0.04938012 0.2079581 0.9695273 -0.1123709 0.2176919 0.9737338 -0.09161752 0.2084436 0.9838367 -0.1714245 0.05175995 0.9847795 -0.170783 0.03228884 0.9852209 -0.170938 0.01095634 0.9817755 -0.1893417 0.01632779 0.9779015 -0.1728616 0.1175911 0.9782731 -0.1707873 0.1175307 0.979365 -0.1791484 0.09354168 0.9751488 -0.1869605 0.1188722 0.9784947 -0.1872635 0.08649033 0.9790055 -0.1841853 0.08731639 0.9766537 -0.1964233 0.08698046 0.9795522 -0.181255 0.08731609 0.9730564 -0.1753351 0.1497291 0.974121 -0.1747546 0.14335 0.9679511 -0.1789653 0.1761881 0.9763042 -0.2160748 0.01190239 0.9658947 -0.2586177 0.01281791 0.960779 -0.2484883 0.123115 0.9398728 -0.3395884 0.03631794 0.9418489 -0.3133392 0.1214048 0.9555184 -0.2946301 0.01333677 0.9238095 -0.3822197 0.02200418 0.9407871 -0.3387945 0.01174992 0.908579 -0.4177126 6.40897e-4 0.9255411 -0.3786457 0.001190185 0.9137102 -0.4061477 -0.01333677 0.9099156 -0.4144747 -0.01626646 0.9123004 -0.4089833 -0.02099692 0.8865693 -0.4604361 0.04464888 0.8832334 -0.4675277 0.0362876 0.8764177 -0.4809508 0.02404904 0.8702192 -0.4925769 0.009308278 0.8705696 -0.4919748 0.008331775 0.8703445 -0.4924261 0.004120051 0.8735171 -0.4865657 0.01489329 0.9747678 -0.2058487 0.08633744 0.9711083 -0.2221158 0.08725321 0.9773762 -0.1932473 0.08597248 0.9697427 -0.225963 0.09241163 0.9643045 -0.250743 0.0851171 0.9576199 -0.2758597 0.08285862 0.9641801 -0.24531 0.1008951 0.9490749 -0.3040592 0.08249241 0.9569656 -0.270188 0.1059022 0.9393889 -0.3330588 0.08136487 0.9479058 -0.2995491 0.1083748 0.9287517 -0.36229 0.07852518 0.9370607 -0.3324759 0.1066645 0.9174531 -0.3910666 0.07312279 0.9245459 -0.3679689 0.099065 0.9058309 -0.4186885 0.06457793 0.9105526 -0.4047206 0.08423411 0.8942593 -0.4444745 0.05237007 0.8955202 -0.440756 0.06146532 0.9113518 -0.4115762 -0.006561517 0.9112838 -0.4117257 0.006622493 0.9099116 -0.4144868 0.01617538 0.9123231 -0.4089325 0.02099746 0.9154003 -0.4024599 0.00827074 0.8704376 -0.4922744 -0.002075254 0.8711488 -0.4909978 -0.004577875 0.8709182 -0.491385 -0.006500482 0.9256249 -0.3784414 8.85064e-4 0.8802279 -0.4733796 -0.03332668 0.8816071 -0.4707581 -0.03399831 0.8972437 -0.43823 -0.05392801 0.8682332 -0.4961463 -0.003143429 0.8703387 -0.492453 8.52607e-4 0.8703853 -0.4923709 5.7987e-4 0.8702362 -0.492617 0.004211664 0.8703821 -0.4923768 4.40669e-6 0.8704062 -0.4923343 1.51006e-4 0.8704165 -0.4923156 -8.3146e-4 0.8703978 -0.4923493 -3.50202e-5 0.8701968 -0.4927044 -3.26912e-4 0.9407864 -0.3388552 -0.009918749 0.9673371 -0.2532179 -0.01181089 0.9555276 -0.2945719 -0.0139473 0.976424 -0.2156776 -0.00891149 0.9798873 -0.1934931 -0.04880052 0.9835757 -0.1801859 -0.01059019 0.9853037 -0.1704482 -0.01113939 0.9753596 -0.2028298 -0.08679628 0.9770193 -0.1953245 -0.08533239 0.9788769 -0.1860153 -0.08484369 0.9846683 -0.1712121 -0.03338789 0.9804166 -0.1732857 -0.09357064 0.9813683 -0.1711504 -0.08731478 0.9779614 -0.1751809 -0.1135929 0.9772815 -0.1931246 -0.08731502 0.9185512 -0.3842607 -0.09277677 0.9176355 -0.3902553 -0.07513946 0.8939495 -0.444701 -0.05563718 0.8828588 -0.4682253 -0.03640937 0.9373024 -0.3331464 -0.102361 0.939347 -0.3314983 -0.08795601 0.957197 -0.2709169 -0.1018723 0.9567947 -0.2762256 -0.09079337 0.9512931 -0.2898955 -0.1048921 0.9663866 -0.2399104 -0.09241175 0.9698791 -0.2267598 -0.08896428 0.9718174 -0.2190656 -0.08707076 0.9838445 -0.1714258 -0.05160778 0.9770214 -0.1762142 -0.1199074 0.974121 -0.1747546 -0.14335 0.973052 -0.1753343 -0.149759 0.9777779 -0.1808574 -0.1060241 0.9811778 -0.181617 -0.06561529 0.9779702 -0.1810061 -0.103977 0.9817463 -0.1817732 -0.05597245 0.9825213 -0.1819529 -0.03930813 0.9800639 -0.1937055 -0.04419183 0.9791935 -0.1925731 -0.06399774 0.9810649 -0.1890044 -0.04229933 0.9800226 -0.1940391 -0.04364198 0.974944 -0.1803699 -0.130196 0.9725703 -0.1798162 -0.1475579 0.9713108 -0.1794846 -0.1560152 0.9791535 -0.1723124 -0.1075503 0.9731025 -0.1695032 -0.1560138 0.9765868 -0.1638886 -0.1393511 0.9815353 -0.1566867 -0.1097173 0.9807258 -0.1321775 -0.1438967 0.9805076 -0.118596 -0.1566529 0.985655 -0.1268692 -0.1113043 0.9846815 -0.08679747 -0.1512241 0.9896767 -0.09177124 -0.1100828 0.9858248 -0.04205513 -0.1624221 0.9875948 -0.01580882 -0.1562267 0.9931496 -0.03128194 -0.1125846 0.9870851 0.07443648 -0.1418536 0.9961335 0.0145269 -0.08664286 0.9837057 0.1596171 -0.08273845 0.9481151 0.3111146 -0.06546407 0.9970492 0.05804675 -0.0502339 0.9750515 0.2151284 -0.05472052 0.9941465 0.1000403 -0.04080349 0.9992439 -0.03888082 0 0.995797 0.09158682 -4.27263e-4 0.9753038 0.2208678 -1.22077e-4 0.999105 0.04171961 -0.006988823 0.982877 -0.1757306 -0.0554232 0.9847531 -0.1651988 -0.05450671 0.9876204 -0.1458495 -0.05774164 0.9908183 -0.1223797 -0.05746656 0.9941197 -0.09662252 -0.04889112 0.9972252 -0.06921613 -0.02740567 0.9986874 -0.04727458 -0.01971554 0.9998701 -0.01608359 0.001129209 0.998896 -0.04696911 -9.76617e-4 0.998967 -0.04544222 3.05187e-5 0.983259 -0.1822137 1.9895e-6 0.9831807 -0.1821699 -0.01303172 0.9832549 -0.1822356 4.63548e-6 0.9832536 -0.1822428 1.79172e-6 0.9830405 -0.1833839 -0.001324057 0.9832575 -0.1822218 2.38776e-5 0.9832695 -0.1821568 1.60455e-4 0.9832555 -0.182233 1.02839e-5 0.9832533 -0.1822443 0 0.9832524 -0.1822494 -3.19083e-5 0.983251 -0.1822566 -5.29431e-5 0.9832562 -0.1822288 3.36319e-5 0.9832552 -0.1822345 -4.32061e-6 0.9832545 -0.1822377 1.81656e-5 0.9832586 -0.1822162 1.43604e-6 0.9832577 -0.1822203 1.34262e-6 0.9832522 -0.1822499 -1.74619e-6 0.9832496 -0.1822646 -1.87917e-6 0.9832558 -0.1822311 -6.14508e-7 0.9832561 -0.1822291 0 0.9832471 -0.1822781 5.43932e-7 0.9832636 -0.1821889 3.45851e-7 0.9832737 -0.1821346 2.16835e-6 0.9832568 -0.1822261 2.55019e-6 0.9831852 -0.1826112 5.76192e-7 0.9832276 -0.1823829 1.06254e-6 0.9828634 -0.1838768 -0.01300108 0.983255 -0.1822351 3.13647e-7 0.9832552 -0.1822342 3.13542e-7 0.9832556 -0.1822322 0 0.9975791 -0.06549406 0.02337765 0.9970499 -0.07089519 0.02942013 0.9986235 -0.0508452 0.01287913 0.9988572 -0.04626679 0.01199394 0.98325 -0.1822623 -6.85447e-7 0.9765301 -0.2102788 -0.04660314 0.9832577 -0.1822204 -9.56237e-7 0.9832581 -0.1822187 -1.25748e-6 0.9760794 -0.212288 -0.0469377 0.9706602 -0.2350581 -0.05066168 0.98325 -0.1822618 -1.07982e-6 0.9799757 -0.1959341 -0.03546345 0.9832611 -0.1822022 -6.67354e-7 0.969668 -0.2391819 -0.05035728 0.9620814 -0.2687199 -0.04678565 0.9832579 -0.1822197 0 0.9832535 -0.1822434 -9.11217e-7 0.9750491 -0.2172947 -0.04541212 0.9832427 -0.1823019 0 0.959609 -0.2776924 -0.04513758 0.9507272 -0.3083332 -0.03238064 0.9832543 -0.1822393 -5.25949e-7 0.9666574 -0.2511405 -0.05002051 0.9832575 -0.1822217 -1.0809e-6 0.950895 -0.3079719 -0.03085517 0.9612569 -0.2743963 -0.02630734 0.9832847 -0.182075 0 0.9823933 -0.1868249 -6.22683e-7 0.9641059 -0.2655182 1.22077e-4 0.9641059 -0.2655182 0 0.9624661 -0.2714022 -1.22075e-4 0.9641315 -0.2654253 0 0.9637946 -0.2651504 -0.02819967 0.9641315 -0.2654253 1.22077e-4 0.9308338 -0.3623843 0.04718255 0.964094 -0.2653014 0.0117498 0.9511757 -0.3074147 0.02758884 0.9572577 -0.2864814 0.03982722 0.9618338 -0.2697261 0.0460835 0.9188792 -0.3913202 0.050296 0.9555505 -0.2947832 -0.005127191 0.9497738 -0.3121457 0.02224814 0.9673633 -0.2485779 0.0491662 0.9705069 -0.2357294 0.05047851 0.9607314 -0.2742418 0.04226851 0.974881 -0.217939 0.04593163 0.9764932 -0.210369 0.04696905 0.9697573 -0.2392729 0.04815977 0.9794223 -0.1981307 0.03842365 0.9801313 -0.1937068 0.04266613 0.9759764 -0.2127804 0.0468471 0.9818397 -0.1867787 0.0332356 0.9819125 -0.1886063 0.01660221 0.9798666 -0.1947708 0.043886 0.983255 -0.1822352 -3.33047e-6 0.9817487 -0.1818346 0.05572843 0.983201 -0.1820155 0.01364195 0.981747 -0.1818343 0.05575883 0.9832559 -0.18223 0 0.9832557 -0.1822315 2.13838e-5 0.9832541 -0.1822401 -2.47659e-5 0.9832508 -0.1822575 -1.07868e-4 0.9832558 -0.1822306 1.70432e-5 0.9832513 -0.1822553 -2.73369e-5 0.9832551 -0.1822349 -2.53271e-6 0.9832562 -0.1822284 0 0.9832027 -0.1820158 0.01351994 0.9818766 -0.1890325 0.01361131 0.9830451 -0.1749039 0.05505609 0.9830383 -0.1747196 0.05575764 0.9847208 -0.1653205 0.05472022 0.9859707 -0.1588197 0.05136311 0.9876319 -0.1456376 0.05807799 0.9836899 -0.172402 0.05130249 0.9886044 -0.1415475 0.05124151 0.9908464 -0.1221085 0.05755978 0.9917104 -0.1188404 0.04886066 0.9941416 -0.09641104 0.04886168 0.9949285 -0.09213769 0.04034644 0.9832558 -0.1822306 0 0.9832544 -0.1822385 -5.54869e-6 0.9832583 -0.1822177 0 0.9832555 -0.1822327 0 0.9832513 -0.1822552 0 0.9832456 -0.1822862 -1.06376e-5 0.9832537 -0.1822422 -2.40558e-6 0.9832541 -0.18224 0 0.9832548 -0.1822365 0 0.9832553 -0.1822339 0 0.9832786 -0.1821077 0 0.9832931 -0.1820298 0 0.9832428 -0.1823011 0 0.983232 -0.182359 0 0.9832158 -0.1824463 0 0.9832504 -0.1822597 0 0.9832922 -0.1820345 0 0.9832858 -0.1820693 0 0.983257 -0.1822248 0 0.9832523 -0.1822496 0 0.9832495 -0.1822652 0 0.9832221 -0.1824124 0 0.9832614 -0.1822007 0 0.9832662 -0.1821746 0 0.9833667 -0.1816314 0 0.9807547 0.1952292 0.00238043 0.9745861 0.2239161 0.006592035 0.97518 0.2213252 0.006256401 0.9828909 0.178688 0.04467958 0.9787806 0.2026168 0.03058022 0.9744725 0.2236129 0.02002048 0.9904508 0.1378525 -0.002014219 0.990653 0.1363902 -0.002105772 0.9851173 0.1545168 0.0752899 0.933157 0.3594254 0.005615532 0.9835062 0.1623612 0.07971566 0.9884057 0.1072118 0.107517 0.9882621 0.08676511 0.1257377 0.9873566 0.0769999 0.1385571 0.9892023 0.0307933 0.1432852 0.9878356 0.01635807 0.1546392 0.9875193 -0.01739609 0.1565344 0.9860524 -0.04068237 0.1613867 0.9856811 -0.04825097 0.161569 0.9847032 -0.08633887 0.1513448 0.9818034 -0.09793615 0.1626979 0.9804838 -0.1137138 0.1603773 0.9799406 -0.1330026 0.1484148 0.9765151 -0.1438664 0.1603771 0.9771636 -0.1688932 0.1289436 0.9746385 -0.1642556 0.1519868 0.9741927 -0.1630928 0.1560429 0.971331 -0.1794827 0.1558915 0.9712969 -0.1794821 0.1561045 0.9725511 -0.1798183 0.1476817 0.9749324 -0.1803678 0.130286 0.9779658 -0.1810109 0.1040103 0.9812068 -0.1816473 0.06509637 0.9812126 -0.1816484 0.06500518 0.9802548 -0.1867486 0.06500643 0.9054453 -0.4244618 -0.00100708 0.9050627 -0.4252781 0 0.9053589 -0.4246473 0 0.8748413 -0.4839476 0.02114999 0.9235128 -0.383566 0.001098692 0.9067685 -0.4216286 -6.40912e-4 0.9051437 -0.4251044 -0.001098692 0.9048393 -0.4247691 -0.02893239 0.9094161 -0.4158874 -1.83116e-4 0.9146202 -0.4043141 3.35708e-4 0.8658531 -0.5002971 -0.00112915 -0.157662 -0.739266 -0.6546974 -0.1926056 -0.7202186 -0.6664746 -0.2630761 -0.6836929 -0.6807019 -0.1148444 -0.7562093 -0.6441726 -0.3053174 -0.6536369 -0.6924883 -0.3731904 -0.6108444 -0.6982823 -0.2286499 -0.7026439 -0.6738032 -0.3806376 -0.6040089 -0.7002059 -0.4301076 -0.5652773 -0.7038957 -0.4457082 -0.5524658 -0.7043619 -0.4782014 -0.5199513 -0.7077954 -0.1935532 -0.8388524 -0.5087866 -0.1644713 -0.8074327 -0.5665702 -0.2025864 -0.7905997 -0.5778504 -0.2512322 -0.8099124 -0.5300229 -0.279282 -0.7446097 -0.6062657 -0.3466672 -0.7005676 -0.6237203 -0.3626013 -0.7417442 -0.5642126 -0.4196411 -0.6491771 -0.6344057 -0.4674406 -0.6570903 -0.5913813 -0.4874251 -0.5912521 -0.6425247 -0.5158948 -0.6102293 -0.6012262 -0.5181803 -0.5618529 -0.6448338 -0.2200461 -0.864406 -0.4520865 -0.294541 -0.8245071 -0.4831497 -0.4399575 -0.7218282 -0.5342298 -0.5112578 -0.6583604 -0.5524283 -0.7392993 -0.4513803 -0.4996924 -0.7191495 -0.4333391 -0.543177 -0.7128715 -0.4298959 -0.5540792 -0.7178304 -0.4325416 -0.5455523 -0.745871 -0.4483343 -0.4926185 -0.7425659 -0.4464978 -0.4992352 -0.7427421 -0.4465852 -0.4988949 -0.7224829 -0.4350523 -0.5373529 -0.7207133 -0.4341676 -0.5404359 -0.7186654 -0.4332196 -0.5439126 -0.7177872 -0.432827 -0.5453828 -0.8213604 -0.299728 -0.4853147 -0.7815566 -0.3689421 -0.5030419 -0.7674354 -0.3517641 -0.5360084 -0.7464414 -0.4486644 -0.4914525 -0.8339306 -0.3227075 -0.4476826 -0.7918823 -0.3794456 -0.4784804 -0.7891631 -0.3763006 -0.4854064 -0.7772373 -0.2626193 -0.5717808 -0.7327884 -0.3164196 -0.6024118 -0.8076658 -0.2883169 -0.5143436 -0.7445738 -0.2364313 -0.6242677 -0.6934384 -0.2818496 -0.6631018 -0.7096056 -0.2104614 -0.672433 -0.6510149 -0.2482164 -0.7173342 -0.6731492 -0.1852174 -0.7159363 -0.6067847 -0.2212954 -0.7634402 -0.6163591 -0.1953513 -0.7628496 -0.5862655 -0.2051166 -0.7837219 -0.5803518 -0.1966652 -0.7902624 -0.7493628 -0.4502769 -0.4854958 -0.7946673 -0.3828064 -0.4711298 -0.7494103 -0.4503176 -0.4853847 -0.7915712 -0.4729529 -0.3869503 -0.7129832 -0.4354441 -0.5495848 -0.7770438 -0.4656891 -0.4234814 -0.8384249 -0.3141957 -0.4453369 -0.8285616 -0.4099623 -0.3813354 -0.8197566 -0.4089016 -0.4009971 -0.8461224 -0.335043 -0.4145157 -0.7314574 -0.4445449 -0.517059 -0.7419549 -0.4588578 -0.4888277 -0.7124146 -0.4359393 -0.5499293 -0.7281665 -0.4463793 -0.5201146 -0.7426486 -0.4594936 -0.4871743 -0.9402721 0.1339191 -0.3129764 -0.9404221 0.1207954 -0.3178281 -0.9329707 0.2064316 -0.2948761 -0.9252043 0.1234175 -0.3588386 -0.9326249 0.1992879 -0.3008241 -0.934223 0.135963 -0.3297599 -0.9323829 0.2072538 -0.2961554 -0.9136461 0.2606319 -0.3119648 -0.9278601 0.266825 -0.2605382 -0.9269527 0.2668884 -0.2636839 -0.921451 0.2502838 -0.29713 -0.9294629 0.1933392 -0.3141954 -0.9297215 -0.0160228 -0.3679149 -0.927794 -0.0285052 -0.3720027 -0.903522 -0.01672452 -0.4282153 -0.9191228 -0.01083439 -0.3938225 -0.8954554 -0.1667553 -0.4127378 -0.8921075 -0.1775913 -0.4154582 -0.86584 -0.154429 -0.4758915 -0.8813169 -0.158214 -0.4452516 -0.8636898 -0.3275917 -0.3830449 -0.9034007 -0.1857097 -0.386496 -0.9154433 -0.1775586 -0.36116 -0.9365084 -0.02749764 -0.3495655 -0.9491068 0.1337642 -0.2851379 -0.9436596 0.1243665 -0.3066588 -0.9449656 -0.0205394 -0.3265247 -0.9325561 0.2070753 -0.2957347 -0.9390213 0.207471 -0.2742169 -0.9361014 0.2036821 -0.2867541 -0.9287138 0.2666112 -0.2576997 -0.9313184 0.2652713 -0.249554 -0.901443 0.2287712 -0.3675111 -0.8968641 0.2164413 -0.3857306 -0.8802922 0.2052102 -0.4277553 -0.9113944 0.203685 -0.3575932 -0.9096987 0.2063432 -0.3603758 -0.9101116 0.218456 -0.3520994 -0.8853722 0.2186115 -0.4102743 -0.860889 0.1921191 -0.4711267 -0.8670181 0.2070112 -0.4532396 -0.83311 0.1750269 -0.5246841 -0.7949895 0.1507943 -0.5875824 -0.8011949 0.1670325 -0.574619 -0.8460873 0.1954762 -0.4959086 -0.7919762 0.150155 -0.5918 -0.7881495 0.1496645 -0.59701 -0.7840847 0.1495108 -0.6023768 -0.7798028 0.1497285 -0.6078562 -0.7752634 0.1503709 -0.6134781 -0.7704581 0.1514669 -0.6192352 -0.768481 0.1519871 -0.6215601 -0.7767103 0.2339286 -0.5848064 -0.7885935 0.1923644 -0.5840517 -0.7865194 0.1907166 -0.5873793 -0.7926523 0.1889461 -0.5796567 -0.7914977 0.1947156 -0.5793249 -0.7721976 0.2322819 -0.5914017 -0.7836764 0.1885486 -0.5918622 -0.7676292 0.2307587 -0.5979096 -0.7803414 0.1858304 -0.597105 -0.7629938 0.2292643 -0.6043826 -0.7768969 0.1829931 -0.6024491 -0.758468 0.2275526 -0.6106932 -0.7734501 0.1808267 -0.6075168 -0.7693873 0.1784759 -0.613343 -0.753763 0.2255674 -0.6172202 -0.7654476 0.175698 -0.6190479 -0.7490236 0.223825 -0.6235913 -0.7630643 0.1739883 -0.6224637 -0.7459593 0.2248071 -0.6269025 -0.8977598 0.1107856 -0.426326 -0.9044263 0.1659005 -0.3930523 -0.9086797 0.170633 -0.3810326 -0.8788114 0.07529181 -0.4711918 -0.9143877 0.1754247 -0.3648579 -0.9213204 0.23561 -0.3092839 -0.9123592 0.1168869 -0.3923496 -0.9234926 0.1862305 -0.3353798 -0.8991892 0.2518145 -0.3578384 -0.8824044 0.241316 -0.4038923 -0.8184387 0.1844287 -0.5441914 -0.8252747 0.2018246 -0.527436 -0.8628717 0.2307562 -0.449671 -0.8145523 0.1839991 -0.5501356 -0.810556 0.1840299 -0.5559964 -0.8063626 0.1845225 -0.5618994 -0.801972 0.185493 -0.5678321 -0.7974401 0.1869615 -0.5737028 -0.8023431 0.2435412 -0.5449158 -0.8150041 0.2139672 -0.538504 -0.8120449 0.2110682 -0.5440896 -0.8148679 0.2271253 -0.5332959 -0.80645 0.2450113 -0.5381522 -0.8175519 0.2164431 -0.5336305 -0.7983575 0.2417748 -0.5515164 -0.8089522 0.2086624 -0.5495967 -0.8054684 0.2061281 -0.5556365 -0.7941923 0.2398172 -0.5583425 -0.8020681 0.2033476 -0.5615484 -0.7900188 0.2385072 -0.5647875 -0.798606 0.2004832 -0.5674812 -0.7855079 0.2371051 -0.571628 -0.7951137 0.197611 -0.5733621 -0.7811152 0.2355492 -0.5782523 -0.9139279 0.2758325 -0.2977453 -0.9340745 0.262802 -0.2417436 -0.9378596 0.2581632 -0.231886 -0.9312704 0.2699444 -0.2446743 -0.8982703 0.2652115 -0.3503904 -0.8793812 0.2543473 -0.4024876 -0.8414475 0.2204714 -0.4933139 -0.8481923 0.2322213 -0.4760705 -0.8596468 0.2574942 -0.441253 -0.8381458 0.2200732 -0.4990787 -0.8345811 0.2201052 -0.5050031 -0.8314784 0.2205047 -0.5099229 -0.8285012 0.2211717 -0.5144599 -0.8253361 0.2221507 -0.5191044 -0.8220069 0.2234623 -0.5238028 -0.8184295 0.2251695 -0.5286511 -0.8335363 0.2555055 -0.4898308 -0.8393584 0.237955 -0.4887279 -0.8373361 0.2359776 -0.4931359 -0.6387841 0.6200457 -0.45552 -0.8008228 0.3718149 -0.4695068 -0.8221837 0.3236547 -0.468254 -0.8211009 0.326072 -0.4684768 -0.8113876 0.3495077 -0.4685027 -0.791422 0.3947344 -0.466729 -0.7705488 0.4380726 -0.4629763 -0.6596495 0.61445 -0.4327977 -0.8411118 0.2394849 -0.4849516 -0.8298414 0.2539178 -0.4968793 -0.8345116 0.2333483 -0.4991383 -0.8261905 0.2525785 -0.5036005 -0.8317738 0.2300852 -0.5051864 -0.8223053 0.2511718 -0.5106142 -0.8296001 0.2280385 -0.5096686 -0.8273147 0.2258421 -0.5143402 -0.8184061 0.2495869 -0.5176077 -0.8249384 0.2233407 -0.519226 -0.8145228 0.2480893 -0.5244087 -0.8226425 0.2212635 -0.5237384 -0.8200721 0.2189728 -0.5287086 -0.8105677 0.2464755 -0.5312531 -0.9415696 0.2096039 -0.2636529 -0.9455711 0.2124429 -0.2465022 -0.956808 0.1376722 -0.2560563 -0.9480411 0.2158606 -0.2337142 -0.9342639 0.2982674 -0.1954165 -0.9332231 0.2982664 -0.2003295 -0.9277982 0.2963766 -0.2266086 -0.9603378 0.1467958 -0.2370707 -0.9670636 0.1427996 -0.2107049 -0.9662468 0.1352623 -0.2192519 -0.9500489 0.223855 -0.2174766 -0.9517369 0.2246203 -0.2091471 -0.9275019 0.2952405 -0.2292889 -0.9221688 0.288895 -0.2571855 -1 -1.72177e-6 0 -0.9348829 0.298413 -0.1922075 -0.921916 0.2872137 -0.2599603 -0.9158303 0.2814207 -0.2864564 -0.8629399 0.2595381 -0.4335605 -0.9154712 0.2792772 -0.2896841 -0.8661553 0.278576 -0.4149342 -0.8622296 0.261794 -0.4336174 -0.8650332 0.2786393 -0.4172265 -0.8597275 0.2577046 -0.4409728 -0.859479 0.2585884 -0.44094 -0.8594567 0.2566681 -0.4421039 -0.8548172 0.2615815 -0.448177 -0.8567911 0.2544065 -0.4485381 -0.8550159 0.2540083 -0.4521366 -0.8510549 0.2623725 -0.4548258 -0.8528081 0.2514507 -0.4577019 -0.6874773 0.576967 -0.4410036 -0.7486349 0.4809819 -0.4562919 -0.847699 0.2609689 -0.4618458 -0.8503059 0.2490092 -0.4636534 -0.6978303 0.5635136 -0.4421373 -0.7462915 0.4853809 -0.4554718 -0.8441259 0.2598696 -0.4689555 -0.8478527 0.2466253 -0.4693846 -0.8407183 0.2581942 -0.4759503 -0.8456419 0.2444939 -0.4744604 -0.8432195 0.2420185 -0.4800085 -0.8372741 0.2569138 -0.4826671 -0.8549771 -0.006866872 -0.5186203 -0.822272 -0.03076308 -0.5682628 -0.8796129 -0.01297044 -0.4755134 -0.7768736 -0.1063299 -0.6206138 -0.7299777 -0.1230821 -0.6722972 -0.8075697 -0.1228094 -0.5768442 -0.8374717 -0.1389224 -0.528528 -0.8854793 -0.3372048 -0.3197174 -0.8939963 -0.3435841 -0.2876121 -0.8580822 -0.4207704 -0.2943592 -0.8724278 -0.4290723 -0.2340228 -0.8692461 -0.425803 -0.251203 -0.9060038 -0.3480146 -0.2409214 -0.8490433 -0.4168918 -0.3245408 -0.8193007 -0.4908785 -0.296285 -0.8110501 -0.4859586 -0.3256408 -0.8269408 -0.4970007 -0.2629815 -0.8370937 -0.5015604 -0.2184293 -0.9429278 -0.1825671 -0.2784896 -0.9092357 -0.3500276 -0.2253251 -0.9516196 -0.1919963 -0.2399115 -0.9342503 -0.1828093 -0.306198 -0.9650748 -0.01785361 -0.2613655 -0.9553842 -0.1891907 -0.2268213 -0.9720857 -0.02923703 -0.2327976 -0.9582756 -0.02288943 -0.2849282 -0.9747787 -0.02377432 -0.221904 -0.7708308 -0.4642015 -0.4362761 -0.7465559 -0.4587922 -0.481834 -0.7846775 -0.4805848 -0.3915605 -0.845311 -0.5071011 -0.1682198 -0.8534026 -0.5113763 -0.1009873 -1 -1.37105e-6 0 -0.8539188 -0.5104896 0.1011091 -0.8533553 -0.5116286 0.1001039 -0.8586187 -0.5109169 0.04168879 -0.8573862 -0.5141326 -0.02359157 -0.8532801 -0.5133903 -0.09134328 -0.8275995 -0.4958516 0.2630788 -0.8197121 -0.4907469 0.2953637 -0.8373616 -0.4996641 0.2217236 -1 2.38131e-6 0 -0.8447044 -0.5066761 0.1724932 -0.7902141 -0.4744886 0.3878434 -0.7716795 -0.4627636 0.4363034 -0.8105888 -0.4873604 0.3246933 -0.7764543 -0.4661899 0.4240116 -0.7334639 -0.4415188 0.5168093 -0.7431659 -0.456868 0.4888519 -0.7463406 -0.4581808 0.4827486 -0.7276784 -0.4489431 0.5185888 -0.7437901 -0.4572122 0.4875791 -0.7138761 -0.4303521 0.5524292 -0.7086271 -0.439325 0.5521243 -0.7464302 -0.4486576 0.4914757 -0.7494854 -0.4503687 0.4852214 -0.7493131 -0.4502531 0.4855946 -0.7391586 -0.4608487 0.4911854 -0.7758015 -0.4937418 0.3928754 -0.7435514 -0.4600234 0.4852937 -0.7459102 -0.4483518 0.4925431 -0.8630228 -0.329272 0.3831079 -0.8222513 -0.4005659 0.4042893 -0.8322722 -0.4056373 0.3778644 -0.8436061 -0.3371434 0.4179272 -0.7907763 -0.3807543 0.4792694 -0.7940556 -0.3833245 0.4717394 -0.8387928 -0.3138606 0.44488 -0.8854725 -0.3376295 0.3192877 -0.8499999 -0.416195 0.3229273 -0.8940333 -0.3432815 0.2878583 -0.8576075 -0.421464 0.2947501 -0.9094721 -0.349689 0.224896 -0.8684213 -0.4272676 0.251569 -0.8716756 -0.4295965 0.2358569 -0.906477 -0.3474594 0.2399408 -1 -6.93821e-6 0 -0.9094371 -0.359667 0.2087197 -0.8738512 -0.4313864 0.2242538 -0.929486 -0.3630843 0.06500542 -0.8870128 -0.4381656 0.1456686 -0.8914512 -0.4391791 0.1115191 -0.9272747 -0.3505472 0.1314476 -0.8970047 -0.4399571 0.04266506 -0.9290142 -0.3643115 -0.06488448 -0.8975469 -0.4401517 -0.02600258 -0.8941269 -0.4370073 -0.09778416 -0.9262005 -0.3526203 -0.1334609 -0.890128 -0.4330699 -0.141854 -0.909308 -0.3597068 -0.2092134 -0.8741623 -0.4314199 -0.2229735 -1 3.50228e-6 0 -0.7333435 -0.4605333 0.5001165 -0.7240344 -0.4586405 0.5151924 -0.7108297 -0.4666737 0.5262477 -0.714266 -0.4702363 0.5183647 -0.7137834 -0.4697518 0.5194676 -0.5635403 -0.676401 0.4742406 -0.6651065 -0.5465697 0.5088173 -0.6984784 -0.4563745 0.5512262 -0.6995888 -0.4572368 0.5490992 -0.7016705 -0.4588585 0.5450757 -0.7022875 -0.4593206 0.5438905 -0.703161 -0.4600149 0.5421726 -0.7060039 -0.4620934 0.5366827 -0.7111255 -0.4657825 0.5266376 -0.7131757 -0.4672814 0.5225214 -0.692443 -0.4543346 0.5604488 -0.6887541 -0.4591591 0.5610623 -0.6938317 -0.4565116 0.5569515 -0.5831951 -0.5701938 0.5785866 -0.5802085 -0.6004125 0.5503299 -0.6388532 -0.5298089 0.5578254 -0.6389819 -0.520964 0.5659494 -0.6807458 -0.4555701 0.573621 -0.6747624 -0.4658544 0.5724295 -0.6898553 -0.4502187 0.566924 -0.6932528 -0.4549252 0.5589665 -0.5579911 -0.2233734 0.7992185 -0.7059218 -0.457491 0.5407184 -0.7072793 -0.4558023 0.5403706 -0.697623 -0.4379905 0.566998 -0.6936488 -0.4525137 0.5604309 -0.6954016 -0.4500609 0.5602338 -0.7053363 -0.4368562 0.5582628 -0.7082864 -0.4421297 0.5503197 -0.7195336 -0.4589865 0.5211552 -0.7056666 -0.4381957 0.5567936 -0.7103373 -0.4442393 0.5459603 -0.7220509 -0.45919 0.5174815 -0.7125646 -0.4463447 0.5413208 -0.7232496 -0.4579136 0.5169383 -0.7158929 -0.4439653 0.5388805 -0.7231365 -0.4561492 0.5186538 -0.7223587 -0.4553768 0.5204132 -0.6358104 -0.3837507 0.6696869 -0.718546 -0.4605055 0.5211778 -0.7400016 -0.4732019 0.4779934 -0.7307196 -0.4580616 0.5061903 -0.4793604 -0.752352 0.4518629 -0.5512145 -0.6923676 0.465607 -0.5812628 -0.7543659 0.3050668 -0.6055029 -0.6997769 0.3790496 -0.5240772 -0.7740303 0.3552751 -0.6388627 -0.7020989 0.3145024 -0.3446513 -0.8479099 0.4028205 -0.329455 -0.8546605 0.4012668 -0.4525104 -0.8463626 0.2809001 -0.3717885 -0.873529 0.3141982 -0.4892593 -0.743884 0.4552605 -0.2552961 -0.8907437 0.3760314 -0.2504422 -0.8904647 0.379936 -0.3122767 -0.9167176 0.2492231 -0.2650325 -0.9202587 0.2878918 -0.2393925 -0.9433786 0.2296263 -0.259352 -0.8321667 0.4901381 -0.2270042 -0.8717901 0.4341096 -0.3040921 -0.8302715 0.4670944 -0.2001779 -0.8616593 0.4663392 -0.3762146 -0.7605475 0.5291787 -0.4489161 -0.7272568 0.5192033 -0.4847984 -0.6730107 0.5585939 -0.243511 -0.9527419 0.1816185 -0.3160878 -0.9290363 0.1923018 -0.4601621 -0.8611178 0.2161645 -0.5922514 -0.7709096 0.2343858 -0.6571046 -0.7145719 0.2400014 -0.1825048 -0.8169379 0.5470872 -0.2414361 -0.7853465 0.5700346 -0.3489563 -0.7182689 0.6019298 -0.4489049 -0.6398016 0.6238096 -0.6177162 -0.5142243 0.5949792 -0.5430321 -0.5479763 0.6362689 -0.6599183 -0.4535469 0.5990018 -0.6615949 -0.4603514 0.5919196 -0.5995322 -0.5071181 0.619187 -0.6527721 -0.4498509 0.6095266 -0.6368537 -0.4531864 0.6237303 -0.5774537 -0.4968525 0.647831 -0.6269914 -0.4538241 0.6331868 -0.6271122 -0.4462849 0.6384044 -0.1926982 -0.7809559 0.5941173 -0.1548269 -0.7979705 0.5824702 -0.2692117 -0.7397292 0.6167055 -0.3423323 -0.6907989 0.6368717 -0.4790577 -0.5831277 0.6560988 -0.4098421 -0.6405671 0.6493871 -0.5422395 -0.519533 0.6603499 -0.5695608 -0.4878897 0.6614865 -0.6588431 -0.3849965 0.6462998 -0.6623547 -0.3795958 0.645905 -0.6268958 -0.4341668 0.6469164 -0.4755576 -0.5244501 0.7062558 -0.5192866 -0.4904763 0.6998389 -0.5499879 -0.4669755 0.6924213 -0.6171233 -0.3953117 0.6803584 -0.6046251 -0.4207441 0.6763157 -0.6172274 -0.4277926 0.6603211 -0.5908534 -0.4120104 0.6936424 -0.5435279 -0.4686627 0.6963713 -0.1918753 -0.7232178 0.6634303 -0.1148746 -0.7562066 0.6441704 -0.1543664 -0.7386881 0.6561335 -0.2290472 -0.6998682 0.6765515 -0.2650301 -0.6838473 0.6797882 -0.3052898 -0.6536431 0.6924948 -0.3729753 -0.6120933 0.6973029 -0.3785918 -0.6039158 0.7013944 -0.4458524 -0.5505326 0.7057829 -0.6321279 -0.4041443 0.6611217 -0.6301938 -0.4323369 0.6449346 -0.64627 -0.4130439 0.6416617 -0.6425296 -0.4362474 0.6299555 -0.6599395 -0.421099 0.6222182 -0.6554069 -0.4400916 0.6138088 -0.6739569 -0.427636 0.6024198 -0.6672791 -0.4451884 0.5971147 -0.6753882 -0.4482038 0.5856314 -0.6862199 -0.4325154 0.5848357 -0.6860842 -0.4494034 0.5721234 -0.4094778 -0.2969836 0.8626289 -0.4342566 -0.2682936 0.8599069 -0.4220499 -0.2629534 0.8675997 -0.4513129 -0.2356361 0.860693 -0.3997347 -0.2896535 0.8696626 -0.4293189 -0.3117269 0.8476507 -0.4546154 -0.2836463 0.8443162 -0.4618214 -0.2432711 0.8529597 -0.4487223 -0.3257303 0.8321948 -0.4745502 -0.2983602 0.8281204 -0.4794865 -0.2559337 0.839399 -0.4677029 -0.3390045 0.8162904 -0.494225 -0.3125758 0.8111955 -0.5106744 -0.279554 0.8130567 -0.4955958 -0.2678946 0.8262066 -0.486205 -0.3514922 0.8000363 -0.5134003 -0.3263763 0.7936615 -0.5249285 -0.2903587 0.8000887 -0.5041151 -0.3632082 0.7835483 -0.5319524 -0.3395584 0.7757105 -0.5385466 -0.3003421 0.7872498 -0.5148538 -0.3701332 0.7732573 -0.5550128 -0.3391847 0.759549 -0.5628967 -0.318987 0.7624924 -0.5510612 -0.3097125 0.7748612 -0.5742871 -0.3275667 0.750263 -0.5770581 -0.3560072 0.7350258 -0.5657168 -0.398773 0.7217651 -0.5849037 -0.3747473 0.7193415 -0.5943698 -0.3431322 0.7273133 -0.5845962 -0.3354065 0.7387489 -0.5786459 -0.4065781 0.7070101 -0.601146 -0.3854634 0.7000297 -0.6119669 -0.356645 0.7059044 -0.5710352 -0.4021753 0.7156633 -0.6035601 -0.3501845 0.7163004 -0.6203649 -0.3628739 0.6953201 -0.6401004 -0.3796533 0.6679335 -0.6286754 -0.3693799 0.6843433 -0.6525636 -0.3894873 0.6499695 -0.663952 -0.3982797 0.6328831 -0.6743168 -0.4059939 0.6168191 -0.6921222 -0.4199794 0.5870129 -0.6835702 -0.4129865 0.601809 -0.7001142 -0.4260808 0.5729705 -0.7075285 -0.4305356 0.5603951 -0.7105544 -0.4310876 0.5561259 -0.5099141 -0.4732301 0.71836 -0.5050612 -0.4690181 0.7245243 -0.4871533 -0.2144304 0.8465822 -0.4777849 -0.2049089 0.8542447 -0.4856281 -0.2113484 0.8482317 -0.5082045 -0.2281914 0.8304559 -0.5022488 -0.2245577 0.835057 -0.5318924 -0.2461085 0.8102599 -0.517057 -0.2354864 0.8229207 -0.5331626 -0.2465305 0.8092963 -0.5613944 -0.271862 0.7816185 -0.5462695 -0.2565474 0.7973539 -0.5596315 -0.2670739 0.7845279 -0.5707638 -0.279034 0.7722493 -0.6038777 -0.307478 0.7353836 -0.5811479 -0.2870642 0.7614862 -0.5931386 -0.294265 0.7493963 -0.6034798 -0.3025944 0.7377322 -0.6121052 -0.3145676 0.7255168 -0.6469448 -0.3457209 0.6796614 -0.618435 -0.3218829 0.7168889 -0.6277524 -0.3268622 0.7064618 -0.6360206 -0.3323848 0.6964182 -0.6452124 -0.339987 0.6841857 -0.6560993 -0.3543266 0.6663232 -0.6858311 -0.3844524 0.6179255 -0.6660799 -0.3647035 0.6506373 -0.6778393 -0.3732237 0.6334334 -0.6876291 -0.3827113 0.6170076 -0.6955654 -0.395286 0.5999484 -0.7195873 -0.4227248 0.5509064 -0.702187 -0.4035561 0.58658 -0.7105505 -0.4099353 0.5719013 -0.7173005 -0.4163474 0.5586905 -0.7220259 -0.4216243 0.5485541 -0.7242833 -0.424462 0.5433651 -0.6244265 -0.1949577 0.7563618 -0.5946055 -0.2173271 0.7740888 -0.6069687 -0.2214178 0.7632583 -0.6731677 -0.185192 0.7159254 -0.6512493 -0.2484263 0.7170487 -0.7095955 -0.2104279 0.6724539 -0.6936419 -0.2820896 0.6627869 -0.7445514 -0.2364033 0.624305 -0.7329024 -0.3166429 0.6021556 -0.7771971 -0.262555 0.5718652 -0.7675026 -0.3509123 0.5364705 -0.7254608 -0.4263162 0.5403342 -0.7352663 -0.4424355 0.5134534 -0.8072019 -0.289566 0.5143703 -0.7829753 -0.3682471 0.5013422 -0.7244135 -0.4244667 0.543188 -0.7260892 -0.4269676 0.5389742 -0.7252345 -0.4257163 0.5411105 -0.7427421 -0.4465852 0.4988949 -0.7425772 -0.4465046 0.4992123 -0.8199617 -0.3014695 0.4865995 -0.8347589 -0.322465 0.4463115 -0.7885568 -0.3788967 0.4843713 -0.716095 -0.4359012 0.5451588 -0.7299634 -0.1230848 0.6723122 -0.7768468 -0.1063304 0.6206473 -0.8075449 -0.1228103 0.5768788 -0.8374165 -0.1388928 0.5286232 -0.8664698 -0.1564412 0.4740847 -0.8787435 -0.1580291 0.450374 -0.8922229 -0.17759 0.415211 -0.8222478 -0.03076332 0.5682977 -0.8549637 -0.006866753 0.5186426 -0.8795807 -0.01293992 0.4755736 -0.9047717 -0.01770108 0.425529 -0.9164804 -0.008942008 0.3999798 -0.895495 -0.1669096 0.4125893 -0.9278274 -0.02859687 0.3719123 -0.8788376 0.075383 0.4711285 -0.8977512 0.110754 0.4263525 -0.9122578 0.1168286 0.3926026 -0.9262603 0.1243966 0.3557633 -0.9326565 0.1387387 0.3330218 -0.9297714 -0.01602262 0.3677884 -0.9401387 0.1225949 0.3179778 -0.9043872 0.165874 0.3931534 -0.9111286 0.1776233 0.3718799 -0.9234471 0.186136 0.3355576 -0.9133199 0.179728 0.3654378 -0.9305669 0.1997799 0.3068115 -0.9303295 0.2062448 0.3032329 -0.9327208 0.2039583 0.2973768 -0.9325677 0.2040802 0.2977734 -0.9336616 0.2033773 0.2948116 -0.9408403 0.1352602 0.3106836 -0.8938239 0.2183668 0.3916565 -0.9129689 0.2012712 0.3549333 -0.9100854 0.2183655 0.3522232 -0.9013935 0.2287131 0.3676684 -0.9212856 0.2355478 0.309435 -0.9214056 0.250227 0.2973182 -0.9136418 0.2605391 0.3120549 -0.9270021 0.2668023 0.2635977 -0.9280706 0.2667108 0.2599049 -0.8801414 0.2050275 0.4281529 -0.885322 0.2185456 0.4104178 -0.8607712 0.1919674 0.4714038 -0.8669659 0.2069523 0.4533663 -0.8408339 0.1883338 0.5074729 -0.8502032 0.2099414 0.4827828 -0.8824044 0.241316 0.4038923 -0.8687099 0.2431802 0.4315167 -0.8991833 0.2517518 0.3578971 -0.879453 0.2543809 0.4023095 -0.8663905 0.2483074 0.4332563 -0.8665075 0.2484891 0.432918 -0.8663148 0.2479981 0.4335847 -0.8679391 0.2529137 0.4274536 -0.8983899 0.2652107 0.3500843 -0.9139807 0.275891 0.2975289 -0.9310212 0.2702788 0.2452529 -0.9373532 0.2587686 0.2332549 -0.9336398 0.263166 0.2430235 -0.9312171 0.2652772 0.2499258 -0.9288148 0.2665223 0.2574276 -0.9154775 0.279096 0.2898386 -0.8690243 0.2785761 0.4088916 -0.9157939 0.2815409 0.2864545 -0.868022 0.2637149 0.4207047 -0.8720892 0.2787633 0.4021834 -0.9219883 0.287034 0.2599024 -0.9221951 0.2891378 0.2568181 -0.9276641 0.2950604 0.2288641 -0.92787 0.2966449 0.2259628 -0.9336386 0.2983542 0.1982517 -0.9331258 0.2983255 0.2006945 -0.9348319 0.2983552 0.1925452 -0.9348878 0.2984756 0.1920864 -0.9567988 0.1374572 0.2562063 -0.9478687 0.2155884 0.234663 -0.9451484 0.2120472 0.2484566 -0.9510253 0.2218173 0.2152861 -0.9499155 0.2212654 0.2206856 -0.9658104 0.1361461 0.2206232 -0.9603378 0.1467958 0.2370707 -0.949134 0.1337028 0.2850759 -0.9409369 0.2096667 0.2658526 -0.93884 0.2076849 0.2746752 -0.943619 0.1244567 0.3067471 -0.9360917 0.2037171 0.2867605 -0.8968436 0.2699137 0.3504545 -0.9091261 0.3291153 0.2552902 -0.8575368 0.4997873 0.1218338 -0.701366 0.7081108 -0.08163934 -0.8805046 0.4438993 0.1663287 -0.9015746 0.2966184 0.31493 -0.9521614 0.2891978 0.09875935 -0.8873434 0.4262605 0.1758511 -0.8863729 0.4286745 0.1748757 -0.8845446 0.433559 0.1720685 -0.8810363 0.442624 0.166911 -0.9521147 0.2917963 0.09128361 -0.9563618 0.2921852 -2.74668e-4 -0.9518439 0.2902715 0.0986697 -0.9344949 0.2870321 -0.2105513 -0.955035 0.2964933 0 -0.9516389 0.2911499 -0.09805709 -0.9325904 0.2845656 -0.2220308 -0.9349845 0.2851403 -0.2109483 -0.9525795 0.2910965 -0.08862906 -0.8901945 0.2719597 -0.3655022 -0.895671 0.2795844 -0.3458411 -0.9036441 0.2801361 -0.3239617 -0.8892484 0.2792845 -0.3622672 -0.9117867 0.2809888 -0.2994833 -0.9194481 0.2820268 -0.2740002 -0.9264045 0.2832164 -0.2481195 -0.8721072 0.2787593 -0.4021471 -0.8786491 0.2789154 -0.3875334 -0.8842977 0.2790688 -0.3743501 -0.7329161 0.2739089 -0.6227422 -0.7309035 0.2740011 -0.625063 -0.737513 0.2740267 -0.6172391 -0.7420089 0.2741218 -0.6117842 -0.7465911 0.274215 -0.6061418 -0.7515888 0.2743343 -0.5998793 -0.7566276 0.2745491 -0.5934119 -0.7615093 0.2747012 -0.5870629 -0.766251 0.2747969 -0.580815 -0.7708225 0.2748556 -0.5747063 -0.7752604 0.27486 -0.5687033 -0.7831885 0.2758342 -0.5572535 -0.7795756 0.2755554 -0.5624334 -0.7872872 0.2755017 -0.5516138 -0.7912425 0.2751922 -0.5460813 -0.7950586 0.274918 -0.5406497 -0.798964 0.2746429 -0.5350028 -0.8033248 0.2743365 -0.5285915 -0.8076697 0.2741878 -0.5220066 -0.8118723 0.273971 -0.5155612 -0.8158595 0.2737843 -0.5093286 -0.8228583 0.2738792 -0.49789 -0.8196903 0.2740033 -0.5030209 -0.8264063 0.2733935 -0.4922486 -0.8297874 0.2729945 -0.4867512 -0.8354893 0.2729012 -0.4769515 -0.8330612 0.2736687 -0.4807437 -0.8384212 0.2722916 -0.4721307 -0.8415435 0.2718062 -0.4668256 -0.8452289 0.271102 -0.4605345 -0.8487106 0.2706754 -0.4543405 -0.8516456 0.2684797 -0.4501315 -0.759889 0.3212109 -0.5651481 -0.7628709 0.3106602 -0.5670258 -0.7610902 0.3096793 -0.5699478 -0.7575393 0.307325 -0.5759215 -0.7541293 0.3041848 -0.5820316 -0.750887 0.3002144 -0.5882518 -0.7478253 0.2953395 -0.5945856 -0.7418655 0.3114199 -0.5938464 -0.7545909 0.3267402 -0.5690638 -0.7291926 0.3160862 -0.6069331 -0.7255941 0.3133407 -0.6126425 -0.7223647 0.310047 -0.6181102 -0.7193208 0.3060218 -0.6236413 -0.718199 0.3043946 -0.625727 -0.9684357 0.1450578 -0.2027086 -0.9533514 0.2250773 -0.2011505 -0.9493612 0.3042156 -0.0785259 -0.9442134 0.3058363 -0.1221697 -0.9483022 0.3056223 -0.08554613 -0.9700545 0.2291995 -0.08038771 -0.9815379 0.1372462 -0.1332176 -0.9645383 0.2234332 -0.1405118 -0.9530801 0.3027186 0 -0.9506231 0.2986033 -0.08456963 -0.9524365 0.304732 -0.001800596 -0.9575169 -0.1937374 -0.2136055 -0.971713 -0.19325 -0.1357511 -0.9771617 -0.0243237 -0.2111008 -0.9778124 -0.1982237 -0.06775313 -0.990356 -0.02813887 -0.1356589 -0.9869469 0.1473447 -0.065005 -0.9973734 -0.02545315 -0.06781405 -0.9717932 -0.1933393 0.1350476 -0.9575708 -0.1940106 0.2131156 -0.9974422 -0.02542203 0.06680536 -0.9904486 -0.02810841 0.1349876 -0.9555038 -0.1892818 0.2262408 -0.9772427 -0.02426242 0.2107324 -0.9778674 -0.1982836 0.06677609 -0.9869787 0.1475585 0.06402844 -0.9816084 0.1373653 0.1325739 -0.9671659 0.1436817 0.2096324 -0.9685283 0.145882 0.2016712 -0.9750096 -0.02313309 0.220955 -0.9705431 0.2262088 0.08292084 -0.9644906 0.2234293 0.140845 -0.9538956 0.2236112 0.2002033 -1 -1.66357e-5 0 -0.9482597 0.3043367 0.09045869 -0.9441748 0.3058336 0.1224738 -0.9484313 0.3066524 0.08026432 -0.9529143 0.2229153 0.2055802 -1 9.90256e-6 0 -0.9729452 0.2310287 -0.001892149 -0.9517481 -0.1919671 0.2394248 -0.9429118 -0.182564 0.2785459 -0.9720696 -0.02801668 0.2330147 -0.9342678 -0.1828127 0.3061427 -0.9650671 -0.01785349 0.261394 -0.9582947 -0.02288919 0.2848638 -0.9036104 -0.1815277 0.3879896 -0.9451099 -0.02212619 0.3260031 -0.9349916 -0.0298174 0.3534144 -0.9167363 -0.1758822 0.3586924 -0.9506231 0.2986033 0.08456963 -1 1.61726e-7 0 -1 1.6658e-7 0 -1 0 0 -1 2.54066e-7 0 -1 -2.24845e-7 0 -1 2.92521e-7 0 -1 -1.36813e-7 0 -1 -4.41155e-7 0 -1 -1.6658e-7 0 -1 -2.54066e-7 0 -1 2.24845e-7 0 -1 -2.92521e-7 0 -1 1.36814e-7 0 -1 4.41158e-7 0 0.9832548 -0.1822363 -9.4625e-6 0.983258 -0.1822192 3.19412e-5 0.983258 -0.182219 -1.10751e-5 0.9832547 -0.1822367 1.83435e-5 0.9831181 -0.1829722 3.9593e-5 0.9832497 -0.182264 0 0.9832543 -0.1822392 0 0.9832716 -0.1821454 -1.01062e-5 0.983255 -0.1822357 -2.51467e-6 0.9832538 -0.1822417 -1.00265e-5 0.9832543 -0.1822392 0 0.9832494 -0.1822658 1.63385e-5 0.983254 -0.1822412 -1.69096e-6 0.9832562 -0.1822288 -3.59093e-6 0.9832735 -0.1821355 0 0.9832568 -0.1822255 -1.31172e-5 0.1444185 0.7796832 -0.6092925 0.1445986 0.7796362 -0.6093101 0.1443254 0.7797055 -0.6092861 0.1446618 0.7796173 -0.6093192 0.1822032 0.9832609 0 0 0 -1 0 0 1 0.1760017 0.9493777 0.260203 0.1806448 0.9747005 0.1316305 0.1760058 0.9494003 0.2601176 0.1683464 0.9077153 0.3843339 -0.1822575 -0.9832509 0 -0.1822574 -0.9832509 0 -0.1158675 -0.6252685 0.7717603 -0.1821985 -0.9832618 0 -0.1158663 -0.6253216 0.7717176 -0.1821985 -0.9832618 0 0.1821985 0.9832618 0 1.33344e-6 0 -1 0.1682211 0.9077286 -0.3843571 0.1682191 0.907718 -0.3843832 0.02401858 0.1294623 -0.9912935 -5.09773e-7 0 -1 0.1823897 0.9832264 0 0.1682191 0.907718 0.3843832 0.0912519 0.4927603 0.8653672 0.1109969 0.5991452 0.792909 0.09122228 0.4926432 0.865437 0.111029 0.5991236 0.7929209 0.04745739 0.2559037 0.9655367 0.04745775 0.2558752 0.9655442 0.02401858 0.1294623 0.9912935 0.02398806 0.1294624 0.9912942 -0.1821931 -0.9832628 0 -4.11683e-7 0 1 -0.1822133 -0.983259 0 -0.1822032 -0.9832609 0 -0.1822032 -0.9832609 0 -2.25469e-6 0 1 0.9832542 -0.1822397 0 0.9832621 -0.1821972 0 0.9832548 -0.1822361 0 0.9832508 -0.1822577 0 0.9832563 -0.1822282 0 0.9832549 -0.1822355 -1.78037e-6 0.9832597 -0.1822097 -2.98898e-6 0.9832251 -0.1823967 -3.99059e-5 0.9833023 -0.1819797 2.31409e-5 0.9832543 -0.182239 0 0.9832597 -0.18221 0 0.9832549 -0.1822355 0 0.9832543 -0.182239 0 0.9832639 -0.1821873 1.84291e-5 0.9832403 -0.1823142 -1.04875e-5 0.9832769 -0.1821172 3.2275e-5 0.9832453 -0.1822877 5.5766e-6 0.983264 -0.182187 1.87899e-5 0.9832529 -0.1822465 -5.59519e-6 0.9832413 -0.182309 -3.84332e-6 0.9832328 -0.1823549 1.19655e-5 0.9832534 -0.1822436 -2.82461e-5 0.9832896 -0.1820484 1.94164e-5 0.9832119 -0.1824672 -3.19445e-5 0.9842619 -0.1767151 5.66395e-4 0.9832549 -0.1822356 -8.91171e-6 0.9832532 -0.1822454 -7.15504e-6 0.9832515 -0.1822538 4.97499e-6 0.9832755 -0.1821244 3.14485e-6 0.9832243 -0.1824008 0 0.9832357 -0.1823391 0 0.9832536 -0.182243 -1.49637e-5 0.9833603 -0.1816661 2.43129e-5 0.9832623 -0.1821956 -3.30704e-5 0.9832381 -0.1823264 -1.93405e-5 0.9832462 -0.1822828 -1.40921e-5 0.182374 0.9832293 0 1.48298e-6 0 -1 -1.17019e-6 0 -1 0.182384 0.9832274 0 -0.01931846 -0.1042219 0.9943664 -0.01931852 -0.1041918 0.9943696 -0.03619557 -0.1953831 0.9800589 -0.03619515 -0.1954417 0.9800472 -0.07001066 -0.3778868 0.923201 -0.07001101 -0.3779497 0.9231752 -0.1014764 -0.5477593 0.8304591 -0.1015076 -0.5477929 0.8304332 -0.128821 -0.6953463 0.7070351 -0.1288209 -0.6953155 0.7070654 -0.1513121 -0.8165302 0.5571205 -0.1513431 -0.8165023 0.5571528 -0.1683154 -0.9076826 0.3844245 -0.1683127 -0.9076986 0.3843879 -0.178599 -0.9636474 0.1987112 -0.1785642 -0.9636548 0.1987065 -0.1821985 -0.9832618 0 -0.182169 -0.9832673 0 -0.1785367 -0.9636404 -0.1988013 -0.1786001 -0.9636533 -0.198682 -0.1683101 -0.9077147 -0.3843512 -0.168314 -0.907736 -0.3842992 -0.1513433 -0.8165643 -0.5570619 -0.1512835 -0.8165099 -0.5571579 -0.1288209 -0.6953155 -0.7070654 -0.1288236 -0.6952691 -0.7071107 -0.1014764 -0.5477593 -0.8304591 -0.07001185 -0.3779236 -0.9231859 -0.07000988 -0.3779129 -0.9231904 -0.03619515 -0.1954417 -0.9800472 -0.03619539 -0.1954124 -0.9800531 -0.01931846 -0.1042219 -0.9943664 0.1821985 0.9832618 0 0.1158466 0.625301 -0.7717372 1.1976e-6 0 1 0.1822116 0.9832593 0 0.1158748 0.6253089 -0.7717266 0.1821984 0.9832618 0 -2.14743e-6 0 1 0.1443569 0.7796491 0.6093508 0.1445679 0.779666 0.6092791 0.1442944 0.7796416 0.6093754 0.1446304 0.7796736 0.6092545 0.9832539 -0.1822413 0 0.9832539 -0.1822412 0 0.9832555 -0.1822322 0 0.9832586 -0.1822158 0 0.9832551 -0.1822351 -2.43708e-6 0.9832557 -0.1822314 0 0.9832556 -0.1822317 0 0.9832552 -0.1822344 0 0.9832553 -0.1822341 -4.19588e-5 0.9832545 -0.182238 8.73729e-6 0.9832554 -0.1822334 0 0.983254 -0.1822409 -4.19588e-5 0.9832537 -0.1822422 1.09216e-5 0.9832546 -0.1822374 0 0.06998068 0.3779506 -0.9231772 0.05014348 0.2706772 -0.9613634 0.04739546 0.2558684 -0.9655491 0.02392709 0.1294626 -0.9912956 0.1821981 0.983262 0 -1.57064e-6 0 1 0.111029 0.5991236 -0.7929209 0.1110887 0.5990855 -0.7929414 0.1109989 0.5991257 -0.7929236 0.1111208 0.5990639 -0.7929532 2.73469e-6 0 -1 0.1821931 0.9832628 0 4.96733e-7 0 1 -2.73475e-6 0 -1 -0.1822133 -0.983259 0 -0.1821931 -0.9832628 0 0.1807326 0.9746804 -0.1316583 1.26879e-7 0 1 2.09429e-6 0 1 0.1823511 0.9831094 -0.01562571 0.1823509 0.9831084 0.01568675 0.180766 0.9746656 0.1317214 0.1807621 0.974675 -0.1316576 0.1823758 0.983229 0 0.920825 -0.1931865 -0.338763 0.9251446 -0.2089922 -0.3169064 0.9337101 -0.190441 -0.3031796 0.1430726 0.7451803 -0.6513345 0.1626047 0.7696868 -0.617367 0.1528716 0.7401866 -0.6547933 0.9374333 -0.1938591 -0.2892016 0.9562622 -0.1892198 -0.2230657 0.17115 0.8032995 -0.5704539 0.1704944 0.8033187 -0.5706231 0.9221649 -0.2020669 -0.3298198 0.1281809 0.6562556 -0.7435712 0.1334311 0.6421602 -0.7548686 0.9176452 -0.1941313 -0.3467568 0.09921616 0.5023068 -0.8589785 0.104436 0.4844894 -0.8685408 0.9119929 -0.1879041 -0.3646385 0.07529121 0.3765478 -0.9233325 0.05246186 0.265819 -0.9625944 0.9085737 -0.1857371 -0.3741599 0.04004144 0.2469629 -0.9681974 0.01971513 0.1642829 -0.9862163 -0.005070149 0.05481058 -0.9984839 0.0210278 0.165293 -0.9860203 0.9102829 -0.1867137 -0.3694905 0.9117949 -0.1895554 -0.3642785 -0.005050063 0.05484026 -0.9984824 0.9608651 -0.1976726 -0.1940713 0.9439436 -0.1938 -0.2672304 0.9166498 -0.1831773 -0.3552457 0.9226481 -0.1882712 -0.3365627 0.932924 -0.1940132 -0.3033345 0.9724887 -0.1922393 -0.1315675 0.975051 -0.1997162 -0.09689778 0.9645406 -0.1978521 -0.1746885 0.9498014 -0.1936165 -0.245744 0.9570438 -0.1989836 -0.2108859 0.9796743 -0.200116 -0.01385581 0.979604 -0.2009381 -1.22077e-4 0.9764474 -0.2002945 -0.08020323 0.9784532 -0.2054873 -0.02011227 0.9786929 -0.2025566 -0.03363221 0.9782805 -0.1981891 -0.06073242 0.96889 -0.1976417 -0.1489637 0.9727825 -0.2024303 -0.1127665 0.9783946 -0.1973696 0.06155782 0.9747855 -0.2007862 0.09735643 0.9795584 -0.2011486 0.002166807 0.9794692 -0.1981889 0.03689718 0.9801405 -0.196907 0.02349942 0.980484 -0.1962677 0.01141411 0.9805924 -0.1960574 0 0.9785532 -0.1998367 -0.0499897 0.9724887 -0.1922393 0.1315675 0.9606944 -0.1984686 0.1941043 0.9757243 -0.1977023 0.09421223 0.9785472 -0.2000554 0.04922795 0.9562622 -0.1892198 0.2230657 0.9374012 -0.1944691 0.288896 0.9609866 -0.1952614 0.1959023 0.9747055 -0.1924203 0.113682 0.9681071 -0.198773 0.1525056 0.9216878 -0.1932798 0.336355 0.9220641 -0.1904677 0.3369274 0.9363078 -0.1906248 0.2949405 0.9199057 -0.1987707 0.3380292 0.9191211 -0.201031 0.338826 0.9209378 -0.1986474 0.3352804 0.9239063 -0.1954447 0.3289355 0.9346815 -0.187449 0.3020486 0.9577502 -0.190256 0.2156784 0.9474344 -0.195139 0.2535526 -0.004399001 0.05465167 0.9984958 0.9309868 -0.185709 0.3142862 0.9171215 -0.1901018 0.3503562 0.9119912 -0.189796 0.3636612 -0.004728496 0.05476689 0.9984881 0.01980674 0.1646191 0.9861584 0.020509 0.1631567 0.986387 0.04693889 0.2745836 0.9604169 -0.005053579 0.0548802 0.9984802 0.05325549 0.2546804 0.9655577 0.1001633 0.482322 0.8702488 0.09921616 0.5023068 0.8589785 0.1334325 0.6422584 0.7547847 0.09036672 0.3622605 0.927686 0.133248 0.6585494 0.7406468 0.1356265 0.7542775 0.6423948 0.1394399 0.7649815 0.6287766 0.1705672 0.8035146 0.5703254 0.1547315 0.7357838 0.659303 0.1701379 0.8028295 0.5714175 0.1709749 0.8032246 0.5706118 0.1701804 0.8019894 0.5725834 0.1705984 0.8020887 0.5723198 0.1776235 0.8763068 0.4478128 0.1812868 0.8491485 0.4960665 0.1912946 0.8894835 0.4150007 0.1949266 0.9347752 0.2969831 0.2027364 0.9456254 0.2543438 0.1928492 0.9744089 0.1154837 0.2005738 0.9796437 0.00827074 0.2077461 0.9781801 0.002288937 0.2017927 0.9711807 -0.1268376 0.1987996 0.9472432 -0.251414 0.1963884 0.9327763 -0.3022581 0.182291 0.8890541 -0.4199438 0.1680076 0.8577698 -0.485803 0.1701666 0.8019881 -0.5725892 0.1880275 0.877299 -0.4415793 0.1701563 0.8028271 -0.5714154 0.1706125 0.8020963 -0.572305 0.9033672 -0.1906226 -0.3841753 0.9117834 -0.2115266 -0.3520053 0.9041327 -0.1994737 -0.3778283 0.9048408 -0.2014894 -0.3750536 -0.00468868 0.05483663 -0.9984843 -0.00505191 0.05488091 -0.9984802 -0.004965484 0.05502337 -0.9984728 -0.00502777 0.05521333 -0.998462 0.9083709 -0.1944067 -0.3702273 0.914241 -0.2032291 -0.350516 0.9300452 -0.2109494 -0.3008593 0.9164959 -0.2109192 -0.3399244 0.931708 -0.202309 -0.3016477 0.942556 -0.2135431 -0.2568804 -0.1014443 -0.9943309 -0.03186154 0.9438153 -0.2135449 -0.2522131 0.9547998 -0.2105229 -0.2098515 0.9547024 -0.2188534 -0.20161 0.9598877 -0.2180897 -0.1762174 0.9632073 -0.2226354 -0.1505497 0.9651075 -0.2163808 -0.1474686 0.9699084 -0.2201063 -0.1040713 0.9693874 -0.2215097 -0.1059328 0.9751228 -0.2155885 -0.05154711 0.9508625 -0.2953667 -0.09284001 0.9759588 -0.2124714 -0.04858583 0.9788013 -0.2048121 0 0.9752954 -0.2144569 0.05298095 0.9754955 -0.2134841 0.05322605 0.9757444 -0.2121356 -0.05404859 0.9768797 -0.2063993 -0.05572748 0.9769858 -0.2070433 -0.05130302 0.9762699 -0.2130831 -0.03863692 0.9760189 -0.2157673 -0.02884018 0.9767947 -0.2122604 -0.0285964 0.9775884 -0.2093917 -0.02182114 0.9780408 -0.2084139 0 0.9780001 -0.2075636 0.02081435 0.9773939 -0.2096944 0.02700906 0.9765954 -0.2133556 0.02722257 0.9767952 -0.2111313 0.03598201 0.9774764 -0.2054263 0.04837328 0.9772824 -0.2049662 0.05392718 0.9759789 -0.211194 0.05350041 0.9698622 -0.2204689 0.1037339 0.9719613 -0.217324 0.08978617 0.9691364 -0.217266 0.1164917 0.9627689 -0.222823 0.1530554 0.9638651 -0.2167796 0.1548251 0.9543654 -0.2209588 0.2009077 0.9577253 -0.2142148 0.1920272 0.9528251 -0.2121967 0.2170186 0.9443162 -0.2149142 0.2491564 0.9444343 -0.2069783 0.2553507 0.9295153 -0.2112826 0.3022596 0.934583 -0.2038058 0.2915784 0.9266318 -0.2026187 0.3167004 0.9112641 -0.2119843 0.3530732 0.9135786 -0.2014914 0.3532357 0.9066748 -0.1918764 0.3756651 0.9059026 -0.1952621 0.3757834 0.9065327 -0.1920858 0.375901 0.9054811 -0.2044191 0.3719098 0.9023233 -0.2091158 0.3769395 -0.005046784 0.0549224 0.9984779 -0.005063593 0.05475866 0.9984869 -0.9735789 0.2283508 1.01985e-6 -0.9735839 0.22833 -1.43509e-7 -0.9735777 0.2283558 -2.39351e-7 -0.9735789 0.2283513 -1.37211e-6 -0.9735766 0.2283608 -4.63094e-6 -0.9735778 0.2283558 0 -0.9735799 0.2283467 1.01682e-6 -0.9735788 0.2283516 -8.71944e-7 -0.9735763 0.2283625 -8.05515e-7 -0.9735721 0.22838 0 -0.9735822 0.2283368 0 -0.9735717 0.2283818 0 -0.9735746 0.2283689 0 -0.9735843 0.2283277 0 -0.9735772 0.2283589 0 -0.9735788 0.2283512 0 -0.9735827 0.228335 0 -0.9735791 0.2283504 2.23019e-7 -0.9735168 0.2286157 2.4786e-7 -0.9735514 0.2284685 -1.68646e-6 -0.9733479 0.2293338 0 -0.004975974 0.05531716 0.9984565 -0.9735809 0.2283428 2.65502e-7 -0.01525938 0.01330614 0.9997951 -0.01489335 0.01272648 0.9998082 -0.02481216 -0.02819985 0.9992944 -0.9735785 0.2283524 0 -0.9735791 0.2283504 2.10474e-7 -0.0423606 -0.1060237 0.993461 -0.04361122 -0.1070901 0.9932925 -0.9735753 0.2283663 2.08185e-7 -0.024293 -0.02697867 0.9993408 -0.9735783 0.2283537 2.43399e-7 -0.05865758 -0.1754235 0.9827441 -0.05996954 -0.1765515 0.9824629 -0.973576 0.2283636 -4.8933e-7 -0.07510769 -0.2474189 0.9659931 -0.07654303 -0.2481239 0.9656996 -0.9735817 0.2283388 -4.70963e-7 -0.9735823 0.2283364 -1.0449e-6 -0.09757065 -0.3433133 0.9341393 -0.09891122 -0.3425728 0.93427 -0.97358 0.2283464 -9.77884e-7 -0.9735797 0.228348 0 -0.1241836 -0.4549839 0.8817983 -0.124883 -0.4528689 0.8827877 -0.9735789 0.2283511 0 -0.9735758 0.2283641 0 -0.9735814 0.2283406 -4.80392e-7 -0.1477748 -0.5551778 0.8184989 -0.1478348 -0.5527325 0.8201413 -0.9735808 0.2283429 -4.57509e-7 -0.9735767 0.2283604 2.8246e-7 -0.1661464 -0.6333645 0.7558075 -0.1658096 -0.6308274 0.758 -0.9735769 0.2283598 2.39579e-7 -0.9735797 0.2283479 -4.7235e-7 -0.1793306 -0.6885736 0.7026429 -0.9735828 0.2283347 -5.41933e-7 -0.9735731 0.2283759 -4.59169e-7 -0.1797566 -0.690827 0.7003183 -0.189435 -0.7309135 0.6556522 -0.9735786 0.2283523 -4.377e-7 -0.9735797 0.2283478 -1.2317e-6 -0.1897705 -0.7324386 0.6538508 -0.1984378 -0.768634 0.6081318 -0.9735822 0.2283372 -1.17885e-6 -0.9735761 0.2283629 -3.44943e-7 -0.1987134 -0.7701022 0.6061812 -0.2074674 -0.8067058 0.553338 -0.9735766 0.2283608 -2.88842e-7 -0.9735826 0.2283352 -4.28555e-7 -0.2076527 -0.8082404 0.5510244 -0.2154372 -0.8410265 0.4962474 -0.9735783 0.2283536 -4.65299e-7 -0.9735724 0.2283791 0 -0.2155593 -0.8422164 0.4941719 -0.2217499 -0.8686275 0.4430726 -0.9735838 0.2283305 0 -0.9735757 0.2283647 -7.51801e-7 -0.2279163 -0.8959783 0.3811524 -0.2278222 -0.8951445 0.3831624 -0.9735823 0.2283368 -7.78671e-7 -0.2218744 -0.8693389 0.4416126 -0.9735899 0.2283041 1.91683e-6 -0.2350584 -0.9251267 0.2981414 -0.9735819 0.2283381 2.14294e-7 -0.9735661 0.2284057 2.6199e-7 -0.9735847 0.2283263 1.56688e-6 -0.2349048 -0.9264352 0.2941728 -0.2414991 -0.9516527 0.18983 -0.9735761 0.228363 1.7312e-6 -0.9735531 0.2284614 -6.97322e-6 -0.2409824 -0.9526375 0.1854978 -0.2453436 -0.9672747 0.0647006 -0.9735839 0.2283296 1.34959e-6 -0.2445502 -0.9677021 0.06122142 -0.245249 -0.9669268 -0.07004058 -0.2443356 -0.9670575 -0.07141458 -0.2413427 -0.9508744 -0.1938859 -0.2406412 -0.9511204 -0.1935506 -0.2351171 -0.9246294 -0.299634 -0.2344773 -0.9249693 -0.299086 -0.2280706 -0.895039 -0.3832612 -0.2274914 -0.8951335 -0.3833845 -0.2219951 -0.868906 -0.4424031 -0.2215092 -0.8687631 -0.442927 -0.2157104 -0.8415699 -0.4952062 -0.2150984 -0.8414413 -0.4956907 -0.2079874 -0.8076564 -0.5517541 -0.2071025 -0.8073825 -0.5524871 -0.1991684 -0.7698472 -0.6063557 -0.1979778 -0.7691441 -0.6076366 -0.1902307 -0.7324481 -0.6537066 -0.1889749 -0.731423 -0.6552166 -0.1804919 -0.6906548 -0.700299 -0.1792416 -0.6901093 -0.7011574 -0.1671214 -0.6334806 -0.7554951 -0.165687 -0.6336026 -0.7557087 -0.1493911 -0.5560584 -0.8176072 -0.1473183 -0.556007 -0.8180181 -0.1288523 -0.4694778 -0.8734917 -0.1202136 -0.4572026 -0.8812007 -0.08981859 -0.3931815 -0.9150634 -0.08945244 -0.3383383 -0.9367633 -0.09735643 -0.3435553 -0.9340726 -0.07703119 -0.2492832 -0.9653621 -0.07507818 -0.2479717 -0.9658537 -0.06033581 -0.1774368 -0.9822809 -0.05838245 -0.1753914 -0.9827662 -0.04419136 -0.1076402 -0.9932074 -0.04181087 -0.1048935 -0.9936042 -0.02569723 -0.02850502 -0.9992633 -0.02359086 -0.0256356 -0.999393 -0.01568686 0.01385575 -0.999781 -0.01443523 0.0147404 -0.9997872 0.9055267 -0.1982814 -0.375108 0.8995134 -0.221567 0.3765419 0.8975862 -0.2289515 0.3767231 0.9066057 -0.2397595 0.3472484 0.8929597 -0.2512031 0.3735238 0.8894633 -0.2743407 0.3655028 0.9015267 -0.2742729 0.3347002 0.8863188 -0.3048294 0.3485945 0.8935109 -0.3204517 0.3145615 0.8769238 -0.3434387 0.336236 0.8947668 -0.3454487 0.282945 0.8732786 -0.3753871 0.3105947 0.8811732 -0.3797166 0.2816898 0.8715394 -0.4102708 0.2685087 0.8837437 -0.4013576 0.2406436 0.8686361 -0.4379498 0.2316708 0.8463574 -0.4727113 0.2454046 0.8775519 -0.4374026 0.1964222 0.8785902 -0.4371893 0.1922107 0.8480431 -0.4948419 0.1896171 0.8887132 -0.4378865 0.1358095 0.8584173 -0.4933145 0.140572 0.8397594 -0.5329219 0.103917 0.9168474 -0.3964399 0.04718214 0.7744529 -0.6326307 -0.001098632 0.9218842 -0.3847517 -0.04577833 0.8310241 -0.5459795 -0.1063271 0.8703259 -0.4725646 -0.1386197 0.8802596 -0.4518643 -0.1447821 0.8483452 -0.4939245 -0.1906541 0.8793662 -0.4355171 -0.1924576 0.9212853 -0.3520398 -0.1652313 0.8495942 -0.4716441 -0.2360967 0.8659067 -0.443971 -0.2304242 0.8998345 -0.3715434 -0.2285904 0.874441 -0.4081965 -0.2621613 0.8792859 -0.3831673 -0.2829121 0.865233 -0.391537 -0.3131625 0.894558 -0.3328155 -0.2983284 0.8784781 -0.344506 -0.3310468 0.8910945 -0.3227387 -0.3190459 0.8857232 -0.3063195 -0.348802 0.9005224 -0.2754029 -0.3364713 0.889178 -0.2770842 -0.364125 0.892834 -0.2538572 -0.3720269 0.9065504 -0.2408902 -0.3466097 0.8980875 -0.229382 -0.3752636 0.9001187 -0.220383 -0.3757895 0.9017598 -0.2081125 -0.3788386 0.9279451 -0.2304221 0.2929566 0.9249997 -0.2516595 0.284681 0.919077 -0.2817811 0.2754942 0.9115299 -0.3291848 0.2464765 0.9053775 -0.3734613 0.2020359 0.9024575 -0.4009023 0.1576325 0.9023916 -0.4203409 0.09488415 0.9032838 -0.4290423 0.001007139 0.9028878 -0.4194595 -0.09406095 0.9032787 -0.399253 -0.1571131 0.9066723 -0.3717576 -0.1993531 0.9132788 -0.3271018 -0.2427475 0.9205687 -0.2793079 -0.2730211 0.9257652 -0.2502868 -0.2833999 0.9284162 -0.2302348 -0.2916083 0.9703918 -0.2179078 -0.1041929 0.9723196 -0.2084784 -0.1055058 0.9730607 -0.2086569 -0.09805679 0.9727395 -0.2187008 -0.07712209 0.9728584 -0.2236747 -0.05929863 0.9742116 -0.2189465 -0.05453824 0.9756431 -0.2158634 -0.03903424 0.9764099 -0.2159253 0 0.9758117 -0.2152804 0.03802651 0.9745713 -0.2177243 0.05298137 0.9733315 -0.2219622 0.0579549 0.9731639 -0.2174794 0.07519912 0.9734032 -0.2077122 0.09665364 0.9726229 -0.2070741 0.105475 0.9706271 -0.2169597 0.1039783 0.9636089 -0.2222703 -0.1485058 0.9657483 -0.2125049 -0.148903 0.9671239 -0.2126274 -0.1395034 0.9675895 -0.2259051 -0.112861 0.9681257 -0.2342948 -0.08853578 0.9695982 -0.2320382 -0.0777021 0.9712462 -0.2321908 -0.05261522 0.9719439 -0.2352112 0.00100708 0.9704773 -0.2351498 0.05365258 0.9684443 -0.2364344 0.07883179 0.9668148 -0.2384153 0.09180146 0.9662013 -0.229564 0.1172845 0.9659348 -0.2152523 0.1436542 0.9651391 -0.2128714 0.1522908 0.9633355 -0.2214771 0.1514357 0.9551617 -0.2247439 -0.1927597 0.9563573 -0.2209302 -0.1912348 0.9570049 -0.2250447 -0.1830205 0.9573534 -0.2447631 -0.153511 0.9577483 -0.2605715 -0.1217404 0.9590596 -0.2642946 -0.1017503 0.9611461 -0.2681431 -0.06555557 0.9624734 -0.2713737 0.001190185 0.9612064 -0.2677461 0.06628799 0.9592574 -0.2638103 0.1011415 0.9579491 -0.2598744 0.1216511 0.957535 -0.2443965 0.1529614 0.9572008 -0.2253224 0.1816496 0.956526 -0.2200418 0.191415 0.9552705 -0.2229096 0.194344 0.9438047 -0.2259943 -0.2411623 0.94409 -0.2323144 -0.2339318 0.9431766 -0.245011 -0.2244714 0.9415726 -0.2749763 -0.1944977 0.94018 -0.3025081 -0.1566865 0.9403281 -0.3157825 -0.1267464 0.9420021 -0.326188 -0.07895284 0.943284 -0.3319866 6.10382e-4 0.942072 -0.326008 0.07886207 0.9405556 -0.3154717 0.1258285 0.9403367 -0.3020516 0.1566261 0.9414798 -0.2752506 0.1945584 0.9429423 -0.2458602 0.2245275 0.944251 -0.2320342 0.2335602 0.9447376 -0.225045 0.2383817 0.8399428 0.4587916 0.2898386 0.842691 0.4686499 0.2650271 0.8436197 0.4799799 0.2406767 0.3237529 -0.6075555 0.7253004 0.3223702 -0.607477 0.7259816 0.2851111 -0.5409237 0.7912733 0.8579251 0.4578185 0.2331666 0.361351 -0.6744302 0.6438707 0.3601706 -0.6747763 0.6441694 0.8394799 0.4587444 0.2912512 0.1998385 -0.3913149 0.8982969 0.2025232 -0.3925337 0.8971632 0.2822453 -0.5363517 0.7954021 0.8365995 0.4545568 0.3057439 0.1368469 -0.2793399 0.9503905 0.1377032 -0.2779396 0.9506774 0.8352554 0.4531522 0.3114506 0.08398973 -0.186047 0.9789445 0.08652061 -0.1640992 0.9826422 0.8363226 0.4539758 0.3073607 0.04452717 -0.08145517 0.995682 0.03961306 -0.05694764 0.997591 -0.02389585 0.006992638 0.9996901 0.003479123 -0.04156678 0.9991298 0.8510202 0.4656272 0.2428085 0.8363956 0.4688283 0.2839765 -0.02373063 0.00694859 0.9996943 0.873207 0.4551285 0.174263 0.8673793 0.4754853 0.1468572 0.8438508 0.4796979 0.2404288 0.8334555 0.472319 0.2868217 0.8842043 0.4586741 0.08832275 0.8757099 0.4803373 0.04907441 0.8598545 0.4894707 0.1451504 0.8873855 0.4610278 6.1039e-4 0.8757099 0.4803373 -0.04907441 0.867716 0.4947129 0.04825049 0.8837593 0.4595658 -0.0881409 0.8673793 0.4754853 -0.1468572 0.8598545 0.4894707 -0.1451504 0.867716 0.4947129 -0.04825049 0.8726353 0.4558957 -0.1751191 0.8507034 0.4665837 -0.2420815 0.8436955 0.4798489 -0.2406722 0.8386911 0.4592796 -0.2926767 0.8392267 0.4594413 -0.2908819 0.8363956 0.4688283 -0.2839765 0.8376141 0.4606343 -0.2936304 0.8389744 0.4594979 -0.2915199 0.8442544 0.4565071 -0.2807772 0.8502943 0.4550102 -0.2645096 0.8605177 0.4538806 -0.2313045 0.8331832 0.4732053 -0.2861511 0.8364418 0.4540048 -0.3069934 -0.02253079 0.007731318 -0.9997163 -0.02315592 0.007261037 -0.9997056 0.04599171 -0.05578821 -0.9973828 0.02978676 -0.08817011 -0.99566 0.08099895 -0.1608687 -0.9836465 -0.02382802 0.006796479 -0.999693 0.08402001 -0.1860466 -0.9789419 0.1377336 -0.278031 -0.9506462 0.06775224 -0.04355061 -0.9967513 0.1368769 -0.2793387 -0.9503866 0.202527 -0.3926327 -0.8971191 0.1998385 -0.3913149 -0.8982969 0.2853849 -0.5400675 -0.7917593 0.2813532 -0.5362162 -0.7958095 0.3237195 -0.6075807 -0.7252941 0.3603646 -0.6751503 -0.6436689 0.3231638 -0.6089116 -0.7244253 0.879471 0.4500357 -0.1549153 0.3603271 -0.6746178 -0.6442478 0.8864472 0.4569875 -0.07330596 0.8890838 0.4577261 0.004120051 0.8876132 0.4583031 -0.04583942 0.8904747 0.4543624 -0.02468961 0.8877125 0.4535461 0.07913631 0.8853228 0.4645892 0.0189827 0.8878997 0.4580345 0.0428797 0.8790208 0.4524201 0.1504608 0.3601698 -0.6747222 0.6442265 -0.02300351 0.007163882 0.9997097 0.8306981 0.4767686 0.2874589 -0.02224326 0.007457494 0.9997249 0.8415328 0.4972776 0.2110393 0.8306785 0.4766529 0.2877069 0.8307147 0.4766256 0.2876479 0.8305516 0.4780845 0.285691 0.8305885 0.4807434 0.2810847 0.8343912 0.485131 0.2616094 0.8525219 0.5068926 0.1275395 0.858249 0.5115252 0.0418412 0.8520562 0.5074677 -0.1283623 0.8584827 0.5111404 -0.0417506 0.8395574 0.4998158 -0.2129031 0.8342117 0.4879103 -0.2569716 -0.02367949 0.006785273 -0.9996966 0.8383296 0.4768307 -0.2642651 0.8341881 0.4769579 -0.2768419 0.8312318 0.4766246 -0.2861517 0.8303107 0.4764077 -0.2891712 0.8378045 0.4793639 -0.261331 -0.02375245 0.006609201 -0.999696 -0.04608321 0.04617476 0.9978699 -0.04599189 0.04614448 0.9978755 -0.06885069 0.08673483 0.9938495 -0.02385044 0.006787776 0.9996925 -0.112769 0.1641025 0.9799764 -0.1135617 0.1670312 0.9793898 -0.06857705 0.08572894 0.9939556 -0.1563167 0.2412197 0.9577986 -0.1576308 0.2464411 0.9562528 -0.2137877 0.3219786 0.9222932 -0.2017294 0.3220957 0.9249647 -0.2538257 0.3849044 0.8873676 0.8378947 0.4831437 0.2539777 -0.2950013 0.4496741 0.8430703 -0.2842608 0.4676234 0.8369733 0.8434055 0.506379 0.1795765 0.8346083 0.4924576 0.2468087 0.8336514 0.5012407 0.2319123 0.8363497 0.5066807 0.2092705 0.8511373 0.5151259 0.1010475 0.8452652 0.5101317 0.1590365 0.8465085 0.5156509 0.1323919 0.8547253 0.517944 0.03433424 0.8526023 0.5172012 0.07464885 0.8520732 0.5181596 -0.07404023 0.8561865 0.5166601 0.002685666 0.8527384 0.5209942 -0.03744709 0.8483452 0.5122666 -0.1337661 0.8503273 0.5162636 -0.1020563 0.8388307 0.5018335 -0.2110124 0.8528525 0.5010299 -0.1470098 0.8432116 0.5067998 -0.1792995 -0.2891739 0.4561471 -0.8416106 -0.2738189 0.3595474 -0.8920477 -0.2223653 0.3294889 -0.9176005 0.8981463 0.4203089 -0.1291263 0.888176 0.4336504 -0.1519562 0.8780984 0.4453666 -0.1749055 -0.2995789 0.4727768 -0.8286946 -0.210554 0.3338222 -0.9188198 -0.1580588 0.2474495 -0.9559217 -0.1566566 0.241745 -0.9576107 -0.1138348 0.1676393 -0.9792542 -0.1130133 0.1644691 -0.9798867 -0.068973 0.08694875 -0.9938223 -0.06863689 0.0858801 -0.9939385 -0.04611355 0.04623562 -0.9978656 -0.04608434 0.04629796 -0.9978641 -0.3287491 0.5274268 0.7834189 -0.3647295 0.5761634 0.7314427 -0.3579571 0.5971039 0.7178676 -0.392721 0.6469765 0.6535992 -0.4227553 0.6829946 0.5956479 -0.4189375 0.7037429 0.573792 -0.4448485 0.7428994 0.5002104 -0.4595344 0.7614347 0.4572148 -0.4591058 0.7859398 0.4141505 -0.4762167 0.8033487 0.3575593 -0.4761586 0.8161107 0.3274697 -0.490381 0.8283496 0.270857 -0.4883409 0.8411452 0.2323747 -0.4996276 0.8469345 0.1818631 -0.4977651 0.8591103 0.1189936 -0.5047497 0.8585231 0.090366 -0.5021908 0.864757 3.0519e-5 -0.5048758 0.8585606 -0.0892986 -0.4977404 0.8591202 -0.1190255 -0.5060287 0.8625164 6.10372e-4 -0.4997285 0.8471029 -0.1807983 -0.4884594 0.8411695 -0.2320373 -0.4905978 0.828599 -0.269699 -0.4764919 0.8164423 -0.3261557 -0.4765331 0.8036726 -0.3564079 -0.4596228 0.7867608 -0.4120125 -0.4576715 0.7619517 -0.4582209 -0.4504035 0.7388412 -0.5012487 -0.427545 0.7053318 -0.5654312 -0.4185705 0.6861016 -0.5950324 -0.4006868 0.64011 -0.6555222 -0.3702552 0.6006424 -0.7086182 -0.3595518 0.5807276 -0.7303959 -0.3397105 0.5157459 -0.7865133 0.3597165 -0.6739679 -0.6452684 0.3601983 -0.6747648 -0.644166 0.3927218 -0.7464706 -0.5371695 0.394093 -0.7347471 -0.5521209 0.4246707 -0.7847328 -0.4514968 0.3597252 -0.6739656 -0.645266 0.4240397 -0.8073968 -0.4102448 0.4673154 -0.8531132 -0.2319791 0.4597992 -0.8768412 -0.1404789 0.4817149 -0.8763281 0 0.4597731 -0.8768498 0.1405108 0.4673154 -0.8531132 0.2319791 0.426239 -0.8049587 0.4127492 0.4201803 -0.7855492 0.4542697 0.3890284 -0.7416781 0.5464161 0.3597223 -0.6739715 0.6452614 0.4003551 -0.7457141 0.5325657 0.3597182 -0.6739715 0.6452636 -0.871208 -0.4909142 0 -0.8712142 -0.4909031 0 -0.8712136 -0.4909044 0 -0.8712097 -0.490911 0 -0.8712106 -0.4909096 0 -0.871226 -0.4908824 0 -0.8712123 -0.4909067 0 -0.8712115 -0.490908 0 -0.8712291 -0.4908766 0 -0.8712153 -0.4909012 0 -0.8712034 -0.4909222 0 -0.87121 -0.4909105 0 -0.8712097 -0.4909111 0 -0.8712008 -0.4909268 0 -0.8712141 -0.4909033 0 -0.8712119 -0.4909073 2.25845e-6 -0.8712123 -0.4909065 0 -0.8712295 -0.4908761 0 -0.8712142 -0.4909031 0 -0.8711815 -0.4909611 1.11684e-5 -0.8712024 -0.4909242 3.8259e-6 -0.871214 -0.4909033 0 -0.8712242 -0.4908855 -1.45167e-6 -0.8712118 -0.4909073 0 -0.8712118 -0.4909075 0 -0.8712124 -0.4909063 0 -0.8712138 -0.4909038 0 -0.8712098 -0.4909109 0 -0.8712131 -0.4909049 0 -0.8712133 -0.4909049 -7.94838e-7 -0.8712126 -0.490906 0 -0.8712206 -0.4908917 -8.73162e-7 -0.8712089 -0.4909126 6.19321e-7 -0.8712133 -0.4909048 -5.37712e-7 -0.8712199 -0.4908928 -1.80131e-6 -0.8712096 -0.4909114 7.33154e-7 -0.8712128 -0.4909056 -1.55985e-6 -0.8712151 -0.4909015 0 -0.8712214 -0.4908903 0 -0.8712164 -0.4908994 -1.01624e-6 -0.8712064 -0.490917 2.10339e-6 -0.8712162 -0.4908996 -1.5928e-6 -0.8711967 -0.4909342 0 -0.8712289 -0.4908771 0 -0.8712335 -0.4908687 0 -0.8712029 -0.4909234 0 -0.8711075 -0.4910925 -1.06852e-5 - - - - - - - - - - 0.312631 0.136698 0.323985 0.137749 0.311605 0.1366209 0.307214 0.137432 0.311605 0.1366209 0.323985 0.137749 0.298191 0.135299 0.312631 0.136698 0.311605 0.1366209 0.294212 0.135592 0.298191 0.135299 0.311605 0.1366209 0.307214 0.137432 0.294212 0.135592 0.311605 0.1366209 0.312631 0.136698 0.336114 0.138861 0.323985 0.137749 0.307214 0.137432 0.323985 0.137749 0.336114 0.138861 0.312631 0.136698 0.336895 0.138879 0.336114 0.138861 0.340058 0.139149 0.336114 0.138861 0.336895 0.138879 0.340058 0.139149 0.339521 0.139158 0.336114 0.138861 0.307214 0.137432 0.336114 0.138861 0.339521 0.139158 0.312631 0.136698 0.337187 0.138953 0.336895 0.138879 0.340463 0.139644 0.336895 0.138879 0.337187 0.138953 0.340058 0.139149 0.336895 0.138879 0.340463 0.139644 0.326007 0.138384 0.338188 0.139526 0.337187 0.138953 0.340463 0.139644 0.337187 0.138953 0.338188 0.139526 0.313591 0.137234 0.326007 0.138384 0.337187 0.138953 0.312631 0.136698 0.313591 0.137234 0.337187 0.138953 0.316413 0.139415 0.338188 0.139526 0.326007 0.138384 0.336292 0.140258 0.338188 0.139526 0.316413 0.139415 0.341617 0.140718 0.338188 0.139526 0.336292 0.140258 0.341617 0.140718 0.340463 0.139644 0.338188 0.139526 0.316413 0.139415 0.326007 0.138384 0.313591 0.137234 0.299192 0.135369 0.313591 0.137234 0.312631 0.136698 0.300289 0.135912 0.313591 0.137234 0.299192 0.135369 0.293944 0.135215 0.313591 0.137234 0.300289 0.135912 0.316413 0.139415 0.313591 0.137234 0.293944 0.135215 0.299192 0.135369 0.312631 0.136698 0.298191 0.135299 0.286465 0.133897 0.27897 0.132984 0.27276 0.1321099 0.253855 0.129788 0.27276 0.1321099 0.27897 0.132984 0.274319 0.132254 0.286465 0.133897 0.27276 0.1321099 0.26686 0.131162 0.274319 0.132254 0.27276 0.1321099 0.266073 0.1310189 0.27276 0.1321099 0.269028 0.131564 0.253855 0.129788 0.269028 0.131564 0.27276 0.1321099 0.266073 0.1310189 0.26686 0.131162 0.27276 0.1321099 0.286465 0.133897 0.285274 0.133805 0.27897 0.132984 0.281001 0.133707 0.27897 0.132984 0.285274 0.133805 0.281001 0.133707 0.253855 0.129788 0.27897 0.132984 0.299192 0.135369 0.298191 0.135299 0.285274 0.133805 0.281001 0.133707 0.285274 0.133805 0.298191 0.135299 0.286465 0.133897 0.299192 0.135369 0.285274 0.133805 0.294212 0.135592 0.281001 0.133707 0.298191 0.135299 0.300289 0.135912 0.299192 0.135369 0.286465 0.133897 0.287727 0.1344839 0.286465 0.133897 0.274319 0.132254 0.293944 0.135215 0.300289 0.135912 0.286465 0.133897 0.287727 0.1344839 0.293944 0.135215 0.286465 0.133897 0.287727 0.1344839 0.274319 0.132254 0.275771 0.1329219 0.272067 0.132389 0.275771 0.1329219 0.274319 0.132254 0.268336 0.131853 0.272067 0.132389 0.274319 0.132254 0.267619 0.131442 0.268336 0.131853 0.274319 0.132254 0.26686 0.131162 0.267619 0.131442 0.274319 0.132254 0.287727 0.1344839 0.275771 0.1329219 0.293944 0.135215 0.296597 0.137521 0.293944 0.135215 0.275771 0.1329219 0.267842 0.134246 0.275771 0.1329219 0.272067 0.132389 0.27819 0.135239 0.296597 0.137521 0.275771 0.1329219 0.267842 0.134246 0.27819 0.135239 0.275771 0.1329219 0.316413 0.139415 0.293944 0.135215 0.296597 0.137521 0.266073 0.1310189 0.269028 0.131564 0.265274 0.131013 0.253855 0.129788 0.265274 0.131013 0.269028 0.131564 0.256094 0.1294929 0.266073 0.1310189 0.265274 0.131013 0.253855 0.129788 0.256094 0.1294929 0.265274 0.131013 0.267842 0.134246 0.272067 0.132389 0.268336 0.131853 0.257811 0.129966 0.268336 0.131853 0.267619 0.131442 0.260133 0.13082 0.268336 0.131853 0.257811 0.129966 0.267842 0.134246 0.268336 0.131853 0.260133 0.13082 0.256781 0.129507 0.267619 0.131442 0.26686 0.131162 0.257811 0.129966 0.267619 0.131442 0.256781 0.129507 0.255693 0.129253 0.26686 0.131162 0.266073 0.1310189 0.256781 0.129507 0.26686 0.131162 0.255693 0.129253 0.255693 0.129253 0.266073 0.1310189 0.256094 0.1294929 0.229008 0.120976 0.225125 0.119643 0.22336 0.118185 0.211212 0.111828 0.22336 0.118185 0.225125 0.119643 0.226042 0.1186079 0.229008 0.120976 0.22336 0.118185 0.218323 0.1128489 0.226042 0.1186079 0.22336 0.118185 0.211212 0.111828 0.218323 0.1128489 0.22336 0.118185 0.229008 0.120976 0.227302 0.121013 0.225125 0.119643 0.211212 0.111828 0.225125 0.119643 0.227302 0.121013 0.2336159 0.123224 0.229894 0.1223 0.227302 0.121013 0.224607 0.122168 0.227302 0.121013 0.229894 0.1223 0.229008 0.120976 0.2336159 0.123224 0.227302 0.121013 0.224607 0.122168 0.211212 0.111828 0.227302 0.121013 0.2336159 0.123224 0.232896 0.123509 0.229894 0.1223 0.225874 0.123079 0.229894 0.1223 0.232896 0.123509 0.225874 0.123079 0.224607 0.122168 0.229894 0.1223 0.239647 0.125351 0.236187 0.124654 0.232896 0.123509 0.227407 0.123946 0.232896 0.123509 0.236187 0.124654 0.2336159 0.123224 0.239647 0.125351 0.232896 0.123509 0.227407 0.123946 0.225874 0.123079 0.232896 0.123509 0.239647 0.125351 0.239766 0.125743 0.236187 0.124654 0.22916 0.124772 0.236187 0.124654 0.239766 0.125743 0.22916 0.124772 0.227407 0.123946 0.236187 0.124654 0.24699 0.12736 0.247571 0.1277379 0.239766 0.125743 0.233767 0.126272 0.239766 0.125743 0.247571 0.1277379 0.239647 0.125351 0.24699 0.12736 0.239766 0.125743 0.231253 0.125553 0.22916 0.124772 0.239766 0.125743 0.233767 0.126272 0.231253 0.125553 0.239766 0.125743 0.255693 0.129253 0.256094 0.1294929 0.247571 0.1277379 0.244586 0.1283749 0.247571 0.1277379 0.256094 0.1294929 0.24699 0.12736 0.255693 0.129253 0.247571 0.1277379 0.236779 0.126968 0.233767 0.126272 0.247571 0.1277379 0.240449 0.127671 0.236779 0.126968 0.247571 0.1277379 0.244586 0.1283749 0.240449 0.127671 0.247571 0.1277379 0.249041 0.1290799 0.256094 0.1294929 0.253855 0.129788 0.249041 0.1290799 0.244586 0.1283749 0.256094 0.1294929 0.256781 0.129507 0.255693 0.129253 0.24699 0.12736 0.248364 0.127749 0.24699 0.12736 0.239647 0.125351 0.248364 0.127749 0.256781 0.129507 0.24699 0.12736 0.2413 0.125897 0.239647 0.125351 0.2336159 0.123224 0.2413 0.125897 0.248364 0.127749 0.239647 0.125351 0.235543 0.123952 0.2336159 0.123224 0.229008 0.120976 0.235543 0.123952 0.2413 0.125897 0.2336159 0.123224 0.231202 0.121911 0.229008 0.120976 0.226042 0.1186079 0.231202 0.121911 0.235543 0.123952 0.229008 0.120976 0.231202 0.121911 0.226042 0.1186079 0.228489 0.1197749 0.219853 0.112112 0.228489 0.1197749 0.226042 0.1186079 0.219853 0.112112 0.226042 0.1186079 0.218323 0.1128489 0.233062 0.123405 0.231202 0.121911 0.228489 0.1197749 0.233062 0.123405 0.228489 0.1197749 0.230484 0.1216 0.222337 0.113238 0.230484 0.1216 0.228489 0.1197749 0.222337 0.113238 0.228489 0.1197749 0.219853 0.112112 0.257811 0.129966 0.256781 0.129507 0.248364 0.127749 0.249637 0.1284199 0.248364 0.127749 0.2413 0.125897 0.249637 0.1284199 0.257811 0.129966 0.248364 0.127749 0.242793 0.1268129 0.2413 0.125897 0.235543 0.123952 0.242793 0.1268129 0.249637 0.1284199 0.2413 0.125897 0.237233 0.125142 0.235543 0.123952 0.231202 0.121911 0.237233 0.125142 0.242793 0.1268129 0.235543 0.123952 0.233062 0.123405 0.237233 0.125142 0.231202 0.121911 0.233174 0.1247439 0.233062 0.123405 0.230484 0.1216 0.233174 0.1247439 0.230484 0.1216 0.231867 0.12392 0.2244009 0.115009 0.231867 0.12392 0.230484 0.1216 0.2244009 0.115009 0.230484 0.1216 0.222337 0.113238 0.256995 0.130347 0.257811 0.129966 0.249637 0.1284199 0.256995 0.130347 0.260133 0.13082 0.257811 0.129966 0.247573 0.128756 0.249637 0.1284199 0.242793 0.1268129 0.25256 0.129653 0.256995 0.130347 0.249637 0.1284199 0.247573 0.128756 0.25256 0.129653 0.249637 0.1284199 0.242583 0.127728 0.242793 0.1268129 0.237233 0.125142 0.245691 0.128389 0.247573 0.128756 0.242793 0.1268129 0.242583 0.127728 0.245691 0.128389 0.242793 0.1268129 0.237201 0.126313 0.237233 0.125142 0.233062 0.123405 0.240199 0.127147 0.242583 0.127728 0.237233 0.125142 0.23974 0.127029 0.240199 0.127147 0.237233 0.125142 0.237201 0.126313 0.23974 0.127029 0.237233 0.125142 0.2349849 0.125548 0.237201 0.126313 0.233062 0.123405 0.234953 0.125535 0.2349849 0.125548 0.233062 0.123405 0.233174 0.1247439 0.234953 0.125535 0.233062 0.123405 0.2377949 0.135298 0.233174 0.1247439 0.231867 0.12392 0.231576 0.123588 0.231867 0.12392 0.2244009 0.115009 0.235647 0.135783 0.231867 0.12392 0.231576 0.123588 0.2377949 0.135298 0.231867 0.12392 0.235647 0.135783 0.267842 0.134246 0.260133 0.13082 0.256995 0.130347 0.257303 0.135936 0.256995 0.130347 0.25256 0.129653 0.267842 0.134246 0.256995 0.130347 0.267639 0.1370429 0.257303 0.135936 0.267639 0.1370429 0.256995 0.130347 0.257303 0.135936 0.25256 0.129653 0.247573 0.128756 0.248914 0.136081 0.247573 0.128756 0.245691 0.128389 0.257303 0.135936 0.247573 0.128756 0.248914 0.136081 0.248914 0.136081 0.245691 0.128389 0.242583 0.127728 0.248914 0.136081 0.242583 0.127728 0.240199 0.127147 0.242647 0.1367239 0.240199 0.127147 0.23974 0.127029 0.248914 0.136081 0.240199 0.127147 0.242647 0.1367239 0.242647 0.1367239 0.23974 0.127029 0.237201 0.126313 0.242647 0.1367239 0.237201 0.126313 0.2349849 0.125548 0.242647 0.1367239 0.2349849 0.125548 0.234953 0.125535 0.2377949 0.135298 0.234953 0.125535 0.233174 0.1247439 0.242647 0.1367239 0.234953 0.125535 0.2377949 0.135298 0.178865 0.07804697 0.171033 0.07421499 0.159538 0.06657397 0.158903 0.06760597 0.159538 0.06657397 0.171033 0.07421499 0.1622959 0.06682097 0.178865 0.07804697 0.159538 0.06657397 0.156321 0.06374698 0.1622959 0.06682097 0.159538 0.06657397 0.134935 0.04589688 0.156321 0.06374698 0.159538 0.06657397 0.158903 0.06760597 0.134935 0.04589688 0.159538 0.06657397 0.178865 0.07804697 0.181343 0.08149999 0.171033 0.07421499 0.158903 0.06760597 0.171033 0.07421499 0.181343 0.08149999 0.192371 0.08802396 0.190567 0.08843296 0.181343 0.08149999 0.178961 0.08517599 0.181343 0.08149999 0.190567 0.08843296 0.178865 0.07804697 0.192371 0.08802396 0.181343 0.08149999 0.178961 0.08517599 0.158903 0.06760597 0.181343 0.08149999 0.203401 0.09692996 0.198795 0.095025 0.190567 0.08843296 0.178961 0.08517599 0.190567 0.08843296 0.198795 0.095025 0.192371 0.08802396 0.203401 0.09692996 0.190567 0.08843296 0.203401 0.09692996 0.206113 0.101284 0.198795 0.095025 0.196161 0.09967195 0.198795 0.095025 0.206113 0.101284 0.196161 0.09967195 0.178961 0.08517599 0.198795 0.095025 0.212435 0.104916 0.212597 0.107221 0.206113 0.101284 0.196161 0.09967195 0.206113 0.101284 0.212597 0.107221 0.203401 0.09692996 0.212435 0.104916 0.206113 0.101284 0.219853 0.112112 0.218323 0.1128489 0.212597 0.107221 0.211212 0.111828 0.212597 0.107221 0.218323 0.1128489 0.212435 0.104916 0.219853 0.112112 0.212597 0.107221 0.211212 0.111828 0.196161 0.09967195 0.212597 0.107221 0.222337 0.113238 0.219853 0.112112 0.212435 0.104916 0.214954 0.1059949 0.212435 0.104916 0.203401 0.09692996 0.214954 0.1059949 0.222337 0.113238 0.212435 0.104916 0.205953 0.09795898 0.203401 0.09692996 0.192371 0.08802396 0.205953 0.09795898 0.214954 0.1059949 0.203401 0.09692996 0.1949509 0.08899796 0.192371 0.08802396 0.178865 0.07804697 0.1949509 0.08899796 0.205953 0.09795898 0.192371 0.08802396 0.18147 0.07896 0.178865 0.07804697 0.1622959 0.06682097 0.18147 0.07896 0.1949509 0.08899796 0.178865 0.07804697 0.18147 0.07896 0.1622959 0.06682097 0.163195 0.06703799 0.160089 0.06429696 0.163195 0.06703799 0.1622959 0.06682097 0.160089 0.06429696 0.1622959 0.06682097 0.156321 0.06374698 0.16492 0.067667 0.18147 0.07896 0.163195 0.06703799 0.160089 0.06429696 0.16492 0.067667 0.163195 0.06703799 0.2244009 0.115009 0.222337 0.113238 0.214954 0.1059949 0.217084 0.107708 0.214954 0.1059949 0.205953 0.09795898 0.217084 0.107708 0.2244009 0.115009 0.214954 0.1059949 0.208145 0.09960699 0.205953 0.09795898 0.1949509 0.08899796 0.208145 0.09960699 0.217084 0.107708 0.205953 0.09795898 0.1972039 0.09057396 0.1949509 0.08899796 0.18147 0.07896 0.1972039 0.09057396 0.208145 0.09960699 0.1949509 0.08899796 0.183776 0.08045697 0.18147 0.07896 0.16492 0.067667 0.183776 0.08045697 0.1972039 0.09057396 0.18147 0.07896 0.183776 0.08045697 0.16492 0.067667 0.166528 0.06854999 0.163527 0.06586998 0.166528 0.06854999 0.16492 0.067667 0.163527 0.06586998 0.16492 0.067667 0.160089 0.06429696 0.167275 0.06907796 0.183776 0.08045697 0.166528 0.06854999 0.166356 0.06834197 0.167275 0.06907796 0.166528 0.06854999 0.166356 0.06834197 0.166528 0.06854999 0.163527 0.06586998 0.221475 0.112702 0.2244009 0.115009 0.217084 0.107708 0.226996 0.118487 0.231576 0.123588 0.2244009 0.115009 0.221475 0.112702 0.226996 0.118487 0.2244009 0.115009 0.215179 0.106597 0.217084 0.107708 0.208145 0.09960699 0.215179 0.106597 0.221475 0.112702 0.217084 0.107708 0.208033 0.100176 0.208145 0.09960699 0.1972039 0.09057396 0.208033 0.100176 0.215179 0.106597 0.208145 0.09960699 0.190837 0.08630698 0.1972039 0.09057396 0.183776 0.08045697 0.199949 0.09341996 0.208033 0.100176 0.1972039 0.09057396 0.190837 0.08630698 0.199949 0.09341996 0.1972039 0.09057396 0.180629 0.07883 0.183776 0.08045697 0.167275 0.06907796 0.180629 0.07883 0.190837 0.08630698 0.183776 0.08045697 0.180629 0.07883 0.167275 0.06907796 0.169251 0.07098197 0.166356 0.06834197 0.169251 0.07098197 0.167275 0.06907796 0.20376 0.106599 0.180629 0.07883 0.169251 0.07098197 0.169881 0.07252097 0.169251 0.07098197 0.166356 0.06834197 0.172489 0.07489299 0.20376 0.106599 0.169251 0.07098197 0.169881 0.07252097 0.172489 0.07489299 0.169251 0.07098197 0.226303 0.119837 0.231576 0.123588 0.226996 0.118487 0.235647 0.135783 0.231576 0.123588 0.226303 0.119837 0.226303 0.119837 0.226996 0.118487 0.221475 0.112702 0.226303 0.119837 0.221475 0.112702 0.215179 0.106597 0.220103 0.115765 0.215179 0.106597 0.208033 0.100176 0.220103 0.115765 0.226303 0.119837 0.215179 0.106597 0.212686 0.111371 0.208033 0.100176 0.199949 0.09341996 0.212686 0.111371 0.220103 0.115765 0.208033 0.100176 0.212686 0.111371 0.199949 0.09341996 0.190837 0.08630698 0.20376 0.106599 0.190837 0.08630698 0.180629 0.07883 0.20376 0.106599 0.212686 0.111371 0.190837 0.08630698 0.159209 0.06148689 0.156321 0.06374698 0.155346 0.06083196 0.134935 0.04589688 0.155346 0.06083196 0.156321 0.06374698 0.162226 0.03692597 0.159209 0.06148689 0.155346 0.06083196 0.162226 0.03692597 0.155346 0.06083196 0.156268 0.04923188 0.134935 0.04589688 0.156268 0.04923188 0.155346 0.06083196 0.159209 0.06148689 0.160089 0.06429696 0.156321 0.06374698 0.162733 0.06317496 0.163527 0.06586998 0.160089 0.06429696 0.159209 0.06148689 0.162733 0.06317496 0.160089 0.06429696 0.165625 0.06575697 0.166356 0.06834197 0.163527 0.06586998 0.162733 0.06317496 0.165625 0.06575697 0.163527 0.06586998 0.168875 0.06966996 0.166356 0.06834197 0.165625 0.06575697 0.168875 0.06966996 0.169881 0.07252097 0.166356 0.06834197 0.167174 0.05686098 0.165625 0.06575697 0.162733 0.06317496 0.186426 0.08204197 0.165625 0.06575697 0.167174 0.05686098 0.186426 0.08204197 0.168875 0.06966996 0.165625 0.06575697 0.166496 0.03914499 0.162733 0.06317496 0.159209 0.06148689 0.16752 0.05494797 0.167174 0.05686098 0.162733 0.06317496 0.169868 0.04250997 0.16752 0.05494797 0.162733 0.06317496 0.166496 0.03914499 0.169868 0.04250997 0.162733 0.06317496 0.162226 0.03692597 0.166496 0.03914499 0.159209 0.06148689 0.162226 0.03692597 0.156268 0.04923188 0.157471 0.03606289 0.134935 0.04589688 0.157471 0.03606289 0.156268 0.04923188 0.160441 0.03025895 0.162226 0.03692597 0.157471 0.03606289 0.105418 0.01844096 0.160441 0.03025895 0.157471 0.03606289 0.134935 0.04589688 0.105418 0.01844096 0.157471 0.03606289 0.179396 0.06071794 0.167174 0.05686098 0.16752 0.05494797 0.186426 0.08204197 0.167174 0.05686098 0.179396 0.06071794 0.179396 0.06071794 0.16752 0.05494797 0.169868 0.04250997 0.167962 0.032637 0.169868 0.04250997 0.166496 0.03914499 0.170036 0.03886598 0.169868 0.04250997 0.167962 0.032637 0.178704 0.05500888 0.169868 0.04250997 0.170036 0.03886598 0.179396 0.06071794 0.169868 0.04250997 0.178704 0.05500888 0.164332 0.03099495 0.166496 0.03914499 0.162226 0.03692597 0.164332 0.03099495 0.167962 0.032637 0.166496 0.03914499 0.160441 0.03025895 0.164332 0.03099495 0.162226 0.03692597 0.197331 0.01375591 0.1936179 0.01482099 0.207411 0.009556949 0.1927019 0.01457798 0.207411 0.009556949 0.1936179 0.01482099 0.204725 0.01278793 0.197331 0.01375591 0.207411 0.009556949 0.194979 0.01332396 0.207411 0.009556949 0.1927019 0.01457798 0.103559 0.01667797 0.207411 0.009556949 0.194979 0.01332396 0.292295 0.01569592 0.204725 0.01278793 0.207411 0.009556949 0.292295 0.01569592 0.207411 0.009556949 0.283415 0.005760908 0.09471297 0.01186388 0.283415 0.005760908 0.207411 0.009556949 0.103559 0.01667797 0.09471297 0.01186388 0.207411 0.009556949 0.189051 0.01804792 0.182124 0.0204119 0.1936179 0.01482099 0.1927019 0.01457798 0.1936179 0.01482099 0.182124 0.0204119 0.192443 0.01616996 0.189051 0.01804792 0.1936179 0.01482099 0.197331 0.01375591 0.192443 0.01616996 0.1936179 0.01482099 0.176306 0.02761989 0.173381 0.02635997 0.182124 0.0204119 0.180259 0.01979088 0.182124 0.0204119 0.173381 0.02635997 0.17717 0.02671897 0.176306 0.02761989 0.182124 0.0204119 0.182303 0.02238392 0.17717 0.02671897 0.182124 0.0204119 0.1826519 0.02213299 0.182303 0.02238392 0.182124 0.0204119 0.189051 0.01804792 0.1826519 0.02213299 0.182124 0.0204119 0.180259 0.01979088 0.1927019 0.01457798 0.182124 0.0204119 0.171168 0.03492099 0.167962 0.032637 0.173381 0.02635997 0.170584 0.02525997 0.173381 0.02635997 0.167962 0.032637 0.172284 0.03273797 0.171168 0.03492099 0.173381 0.02635997 0.173529 0.03089797 0.172284 0.03273797 0.173381 0.02635997 0.176306 0.02761989 0.173529 0.03089797 0.173381 0.02635997 0.170584 0.02525997 0.180259 0.01979088 0.173381 0.02635997 0.170251 0.03777092 0.170036 0.03886598 0.167962 0.032637 0.171168 0.03492099 0.170251 0.03777092 0.167962 0.032637 0.164332 0.03099495 0.170584 0.02525997 0.167962 0.032637 0.178704 0.05500888 0.170036 0.03886598 0.170251 0.03777092 0.17879 0.04752898 0.170251 0.03777092 0.171168 0.03492099 0.178704 0.05500888 0.170251 0.03777092 0.17879 0.04752898 0.17879 0.04752898 0.171168 0.03492099 0.172284 0.03273797 0.180754 0.04013293 0.172284 0.03273797 0.173529 0.03089797 0.17879 0.04752898 0.172284 0.03273797 0.180754 0.04013293 0.180754 0.04013293 0.173529 0.03089797 0.176306 0.02761989 0.185123 0.03366088 0.176306 0.02761989 0.17717 0.02671897 0.180754 0.04013293 0.176306 0.02761989 0.185123 0.03366088 0.185123 0.03366088 0.17717 0.02671897 0.182303 0.02238392 0.185123 0.03366088 0.182303 0.02238392 0.1826519 0.02213299 0.191695 0.02521795 0.1826519 0.02213299 0.189051 0.01804792 0.185123 0.03366088 0.1826519 0.02213299 0.191695 0.02521795 0.191695 0.02521795 0.189051 0.01804792 0.192443 0.01616996 0.202787 0.01642888 0.192443 0.01616996 0.197331 0.01375591 0.200999 0.02475899 0.191695 0.02521795 0.192443 0.01616996 0.202787 0.01642888 0.200999 0.02475899 0.192443 0.01616996 0.204725 0.01278793 0.202787 0.01642888 0.197331 0.01375591 0.184489 0.01698398 0.1927019 0.01457798 0.180259 0.01979088 0.184489 0.01698398 0.194979 0.01332396 0.1927019 0.01457798 0.175804 0.02055096 0.180259 0.01979088 0.170584 0.02525997 0.175804 0.02055096 0.184489 0.01698398 0.180259 0.01979088 0.1639029 0.027188 0.170584 0.02525997 0.164332 0.03099495 0.168925 0.02397096 0.175804 0.02055096 0.170584 0.02525997 0.1639029 0.027188 0.168925 0.02397096 0.170584 0.02525997 0.160441 0.03025895 0.1639029 0.027188 0.164332 0.03099495 0.105418 0.01844096 0.194979 0.01332396 0.184489 0.01698398 0.104487 0.01756298 0.103559 0.01667797 0.194979 0.01332396 0.105418 0.01844096 0.104487 0.01756298 0.194979 0.01332396 0.105418 0.01844096 0.184489 0.01698398 0.175804 0.02055096 0.105418 0.01844096 0.175804 0.02055096 0.168925 0.02397096 0.105418 0.01844096 0.168925 0.02397096 0.1639029 0.027188 0.105418 0.01844096 0.1639029 0.027188 0.160441 0.03025895 0.2017379 0.034361 0.1937 0.03635096 0.191695 0.02521795 0.185123 0.03366088 0.191695 0.02521795 0.1937 0.03635096 0.200999 0.02475899 0.2017379 0.034361 0.191695 0.02521795 0.204758 0.04518991 0.198291 0.04933691 0.1937 0.03635096 0.1900939 0.04718798 0.1937 0.03635096 0.198291 0.04933691 0.2017379 0.034361 0.204758 0.04518991 0.1937 0.03635096 0.1900939 0.04718798 0.185123 0.03366088 0.1937 0.03635096 0.209877 0.05730789 0.205192 0.06394499 0.198291 0.04933691 0.197272 0.062442 0.198291 0.04933691 0.205192 0.06394499 0.204758 0.04518991 0.209877 0.05730789 0.198291 0.04933691 0.197272 0.062442 0.1900939 0.04718798 0.198291 0.04933691 0.216978 0.07082998 0.213966 0.07990497 0.205192 0.06394499 0.206218 0.07912498 0.205192 0.06394499 0.213966 0.07990497 0.209877 0.05730789 0.216978 0.07082998 0.205192 0.06394499 0.206218 0.07912498 0.197272 0.062442 0.205192 0.06394499 0.225933 0.08586698 0.2241269 0.09696 0.213966 0.07990497 0.216446 0.09695196 0.213966 0.07990497 0.2241269 0.09696 0.216978 0.07082998 0.225933 0.08586698 0.213966 0.07990497 0.216446 0.09695196 0.206218 0.07912498 0.213966 0.07990497 0.242631 0.111773 0.235203 0.1148959 0.2241269 0.09696 0.227484 0.11568 0.2241269 0.09696 0.235203 0.1148959 0.236759 0.102785 0.242631 0.111773 0.2241269 0.09696 0.225933 0.08586698 0.236759 0.102785 0.2241269 0.09696 0.227484 0.11568 0.216446 0.09695196 0.2241269 0.09696 0.254964 0.13041 0.246784 0.133549 0.235203 0.1148959 0.238924 0.135125 0.235203 0.1148959 0.246784 0.133549 0.24865 0.120882 0.254964 0.13041 0.235203 0.1148959 0.242631 0.111773 0.24865 0.120882 0.235203 0.1148959 0.238924 0.135125 0.227484 0.11568 0.235203 0.1148959 0.261659 0.140609 0.258538 0.152803 0.246784 0.133549 0.25044 0.155151 0.246784 0.133549 0.258538 0.152803 0.254964 0.13041 0.261659 0.140609 0.246784 0.133549 0.25044 0.155151 0.238924 0.135125 0.246784 0.133549 0.275991 0.162976 0.270169 0.17255 0.258538 0.152803 0.261741 0.175635 0.258538 0.152803 0.270169 0.17255 0.268676 0.15141 0.275991 0.162976 0.258538 0.152803 0.261659 0.140609 0.268676 0.15141 0.258538 0.152803 0.261741 0.175635 0.25044 0.155151 0.258538 0.152803 0.291417 0.188354 0.28144 0.192698 0.270169 0.17255 0.261741 0.175635 0.270169 0.17255 0.28144 0.192698 0.283578 0.175301 0.291417 0.188354 0.270169 0.17255 0.275991 0.162976 0.283578 0.175301 0.270169 0.17255 0.283562 0.196858 0.28144 0.192698 0.291417 0.188354 0.272602 0.19647 0.261741 0.175635 0.28144 0.192698 0.283562 0.196858 0.272602 0.19647 0.28144 0.192698 0.331011 0.193936 0.291417 0.188354 0.283578 0.175301 0.331011 0.193936 0.292634 0.190518 0.291417 0.188354 0.283562 0.196858 0.291417 0.188354 0.292634 0.190518 0.329543 0.166254 0.283578 0.175301 0.275991 0.162976 0.329543 0.166254 0.331011 0.193936 0.283578 0.175301 0.329543 0.166254 0.275991 0.162976 0.268676 0.15141 0.329543 0.166254 0.268676 0.15141 0.261659 0.140609 0.3271 0.139321 0.261659 0.140609 0.254964 0.13041 0.3271 0.139321 0.329543 0.166254 0.261659 0.140609 0.3271 0.139321 0.254964 0.13041 0.24865 0.120882 0.323682 0.113506 0.24865 0.120882 0.242631 0.111773 0.323682 0.113506 0.3271 0.139321 0.24865 0.120882 0.323682 0.113506 0.242631 0.111773 0.236759 0.102785 0.31929 0.08919399 0.236759 0.102785 0.225933 0.08586698 0.31929 0.08919399 0.323682 0.113506 0.236759 0.102785 0.31929 0.08919399 0.225933 0.08586698 0.216978 0.07082998 0.313931 0.06679499 0.216978 0.07082998 0.209877 0.05730789 0.313931 0.06679499 0.31929 0.08919399 0.216978 0.07082998 0.307621 0.04675096 0.209877 0.05730789 0.204758 0.04518991 0.307621 0.04675096 0.313931 0.06679499 0.209877 0.05730789 0.307621 0.04675096 0.204758 0.04518991 0.2017379 0.034361 0.300391 0.02954399 0.2017379 0.034361 0.200999 0.02475899 0.300391 0.02954399 0.307621 0.04675096 0.2017379 0.034361 0.292295 0.01569592 0.200999 0.02475899 0.202787 0.01642888 0.292295 0.01569592 0.300391 0.02954399 0.200999 0.02475899 0.292295 0.01569592 0.202787 0.01642888 0.204725 0.01278793 0.180754 0.04013293 0.185123 0.03366088 0.1900939 0.04718798 0.187104 0.05429589 0.1900939 0.04718798 0.197272 0.062442 0.187104 0.05429589 0.180754 0.04013293 0.1900939 0.04718798 0.195015 0.06980198 0.197272 0.062442 0.206218 0.07912498 0.195015 0.06980198 0.187104 0.05429589 0.197272 0.062442 0.204114 0.08640795 0.206218 0.07912498 0.216446 0.09695196 0.204114 0.08640795 0.195015 0.06980198 0.206218 0.07912498 0.214019 0.103893 0.216446 0.09695196 0.227484 0.11568 0.214019 0.103893 0.204114 0.08640795 0.216446 0.09695196 0.224385 0.122079 0.227484 0.11568 0.238924 0.135125 0.224385 0.122079 0.214019 0.103893 0.227484 0.11568 0.234923 0.140833 0.238924 0.135125 0.25044 0.155151 0.234923 0.140833 0.224385 0.122079 0.238924 0.135125 0.245393 0.16005 0.25044 0.155151 0.261741 0.175635 0.245393 0.16005 0.234923 0.140833 0.25044 0.155151 0.255582 0.1796309 0.261741 0.175635 0.272602 0.19647 0.255582 0.1796309 0.245393 0.16005 0.261741 0.175635 0.265325 0.19949 0.255582 0.1796309 0.272602 0.19647 0.27436 0.200125 0.265325 0.19949 0.272602 0.19647 0.27436 0.200125 0.272602 0.19647 0.283562 0.196858 0.17879 0.04752898 0.180754 0.04013293 0.187104 0.05429589 0.186985 0.06387799 0.187104 0.05429589 0.195015 0.06980198 0.186985 0.06387799 0.17879 0.04752898 0.187104 0.05429589 0.1964499 0.08144497 0.195015 0.06980198 0.204114 0.08640795 0.1964499 0.08144497 0.186985 0.06387799 0.195015 0.06980198 0.206772 0.09998196 0.204114 0.08640795 0.214019 0.103893 0.206772 0.09998196 0.1964499 0.08144497 0.204114 0.08640795 0.217571 0.11929 0.214019 0.103893 0.224385 0.122079 0.217571 0.11929 0.206772 0.09998196 0.214019 0.103893 0.228525 0.139218 0.224385 0.122079 0.234923 0.140833 0.228525 0.139218 0.217571 0.11929 0.224385 0.122079 0.2393749 0.1596519 0.234923 0.140833 0.245393 0.16005 0.2393749 0.1596519 0.228525 0.139218 0.234923 0.140833 0.249891 0.18049 0.245393 0.16005 0.255582 0.1796309 0.249891 0.18049 0.2393749 0.1596519 0.245393 0.16005 0.249891 0.18049 0.255582 0.1796309 0.265325 0.19949 0.259891 0.201642 0.249891 0.18049 0.265325 0.19949 0.266771 0.202735 0.259891 0.201642 0.265325 0.19949 0.266771 0.202735 0.265325 0.19949 0.27436 0.200125 0.178704 0.05500888 0.17879 0.04752898 0.186985 0.06387799 0.188668 0.07370996 0.186985 0.06387799 0.1964499 0.08144497 0.188668 0.07370996 0.178704 0.05500888 0.186985 0.06387799 0.1996459 0.09351998 0.1964499 0.08144497 0.206772 0.09998196 0.1996459 0.09351998 0.188668 0.07370996 0.1964499 0.08144497 0.211193 0.114205 0.206772 0.09998196 0.217571 0.11929 0.211193 0.114205 0.1996459 0.09351998 0.206772 0.09998196 0.222929 0.1355929 0.217571 0.11929 0.228525 0.139218 0.222929 0.1355929 0.211193 0.114205 0.217571 0.11929 0.234555 0.1575649 0.228525 0.139218 0.2393749 0.1596519 0.234555 0.1575649 0.222929 0.1355929 0.228525 0.139218 0.245806 0.1800169 0.2393749 0.1596519 0.249891 0.18049 0.245806 0.1800169 0.234555 0.1575649 0.2393749 0.1596519 0.245806 0.1800169 0.249891 0.18049 0.259891 0.201642 0.256474 0.2028599 0.245806 0.1800169 0.259891 0.201642 0.261117 0.204578 0.256474 0.2028599 0.259891 0.201642 0.261117 0.204578 0.259891 0.201642 0.266771 0.202735 0.179396 0.06071794 0.178704 0.05500888 0.188668 0.07370996 0.190423 0.08065098 0.188668 0.07370996 0.1996459 0.09351998 0.190423 0.08065098 0.179396 0.06071794 0.188668 0.07370996 0.196375 0.09120696 0.1996459 0.09351998 0.211193 0.114205 0.196375 0.09120696 0.190423 0.08065098 0.1996459 0.09351998 0.208956 0.113497 0.211193 0.114205 0.222929 0.1355929 0.20257 0.102162 0.196375 0.09120696 0.211193 0.114205 0.208956 0.113497 0.20257 0.102162 0.211193 0.114205 0.2212859 0.135763 0.222929 0.1355929 0.234555 0.1575649 0.215505 0.12524 0.208956 0.113497 0.222929 0.1355929 0.2212859 0.135763 0.215505 0.12524 0.222929 0.1355929 0.235556 0.1626729 0.234555 0.1575649 0.245806 0.1800169 0.222164 0.137376 0.2212859 0.135763 0.234555 0.1575649 0.228853 0.149837 0.222164 0.137376 0.234555 0.1575649 0.235556 0.1626729 0.228853 0.149837 0.234555 0.1575649 0.248731 0.189283 0.245806 0.1800169 0.256474 0.2028599 0.242192 0.175814 0.235556 0.1626729 0.245806 0.1800169 0.248731 0.189283 0.242192 0.175814 0.245806 0.1800169 0.255133 0.203131 0.248731 0.189283 0.256474 0.2028599 0.255724 0.204443 0.255133 0.203131 0.256474 0.2028599 0.257587 0.205596 0.256474 0.2028599 0.261117 0.204578 0.256262 0.205772 0.256474 0.2028599 0.257587 0.205596 0.255724 0.204443 0.256474 0.2028599 0.256262 0.205772 0.186426 0.08204197 0.179396 0.06071794 0.190423 0.08065098 0.186426 0.08204197 0.190423 0.08065098 0.196375 0.09120696 0.186426 0.08204197 0.196375 0.09120696 0.20257 0.102162 0.2044849 0.108388 0.20257 0.102162 0.208956 0.113497 0.186426 0.08204197 0.20257 0.102162 0.2044849 0.108388 0.2044849 0.108388 0.208956 0.113497 0.215505 0.12524 0.2044849 0.108388 0.215505 0.12524 0.2212859 0.135763 0.219601 0.140487 0.2212859 0.135763 0.222164 0.137376 0.216511 0.135565 0.2212859 0.135763 0.219601 0.140487 0.2140949 0.13178 0.2212859 0.135763 0.216511 0.135565 0.211591 0.1279129 0.2212859 0.135763 0.2140949 0.13178 0.208992 0.12396 0.2212859 0.135763 0.211591 0.1279129 0.206297 0.119925 0.2212859 0.135763 0.208992 0.12396 0.2035059 0.11581 0.2212859 0.135763 0.206297 0.119925 0.2044849 0.108388 0.2212859 0.135763 0.2035059 0.11581 0.222541 0.145258 0.222164 0.137376 0.228853 0.149837 0.219601 0.140487 0.222164 0.137376 0.222541 0.145258 0.228034 0.154409 0.228853 0.149837 0.235556 0.1626729 0.225349 0.149896 0.228853 0.149837 0.228034 0.154409 0.222541 0.145258 0.228853 0.149837 0.225349 0.149896 0.235357 0.167123 0.235556 0.1626729 0.242192 0.175814 0.233036 0.163027 0.235556 0.1626729 0.235357 0.167123 0.230596 0.158788 0.235556 0.1626729 0.233036 0.163027 0.228034 0.154409 0.235556 0.1626729 0.230596 0.158788 0.241654 0.178567 0.242192 0.175814 0.248731 0.189283 0.239661 0.174892 0.242192 0.175814 0.241654 0.178567 0.2375659 0.171081 0.242192 0.175814 0.239661 0.174892 0.235357 0.167123 0.242192 0.175814 0.2375659 0.171081 0.25039 0.195321 0.248731 0.189283 0.255133 0.203131 0.247974 0.190578 0.248731 0.189283 0.25039 0.195321 0.245387 0.185593 0.248731 0.189283 0.247974 0.190578 0.243562 0.182137 0.248731 0.189283 0.245387 0.185593 0.241654 0.178567 0.248731 0.189283 0.243562 0.182137 0.254669 0.203925 0.255133 0.203131 0.255724 0.204443 0.254669 0.203925 0.254626 0.2038249 0.255133 0.203131 0.252599 0.199742 0.255133 0.203131 0.254626 0.2038249 0.25039 0.195321 0.255133 0.203131 0.252599 0.199742 0.273902 3.42e-4 0.292295 0.01569592 0.283415 0.005760908 0.09471297 0.01186388 0.273902 3.42e-4 0.283415 0.005760908 0.331011 0.193936 0.293952 0.193083 0.292634 0.190518 0.283562 0.196858 0.292634 0.190518 0.293952 0.193083 0.331011 0.193936 0.297333 0.2013249 0.293952 0.193083 0.286677 0.205031 0.293952 0.193083 0.297333 0.2013249 0.286677 0.205031 0.283562 0.196858 0.293952 0.193083 0.3315 0.222023 0.297698 0.202439 0.297333 0.2013249 0.286677 0.205031 0.297333 0.2013249 0.297698 0.202439 0.331011 0.193936 0.3315 0.222023 0.297333 0.2013249 0.3315 0.222023 0.2999 0.211465 0.297698 0.202439 0.288591 0.21345 0.297698 0.202439 0.2999 0.211465 0.288591 0.21345 0.286677 0.205031 0.297698 0.202439 0.3315 0.222023 0.300005 0.2121109 0.2999 0.211465 0.288591 0.21345 0.2999 0.211465 0.300005 0.2121109 0.3315 0.222023 0.300779 0.222023 0.300005 0.2121109 0.289273 0.222023 0.300005 0.2121109 0.300779 0.222023 0.288591 0.21345 0.300005 0.2121109 0.289273 0.222023 0.331483 0.227324 0.300779 0.222023 0.3315 0.222023 0.300559 0.227309 0.300779 0.222023 0.331483 0.227324 0.288588 0.230619 0.300779 0.222023 0.300559 0.227309 0.289273 0.222023 0.300779 0.222023 0.288588 0.230619 0.329525 0.222023 0.3315 0.222023 0.331011 0.193936 0.328976 0.251012 0.331483 0.227324 0.3315 0.222023 0.329525 0.222023 0.328976 0.251012 0.3315 0.222023 0.328983 0.193203 0.331011 0.193936 0.329543 0.166254 0.328983 0.193203 0.329525 0.222023 0.331011 0.193936 0.327353 0.1647689 0.329543 0.166254 0.3271 0.139321 0.327353 0.1647689 0.328983 0.193203 0.329543 0.166254 0.324634 0.137216 0.3271 0.139321 0.323682 0.113506 0.324634 0.137216 0.327353 0.1647689 0.3271 0.139321 0.320856 0.111151 0.323682 0.113506 0.31929 0.08919399 0.320856 0.111151 0.324634 0.137216 0.323682 0.113506 0.315974 0.08675396 0.31929 0.08919399 0.313931 0.06679499 0.315974 0.08675396 0.320856 0.111151 0.31929 0.08919399 0.303027 0.04549199 0.313931 0.06679499 0.307621 0.04675096 0.310013 0.06464898 0.315974 0.08675396 0.313931 0.06679499 0.303027 0.04549199 0.310013 0.06464898 0.313931 0.06679499 0.29509 0.02988499 0.307621 0.04675096 0.300391 0.02954399 0.29509 0.02988499 0.303027 0.04549199 0.307621 0.04675096 0.286306 0.01843392 0.300391 0.02954399 0.292295 0.01569592 0.286306 0.01843392 0.29509 0.02988499 0.300391 0.02954399 0.273902 3.42e-4 0.263948 0 0.292295 0.01569592 0.286306 0.01843392 0.292295 0.01569592 0.263948 0 0.328976 0.251012 0.331431 0.232622 0.331483 0.227324 0.300559 0.227309 0.331483 0.227324 0.331431 0.232622 0.328976 0.251012 0.331101 0.247395 0.331431 0.232622 0.2999 0.232567 0.331431 0.232622 0.331101 0.247395 0.3 0.23195 0.300559 0.227309 0.331431 0.232622 0.2999 0.232567 0.3 0.23195 0.331431 0.232622 0.328976 0.251012 0.330505 0.261983 0.331101 0.247395 0.293953 0.250962 0.331101 0.247395 0.330505 0.261983 0.297692 0.2416689 0.2999 0.232567 0.331101 0.247395 0.224198 0.193901 0.224207 0.249981 0.224965 0.222023 0.293953 0.250962 0.297692 0.2416689 0.331101 0.247395 0.327332 0.279546 0.329635 0.276478 0.330505 0.261983 0.283381 0.269035 0.330505 0.261983 0.329635 0.276478 0.328976 0.251012 0.327332 0.279546 0.330505 0.261983 0.292882 0.253064 0.293953 0.250962 0.330505 0.261983 0.291417 0.255692 0.292882 0.253064 0.330505 0.261983 0.283381 0.269035 0.291417 0.255692 0.330505 0.261983 0.327332 0.279546 0.328495 0.290818 0.329635 0.276478 0.275616 0.281633 0.329635 0.276478 0.328495 0.290818 0.275616 0.281633 0.283381 0.269035 0.329635 0.276478 0.324598 0.307123 0.327084 0.30487 0.328495 0.290818 0.268146 0.29346 0.328495 0.290818 0.327084 0.30487 0.327332 0.279546 0.324598 0.307123 0.328495 0.290818 0.268146 0.29346 0.275616 0.281633 0.328495 0.290818 0.324598 0.307123 0.325399 0.318655 0.327084 0.30487 0.261011 0.304437 0.327084 0.30487 0.325399 0.318655 0.261011 0.304437 0.268146 0.29346 0.327084 0.30487 0.320813 0.333143 0.323458 0.33198 0.325399 0.318655 0.247663 0.32469 0.325399 0.318655 0.323458 0.33198 0.324598 0.307123 0.320813 0.333143 0.325399 0.318655 0.254195 0.314784 0.261011 0.304437 0.325399 0.318655 0.247663 0.32469 0.254195 0.314784 0.325399 0.318655 0.31594 0.357435 0.321246 0.344899 0.323458 0.33198 0.241447 0.334073 0.323458 0.33198 0.321246 0.344899 0.320813 0.333143 0.31594 0.357435 0.323458 0.33198 0.241447 0.334073 0.247663 0.32469 0.323458 0.33198 0.31594 0.357435 0.318761 0.357353 0.321246 0.344899 0.235572 0.343052 0.321246 0.344899 0.318761 0.357353 0.235572 0.343052 0.241447 0.334073 0.321246 0.344899 0.310008 0.379411 0.315988 0.369368 0.318761 0.357353 0.22486 0.35992 0.318761 0.357353 0.315988 0.369368 0.31594 0.357435 0.310008 0.379411 0.318761 0.357353 0.22486 0.35992 0.235572 0.343052 0.318761 0.357353 0.310008 0.379411 0.312956 0.380731 0.315988 0.369368 0.216 0.374962 0.315988 0.369368 0.312956 0.380731 0.216 0.374962 0.22486 0.35992 0.315988 0.369368 0.303065 0.398465 0.309645 0.391459 0.312956 0.380731 0.216 0.374962 0.312956 0.380731 0.309645 0.391459 0.310008 0.379411 0.303065 0.398465 0.312956 0.380731 0.303065 0.398465 0.306089 0.401393 0.309645 0.391459 0.2091259 0.388325 0.309645 0.391459 0.306089 0.401393 0.2091259 0.388325 0.216 0.374962 0.309645 0.391459 0.295172 0.414028 0.30227 0.410519 0.306089 0.401393 0.204291 0.400194 0.306089 0.401393 0.30227 0.410519 0.303065 0.398465 0.295172 0.414028 0.306089 0.401393 0.204291 0.400194 0.2091259 0.388325 0.306089 0.401393 0.286418 0.4255 0.298222 0.418716 0.30227 0.410519 0.20156 0.410679 0.30227 0.410519 0.298222 0.418716 0.295172 0.414028 0.286418 0.4255 0.30227 0.410519 0.20156 0.410679 0.204291 0.400194 0.30227 0.410519 0.264424 0.444149 0.293935 0.425939 0.298222 0.418716 0.201037 0.419924 0.298222 0.418716 0.293935 0.425939 0.276936 0.432239 0.264424 0.444149 0.298222 0.418716 0.286418 0.4255 0.276936 0.432239 0.298222 0.418716 0.201037 0.419924 0.20156 0.410679 0.298222 0.418716 0.269679 0.444504 0.289443 0.432094 0.293935 0.425939 0.201037 0.419924 0.293935 0.425939 0.289443 0.432094 0.264424 0.444149 0.269679 0.444504 0.293935 0.425939 0.274843 0.44339 0.284745 0.437107 0.289443 0.432094 0.2029049 0.42791 0.289443 0.432094 0.284745 0.437107 0.269679 0.444504 0.274843 0.44339 0.289443 0.432094 0.2029049 0.42791 0.201037 0.419924 0.289443 0.432094 0.274843 0.44339 0.279872 0.440902 0.284745 0.437107 0.207411 0.434488 0.284745 0.437107 0.279872 0.440902 0.207411 0.434488 0.2029049 0.42791 0.284745 0.437107 0.103572 0.427369 0.279872 0.440902 0.274843 0.44339 0.103572 0.427369 0.207411 0.434488 0.279872 0.440902 0.09509795 0.432124 0.274843 0.44339 0.269679 0.444504 0.09509795 0.432124 0.103572 0.427369 0.274843 0.44339 0.08516895 0.432272 0.269679 0.444504 0.264424 0.444149 0.08516895 0.432272 0.09509795 0.432124 0.269679 0.444504 0.276936 0.432239 0.259093 0.442263 0.264424 0.444149 0.08516895 0.432272 0.264424 0.444149 0.259093 0.442263 0.266913 0.433587 0.25375 0.438768 0.259093 0.442263 0.07402199 0.427364 0.259093 0.442263 0.25375 0.438768 0.276936 0.432239 0.266913 0.433587 0.259093 0.442263 0.07402199 0.427364 0.08516895 0.432272 0.259093 0.442263 0.256604 0.428902 0.248408 0.433595 0.25375 0.438768 0.07402199 0.427364 0.25375 0.438768 0.248408 0.433595 0.266913 0.433587 0.256604 0.428902 0.25375 0.438768 0.246341 0.417634 0.243149 0.426708 0.248408 0.433595 0.06220096 0.41699 0.248408 0.433595 0.243149 0.426708 0.256604 0.428902 0.246341 0.417634 0.248408 0.433595 0.06220096 0.41699 0.07402199 0.427364 0.248408 0.433595 0.246341 0.417634 0.2379879 0.418034 0.243149 0.426708 0.06220096 0.41699 0.243149 0.426708 0.2379879 0.418034 0.236533 0.39945 0.233022 0.407613 0.2379879 0.418034 0.05046695 0.400912 0.2379879 0.418034 0.233022 0.407613 0.246341 0.417634 0.236533 0.39945 0.2379879 0.418034 0.05046695 0.400912 0.06220096 0.41699 0.2379879 0.418034 0.236533 0.39945 0.2282699 0.395376 0.233022 0.407613 0.05046695 0.400912 0.233022 0.407613 0.2282699 0.395376 0.227659 0.374435 0.2238399 0.381508 0.2282699 0.395376 0.03965193 0.379144 0.2282699 0.395376 0.2238399 0.381508 0.236533 0.39945 0.227659 0.374435 0.2282699 0.395376 0.03965193 0.379144 0.05046695 0.400912 0.2282699 0.395376 0.227659 0.374435 0.219759 0.365979 0.2238399 0.381508 0.03965193 0.379144 0.2238399 0.381508 0.219759 0.365979 0.220194 0.343164 0.216085 0.348883 0.219759 0.365979 0.03041189 0.352033 0.219759 0.365979 0.216085 0.348883 0.227659 0.374435 0.220194 0.343164 0.219759 0.365979 0.03041189 0.352033 0.03965193 0.379144 0.219759 0.365979 0.220194 0.343164 0.212841 0.3302 0.216085 0.348883 0.03041189 0.352033 0.216085 0.348883 0.212841 0.3302 0.2144629 0.3062 0.210112 0.31027 0.212841 0.3302 0.02293497 0.320245 0.212841 0.3302 0.210112 0.31027 0.220194 0.343164 0.2144629 0.3062 0.212841 0.3302 0.02293497 0.320245 0.03041189 0.352033 0.212841 0.3302 0.2144629 0.3062 0.207937 0.289185 0.210112 0.31027 0.01718389 0.284609 0.210112 0.31027 0.207937 0.289185 0.01718389 0.284609 0.02293497 0.320245 0.210112 0.31027 0.21087 0.265158 0.206355 0.267299 0.207937 0.289185 0.01718389 0.284609 0.207937 0.289185 0.206355 0.267299 0.2144629 0.3062 0.21087 0.265158 0.207937 0.289185 0.21087 0.265158 0.2054 0.244892 0.206355 0.267299 0.01371991 0.246266 0.206355 0.267299 0.2054 0.244892 0.01371991 0.246266 0.01718389 0.284609 0.206355 0.267299 0.209648 0.222023 0.2050729 0.222023 0.2054 0.244892 0.01312589 0.226617 0.2054 0.244892 0.2050729 0.222023 0.21087 0.265158 0.209648 0.222023 0.2054 0.244892 0.01312589 0.226617 0.01371991 0.246266 0.2054 0.244892 0.210884 0.178638 0.205114 0.213873 0.2050729 0.222023 0.01312589 0.226617 0.2050729 0.222023 0.205114 0.213873 0.210884 0.178638 0.2050729 0.222023 0.209648 0.222023 0.210884 0.178638 0.205238 0.2057369 0.205114 0.213873 0.01312589 0.226617 0.205114 0.213873 0.205238 0.2057369 0.210884 0.178638 0.207245 0.163331 0.205238 0.2057369 0.01329195 0.206915 0.205238 0.2057369 0.207245 0.163331 0.01329195 0.206915 0.01312589 0.226617 0.205238 0.2057369 0.2145079 0.1374689 0.211414 0.123624 0.207245 0.163331 0.01619696 0.167423 0.207245 0.163331 0.211414 0.123624 0.210884 0.178638 0.2145079 0.1374689 0.207245 0.163331 0.01441293 0.186955 0.01329195 0.206915 0.207245 0.163331 0.01619696 0.167423 0.01441293 0.186955 0.207245 0.163331 0.2202669 0.100508 0.2175 0.08816295 0.211414 0.123624 0.021649 0.130453 0.211414 0.123624 0.2175 0.08816295 0.2145079 0.1374689 0.2202669 0.100508 0.211414 0.123624 0.01862895 0.1485339 0.01619696 0.167423 0.211414 0.123624 0.021649 0.130453 0.01862895 0.1485339 0.211414 0.123624 0.22774 0.06933397 0.225167 0.05810195 0.2175 0.08816295 0.02899998 0.09718799 0.2175 0.08816295 0.225167 0.05810195 0.2202669 0.100508 0.22774 0.06933397 0.2175 0.08816295 0.02511799 0.113284 0.021649 0.130453 0.2175 0.08816295 0.02899998 0.09718799 0.02511799 0.113284 0.2175 0.08816295 0.236591 0.04446291 0.234032 0.034132 0.225167 0.05810195 0.038185 0.06864798 0.225167 0.05810195 0.234032 0.034132 0.22774 0.06933397 0.236591 0.04446291 0.225167 0.05810195 0.03337496 0.08227598 0.02899998 0.09718799 0.225167 0.05810195 0.038185 0.06864798 0.03337496 0.08227598 0.225167 0.05810195 0.246347 0.02640098 0.243697 0.016532 0.234032 0.034132 0.04907596 0.04560589 0.234032 0.034132 0.243697 0.016532 0.236591 0.04446291 0.246347 0.02640098 0.234032 0.034132 0.04341989 0.05640697 0.038185 0.06864798 0.234032 0.034132 0.04907596 0.04560589 0.04341989 0.05640697 0.234032 0.034132 0.25655 0.01518392 0.253783 0.00525099 0.243697 0.016532 0.06100291 0.02847898 0.243697 0.016532 0.253783 0.00525099 0.246347 0.02640098 0.25655 0.01518392 0.243697 0.016532 0.05497992 0.03628993 0.04907596 0.04560589 0.243697 0.016532 0.06100291 0.02847898 0.05497992 0.03628993 0.243697 0.016532 0.276816 0.011756 0.263948 0 0.253783 0.00525099 0.07302999 0.01733297 0.253783 0.00525099 0.263948 0 0.266813 0.0104739 0.276816 0.011756 0.253783 0.00525099 0.25655 0.01518392 0.266813 0.0104739 0.253783 0.00525099 0.06707096 0.02216392 0.06100291 0.02847898 0.253783 0.00525099 0.07302999 0.01733297 0.06707096 0.02216392 0.253783 0.00525099 0.08442395 0.01192688 0.263948 0 0.273902 3.42e-4 0.276816 0.011756 0.286306 0.01843392 0.263948 0 0.08442395 0.01192688 0.07302999 0.01733297 0.263948 0 0.09471297 0.01186388 0.08442395 0.01192688 0.273902 3.42e-4 0.06281995 0.222023 0.209648 0.222023 0.21087 0.265158 0.06441098 0.181628 0.210884 0.178638 0.209648 0.222023 0.06441098 0.181628 0.209648 0.222023 0.06281995 0.222023 0.06442999 0.262652 0.21087 0.265158 0.2144629 0.3062 0.06442999 0.262652 0.06281995 0.222023 0.21087 0.265158 0.06915998 0.30132 0.2144629 0.3062 0.220194 0.343164 0.06915998 0.30132 0.06442999 0.262652 0.2144629 0.3062 0.07669895 0.336237 0.220194 0.343164 0.227659 0.374435 0.07669895 0.336237 0.06915998 0.30132 0.220194 0.343164 0.08652597 0.365936 0.227659 0.374435 0.236533 0.39945 0.08652597 0.365936 0.07669895 0.336237 0.227659 0.374435 0.09822797 0.389906 0.236533 0.39945 0.246341 0.417634 0.09822797 0.389906 0.08652597 0.365936 0.236533 0.39945 0.111204 0.407595 0.246341 0.417634 0.256604 0.428902 0.111204 0.407595 0.09822797 0.389906 0.246341 0.417634 0.138685 0.423991 0.256604 0.428902 0.266913 0.433587 0.12486 0.418879 0.111204 0.407595 0.256604 0.428902 0.138685 0.423991 0.12486 0.418879 0.256604 0.428902 0.152242 0.42335 0.266913 0.433587 0.276936 0.432239 0.152242 0.42335 0.138685 0.423991 0.266913 0.433587 0.165178 0.417468 0.276936 0.432239 0.286418 0.4255 0.165178 0.417468 0.152242 0.42335 0.276936 0.432239 0.177215 0.406904 0.286418 0.4255 0.295172 0.414028 0.177215 0.406904 0.165178 0.417468 0.286418 0.4255 0.188142 0.39223 0.295172 0.414028 0.303065 0.398465 0.188142 0.39223 0.177215 0.406904 0.295172 0.414028 0.188142 0.39223 0.303065 0.398465 0.310008 0.379411 0.1978 0.374019 0.310008 0.379411 0.31594 0.357435 0.1978 0.374019 0.188142 0.39223 0.310008 0.379411 0.20607 0.352856 0.31594 0.357435 0.320813 0.333143 0.20607 0.352856 0.1978 0.374019 0.31594 0.357435 0.212862 0.329381 0.320813 0.333143 0.324598 0.307123 0.212862 0.329381 0.20607 0.352856 0.320813 0.333143 0.218131 0.304213 0.324598 0.307123 0.327332 0.279546 0.218131 0.304213 0.212862 0.329381 0.324598 0.307123 0.221928 0.277544 0.327332 0.279546 0.328976 0.251012 0.221928 0.277544 0.218131 0.304213 0.327332 0.279546 0.224207 0.249981 0.328976 0.251012 0.329525 0.222023 0.224207 0.249981 0.221928 0.277544 0.328976 0.251012 0.224965 0.222023 0.329525 0.222023 0.328983 0.193203 0.224965 0.222023 0.224207 0.249981 0.329525 0.222023 0.224198 0.193901 0.328983 0.193203 0.327353 0.1647689 0.224198 0.193901 0.224965 0.222023 0.328983 0.193203 0.221898 0.16624 0.327353 0.1647689 0.324634 0.137216 0.221898 0.16624 0.224198 0.193901 0.327353 0.1647689 0.2180809 0.139549 0.324634 0.137216 0.320856 0.111151 0.2180809 0.139549 0.221898 0.16624 0.324634 0.137216 0.212803 0.114426 0.320856 0.111151 0.315974 0.08675396 0.212803 0.114426 0.2180809 0.139549 0.320856 0.111151 0.206024 0.091053 0.315974 0.08675396 0.310013 0.06464898 0.206024 0.091053 0.212803 0.114426 0.315974 0.08675396 0.197794 0.07001298 0.310013 0.06464898 0.303027 0.04549199 0.197794 0.07001298 0.206024 0.091053 0.310013 0.06464898 0.177328 0.03726589 0.303027 0.04549199 0.29509 0.02988499 0.188195 0.0518999 0.197794 0.07001298 0.303027 0.04549199 0.177328 0.03726589 0.188195 0.0518999 0.303027 0.04549199 0.165331 0.02667999 0.29509 0.02988499 0.286306 0.01843392 0.165331 0.02667999 0.177328 0.03726589 0.29509 0.02988499 0.152405 0.020738 0.286306 0.01843392 0.276816 0.011756 0.152405 0.020738 0.165331 0.02667999 0.286306 0.01843392 0.13882 0.02003395 0.276816 0.011756 0.266813 0.0104739 0.13882 0.02003395 0.152405 0.020738 0.276816 0.011756 0.124932 0.02512598 0.266813 0.0104739 0.25655 0.01518392 0.124932 0.02512598 0.13882 0.02003395 0.266813 0.0104739 0.124932 0.02512598 0.25655 0.01518392 0.246347 0.02640098 0.111195 0.03646188 0.246347 0.02640098 0.236591 0.04446291 0.111195 0.03646188 0.124932 0.02512598 0.246347 0.02640098 0.09815096 0.05426889 0.236591 0.04446291 0.22774 0.06933397 0.09815096 0.05426889 0.111195 0.03646188 0.236591 0.04446291 0.08641898 0.07837396 0.22774 0.06933397 0.2202669 0.100508 0.08641898 0.07837396 0.09815096 0.05426889 0.22774 0.06933397 0.07660299 0.108164 0.2202669 0.100508 0.2145079 0.1374689 0.07660299 0.108164 0.08641898 0.07837396 0.2202669 0.100508 0.06909996 0.1430799 0.2145079 0.1374689 0.210884 0.178638 0.06909996 0.1430799 0.07660299 0.108164 0.2145079 0.1374689 0.06441098 0.181628 0.06909996 0.1430799 0.210884 0.178638 0.288588 0.230619 0.300559 0.227309 0.3 0.23195 0.286663 0.239062 0.3 0.23195 0.2999 0.232567 0.286663 0.239062 0.288588 0.230619 0.3 0.23195 0.286663 0.239062 0.2999 0.232567 0.297692 0.2416689 0.221898 0.16624 0.221928 0.277544 0.224198 0.193901 0.283562 0.247188 0.286663 0.239062 0.297692 0.2416689 0.283562 0.247188 0.297692 0.2416689 0.293953 0.250962 0.28144 0.251348 0.293953 0.250962 0.292882 0.253064 0.28144 0.251348 0.283562 0.247188 0.293953 0.250962 0.28144 0.251348 0.292882 0.253064 0.291417 0.255692 0.28144 0.251348 0.291417 0.255692 0.283381 0.269035 0.270178 0.271482 0.283381 0.269035 0.275616 0.281633 0.270178 0.271482 0.28144 0.251348 0.283381 0.269035 0.270178 0.271482 0.275616 0.281633 0.268146 0.29346 0.258564 0.291199 0.268146 0.29346 0.261011 0.304437 0.258564 0.291199 0.270178 0.271482 0.268146 0.29346 0.246834 0.310419 0.261011 0.304437 0.254195 0.314784 0.246834 0.310419 0.258564 0.291199 0.261011 0.304437 0.246834 0.310419 0.254195 0.314784 0.247663 0.32469 0.235265 0.32905 0.247663 0.32469 0.241447 0.334073 0.235265 0.32905 0.246834 0.310419 0.247663 0.32469 0.235265 0.32905 0.241447 0.334073 0.235572 0.343052 0.224201 0.346964 0.235572 0.343052 0.22486 0.35992 0.224201 0.346964 0.235265 0.32905 0.235572 0.343052 0.214047 0.364001 0.22486 0.35992 0.216 0.374962 0.214047 0.364001 0.224201 0.346964 0.22486 0.35992 0.205269 0.37995 0.216 0.374962 0.2091259 0.388325 0.205269 0.37995 0.214047 0.364001 0.216 0.374962 0.198356 0.394553 0.2091259 0.388325 0.204291 0.400194 0.198356 0.394553 0.205269 0.37995 0.2091259 0.388325 0.193742 0.407543 0.204291 0.400194 0.20156 0.410679 0.193742 0.407543 0.198356 0.394553 0.204291 0.400194 0.191705 0.418687 0.20156 0.410679 0.201037 0.419924 0.191705 0.418687 0.193742 0.407543 0.20156 0.410679 0.192358 0.427814 0.201037 0.419924 0.2029049 0.42791 0.191705 0.418687 0.201037 0.419924 0.192358 0.427814 0.206154 0.433996 0.2029049 0.42791 0.207411 0.434488 0.2180809 0.139549 0.218131 0.304213 0.221898 0.16624 0.206154 0.433996 0.204338 0.433297 0.2029049 0.42791 0.204155 0.433224 0.2029049 0.42791 0.204338 0.433297 0.203212 0.432838 0.2029049 0.42791 0.204155 0.433224 0.201961 0.432312 0.2029049 0.42791 0.203212 0.432838 0.200432 0.431659 0.2029049 0.42791 0.201961 0.432312 0.198703 0.430894 0.2029049 0.42791 0.200432 0.431659 0.196727 0.429984 0.2029049 0.42791 0.198703 0.430894 0.195488 0.429392 0.2029049 0.42791 0.196727 0.429984 0.19442 0.428867 0.2029049 0.42791 0.195488 0.429392 0.193005 0.428151 0.2029049 0.42791 0.19442 0.428867 0.192358 0.427814 0.2029049 0.42791 0.193005 0.428151 0.10449 0.426483 0.207411 0.434488 0.103572 0.427369 0.205032 0.433806 0.207411 0.434488 0.10449 0.426483 0.212803 0.114426 0.212862 0.329381 0.2180809 0.139549 0.205373 0.433779 0.207411 0.434488 0.205032 0.433806 0.205853 0.433893 0.207411 0.434488 0.205373 0.433779 0.206154 0.433996 0.207411 0.434488 0.205853 0.433893 0.09889596 0.42661 0.103572 0.427369 0.09509795 0.432124 0.10449 0.426483 0.103572 0.427369 0.09889596 0.42661 0.08077096 0.431224 0.09509795 0.432124 0.08516895 0.432272 0.09054195 0.431158 0.09509795 0.432124 0.08077096 0.431224 0.09889596 0.42661 0.09509795 0.432124 0.09054195 0.431158 0.06994098 0.426483 0.08516895 0.432272 0.07402199 0.427364 0.08077096 0.431224 0.08516895 0.432272 0.06994098 0.426483 0.05857288 0.416697 0.07402199 0.427364 0.06220096 0.41699 0.06994098 0.426483 0.07402199 0.427364 0.05857288 0.416697 0.04732197 0.401737 0.06220096 0.41699 0.05046695 0.400912 0.05857288 0.416697 0.06220096 0.41699 0.04732197 0.401737 0.03690797 0.381681 0.05046695 0.400912 0.03965193 0.379144 0.04732197 0.401737 0.05046695 0.400912 0.03690797 0.381681 0.027951 0.356862 0.03965193 0.379144 0.03041189 0.352033 0.03690797 0.381681 0.03965193 0.379144 0.027951 0.356862 0.02059292 0.327634 0.03041189 0.352033 0.02293497 0.320245 0.027951 0.356862 0.03041189 0.352033 0.02059292 0.327634 0.01471793 0.294602 0.02293497 0.320245 0.01718389 0.284609 0.02059292 0.327634 0.02293497 0.320245 0.01471793 0.294602 0.01076591 0.258943 0.01718389 0.284609 0.01371991 0.246266 0.01471793 0.294602 0.01718389 0.284609 0.01076591 0.258943 0.01076591 0.258943 0.01371991 0.246266 0.01312589 0.226617 0.009323954 0.222046 0.01312589 0.226617 0.01329195 0.206915 0.01076591 0.258943 0.01312589 0.226617 0.009323954 0.222046 0.009323954 0.222046 0.01329195 0.206915 0.01441293 0.186955 0.01071697 0.185176 0.01441293 0.186955 0.01619696 0.167423 0.009323954 0.222046 0.01441293 0.186955 0.01071697 0.185176 0.01469093 0.149532 0.01619696 0.167423 0.01862895 0.1485339 0.01071697 0.185176 0.01619696 0.167423 0.01469093 0.149532 0.01469093 0.149532 0.01862895 0.1485339 0.021649 0.130453 0.020563 0.116497 0.021649 0.130453 0.02511799 0.113284 0.01469093 0.149532 0.021649 0.130453 0.020563 0.116497 0.020563 0.116497 0.02511799 0.113284 0.02899998 0.09718799 0.02794295 0.08725696 0.02899998 0.09718799 0.03337496 0.08227598 0.020563 0.116497 0.02899998 0.09718799 0.02794295 0.08725696 0.02794295 0.08725696 0.03337496 0.08227598 0.038185 0.06864798 0.03690499 0.06243598 0.038185 0.06864798 0.04341989 0.05640697 0.02794295 0.08725696 0.038185 0.06864798 0.03690499 0.06243598 0.03690499 0.06243598 0.04341989 0.05640697 0.04907596 0.04560589 0.04735893 0.04236495 0.04907596 0.04560589 0.05497992 0.03628993 0.03690499 0.06243598 0.04907596 0.04560589 0.04735893 0.04236495 0.04735893 0.04236495 0.05497992 0.03628993 0.06100291 0.02847898 0.05859988 0.0273739 0.06100291 0.02847898 0.06707096 0.02216392 0.04735893 0.04236495 0.06100291 0.02847898 0.05859988 0.0273739 0.05859988 0.0273739 0.06707096 0.02216392 0.07302999 0.01733297 0.06989198 0.01757198 0.07302999 0.01733297 0.08442395 0.01192688 0.05859988 0.0273739 0.07302999 0.01733297 0.06989198 0.01757198 0.08063697 0.01283293 0.08442395 0.01192688 0.09471297 0.01186388 0.06989198 0.01757198 0.08442395 0.01192688 0.08063697 0.01283293 0.09041899 0.0128979 0.09471297 0.01186388 0.103559 0.01667797 0.08063697 0.01283293 0.09471297 0.01186388 0.09041899 0.0128979 0.100785 0.0191999 0.103559 0.01667797 0.104487 0.01756298 0.09888899 0.01744395 0.103559 0.01667797 0.100785 0.0191999 0.09041899 0.0128979 0.103559 0.01667797 0.09888899 0.01744395 0.276925 0.236818 0.278506 0.229477 0.288588 0.230619 0.279062 0.222023 0.288588 0.230619 0.278506 0.229477 0.286663 0.239062 0.276925 0.236818 0.288588 0.230619 0.279062 0.222023 0.289273 0.222023 0.288588 0.230619 0.268912 0.2350389 0.270214 0.228574 0.278506 0.229477 0.279062 0.222023 0.278506 0.229477 0.270214 0.228574 0.276925 0.236818 0.268912 0.2350389 0.278506 0.229477 0.26295 0.233797 0.264057 0.227949 0.270214 0.228574 0.27065 0.222023 0.270214 0.228574 0.264057 0.227949 0.268912 0.2350389 0.26295 0.233797 0.270214 0.228574 0.27065 0.222023 0.279062 0.222023 0.270214 0.228574 0.259243 0.23313 0.26025 0.22762 0.264057 0.227949 0.264414 0.222023 0.264057 0.227949 0.26025 0.22762 0.26295 0.233797 0.259243 0.23313 0.264057 0.227949 0.264414 0.222023 0.27065 0.222023 0.264057 0.227949 0.258504 0.230222 0.258906 0.2275699 0.26025 0.22762 0.260579 0.222023 0.26025 0.22762 0.258906 0.2275699 0.257904 0.233026 0.258504 0.230222 0.26025 0.22762 0.259243 0.23313 0.257904 0.233026 0.26025 0.22762 0.260579 0.222023 0.264414 0.222023 0.26025 0.22762 0.258482 0.2263399 0.258906 0.2275699 0.258504 0.230222 0.259242 0.222023 0.260579 0.222023 0.258906 0.2275699 0.258482 0.2263399 0.259242 0.222023 0.258906 0.2275699 0.257839 0.230602 0.258504 0.230222 0.257904 0.233026 0.257839 0.230602 0.258482 0.2263399 0.258504 0.230222 0.25627 0.238276 0.257904 0.233026 0.259243 0.23313 0.257286 0.232965 0.257904 0.233026 0.25627 0.238276 0.257582 0.2317799 0.257839 0.230602 0.257904 0.233026 0.257286 0.232965 0.257582 0.2317799 0.257904 0.233026 0.261117 0.239467 0.259243 0.23313 0.26295 0.233797 0.257587 0.23845 0.25627 0.238276 0.259243 0.23313 0.261117 0.239467 0.257587 0.23845 0.259243 0.23313 0.266771 0.24131 0.26295 0.233797 0.268912 0.2350389 0.266771 0.24131 0.261117 0.239467 0.26295 0.233797 0.266771 0.24131 0.268912 0.2350389 0.276925 0.236818 0.27436 0.24392 0.276925 0.236818 0.286663 0.239062 0.27436 0.24392 0.266771 0.24131 0.276925 0.236818 0.283562 0.247188 0.27436 0.24392 0.286663 0.239062 0.255784 0.23946 0.25627 0.238276 0.257587 0.23845 0.256014 0.23791 0.25627 0.238276 0.255717 0.23768 0.255587 0.2380239 0.255717 0.23768 0.25627 0.238276 0.256164 0.23652 0.25627 0.238276 0.256014 0.23791 0.25695 0.234158 0.257286 0.232965 0.25627 0.238276 0.256574 0.235347 0.25695 0.234158 0.25627 0.238276 0.256164 0.23652 0.256574 0.235347 0.25627 0.238276 0.255587 0.2380239 0.25627 0.238276 0.255784 0.23946 0.256474 0.241186 0.257587 0.23845 0.261117 0.239467 0.255784 0.23946 0.257587 0.23845 0.255133 0.240914 0.256474 0.241186 0.255133 0.240914 0.257587 0.23845 0.259891 0.242404 0.261117 0.239467 0.266771 0.24131 0.259891 0.242404 0.256474 0.241186 0.261117 0.239467 0.265325 0.244556 0.266771 0.24131 0.27436 0.24392 0.259891 0.242404 0.266771 0.24131 0.265325 0.244556 0.272602 0.2475759 0.27436 0.24392 0.283562 0.247188 0.265325 0.244556 0.27436 0.24392 0.272602 0.2475759 0.272602 0.2475759 0.283562 0.247188 0.28144 0.251348 0.288591 0.21345 0.289273 0.222023 0.279062 0.222023 0.278509 0.21459 0.279062 0.222023 0.27065 0.222023 0.288591 0.21345 0.279062 0.222023 0.278509 0.21459 0.264059 0.216114 0.27065 0.222023 0.264414 0.222023 0.270216 0.21549 0.27065 0.222023 0.264059 0.216114 0.278509 0.21459 0.27065 0.222023 0.270216 0.21549 0.260252 0.216441 0.264414 0.222023 0.260579 0.222023 0.264059 0.216114 0.264414 0.222023 0.260252 0.216441 0.260252 0.216441 0.260579 0.222023 0.259242 0.222023 0.260252 0.216441 0.259242 0.222023 0.258889 0.216339 0.258481 0.217702 0.258889 0.216339 0.259242 0.222023 0.258697 0.22202 0.258481 0.217702 0.259242 0.222023 0.258482 0.2263399 0.258697 0.22202 0.259242 0.222023 0.286677 0.205031 0.27436 0.200125 0.283562 0.196858 0.268922 0.209042 0.266771 0.202735 0.27436 0.200125 0.276937 0.2072679 0.268922 0.209042 0.27436 0.200125 0.286677 0.205031 0.276937 0.2072679 0.27436 0.200125 0.262959 0.210281 0.261117 0.204578 0.266771 0.202735 0.268922 0.209042 0.262959 0.210281 0.266771 0.202735 0.259251 0.210945 0.257587 0.205596 0.261117 0.204578 0.262959 0.210281 0.259251 0.210945 0.261117 0.204578 0.257878 0.210911 0.256262 0.205772 0.257587 0.205596 0.259251 0.210945 0.257878 0.210911 0.257587 0.205596 0.256164 0.207526 0.256262 0.205772 0.257878 0.210911 0.255275 0.205283 0.255724 0.204443 0.256262 0.205772 0.256014 0.206136 0.255726 0.206362 0.256262 0.205772 0.255613 0.206085 0.256262 0.205772 0.255726 0.206362 0.256164 0.207526 0.256014 0.206136 0.256262 0.205772 0.255499 0.205811 0.255275 0.205283 0.256262 0.205772 0.255613 0.206085 0.255499 0.205811 0.256262 0.205772 0.258384 0.2131879 0.257878 0.210911 0.259251 0.210945 0.257582 0.212265 0.257878 0.210911 0.258384 0.2131879 0.256575 0.2087 0.256164 0.207526 0.257878 0.210911 0.25695 0.209888 0.256575 0.2087 0.257878 0.210911 0.257286 0.21108 0.25695 0.209888 0.257878 0.210911 0.257582 0.212265 0.257286 0.21108 0.257878 0.210911 0.260252 0.216441 0.259251 0.210945 0.262959 0.210281 0.258889 0.216339 0.258384 0.2131879 0.259251 0.210945 0.260252 0.216441 0.258889 0.216339 0.259251 0.210945 0.264059 0.216114 0.262959 0.210281 0.268922 0.209042 0.264059 0.216114 0.260252 0.216441 0.262959 0.210281 0.270216 0.21549 0.268922 0.209042 0.276937 0.2072679 0.270216 0.21549 0.264059 0.216114 0.268922 0.209042 0.278509 0.21459 0.276937 0.2072679 0.286677 0.205031 0.278509 0.21459 0.270216 0.21549 0.276937 0.2072679 0.288591 0.21345 0.278509 0.21459 0.286677 0.205031 0.257839 0.2134439 0.258384 0.2131879 0.258889 0.216339 0.257839 0.2134439 0.257582 0.212265 0.258384 0.2131879 0.258481 0.217702 0.257839 0.2134439 0.258889 0.216339 0.2180809 0.139549 0.212862 0.329381 0.218131 0.304213 0.254802 0.204223 0.254669 0.203925 0.255724 0.204443 0.212803 0.114426 0.20607 0.352856 0.212862 0.329381 0.255044 0.204756 0.254802 0.204223 0.255724 0.204443 0.255275 0.205283 0.255044 0.204756 0.255724 0.204443 0.256164 0.207526 0.255726 0.206362 0.256014 0.206136 0.255792 0.206525 0.255613 0.206085 0.255726 0.206362 0.255839 0.206646 0.255726 0.206362 0.256164 0.207526 0.255792 0.206525 0.255726 0.206362 0.255839 0.206646 0.253969 0.202552 0.254626 0.2038249 0.254669 0.203925 0.254281 0.203195 0.254626 0.2038249 0.253969 0.202552 0.25197 0.1985239 0.254626 0.2038249 0.254281 0.203195 0.252599 0.199742 0.254626 0.2038249 0.25197 0.1985239 0.206024 0.091053 0.20607 0.352856 0.212803 0.114426 0.253969 0.202552 0.254669 0.203925 0.254183 0.2029899 0.254395 0.203427 0.254669 0.203925 0.254802 0.204223 0.254183 0.2029899 0.254669 0.203925 0.254395 0.203427 0.188195 0.0518999 0.1978 0.374019 0.197794 0.07001298 0.254395 0.203427 0.254802 0.204223 0.254599 0.203849 0.254788 0.204243 0.254802 0.204223 0.255044 0.204756 0.254788 0.204243 0.254599 0.203849 0.254802 0.204223 0.255225 0.205184 0.255044 0.204756 0.255275 0.205283 0.254788 0.204243 0.255044 0.204756 0.254793 0.204252 0.25501 0.204712 0.254793 0.204252 0.255044 0.204756 0.255225 0.205184 0.25501 0.204712 0.255044 0.204756 0.255428 0.205647 0.255275 0.205283 0.255499 0.205811 0.255428 0.205647 0.255225 0.205184 0.255275 0.205283 0.255792 0.206525 0.255499 0.205811 0.255613 0.206085 0.255617 0.2060959 0.255428 0.205647 0.255499 0.205811 0.255792 0.206525 0.255617 0.2060959 0.255499 0.205811 0.256164 0.23652 0.256014 0.23791 0.255717 0.23768 0.256343 0.236052 0.256164 0.23652 0.255717 0.23768 0.255839 0.237399 0.255717 0.23768 0.255587 0.2380239 0.256343 0.236052 0.255717 0.23768 0.255839 0.237399 0.256714 0.209093 0.256164 0.207526 0.256575 0.2087 0.255951 0.20693 0.255839 0.206646 0.256164 0.207526 0.256347 0.2080039 0.255951 0.20693 0.256164 0.207526 0.256714 0.209093 0.256347 0.2080039 0.256164 0.207526 0.257053 0.210198 0.256575 0.2087 0.25695 0.209888 0.257053 0.210198 0.256714 0.209093 0.256575 0.2087 0.257358 0.21131 0.25695 0.209888 0.257286 0.21108 0.257358 0.21131 0.257053 0.210198 0.25695 0.209888 0.257629 0.212417 0.257286 0.21108 0.257582 0.212265 0.257629 0.212417 0.257358 0.21131 0.257286 0.21108 0.257629 0.212417 0.257582 0.212265 0.257839 0.2134439 0.257857 0.213481 0.257839 0.2134439 0.258481 0.217702 0.257629 0.212417 0.257839 0.2134439 0.257857 0.213481 0.257866 0.21352 0.258481 0.217702 0.258697 0.22202 0.257866 0.21352 0.257857 0.213481 0.258481 0.217702 0.258708 0.222023 0.258697 0.22202 0.258482 0.2263399 0.258708 0.222023 0.257866 0.21352 0.258697 0.22202 0.258708 0.222023 0.258482 0.2263399 0.257839 0.230602 0.257857 0.230565 0.257839 0.230602 0.257582 0.2317799 0.258708 0.222023 0.257839 0.230602 0.257857 0.230565 0.257626 0.231642 0.257582 0.2317799 0.257286 0.232965 0.257866 0.230526 0.257857 0.230565 0.257582 0.2317799 0.257626 0.231642 0.257866 0.230526 0.257582 0.2317799 0.257353 0.232755 0.257286 0.232965 0.25695 0.234158 0.257353 0.232755 0.257626 0.231642 0.257286 0.232965 0.257047 0.233868 0.25695 0.234158 0.256574 0.235347 0.257047 0.233868 0.257353 0.232755 0.25695 0.234158 0.256709 0.23497 0.256574 0.235347 0.256164 0.23652 0.256709 0.23497 0.257047 0.233868 0.256574 0.235347 0.256343 0.236052 0.256709 0.23497 0.256164 0.23652 0.254709 0.240029 0.255133 0.240914 0.254626 0.24022 0.248691 0.254847 0.254626 0.24022 0.255133 0.240914 0.254167 0.241088 0.254709 0.240029 0.254626 0.24022 0.248691 0.254847 0.252813 0.243872 0.254626 0.24022 0.254281 0.24085 0.254626 0.24022 0.252813 0.243872 0.254167 0.241088 0.254626 0.24022 0.254281 0.24085 0.255151 0.239046 0.255784 0.23946 0.255133 0.240914 0.254805 0.239818 0.255151 0.239046 0.255133 0.240914 0.197794 0.07001298 0.1978 0.374019 0.206024 0.091053 0.254709 0.240029 0.254805 0.239818 0.255133 0.240914 0.177328 0.03726589 0.188142 0.39223 0.188195 0.0518999 0.245798 0.264049 0.248691 0.254847 0.255133 0.240914 0.256474 0.241186 0.245798 0.264049 0.255133 0.240914 0.255445 0.2383649 0.255587 0.2380239 0.255784 0.23946 0.255151 0.239046 0.255445 0.2383649 0.255784 0.23946 0.255606 0.237976 0.255587 0.2380239 0.255445 0.2383649 0.255951 0.237115 0.255839 0.237399 0.255587 0.2380239 0.255785 0.237536 0.255951 0.237115 0.255587 0.2380239 0.255606 0.237976 0.255785 0.237536 0.255587 0.2380239 0.255606 0.237976 0.255445 0.2383649 0.255151 0.239046 0.255212 0.238892 0.255151 0.239046 0.254805 0.239818 0.255212 0.238892 0.255606 0.237976 0.255151 0.239046 0.206024 0.091053 0.1978 0.374019 0.20607 0.352856 0.255212 0.238892 0.254805 0.239818 0.25479 0.239799 0.254375 0.240661 0.254805 0.239818 0.254709 0.240029 0.254586 0.240225 0.254805 0.239818 0.254375 0.240661 0.254793 0.239794 0.254805 0.239818 0.254586 0.240225 0.25479 0.239799 0.254805 0.239818 0.254793 0.239794 0.188195 0.0518999 0.188142 0.39223 0.1978 0.374019 0.254375 0.240661 0.254709 0.240029 0.254167 0.241088 0.248691 0.254847 0.250844 0.247824 0.252813 0.243872 0.25148 0.246499 0.252813 0.243872 0.250844 0.247824 0.254281 0.24085 0.252813 0.243872 0.25148 0.246499 0.248691 0.254847 0.248692 0.252068 0.250844 0.247824 0.25148 0.246499 0.250844 0.247824 0.248692 0.252068 0.248691 0.254847 0.246397 0.256516 0.248692 0.252068 0.248434 0.252488 0.248692 0.252068 0.246397 0.256516 0.25148 0.246499 0.248692 0.252068 0.248434 0.252488 0.242118 0.268382 0.243955 0.261168 0.246397 0.256516 0.245287 0.258525 0.246397 0.256516 0.243955 0.261168 0.248691 0.254847 0.242118 0.268382 0.246397 0.256516 0.248434 0.252488 0.246397 0.256516 0.245287 0.258525 0.242118 0.268382 0.241358 0.266027 0.243955 0.261168 0.2420679 0.264553 0.243955 0.261168 0.241358 0.266027 0.245287 0.258525 0.243955 0.261168 0.2420679 0.264553 0.242118 0.268382 0.238589 0.271112 0.241358 0.266027 0.238785 0.270554 0.241358 0.266027 0.238589 0.271112 0.2420679 0.264553 0.241358 0.266027 0.238785 0.270554 0.235453 0.281572 0.2356359 0.276427 0.238589 0.271112 0.238785 0.270554 0.238589 0.271112 0.2356359 0.276427 0.242118 0.268382 0.235453 0.281572 0.238589 0.271112 0.235453 0.281572 0.2324579 0.28203 0.2356359 0.276427 0.235444 0.276518 0.2356359 0.276427 0.2324579 0.28203 0.238785 0.270554 0.2356359 0.276427 0.235444 0.276518 0.228731 0.29444 0.229048 0.287912 0.2324579 0.28203 0.232047 0.282442 0.2324579 0.28203 0.229048 0.287912 0.235453 0.281572 0.228731 0.29444 0.2324579 0.28203 0.235444 0.276518 0.2324579 0.28203 0.232047 0.282442 0.228731 0.29444 0.2266539 0.291966 0.229048 0.287912 0.228595 0.288325 0.229048 0.287912 0.2266539 0.291966 0.232047 0.282442 0.229048 0.287912 0.228595 0.288325 0.221704 0.307515 0.224159 0.296125 0.2266539 0.291966 0.225087 0.294163 0.2266539 0.291966 0.224159 0.296125 0.228731 0.29444 0.221704 0.307515 0.2266539 0.291966 0.228595 0.288325 0.2266539 0.291966 0.225087 0.294163 0.221704 0.307515 0.221556 0.300396 0.224159 0.296125 0.225087 0.294163 0.224159 0.296125 0.221556 0.300396 0.221704 0.307515 0.218845 0.304771 0.221556 0.300396 0.221526 0.299956 0.221556 0.300396 0.218845 0.304771 0.225087 0.294163 0.221556 0.300396 0.221526 0.299956 0.2048619 0.335077 0.216014 0.309265 0.218845 0.304771 0.217912 0.305703 0.218845 0.304771 0.216014 0.309265 0.221704 0.307515 0.2048619 0.335077 0.218845 0.304771 0.221526 0.299956 0.218845 0.304771 0.217912 0.305703 0.2048619 0.335077 0.213043 0.313899 0.216014 0.309265 0.214246 0.311401 0.216014 0.309265 0.213043 0.313899 0.217912 0.305703 0.216014 0.309265 0.214246 0.311401 0.2048619 0.335077 0.2099339 0.318661 0.213043 0.313899 0.210527 0.317051 0.213043 0.313899 0.2099339 0.318661 0.214246 0.311401 0.213043 0.313899 0.210527 0.317051 0.2048619 0.335077 0.206688 0.323541 0.2099339 0.318661 0.210527 0.317051 0.2099339 0.318661 0.206688 0.323541 0.2048619 0.335077 0.203305 0.328532 0.206688 0.323541 0.206758 0.32265 0.206688 0.323541 0.203305 0.328532 0.210527 0.317051 0.206688 0.323541 0.206758 0.32265 0.2048619 0.335077 0.1997759 0.333635 0.203305 0.328532 0.202938 0.328199 0.203305 0.328532 0.1997759 0.333635 0.206758 0.32265 0.203305 0.328532 0.202938 0.328199 0.186627 0.361725 0.196096 0.338851 0.1997759 0.333635 0.1990669 0.333695 0.1997759 0.333635 0.196096 0.338851 0.2048619 0.335077 0.186627 0.361725 0.1997759 0.333635 0.202938 0.328199 0.1997759 0.333635 0.1990669 0.333695 0.186627 0.361725 0.192263 0.344173 0.196096 0.338851 0.195147 0.339138 0.196096 0.338851 0.192263 0.344173 0.1990669 0.333695 0.196096 0.338851 0.195147 0.339138 0.186627 0.361725 0.18928 0.348236 0.192263 0.344173 0.191178 0.344528 0.192263 0.344173 0.18928 0.348236 0.195147 0.339138 0.192263 0.344173 0.191178 0.344528 0.186627 0.361725 0.186204 0.35236 0.18928 0.348236 0.18716 0.349864 0.18928 0.348236 0.186204 0.35236 0.191178 0.344528 0.18928 0.348236 0.18716 0.349864 0.186627 0.361725 0.183032 0.356542 0.186204 0.35236 0.18716 0.349864 0.186204 0.35236 0.183032 0.356542 0.167174 0.387185 0.179761 0.36078 0.183032 0.356542 0.183094 0.355144 0.183032 0.356542 0.179761 0.36078 0.186627 0.361725 0.167174 0.387185 0.183032 0.356542 0.18716 0.349864 0.183032 0.356542 0.183094 0.355144 0.167174 0.387185 0.1763859 0.365078 0.179761 0.36078 0.178981 0.360369 0.179761 0.36078 0.1763859 0.365078 0.183094 0.355144 0.179761 0.36078 0.178981 0.360369 0.167174 0.387185 0.172906 0.369431 0.1763859 0.365078 0.17482 0.365537 0.1763859 0.365078 0.172906 0.369431 0.178981 0.360369 0.1763859 0.365078 0.17482 0.365537 0.167174 0.387185 0.169319 0.373836 0.172906 0.369431 0.170612 0.370648 0.172906 0.369431 0.169319 0.373836 0.17482 0.365537 0.172906 0.369431 0.170612 0.370648 0.167174 0.387185 0.165625 0.378289 0.169319 0.373836 0.170612 0.370648 0.169319 0.373836 0.165625 0.378289 0.1696979 0.401764 0.165625 0.378289 0.167174 0.387185 0.170612 0.370648 0.165625 0.378289 0.166356 0.375704 0.163525 0.378177 0.166356 0.375704 0.165625 0.378289 0.162731 0.380872 0.163525 0.378177 0.165625 0.378289 0.166499 0.404899 0.162731 0.380872 0.165625 0.378289 0.1696979 0.401764 0.166499 0.404899 0.165625 0.378289 0.179336 0.38344 0.167174 0.387185 0.186627 0.361725 0.16752 0.389098 0.167174 0.387185 0.179336 0.38344 0.1696979 0.401764 0.167174 0.387185 0.16752 0.389098 0.179336 0.38344 0.169868 0.401536 0.16752 0.389098 0.190311 0.363594 0.186627 0.361725 0.2048619 0.335077 0.190311 0.363594 0.179336 0.38344 0.186627 0.361725 0.2153609 0.319066 0.2048619 0.335077 0.221704 0.307515 0.196245 0.353069 0.190311 0.363594 0.2048619 0.335077 0.202428 0.342135 0.196245 0.353069 0.2048619 0.335077 0.20881 0.330809 0.202428 0.342135 0.2048619 0.335077 0.2153609 0.319066 0.20881 0.330809 0.2048619 0.335077 0.222921 0.308472 0.221704 0.307515 0.228731 0.29444 0.222921 0.308472 0.2153609 0.319066 0.221704 0.307515 0.234544 0.286502 0.228731 0.29444 0.235453 0.281572 0.234544 0.286502 0.222921 0.308472 0.228731 0.29444 0.234544 0.286502 0.235453 0.281572 0.242118 0.268382 0.245798 0.264049 0.242118 0.268382 0.248691 0.254847 0.245798 0.264049 0.234544 0.286502 0.242118 0.268382 0.1696979 0.401764 0.16752 0.389098 0.169868 0.401536 0.178688 0.389065 0.169868 0.401536 0.179336 0.38344 0.169798 0.402753 0.1696979 0.401764 0.169868 0.401536 0.178688 0.389065 0.169798 0.402753 0.169868 0.401536 0.188655 0.370361 0.179336 0.38344 0.190311 0.363594 0.188655 0.370361 0.178688 0.389065 0.179336 0.38344 0.199632 0.35055 0.190311 0.363594 0.196245 0.353069 0.199632 0.35055 0.188655 0.370361 0.190311 0.363594 0.199632 0.35055 0.196245 0.353069 0.202428 0.342135 0.211179 0.329864 0.202428 0.342135 0.20881 0.330809 0.211179 0.329864 0.199632 0.35055 0.202428 0.342135 0.211179 0.329864 0.20881 0.330809 0.2153609 0.319066 0.222921 0.308472 0.211179 0.329864 0.2153609 0.319066 0.170612 0.370648 0.166356 0.375704 0.169251 0.373064 0.163525 0.378177 0.169251 0.373064 0.166356 0.375704 0.17251 0.369127 0.170612 0.370648 0.169251 0.373064 0.180633 0.365213 0.17251 0.369127 0.169251 0.373064 0.167275 0.374968 0.169251 0.373064 0.163525 0.378177 0.183776 0.363589 0.169251 0.373064 0.167275 0.374968 0.180633 0.365213 0.169251 0.373064 0.183776 0.363589 0.175664 0.365252 0.17482 0.365537 0.170612 0.370648 0.17251 0.369127 0.175664 0.365252 0.170612 0.370648 0.178713 0.361442 0.178981 0.360369 0.17482 0.365537 0.175664 0.365252 0.178713 0.361442 0.17482 0.365537 0.181659 0.3577 0.183094 0.355144 0.178981 0.360369 0.178713 0.361442 0.181659 0.3577 0.178981 0.360369 0.185427 0.352823 0.18716 0.349864 0.183094 0.355144 0.181659 0.3577 0.185427 0.352823 0.183094 0.355144 0.189024 0.34807 0.191178 0.344528 0.18716 0.349864 0.185427 0.352823 0.189024 0.34807 0.18716 0.349864 0.195729 0.338947 0.195147 0.339138 0.191178 0.344528 0.1929579 0.34276 0.195729 0.338947 0.191178 0.344528 0.192457 0.343443 0.1929579 0.34276 0.191178 0.344528 0.189024 0.34807 0.192457 0.343443 0.191178 0.344528 0.198859 0.334567 0.1990669 0.333695 0.195147 0.339138 0.195729 0.338947 0.198859 0.334567 0.195147 0.339138 0.201847 0.33031 0.202938 0.328199 0.1990669 0.333695 0.198859 0.334567 0.201847 0.33031 0.1990669 0.333695 0.20744 0.322135 0.206758 0.32265 0.202938 0.328199 0.204703 0.32617 0.20744 0.322135 0.202938 0.328199 0.201847 0.33031 0.204703 0.32617 0.202938 0.328199 0.210057 0.318216 0.210527 0.317051 0.206758 0.32265 0.20744 0.322135 0.210057 0.318216 0.206758 0.32265 0.213784 0.312527 0.214246 0.311401 0.210527 0.317051 0.210057 0.318216 0.213784 0.312527 0.210527 0.317051 0.21728 0.307069 0.217912 0.305703 0.214246 0.311401 0.215221 0.310297 0.21728 0.307069 0.214246 0.311401 0.213784 0.312527 0.215221 0.310297 0.214246 0.311401 0.220575 0.301816 0.221526 0.299956 0.217912 0.305703 0.21728 0.307069 0.220575 0.301816 0.217912 0.305703 0.223679 0.296765 0.225087 0.294163 0.221526 0.299956 0.220575 0.301816 0.223679 0.296765 0.221526 0.299956 0.226618 0.291891 0.228595 0.288325 0.225087 0.294163 0.223679 0.296765 0.226618 0.291891 0.225087 0.294163 0.232056 0.282619 0.232047 0.282442 0.228595 0.288325 0.229405 0.28718 0.232056 0.282619 0.228595 0.288325 0.226618 0.291891 0.229405 0.28718 0.228595 0.288325 0.234594 0.278177 0.235444 0.276518 0.232047 0.282442 0.232056 0.282619 0.234594 0.278177 0.232047 0.282442 0.237027 0.273846 0.238785 0.270554 0.235444 0.276518 0.235872 0.275911 0.237027 0.273846 0.235444 0.276518 0.234594 0.278177 0.235872 0.275911 0.235444 0.276518 0.241604 0.265499 0.2420679 0.264553 0.238785 0.270554 0.2393659 0.269615 0.241604 0.265499 0.238785 0.270554 0.237027 0.273846 0.2393659 0.269615 0.238785 0.270554 0.243725 0.261539 0.245287 0.258525 0.2420679 0.264553 0.241604 0.265499 0.243725 0.261539 0.2420679 0.264553 0.247718 0.253914 0.248434 0.252488 0.245287 0.258525 0.245754 0.257693 0.247718 0.253914 0.245287 0.258525 0.243725 0.261539 0.245754 0.257693 0.245287 0.258525 0.251219 0.247036 0.25148 0.246499 0.248434 0.252488 0.249544 0.250351 0.251219 0.247036 0.248434 0.252488 0.247718 0.253914 0.249544 0.250351 0.248434 0.252488 0.253969 0.2414939 0.254281 0.24085 0.25148 0.246499 0.251219 0.247036 0.253969 0.2414939 0.25148 0.246499 0.254167 0.241088 0.254281 0.24085 0.253969 0.2414939 0.2395409 0.273517 0.253969 0.2414939 0.251219 0.247036 0.254167 0.241088 0.253969 0.2414939 0.2395409 0.273517 0.2395409 0.273517 0.251219 0.247036 0.249544 0.250351 0.235872 0.275911 0.249544 0.250351 0.247718 0.253914 0.2395409 0.273517 0.249544 0.250351 0.235872 0.275911 0.2393659 0.269615 0.247718 0.253914 0.245754 0.257693 0.237027 0.273846 0.247718 0.253914 0.2393659 0.269615 0.235872 0.275911 0.247718 0.253914 0.237027 0.273846 0.241604 0.265499 0.245754 0.257693 0.243725 0.261539 0.2393659 0.269615 0.245754 0.257693 0.241604 0.265499 0.232056 0.282619 0.235872 0.275911 0.234594 0.278177 0.229405 0.28718 0.235872 0.275911 0.232056 0.282619 0.226618 0.291891 0.235872 0.275911 0.229405 0.28718 0.223679 0.296765 0.235872 0.275911 0.226618 0.291891 0.220575 0.301816 0.235872 0.275911 0.223679 0.296765 0.21728 0.307069 0.235872 0.275911 0.220575 0.301816 0.215221 0.310297 0.235872 0.275911 0.21728 0.307069 0.2395409 0.273517 0.235872 0.275911 0.215221 0.310297 0.210057 0.318216 0.215221 0.310297 0.213784 0.312527 0.20744 0.322135 0.215221 0.310297 0.210057 0.318216 0.204703 0.32617 0.215221 0.310297 0.20744 0.322135 0.201847 0.33031 0.215221 0.310297 0.204703 0.32617 0.222189 0.306503 0.215221 0.310297 0.201847 0.33031 0.2395409 0.273517 0.215221 0.310297 0.222189 0.306503 0.222189 0.306503 0.201847 0.33031 0.198859 0.334567 0.222189 0.306503 0.198859 0.334567 0.195729 0.338947 0.222189 0.306503 0.195729 0.338947 0.1929579 0.34276 0.180633 0.365213 0.1929579 0.34276 0.192457 0.343443 0.203694 0.33752 0.1929579 0.34276 0.180633 0.365213 0.222189 0.306503 0.1929579 0.34276 0.203694 0.33752 0.180633 0.365213 0.192457 0.343443 0.189024 0.34807 0.180633 0.365213 0.189024 0.34807 0.185427 0.352823 0.180633 0.365213 0.185427 0.352823 0.181659 0.3577 0.180633 0.365213 0.181659 0.3577 0.178713 0.361442 0.180633 0.365213 0.178713 0.361442 0.175664 0.365252 0.180633 0.365213 0.175664 0.365252 0.17251 0.369127 0.1622959 0.377225 0.156316 0.380298 0.159538 0.377472 0.158903 0.376439 0.159538 0.377472 0.156316 0.380298 0.171033 0.36983 0.1622959 0.377225 0.159538 0.377472 0.158903 0.376439 0.171033 0.36983 0.159538 0.377472 0.163195 0.377008 0.160086 0.37975 0.156316 0.380298 0.155346 0.383214 0.156316 0.380298 0.160086 0.37975 0.1622959 0.377225 0.163195 0.377008 0.156316 0.380298 0.134935 0.398149 0.156316 0.380298 0.155346 0.383214 0.134935 0.398149 0.158903 0.376439 0.156316 0.380298 0.16492 0.376379 0.163525 0.378177 0.160086 0.37975 0.15921 0.382558 0.160086 0.37975 0.163525 0.378177 0.163195 0.377008 0.16492 0.376379 0.160086 0.37975 0.15921 0.382558 0.155346 0.383214 0.160086 0.37975 0.166528 0.375496 0.167275 0.374968 0.163525 0.378177 0.16492 0.376379 0.166528 0.375496 0.163525 0.378177 0.162731 0.380872 0.15921 0.382558 0.163525 0.378177 0.181469 0.365086 0.167275 0.374968 0.166528 0.375496 0.183776 0.363589 0.167275 0.374968 0.181469 0.365086 0.181469 0.365086 0.166528 0.375496 0.16492 0.376379 0.178865 0.365999 0.16492 0.376379 0.163195 0.377008 0.181469 0.365086 0.16492 0.376379 0.178865 0.365999 0.178865 0.365999 0.163195 0.377008 0.1622959 0.377225 0.178865 0.365999 0.1622959 0.377225 0.171033 0.36983 0.156268 0.394814 0.155346 0.383214 0.15921 0.382558 0.156268 0.394814 0.134935 0.398149 0.155346 0.383214 0.166499 0.404899 0.15921 0.382558 0.162731 0.380872 0.156268 0.394814 0.15921 0.382558 0.157471 0.407983 0.162227 0.40712 0.157471 0.407983 0.15921 0.382558 0.177328 0.03726589 0.177215 0.406904 0.188142 0.39223 0.166499 0.404899 0.162227 0.40712 0.15921 0.382558 0.165331 0.02667999 0.165178 0.417468 0.177215 0.406904 0.219852 0.331934 0.218323 0.331196 0.22336 0.325861 0.224606 0.321878 0.22336 0.325861 0.218323 0.331196 0.226041 0.325438 0.219852 0.331934 0.22336 0.325861 0.225125 0.324403 0.226041 0.325438 0.22336 0.325861 0.224606 0.321878 0.225125 0.324403 0.22336 0.325861 0.219852 0.331934 0.212597 0.336825 0.218323 0.331196 0.211212 0.332217 0.218323 0.331196 0.212597 0.336825 0.211212 0.332217 0.224606 0.321878 0.218323 0.331196 0.2124339 0.339131 0.206113 0.342761 0.212597 0.336825 0.211212 0.332217 0.212597 0.336825 0.206113 0.342761 0.219852 0.331934 0.2124339 0.339131 0.212597 0.336825 0.2034 0.347116 0.198796 0.34902 0.206113 0.342761 0.196161 0.344374 0.206113 0.342761 0.198796 0.34902 0.2124339 0.339131 0.2034 0.347116 0.206113 0.342761 0.196161 0.344374 0.211212 0.332217 0.206113 0.342761 0.1923699 0.356022 0.190567 0.355612 0.198796 0.34902 0.196161 0.344374 0.198796 0.34902 0.190567 0.355612 0.2034 0.347116 0.1923699 0.356022 0.198796 0.34902 0.1923699 0.356022 0.181344 0.362545 0.190567 0.355612 0.178961 0.35887 0.190567 0.355612 0.181344 0.362545 0.178961 0.35887 0.196161 0.344374 0.190567 0.355612 0.178865 0.365999 0.171033 0.36983 0.181344 0.362545 0.178961 0.35887 0.181344 0.362545 0.171033 0.36983 0.1923699 0.356022 0.178865 0.365999 0.181344 0.362545 0.158903 0.376439 0.178961 0.35887 0.171033 0.36983 0.181469 0.365086 0.178865 0.365999 0.1923699 0.356022 0.1949509 0.355048 0.1923699 0.356022 0.2034 0.347116 0.1949509 0.355048 0.181469 0.365086 0.1923699 0.356022 0.205952 0.346087 0.2034 0.347116 0.2124339 0.339131 0.205952 0.346087 0.1949509 0.355048 0.2034 0.347116 0.214954 0.338051 0.2124339 0.339131 0.219852 0.331934 0.214954 0.338051 0.205952 0.346087 0.2124339 0.339131 0.2223359 0.330809 0.219852 0.331934 0.226041 0.325438 0.2223359 0.330809 0.214954 0.338051 0.219852 0.331934 0.2223359 0.330809 0.226041 0.325438 0.228488 0.324271 0.228476 0.323401 0.228488 0.324271 0.226041 0.325438 0.228476 0.323401 0.226041 0.325438 0.225125 0.324403 0.2244 0.329037 0.2223359 0.330809 0.228488 0.324271 0.2244 0.329037 0.228488 0.324271 0.2304829 0.322447 0.230708 0.322435 0.2304829 0.322447 0.228488 0.324271 0.230708 0.322435 0.228488 0.324271 0.228476 0.323401 0.183776 0.363589 0.181469 0.365086 0.1949509 0.355048 0.197203 0.353472 0.1949509 0.355048 0.205952 0.346087 0.197203 0.353472 0.183776 0.363589 0.1949509 0.355048 0.208145 0.344439 0.205952 0.346087 0.214954 0.338051 0.208145 0.344439 0.197203 0.353472 0.205952 0.346087 0.217083 0.336338 0.214954 0.338051 0.2223359 0.330809 0.217083 0.336338 0.208145 0.344439 0.214954 0.338051 0.2244 0.329037 0.217083 0.336338 0.2223359 0.330809 0.226998 0.325557 0.2244 0.329037 0.2304829 0.322447 0.231486 0.320561 0.2304829 0.322447 0.231867 0.320125 0.232589 0.320895 0.231867 0.320125 0.2304829 0.322447 0.231486 0.320561 0.226998 0.325557 0.2304829 0.322447 0.232589 0.320895 0.2304829 0.322447 0.230708 0.322435 0.190843 0.357735 0.183776 0.363589 0.197203 0.353472 0.190843 0.357735 0.180633 0.365213 0.183776 0.363589 0.199955 0.35062 0.197203 0.353472 0.208145 0.344439 0.199955 0.35062 0.190843 0.357735 0.197203 0.353472 0.215184 0.337445 0.208145 0.344439 0.217083 0.336338 0.208039 0.343864 0.199955 0.35062 0.208145 0.344439 0.215184 0.337445 0.208039 0.343864 0.208145 0.344439 0.221478 0.331341 0.217083 0.336338 0.2244 0.329037 0.221478 0.331341 0.215184 0.337445 0.217083 0.336338 0.226998 0.325557 0.221478 0.331341 0.2244 0.329037 0.235621 0.308344 0.231486 0.320561 0.231867 0.320125 0.233174 0.319302 0.231867 0.320125 0.232589 0.320895 0.237793 0.308753 0.231867 0.320125 0.233174 0.319302 0.235621 0.308344 0.231867 0.320125 0.237793 0.308753 0.203694 0.33752 0.180633 0.365213 0.190843 0.357735 0.203694 0.33752 0.190843 0.357735 0.199955 0.35062 0.212607 0.332758 0.199955 0.35062 0.208039 0.343864 0.203694 0.33752 0.199955 0.35062 0.212607 0.332758 0.220017 0.328373 0.208039 0.343864 0.215184 0.337445 0.212607 0.332758 0.208039 0.343864 0.220017 0.328373 0.220017 0.328373 0.215184 0.337445 0.221478 0.331341 0.226215 0.324308 0.221478 0.331341 0.226998 0.325557 0.220017 0.328373 0.221478 0.331341 0.226215 0.324308 0.226215 0.324308 0.226998 0.325557 0.231486 0.320561 0.239935 0.294503 0.231486 0.320561 0.235621 0.308344 0.226215 0.324308 0.231486 0.320561 0.239935 0.294503 0.257059 0.314532 0.256092 0.314553 0.265274 0.313032 0.253855 0.314258 0.265274 0.313032 0.256092 0.314553 0.266074 0.313027 0.257059 0.314532 0.265274 0.313032 0.274319 0.31179 0.266074 0.313027 0.265274 0.313032 0.274319 0.31179 0.265274 0.313032 0.269028 0.312482 0.281002 0.310339 0.269028 0.312482 0.265274 0.313032 0.253855 0.314258 0.281002 0.310339 0.265274 0.313032 0.249329 0.316133 0.247568 0.316309 0.256092 0.314553 0.249117 0.314954 0.256092 0.314553 0.247568 0.316309 0.257059 0.314532 0.249329 0.316133 0.256092 0.314553 0.249117 0.314954 0.253855 0.314258 0.256092 0.314553 0.2426339 0.31782 0.239764 0.318304 0.247568 0.316309 0.240607 0.316346 0.247568 0.316309 0.239764 0.318304 0.249329 0.316133 0.2426339 0.31782 0.247568 0.316309 0.244715 0.31565 0.249117 0.314954 0.247568 0.316309 0.240607 0.316346 0.244715 0.31565 0.247568 0.316309 0.236897 0.319592 0.236185 0.319393 0.239764 0.318304 0.231367 0.318456 0.239764 0.318304 0.236185 0.319393 0.2426339 0.31782 0.236897 0.319592 0.239764 0.318304 0.2369419 0.317044 0.240607 0.316346 0.239764 0.318304 0.233912 0.317737 0.2369419 0.317044 0.239764 0.318304 0.231367 0.318456 0.233912 0.317737 0.239764 0.318304 0.236897 0.319592 0.232894 0.320538 0.236185 0.319393 0.227461 0.320072 0.236185 0.319393 0.232894 0.320538 0.2292439 0.319239 0.231367 0.318456 0.236185 0.319393 0.227461 0.320072 0.2292439 0.319239 0.236185 0.319393 0.232145 0.321452 0.229893 0.321746 0.232894 0.320538 0.225901 0.32095 0.232894 0.320538 0.229893 0.321746 0.236897 0.319592 0.232145 0.321452 0.232894 0.320538 0.225901 0.32095 0.227461 0.320072 0.232894 0.320538 0.228476 0.323401 0.227301 0.323033 0.229893 0.321746 0.224606 0.321878 0.229893 0.321746 0.227301 0.323033 0.232145 0.321452 0.228476 0.323401 0.229893 0.321746 0.224606 0.321878 0.225901 0.32095 0.229893 0.321746 0.228476 0.323401 0.225125 0.324403 0.227301 0.323033 0.224606 0.321878 0.227301 0.323033 0.225125 0.324403 0.230708 0.322435 0.228476 0.323401 0.232145 0.321452 0.23415 0.320667 0.232145 0.321452 0.236897 0.319592 0.23415 0.320667 0.230708 0.322435 0.232145 0.321452 0.238669 0.318971 0.236897 0.319592 0.2426339 0.31782 0.238669 0.318971 0.23415 0.320667 0.236897 0.319592 0.244168 0.317344 0.2426339 0.31782 0.249329 0.316133 0.244168 0.317344 0.238669 0.318971 0.2426339 0.31782 0.250622 0.315785 0.249329 0.316133 0.257059 0.314532 0.250622 0.315785 0.244168 0.317344 0.249329 0.316133 0.258105 0.314295 0.257059 0.314532 0.266074 0.313027 0.258105 0.314295 0.250622 0.315785 0.257059 0.314532 0.258105 0.314295 0.266074 0.313027 0.26686 0.312884 0.274319 0.31179 0.26686 0.312884 0.266074 0.313027 0.259099 0.313864 0.258105 0.314295 0.26686 0.312884 0.259099 0.313864 0.26686 0.312884 0.267619 0.312604 0.274319 0.31179 0.267619 0.312604 0.26686 0.312884 0.232589 0.320895 0.230708 0.322435 0.23415 0.320667 0.235891 0.319393 0.23415 0.320667 0.238669 0.318971 0.235891 0.319393 0.232589 0.320895 0.23415 0.320667 0.240249 0.317941 0.238669 0.318971 0.244168 0.317344 0.240249 0.317941 0.235891 0.319393 0.238669 0.318971 0.24557 0.316537 0.244168 0.317344 0.250622 0.315785 0.24557 0.316537 0.240249 0.317941 0.244168 0.317344 0.251829 0.315178 0.250622 0.315785 0.258105 0.314295 0.251829 0.315178 0.24557 0.316537 0.250622 0.315785 0.259099 0.313864 0.251829 0.315178 0.258105 0.314295 0.260136 0.313226 0.259099 0.313864 0.267619 0.312604 0.260136 0.313226 0.267619 0.312604 0.268337 0.312192 0.272067 0.311656 0.268337 0.312192 0.267619 0.312604 0.275771 0.311124 0.272067 0.311656 0.267619 0.312604 0.274319 0.31179 0.275771 0.311124 0.267619 0.312604 0.234953 0.31851 0.232589 0.320895 0.235891 0.319393 0.234953 0.31851 0.233174 0.319302 0.232589 0.320895 0.239742 0.317017 0.235891 0.319393 0.240249 0.317941 0.234986 0.318497 0.234953 0.31851 0.235891 0.319393 0.237203 0.317732 0.234986 0.318497 0.235891 0.319393 0.239742 0.317017 0.237203 0.317732 0.235891 0.319393 0.242586 0.316317 0.240249 0.317941 0.24557 0.316537 0.240198 0.316899 0.239742 0.317017 0.240249 0.317941 0.242586 0.316317 0.240198 0.316899 0.240249 0.317941 0.247573 0.315289 0.24557 0.316537 0.251829 0.315178 0.2456949 0.315656 0.242586 0.316317 0.24557 0.316537 0.247573 0.315289 0.2456949 0.315656 0.24557 0.316537 0.256995 0.313699 0.251829 0.315178 0.259099 0.313864 0.252563 0.314392 0.247573 0.315289 0.251829 0.315178 0.256995 0.313699 0.252563 0.314392 0.251829 0.315178 0.260136 0.313226 0.256995 0.313699 0.259099 0.313864 0.267841 0.309791 0.260136 0.313226 0.268337 0.312192 0.275771 0.311124 0.268337 0.312192 0.272067 0.311656 0.267841 0.309791 0.268337 0.312192 0.275771 0.311124 0.237793 0.308753 0.233174 0.319302 0.234953 0.31851 0.242646 0.307325 0.234953 0.31851 0.234986 0.318497 0.237793 0.308753 0.234953 0.31851 0.242646 0.307325 0.242646 0.307325 0.234986 0.318497 0.237203 0.317732 0.242646 0.307325 0.237203 0.317732 0.239742 0.317017 0.242646 0.307325 0.239742 0.317017 0.240198 0.316899 0.248913 0.307968 0.240198 0.316899 0.242586 0.316317 0.242646 0.307325 0.240198 0.316899 0.248913 0.307968 0.248913 0.307968 0.242586 0.316317 0.2456949 0.315656 0.248913 0.307968 0.2456949 0.315656 0.247573 0.315289 0.257303 0.308111 0.247573 0.315289 0.252563 0.314392 0.248913 0.307968 0.247573 0.315289 0.257303 0.308111 0.257303 0.308111 0.252563 0.314392 0.256995 0.313699 0.267841 0.309791 0.256995 0.313699 0.260136 0.313226 0.267638 0.306984 0.256995 0.313699 0.267841 0.309791 0.267725 0.303748 0.256995 0.313699 0.267638 0.306984 0.257303 0.308111 0.256995 0.313699 0.267725 0.303748 0.274319 0.31179 0.269028 0.312482 0.27276 0.311936 0.281002 0.310339 0.27276 0.311936 0.269028 0.312482 0.278973 0.311061 0.274319 0.31179 0.27276 0.311936 0.281002 0.310339 0.278973 0.311061 0.27276 0.311936 0.283379 0.310542 0.275771 0.311124 0.274319 0.31179 0.287725 0.309563 0.275771 0.311124 0.283379 0.310542 0.296732 0.306403 0.275771 0.311124 0.287725 0.309563 0.278192 0.308804 0.275771 0.311124 0.296732 0.306403 0.267841 0.309791 0.275771 0.311124 0.278192 0.308804 0.283379 0.310542 0.274319 0.31179 0.278973 0.311061 0.302479 0.308332 0.298196 0.308747 0.311605 0.307425 0.294213 0.308454 0.311605 0.307425 0.298196 0.308747 0.312631 0.307347 0.302479 0.308332 0.311605 0.307425 0.337187 0.305093 0.312631 0.307347 0.311605 0.307425 0.337187 0.305093 0.311605 0.307425 0.323941 0.306301 0.307215 0.306614 0.323941 0.306301 0.311605 0.307425 0.294213 0.308454 0.307215 0.306614 0.311605 0.307425 0.292753 0.309393 0.28528 0.31024 0.298196 0.308747 0.294213 0.308454 0.298196 0.308747 0.28528 0.31024 0.302479 0.308332 0.292753 0.309393 0.298196 0.308747 0.283379 0.310542 0.278973 0.311061 0.28528 0.31024 0.281002 0.310339 0.28528 0.31024 0.278973 0.311061 0.292753 0.309393 0.283379 0.310542 0.28528 0.31024 0.281002 0.310339 0.294213 0.308454 0.28528 0.31024 0.287725 0.309563 0.283379 0.310542 0.292753 0.309393 0.293943 0.308831 0.292753 0.309393 0.302479 0.308332 0.293943 0.308831 0.287725 0.309563 0.292753 0.309393 0.300286 0.308134 0.302479 0.308332 0.312631 0.307347 0.300286 0.308134 0.293943 0.308831 0.302479 0.308332 0.300286 0.308134 0.312631 0.307347 0.313591 0.306811 0.325874 0.305674 0.313591 0.306811 0.312631 0.307347 0.338188 0.304519 0.325874 0.305674 0.312631 0.307347 0.337187 0.305093 0.338188 0.304519 0.312631 0.307347 0.300286 0.308134 0.313591 0.306811 0.293943 0.308831 0.316415 0.304629 0.293943 0.308831 0.313591 0.306811 0.338188 0.304519 0.313591 0.306811 0.325874 0.305674 0.316415 0.304629 0.313591 0.306811 0.338188 0.304519 0.296732 0.306403 0.287725 0.309563 0.293943 0.308831 0.316415 0.304629 0.296732 0.306403 0.293943 0.308831 0.337187 0.305093 0.323941 0.306301 0.336114 0.305185 0.332488 0.303083 0.336114 0.305185 0.323941 0.306301 0.340934 0.30477 0.337187 0.305093 0.336114 0.305185 0.332488 0.303083 0.340934 0.30477 0.336114 0.305185 0.307215 0.306614 0.332488 0.303083 0.323941 0.306301 0.343492 0.304607 0.338188 0.304519 0.337187 0.305093 0.34285 0.304306 0.338188 0.304519 0.343492 0.304607 0.341618 0.303328 0.338188 0.304519 0.34285 0.304306 0.338728 0.301844 0.338188 0.304519 0.341618 0.303328 0.335085 0.303091 0.338188 0.304519 0.338728 0.301844 0.316415 0.304629 0.338188 0.304519 0.335085 0.303091 0.340934 0.30477 0.343492 0.304607 0.337187 0.305093 0.365668 0.303376 0.364729 0.303404 0.372362 0.303052 0.365133 0.303352 0.372362 0.303052 0.364729 0.303404 0.36895 0.303271 0.365668 0.303376 0.372362 0.303052 0.332488 0.303083 0.372362 0.303052 0.365133 0.303352 0.430379 0.303143 0.36895 0.303271 0.372362 0.303052 0.431301 0.302447 0.430379 0.303143 0.372362 0.303052 0.336903 0.302169 0.431301 0.302447 0.372362 0.303052 0.332488 0.303083 0.336903 0.302169 0.372362 0.303052 0.359368 0.303659 0.357308 0.303775 0.364729 0.303404 0.358374 0.303673 0.364729 0.303404 0.357308 0.303775 0.365668 0.303376 0.359368 0.303659 0.364729 0.303404 0.358374 0.303673 0.365133 0.303352 0.364729 0.303404 0.35341 0.303913 0.350201 0.304173 0.357308 0.303775 0.352071 0.304016 0.357308 0.303775 0.350201 0.304173 0.355389 0.30383 0.35341 0.303913 0.357308 0.303775 0.359368 0.303659 0.355389 0.30383 0.357308 0.303775 0.352071 0.304016 0.358374 0.303673 0.357308 0.303775 0.34556 0.304209 0.343492 0.304607 0.350201 0.304173 0.346249 0.304381 0.350201 0.304173 0.343492 0.304607 0.347884 0.304128 0.34556 0.304209 0.350201 0.304173 0.35341 0.303913 0.347884 0.304128 0.350201 0.304173 0.346249 0.304381 0.352071 0.304016 0.350201 0.304173 0.34556 0.304209 0.34285 0.304306 0.343492 0.304607 0.340934 0.30477 0.346249 0.304381 0.343492 0.304607 0.341618 0.303328 0.34285 0.304306 0.34556 0.304209 0.34613 0.302869 0.34556 0.304209 0.347884 0.304128 0.341618 0.303328 0.34556 0.304209 0.34613 0.302869 0.350315 0.303598 0.347884 0.304128 0.35341 0.303913 0.34613 0.302869 0.347884 0.304128 0.350315 0.303598 0.350315 0.303598 0.35341 0.303913 0.355389 0.30383 0.360021 0.303548 0.355389 0.30383 0.359368 0.303659 0.355164 0.303386 0.350315 0.303598 0.355389 0.30383 0.360021 0.303548 0.355164 0.303386 0.355389 0.30383 0.365755 0.303429 0.359368 0.303659 0.365668 0.303376 0.365755 0.303429 0.360021 0.303548 0.359368 0.303659 0.36895 0.303271 0.365755 0.303429 0.365668 0.303376 0.332488 0.303083 0.365133 0.303352 0.358374 0.303673 0.332488 0.303083 0.358374 0.303673 0.352071 0.304016 0.332488 0.303083 0.352071 0.304016 0.346249 0.304381 0.332488 0.303083 0.346249 0.304381 0.340934 0.30477 0.351159 0.302884 0.34613 0.302869 0.350315 0.303598 0.355164 0.303386 0.351159 0.302884 0.350315 0.303598 0.348046 0.301937 0.343119 0.301548 0.34613 0.302869 0.341618 0.303328 0.34613 0.302869 0.343119 0.301548 0.351159 0.302884 0.348046 0.301937 0.34613 0.302869 0.346105 0.300471 0.341401 0.299603 0.343119 0.301548 0.338728 0.301844 0.343119 0.301548 0.341401 0.299603 0.348046 0.301937 0.346105 0.300471 0.343119 0.301548 0.338728 0.301844 0.341618 0.303328 0.343119 0.301548 0.345395 0.298407 0.340894 0.297071 0.341401 0.299603 0.336978 0.299755 0.341401 0.299603 0.340894 0.297071 0.346105 0.300471 0.345395 0.298407 0.341401 0.299603 0.336978 0.299755 0.338728 0.301844 0.341401 0.299603 0.34583 0.295793 0.341395 0.294023 0.340894 0.297071 0.336282 0.297106 0.340894 0.297071 0.341395 0.294023 0.345395 0.298407 0.34583 0.295793 0.340894 0.297071 0.336282 0.297106 0.336978 0.299755 0.340894 0.297071 0.34731 0.292577 0.342687 0.290524 0.341395 0.294023 0.336465 0.29396 0.341395 0.294023 0.342687 0.290524 0.34645 0.294271 0.34731 0.292577 0.341395 0.294023 0.34583 0.295793 0.34645 0.294271 0.341395 0.294023 0.336465 0.29396 0.336282 0.297106 0.341395 0.294023 0.349793 0.288609 0.344588 0.286629 0.342687 0.290524 0.337349 0.290376 0.342687 0.290524 0.344588 0.286629 0.348424 0.290705 0.349793 0.288609 0.342687 0.290524 0.34731 0.292577 0.348424 0.290705 0.342687 0.290524 0.337349 0.290376 0.336465 0.29396 0.342687 0.290524 0.35015 0.282916 0.346962 0.282381 0.344588 0.286629 0.338782 0.286402 0.344588 0.286629 0.346962 0.282381 0.353322 0.283701 0.35015 0.282916 0.344588 0.286629 0.351423 0.286277 0.353322 0.283701 0.344588 0.286629 0.349793 0.288609 0.351423 0.286277 0.344588 0.286629 0.338782 0.286402 0.337349 0.290376 0.344588 0.286629 0.353618 0.276597 0.346962 0.282381 0.35015 0.282916 0.343785 0.2821 0.338782 0.286402 0.346962 0.282381 0.349413 0.275747 0.343785 0.2821 0.346962 0.282381 0.349413 0.275747 0.346962 0.282381 0.353618 0.276597 0.353618 0.276597 0.35015 0.282916 0.353322 0.283701 0.422131 0.276751 0.353322 0.283701 0.351423 0.286277 0.422131 0.276751 0.357815 0.277849 0.353322 0.283701 0.353618 0.276597 0.353322 0.283701 0.357815 0.277849 0.423519 0.286663 0.351423 0.286277 0.349793 0.288609 0.423519 0.286663 0.422131 0.276751 0.351423 0.286277 0.423519 0.286663 0.349793 0.288609 0.348424 0.290705 0.423519 0.286663 0.348424 0.290705 0.34731 0.292577 0.423519 0.286663 0.34731 0.292577 0.34645 0.294271 0.425096 0.294387 0.34645 0.294271 0.34583 0.295793 0.425096 0.294387 0.423519 0.286663 0.34645 0.294271 0.425096 0.294387 0.34583 0.295793 0.345395 0.298407 0.426803 0.299748 0.345395 0.298407 0.346105 0.300471 0.426803 0.299748 0.425096 0.294387 0.345395 0.298407 0.426803 0.299748 0.346105 0.300471 0.348046 0.301937 0.426803 0.299748 0.348046 0.301937 0.351159 0.302884 0.428583 0.302665 0.351159 0.302884 0.355164 0.303386 0.428583 0.302665 0.426803 0.299748 0.351159 0.302884 0.428583 0.302665 0.355164 0.303386 0.360021 0.303548 0.430379 0.303143 0.360021 0.303548 0.365755 0.303429 0.428583 0.302665 0.360021 0.303548 0.430379 0.303143 0.430379 0.303143 0.365755 0.303429 0.36895 0.303271 0.335085 0.303091 0.338728 0.301844 0.336978 0.299755 0.332862 0.300849 0.336978 0.299755 0.336282 0.297106 0.332862 0.300849 0.335085 0.303091 0.336978 0.299755 0.331714 0.29793 0.336282 0.297106 0.336465 0.29396 0.331714 0.29793 0.332862 0.300849 0.336282 0.297106 0.331609 0.294273 0.336465 0.29396 0.337349 0.290376 0.331554 0.296207 0.331714 0.29793 0.336465 0.29396 0.331609 0.294273 0.331554 0.296207 0.336465 0.29396 0.332516 0.289478 0.337349 0.290376 0.338782 0.286402 0.331903 0.292093 0.331609 0.294273 0.337349 0.290376 0.332516 0.289478 0.331903 0.292093 0.337349 0.290376 0.343785 0.2821 0.34065 0.282079 0.338782 0.286402 0.333434 0.28639 0.338782 0.286402 0.34065 0.282079 0.333434 0.28639 0.332516 0.289478 0.338782 0.286402 0.345257 0.275325 0.34065 0.282079 0.343785 0.2821 0.33759 0.282316 0.333434 0.28639 0.34065 0.282079 0.341214 0.27534 0.33759 0.282316 0.34065 0.282079 0.341214 0.27534 0.34065 0.282079 0.345257 0.275325 0.345257 0.275325 0.343785 0.2821 0.349413 0.275747 0.319128 0.302308 0.335085 0.303091 0.332862 0.300849 0.316415 0.304629 0.335085 0.303091 0.319128 0.302308 0.321727 0.299857 0.332862 0.300849 0.331714 0.29793 0.319128 0.302308 0.332862 0.300849 0.321727 0.299857 0.324217 0.29728 0.331714 0.29793 0.331554 0.296207 0.321727 0.299857 0.331714 0.29793 0.324217 0.29728 0.326588 0.294585 0.331554 0.296207 0.331609 0.294273 0.324217 0.29728 0.331554 0.296207 0.326588 0.294585 0.326588 0.294585 0.331609 0.294273 0.331903 0.292093 0.328818 0.291783 0.331903 0.292093 0.332516 0.289478 0.326588 0.294585 0.331903 0.292093 0.328818 0.291783 0.330899 0.288882 0.332516 0.289478 0.333434 0.28639 0.328818 0.291783 0.332516 0.289478 0.330899 0.288882 0.33759 0.282316 0.334629 0.282811 0.333434 0.28639 0.332836 0.285888 0.333434 0.28639 0.334629 0.282811 0.330899 0.288882 0.333434 0.28639 0.332836 0.285888 0.335927 0.279297 0.334629 0.282811 0.33759 0.282316 0.318789 0.281193 0.316139 0.2849 0.334629 0.282811 0.332836 0.285888 0.334629 0.282811 0.316139 0.2849 0.335927 0.279297 0.318789 0.281193 0.334629 0.282811 0.335927 0.279297 0.33759 0.282316 0.337355 0.275781 0.341214 0.27534 0.337355 0.275781 0.33759 0.282316 0.432198 0.301148 0.430379 0.303143 0.431301 0.302447 0.428583 0.302665 0.430379 0.303143 0.432198 0.301148 0.336903 0.302169 0.432198 0.301148 0.431301 0.302447 0.341044 0.300792 0.433073 0.299248 0.432198 0.301148 0.428583 0.302665 0.432198 0.301148 0.433073 0.299248 0.336903 0.302169 0.341044 0.300792 0.432198 0.301148 0.348488 0.29673 0.433918 0.296785 0.433073 0.299248 0.428583 0.302665 0.433073 0.299248 0.433918 0.296785 0.341044 0.300792 0.348488 0.29673 0.433073 0.299248 0.348488 0.29673 0.434726 0.293782 0.433918 0.296785 0.43068 0.29824 0.433918 0.296785 0.434726 0.293782 0.43068 0.29824 0.428583 0.302665 0.433918 0.296785 0.354806 0.291061 0.435494 0.290277 0.434726 0.293782 0.43392 0.291867 0.434726 0.293782 0.435494 0.290277 0.348488 0.29673 0.354806 0.291061 0.434726 0.293782 0.432346 0.296115 0.43068 0.29824 0.434726 0.293782 0.43392 0.291867 0.432346 0.296115 0.434726 0.293782 0.360035 0.283965 0.436215 0.286297 0.435494 0.290277 0.43392 0.291867 0.435494 0.290277 0.436215 0.286297 0.354806 0.291061 0.360035 0.283965 0.435494 0.290277 0.360035 0.283965 0.436887 0.281883 0.436215 0.286297 0.435363 0.285685 0.436215 0.286297 0.436887 0.281883 0.435363 0.285685 0.43392 0.291867 0.436215 0.286297 0.364239 0.275635 0.437505 0.277066 0.436887 0.281883 0.43664 0.277788 0.436887 0.281883 0.437505 0.277066 0.360035 0.283965 0.364239 0.275635 0.436887 0.281883 0.43664 0.277788 0.435363 0.285685 0.436887 0.281883 0.364239 0.275635 0.438067 0.271887 0.437505 0.277066 0.43664 0.277788 0.437505 0.277066 0.438067 0.271887 0.36751 0.266266 0.438569 0.26638 0.438067 0.271887 0.437722 0.268451 0.438067 0.271887 0.438569 0.26638 0.364239 0.275635 0.36751 0.266266 0.438067 0.271887 0.437722 0.268451 0.43664 0.277788 0.438067 0.271887 0.36751 0.266266 0.43901 0.260589 0.438569 0.26638 0.437722 0.268451 0.438569 0.26638 0.43901 0.260589 0.369944 0.256054 0.439386 0.254547 0.43901 0.260589 0.438583 0.257972 0.43901 0.260589 0.439386 0.254547 0.36751 0.266266 0.369944 0.256054 0.43901 0.260589 0.438583 0.257972 0.437722 0.268451 0.43901 0.260589 0.371624 0.245178 0.439696 0.248298 0.439386 0.254547 0.438583 0.257972 0.439386 0.254547 0.439696 0.248298 0.369944 0.256054 0.371624 0.245178 0.439386 0.254547 0.371624 0.245178 0.439939 0.2418799 0.439696 0.248298 0.439216 0.2465119 0.439696 0.248298 0.439939 0.2418799 0.439216 0.2465119 0.438583 0.257972 0.439696 0.248298 0.372616 0.233779 0.440114 0.235335 0.439939 0.2418799 0.439216 0.2465119 0.439939 0.2418799 0.440114 0.235335 0.371624 0.245178 0.372616 0.233779 0.439939 0.2418799 0.372616 0.233779 0.440218 0.2287279 0.440114 0.235335 0.439601 0.23442 0.440114 0.235335 0.440218 0.2287279 0.439601 0.23442 0.439216 0.2465119 0.440114 0.235335 0.372947 0.222023 0.440254 0.222023 0.440218 0.2287279 0.439601 0.23442 0.440218 0.2287279 0.440254 0.222023 0.372616 0.233779 0.372947 0.222023 0.440218 0.2287279 0.372617 0.2102749 0.440124 0.209184 0.440254 0.222023 0.43973 0.222023 0.440254 0.222023 0.440124 0.209184 0.372947 0.222023 0.372617 0.2102749 0.440254 0.222023 0.439601 0.23442 0.440254 0.222023 0.43973 0.222023 0.371626 0.198885 0.439735 0.196658 0.440124 0.209184 0.439221 0.197649 0.440124 0.209184 0.439735 0.196658 0.372617 0.2102749 0.371626 0.198885 0.440124 0.209184 0.439602 0.209694 0.43973 0.222023 0.440124 0.209184 0.439221 0.197649 0.439602 0.209694 0.440124 0.209184 0.369948 0.188017 0.439096 0.184735 0.439735 0.196658 0.438592 0.1862069 0.439735 0.196658 0.439096 0.184735 0.371626 0.198885 0.369948 0.188017 0.439735 0.196658 0.438592 0.1862069 0.439221 0.197649 0.439735 0.196658 0.367519 0.177809 0.438217 0.173703 0.439096 0.184735 0.437733 0.175714 0.439096 0.184735 0.438217 0.173703 0.369948 0.188017 0.367519 0.177809 0.439096 0.184735 0.437733 0.175714 0.438592 0.1862069 0.439096 0.184735 0.364253 0.168443 0.437114 0.1638399 0.438217 0.173703 0.436651 0.166337 0.438217 0.173703 0.437114 0.1638399 0.367519 0.177809 0.364253 0.168443 0.438217 0.173703 0.436651 0.166337 0.437733 0.175714 0.438217 0.173703 0.360053 0.160111 0.435809 0.155419 0.437114 0.1638399 0.435369 0.158392 0.437114 0.1638399 0.435809 0.155419 0.364253 0.168443 0.360053 0.160111 0.437114 0.1638399 0.435369 0.158392 0.436651 0.166337 0.437114 0.1638399 0.354827 0.153008 0.434327 0.148696 0.435809 0.155419 0.433919 0.152175 0.435809 0.155419 0.434327 0.148696 0.360053 0.160111 0.354827 0.153008 0.435809 0.155419 0.433919 0.152175 0.435369 0.158392 0.435809 0.155419 0.348508 0.14733 0.432701 0.143911 0.434327 0.148696 0.43067 0.1457999 0.434327 0.148696 0.432701 0.143911 0.354827 0.153008 0.348508 0.14733 0.434327 0.148696 0.432339 0.147917 0.433919 0.152175 0.434327 0.148696 0.43067 0.1457999 0.432339 0.147917 0.434327 0.148696 0.372362 0.140994 0.43097 0.141273 0.432701 0.143911 0.429115 0.140987 0.432701 0.143911 0.43097 0.141273 0.332488 0.140962 0.372362 0.140994 0.432701 0.143911 0.336911 0.141878 0.332488 0.140962 0.432701 0.143911 0.341057 0.143259 0.336911 0.141878 0.432701 0.143911 0.348508 0.14733 0.341057 0.143259 0.432701 0.143911 0.429115 0.140987 0.42726 0.143306 0.432701 0.143911 0.43067 0.1457999 0.432701 0.143911 0.42726 0.143306 0.36605 0.1406289 0.43097 0.141273 0.372362 0.140994 0.355875 0.140614 0.429115 0.140987 0.43097 0.141273 0.360567 0.140497 0.355875 0.140614 0.43097 0.141273 0.36605 0.1406289 0.360567 0.140497 0.43097 0.141273 0.36895 0.140855 0.372362 0.140994 0.332488 0.140962 0.368953 0.140825 0.36605 0.1406289 0.372362 0.140994 0.368559 0.140826 0.368953 0.140825 0.372362 0.140994 0.368559 0.140826 0.372362 0.140994 0.36895 0.140855 0.330746 0.141438 0.332488 0.140962 0.336911 0.141878 0.353444 0.14011 0.332488 0.140962 0.349774 0.139894 0.307214 0.137432 0.349774 0.139894 0.332488 0.140962 0.35675 0.140289 0.332488 0.140962 0.353444 0.14011 0.359728 0.14044 0.332488 0.140962 0.35675 0.140289 0.362407 0.140568 0.332488 0.140962 0.359728 0.14044 0.364816 0.140677 0.332488 0.140962 0.362407 0.140568 0.36895 0.140855 0.332488 0.140962 0.364816 0.140677 0.330746 0.141438 0.307214 0.137432 0.332488 0.140962 0.339049 0.1437 0.336911 0.141878 0.341057 0.143259 0.339049 0.1437 0.330746 0.141438 0.336911 0.141878 0.346514 0.147725 0.341057 0.143259 0.348508 0.14733 0.339049 0.1437 0.341057 0.143259 0.346514 0.147725 0.353003 0.1535 0.348508 0.14733 0.354827 0.153008 0.346514 0.147725 0.348508 0.14733 0.353003 0.1535 0.353003 0.1535 0.354827 0.153008 0.360053 0.160111 0.358451 0.160922 0.360053 0.160111 0.364253 0.168443 0.353003 0.1535 0.360053 0.160111 0.358451 0.160922 0.362835 0.169849 0.364253 0.168443 0.367519 0.177809 0.358451 0.160922 0.364253 0.168443 0.362835 0.169849 0.366203 0.180059 0.367519 0.177809 0.369948 0.188017 0.362835 0.169849 0.367519 0.177809 0.366203 0.180059 0.36863 0.191296 0.369948 0.188017 0.371626 0.198885 0.366203 0.180059 0.369948 0.188017 0.36863 0.191296 0.370193 0.203283 0.371626 0.198885 0.372617 0.2102749 0.36863 0.191296 0.371626 0.198885 0.370193 0.203283 0.370958 0.215725 0.372617 0.2102749 0.372947 0.222023 0.370193 0.203283 0.372617 0.2102749 0.370958 0.215725 0.370958 0.22832 0.372947 0.222023 0.372616 0.233779 0.370958 0.215725 0.372947 0.222023 0.370958 0.22832 0.370193 0.2407619 0.372616 0.233779 0.371624 0.245178 0.370958 0.22832 0.372616 0.233779 0.370193 0.2407619 0.36863 0.252749 0.371624 0.245178 0.369944 0.256054 0.370193 0.2407619 0.371624 0.245178 0.36863 0.252749 0.366203 0.263986 0.369944 0.256054 0.36751 0.266266 0.36863 0.252749 0.369944 0.256054 0.366203 0.263986 0.362836 0.274196 0.36751 0.266266 0.364239 0.275635 0.366203 0.263986 0.36751 0.266266 0.362836 0.274196 0.358451 0.283123 0.364239 0.275635 0.360035 0.283965 0.362836 0.274196 0.364239 0.275635 0.358451 0.283123 0.358451 0.283123 0.360035 0.283965 0.354806 0.291061 0.353003 0.290545 0.354806 0.291061 0.348488 0.29673 0.358451 0.283123 0.354806 0.291061 0.353003 0.290545 0.346514 0.296321 0.348488 0.29673 0.341044 0.300792 0.353003 0.290545 0.348488 0.29673 0.346514 0.296321 0.33905 0.300346 0.341044 0.300792 0.336903 0.302169 0.346514 0.296321 0.341044 0.300792 0.33905 0.300346 0.33905 0.300346 0.336903 0.302169 0.332488 0.303083 0.305789 0.306278 0.332488 0.303083 0.307215 0.306614 0.330746 0.302607 0.332488 0.303083 0.305789 0.306278 0.33905 0.300346 0.332488 0.303083 0.330746 0.302607 0.422131 0.276751 0.358095 0.277491 0.357815 0.277849 0.359847 0.27062 0.357815 0.277849 0.358095 0.277491 0.353618 0.276597 0.357815 0.277849 0.359847 0.27062 0.422131 0.276751 0.362664 0.271675 0.358095 0.277491 0.359847 0.27062 0.358095 0.277491 0.362664 0.271675 0.420985 0.264923 0.368865 0.263799 0.362664 0.271675 0.364722 0.262125 0.362664 0.271675 0.368865 0.263799 0.422131 0.276751 0.420985 0.264923 0.362664 0.271675 0.359847 0.27062 0.362664 0.271675 0.364722 0.262125 0.420129 0.251546 0.369529 0.262944 0.368865 0.263799 0.370912 0.253366 0.368865 0.263799 0.369529 0.262944 0.420985 0.264923 0.420129 0.251546 0.368865 0.263799 0.364722 0.262125 0.368865 0.263799 0.370912 0.253366 0.420129 0.251546 0.375402 0.255361 0.369529 0.262944 0.370912 0.253366 0.369529 0.262944 0.375402 0.255361 0.420129 0.251546 0.376086 0.254465 0.375402 0.255361 0.376398 0.243654 0.375402 0.255361 0.376086 0.254465 0.370912 0.253366 0.375402 0.255361 0.376398 0.243654 0.420129 0.251546 0.382163 0.246408 0.376086 0.254465 0.376398 0.243654 0.376086 0.254465 0.382163 0.246408 0.419599 0.237073 0.3831 0.245101 0.382163 0.246408 0.378011 0.2412379 0.382163 0.246408 0.3831 0.245101 0.420129 0.251546 0.419599 0.237073 0.382163 0.246408 0.376398 0.243654 0.382163 0.246408 0.378011 0.2412379 0.419599 0.237073 0.38399 0.2437649 0.3831 0.245101 0.378011 0.2412379 0.3831 0.245101 0.38399 0.2437649 0.419599 0.237073 0.387442 0.237053 0.38399 0.2437649 0.382089 0.23555 0.38399 0.2437649 0.387442 0.237053 0.382089 0.23555 0.378011 0.2412379 0.38399 0.2437649 0.419419 0.222023 0.387534 0.236823 0.387442 0.237053 0.384004 0.228925 0.387442 0.237053 0.387534 0.236823 0.419599 0.237073 0.419419 0.222023 0.387442 0.237053 0.382089 0.23555 0.387442 0.237053 0.384004 0.228925 0.419419 0.222023 0.389594 0.2297019 0.387534 0.236823 0.384004 0.228925 0.387534 0.236823 0.389594 0.2297019 0.419419 0.222023 0.389641 0.22946 0.389594 0.2297019 0.383527 0.222023 0.389594 0.2297019 0.389641 0.22946 0.384004 0.228925 0.389594 0.2297019 0.383527 0.222023 0.419419 0.222023 0.390326 0.222023 0.389641 0.22946 0.383527 0.222023 0.389641 0.22946 0.390326 0.222023 0.419612 0.206421 0.390326 0.222023 0.419419 0.222023 0.389904 0.2162179 0.390326 0.222023 0.419612 0.206421 0.384287 0.216834 0.390326 0.222023 0.389904 0.2162179 0.383527 0.222023 0.390326 0.222023 0.384287 0.216834 0.420136 0.222023 0.419419 0.222023 0.419599 0.237073 0.42031 0.207628 0.419612 0.206421 0.419419 0.222023 0.420136 0.222023 0.42031 0.207628 0.419419 0.222023 0.42082 0.250131 0.419599 0.237073 0.420129 0.251546 0.420309 0.236339 0.420136 0.222023 0.419599 0.237073 0.42082 0.250131 0.420309 0.236339 0.419599 0.237073 0.421647 0.262862 0.420129 0.251546 0.420985 0.264923 0.421647 0.262862 0.42082 0.250131 0.420129 0.251546 0.422746 0.274032 0.420985 0.264923 0.422131 0.276751 0.422746 0.274032 0.421647 0.262862 0.420985 0.264923 0.424087 0.283401 0.422131 0.276751 0.423519 0.286663 0.424087 0.283401 0.422746 0.274032 0.422131 0.276751 0.425612 0.290649 0.423519 0.286663 0.425096 0.294387 0.425612 0.290649 0.424087 0.283401 0.423519 0.286663 0.427259 0.295569 0.425096 0.294387 0.426803 0.299748 0.427259 0.295569 0.425612 0.290649 0.425096 0.294387 0.43068 0.29824 0.426803 0.299748 0.428583 0.302665 0.428967 0.29809 0.427259 0.295569 0.426803 0.299748 0.43068 0.29824 0.428967 0.29809 0.426803 0.299748 0.420827 0.193785 0.420182 0.191462 0.419612 0.206421 0.386701 0.205245 0.419612 0.206421 0.420182 0.191462 0.42031 0.207628 0.420827 0.193785 0.419612 0.206421 0.389566 0.214195 0.389904 0.2162179 0.419612 0.206421 0.388687 0.210593 0.389566 0.214195 0.419612 0.206421 0.387395 0.206872 0.388687 0.210593 0.419612 0.206421 0.386701 0.205245 0.387395 0.206872 0.419612 0.206421 0.421659 0.181039 0.421099 0.177721 0.420182 0.191462 0.372071 0.184367 0.420182 0.191462 0.421099 0.177721 0.420827 0.193785 0.421659 0.181039 0.420182 0.191462 0.38399 0.200281 0.386701 0.205245 0.420182 0.191462 0.3831 0.198944 0.38399 0.200281 0.420182 0.191462 0.382163 0.197637 0.3831 0.198944 0.420182 0.191462 0.372071 0.184367 0.382163 0.197637 0.420182 0.191462 0.422761 0.1698909 0.422323 0.165695 0.421099 0.177721 0.362665 0.172372 0.421099 0.177721 0.422323 0.165695 0.421659 0.181039 0.422761 0.1698909 0.421099 0.177721 0.362665 0.172372 0.372071 0.184367 0.421099 0.177721 0.4241 0.160569 0.423799 0.155779 0.422323 0.165695 0.353322 0.160345 0.422323 0.165695 0.423799 0.155779 0.422761 0.1698909 0.4241 0.160569 0.422323 0.165695 0.358066 0.166517 0.362665 0.172372 0.422323 0.165695 0.357815 0.166197 0.358066 0.166517 0.422323 0.165695 0.353322 0.160345 0.357815 0.166197 0.422323 0.165695 0.425619 0.15337 0.425466 0.148259 0.423799 0.155779 0.349551 0.1550779 0.423799 0.155779 0.425466 0.148259 0.4241 0.160569 0.425619 0.15337 0.423799 0.155779 0.351277 0.1575649 0.353322 0.160345 0.423799 0.155779 0.349551 0.1550779 0.351277 0.1575649 0.423799 0.155779 0.42896 0.145961 0.42726 0.143306 0.425466 0.148259 0.345648 0.147647 0.425466 0.148259 0.42726 0.143306 0.427257 0.148479 0.42896 0.145961 0.425466 0.148259 0.425619 0.15337 0.427257 0.148479 0.425466 0.148259 0.348134 0.152873 0.349551 0.1550779 0.425466 0.148259 0.347018 0.150933 0.348134 0.152873 0.425466 0.148259 0.346195 0.149197 0.347018 0.150933 0.425466 0.148259 0.345648 0.147647 0.346195 0.149197 0.425466 0.148259 0.348706 0.141831 0.42726 0.143306 0.429115 0.140987 0.42896 0.145961 0.43067 0.1457999 0.42726 0.143306 0.345394 0.146278 0.345648 0.147647 0.42726 0.143306 0.345456 0.145071 0.345394 0.146278 0.42726 0.143306 0.346487 0.1431429 0.345456 0.145071 0.42726 0.143306 0.348706 0.141831 0.346487 0.1431429 0.42726 0.143306 0.351917 0.141025 0.348706 0.141831 0.429115 0.140987 0.355875 0.140614 0.351917 0.141025 0.429115 0.140987 0.392787 0.222023 0.43973 0.222023 0.439602 0.209694 0.392611 0.234269 0.439601 0.23442 0.43973 0.222023 0.392611 0.234269 0.43973 0.222023 0.392787 0.222023 0.392609 0.209709 0.439602 0.209694 0.439221 0.197649 0.392609 0.209709 0.392787 0.222023 0.439602 0.209694 0.392076 0.197699 0.439221 0.197649 0.438592 0.1862069 0.392076 0.197699 0.392609 0.209709 0.439221 0.197649 0.391201 0.18632 0.438592 0.1862069 0.437733 0.175714 0.391201 0.18632 0.392076 0.197699 0.438592 0.1862069 0.390011 0.175916 0.437733 0.175714 0.436651 0.166337 0.390011 0.175916 0.391201 0.18632 0.437733 0.175714 0.388517 0.1666499 0.436651 0.166337 0.435369 0.158392 0.388517 0.1666499 0.390011 0.175916 0.436651 0.166337 0.386752 0.158818 0.435369 0.158392 0.433919 0.152175 0.386752 0.158818 0.388517 0.1666499 0.435369 0.158392 0.382587 0.148488 0.433919 0.152175 0.432339 0.147917 0.38476 0.152691 0.386752 0.158818 0.433919 0.152175 0.382587 0.148488 0.38476 0.152691 0.433919 0.152175 0.380288 0.146394 0.432339 0.147917 0.43067 0.1457999 0.380288 0.146394 0.382587 0.148488 0.432339 0.147917 0.377925 0.146558 0.43067 0.1457999 0.42896 0.145961 0.377925 0.146558 0.380288 0.146394 0.43067 0.1457999 0.37557 0.149075 0.42896 0.145961 0.427257 0.148479 0.37557 0.149075 0.377925 0.146558 0.42896 0.145961 0.37557 0.149075 0.427257 0.148479 0.425619 0.15337 0.3733 0.153969 0.425619 0.15337 0.4241 0.160569 0.3733 0.153969 0.37557 0.149075 0.425619 0.15337 0.371199 0.161169 0.4241 0.160569 0.422761 0.1698909 0.371199 0.161169 0.3733 0.153969 0.4241 0.160569 0.369353 0.170467 0.422761 0.1698909 0.421659 0.181039 0.369353 0.170467 0.371199 0.161169 0.422761 0.1698909 0.367839 0.181545 0.421659 0.181039 0.420827 0.193785 0.367839 0.181545 0.369353 0.170467 0.421659 0.181039 0.366701 0.194167 0.420827 0.193785 0.42031 0.207628 0.366701 0.194167 0.367839 0.181545 0.420827 0.193785 0.365997 0.207836 0.42031 0.207628 0.420136 0.222023 0.365997 0.207836 0.366701 0.194167 0.42031 0.207628 0.36576 0.222023 0.420136 0.222023 0.420309 0.236339 0.36576 0.222023 0.365997 0.207836 0.420136 0.222023 0.366 0.236288 0.420309 0.236339 0.42082 0.250131 0.366 0.236288 0.36576 0.222023 0.420309 0.236339 0.36671 0.250008 0.42082 0.250131 0.421647 0.262862 0.36671 0.250008 0.366 0.236288 0.42082 0.250131 0.367856 0.262644 0.421647 0.262862 0.422746 0.274032 0.367856 0.262644 0.36671 0.250008 0.421647 0.262862 0.369373 0.273702 0.422746 0.274032 0.424087 0.283401 0.369373 0.273702 0.367856 0.262644 0.422746 0.274032 0.371217 0.282953 0.424087 0.283401 0.425612 0.290649 0.371217 0.282953 0.369373 0.273702 0.424087 0.283401 0.373309 0.290103 0.425612 0.290649 0.427259 0.295569 0.373309 0.290103 0.371217 0.282953 0.425612 0.290649 0.377915 0.297482 0.427259 0.295569 0.428967 0.29809 0.375568 0.294968 0.373309 0.290103 0.427259 0.295569 0.377915 0.297482 0.375568 0.294968 0.427259 0.295569 0.380275 0.297657 0.428967 0.29809 0.43068 0.29824 0.380275 0.297657 0.377915 0.297482 0.428967 0.29809 0.382577 0.295572 0.43068 0.29824 0.432346 0.296115 0.382577 0.295572 0.380275 0.297657 0.43068 0.29824 0.384758 0.291358 0.432346 0.296115 0.43392 0.291867 0.384758 0.291358 0.382577 0.295572 0.432346 0.296115 0.384758 0.291358 0.43392 0.291867 0.435363 0.285685 0.386761 0.285197 0.435363 0.285685 0.43664 0.277788 0.386761 0.285197 0.384758 0.291358 0.435363 0.285685 0.388532 0.277317 0.43664 0.277788 0.437722 0.268451 0.388532 0.277317 0.386761 0.285197 0.43664 0.277788 0.390027 0.268011 0.437722 0.268451 0.438583 0.257972 0.390027 0.268011 0.388532 0.277317 0.437722 0.268451 0.391213 0.257594 0.438583 0.257972 0.439216 0.2465119 0.391213 0.257594 0.390027 0.268011 0.438583 0.257972 0.392083 0.246232 0.439216 0.2465119 0.439601 0.23442 0.392083 0.246232 0.391213 0.257594 0.439216 0.2465119 0.392611 0.234269 0.392083 0.246232 0.439601 0.23442 0.383203 0.211762 0.389904 0.2162179 0.389566 0.214195 0.384287 0.216834 0.389904 0.2162179 0.383203 0.211762 0.383203 0.211762 0.389566 0.214195 0.388687 0.210593 0.381428 0.206928 0.388687 0.210593 0.387395 0.206872 0.383203 0.211762 0.388687 0.210593 0.381428 0.206928 0.381428 0.206928 0.387395 0.206872 0.386701 0.205245 0.378011 0.202808 0.386701 0.205245 0.38399 0.200281 0.381428 0.206928 0.386701 0.205245 0.378011 0.202808 0.376398 0.200392 0.38399 0.200281 0.3831 0.198944 0.376398 0.200392 0.378011 0.202808 0.38399 0.200281 0.376398 0.200392 0.3831 0.198944 0.382163 0.197637 0.367789 0.186245 0.382163 0.197637 0.372071 0.184367 0.376398 0.200392 0.382163 0.197637 0.367789 0.186245 0.359847 0.173426 0.372071 0.184367 0.362665 0.172372 0.367789 0.186245 0.372071 0.184367 0.359847 0.173426 0.353618 0.16745 0.362665 0.172372 0.358066 0.166517 0.359847 0.173426 0.362665 0.172372 0.353618 0.16745 0.353618 0.16745 0.358066 0.166517 0.357815 0.166197 0.35015 0.1611289 0.357815 0.166197 0.353322 0.160345 0.353618 0.16745 0.357815 0.166197 0.35015 0.1611289 0.35015 0.1611289 0.353322 0.160345 0.351277 0.1575649 0.344588 0.1574169 0.351277 0.1575649 0.349551 0.1550779 0.346963 0.161665 0.351277 0.1575649 0.344588 0.1574169 0.35015 0.1611289 0.351277 0.1575649 0.346963 0.161665 0.342688 0.153522 0.349551 0.1550779 0.348134 0.152873 0.344588 0.1574169 0.349551 0.1550779 0.342688 0.153522 0.342688 0.153522 0.348134 0.152873 0.347018 0.150933 0.341393 0.15002 0.347018 0.150933 0.346195 0.149197 0.342688 0.153522 0.347018 0.150933 0.341393 0.15002 0.341393 0.15002 0.346195 0.149197 0.345648 0.147647 0.340895 0.146972 0.345648 0.147647 0.345394 0.146278 0.341393 0.15002 0.345648 0.147647 0.340895 0.146972 0.340895 0.146972 0.345394 0.146278 0.345456 0.145071 0.341402 0.1444399 0.345456 0.145071 0.346487 0.1431429 0.340895 0.146972 0.345456 0.145071 0.341402 0.1444399 0.343122 0.142496 0.346487 0.1431429 0.348706 0.141831 0.341402 0.1444399 0.346487 0.1431429 0.343122 0.142496 0.346136 0.141176 0.348706 0.141831 0.351917 0.141025 0.343122 0.142496 0.348706 0.141831 0.346136 0.141176 0.35032 0.140447 0.351917 0.141025 0.355875 0.140614 0.346136 0.141176 0.351917 0.141025 0.35032 0.140447 0.355389 0.1402159 0.355875 0.140614 0.360567 0.140497 0.35032 0.140447 0.355875 0.140614 0.355389 0.1402159 0.359321 0.140385 0.360567 0.140497 0.36605 0.1406289 0.359321 0.140385 0.355389 0.1402159 0.360567 0.140497 0.362431 0.140523 0.359321 0.140385 0.36605 0.1406289 0.365642 0.140669 0.362431 0.140523 0.36605 0.1406289 0.368953 0.140825 0.365642 0.140669 0.36605 0.1406289 0.361429 0.211134 0.36081 0.207728 0.355961 0.208287 0.355462 0.207275 0.355961 0.208287 0.36081 0.207728 0.357268 0.21143 0.361429 0.211134 0.355961 0.208287 0.34285 0.2123219 0.357268 0.21143 0.355961 0.208287 0.34285 0.2123219 0.355961 0.208287 0.348244 0.208151 0.355462 0.207275 0.348244 0.208151 0.355961 0.208287 0.366034 0.210512 0.366225 0.206598 0.36081 0.207728 0.359746 0.2057729 0.36081 0.207728 0.366225 0.206598 0.361429 0.211134 0.366034 0.210512 0.36081 0.207728 0.355462 0.207275 0.36081 0.207728 0.355014 0.2064 0.359746 0.2057729 0.355014 0.2064 0.36081 0.207728 0.370978 0.209588 0.372024 0.2049379 0.366225 0.206598 0.365005 0.204531 0.366225 0.206598 0.372024 0.2049379 0.366034 0.210512 0.370978 0.209588 0.366225 0.206598 0.359746 0.2057729 0.366225 0.206598 0.365005 0.204531 0.376149 0.208383 0.378011 0.202808 0.372024 0.2049379 0.376398 0.200392 0.372024 0.2049379 0.378011 0.202808 0.370978 0.209588 0.376149 0.208383 0.372024 0.2049379 0.370617 0.2027159 0.372024 0.2049379 0.376398 0.200392 0.365005 0.204531 0.372024 0.2049379 0.370617 0.2027159 0.376149 0.208383 0.381428 0.206928 0.378011 0.202808 0.383203 0.211762 0.381428 0.206928 0.376149 0.208383 0.377712 0.212763 0.376149 0.208383 0.370978 0.209588 0.377712 0.212763 0.383203 0.211762 0.376149 0.208383 0.372345 0.213587 0.370978 0.209588 0.366034 0.210512 0.372345 0.213587 0.377712 0.212763 0.370978 0.209588 0.367228 0.214214 0.366034 0.210512 0.361429 0.211134 0.367228 0.214214 0.372345 0.213587 0.366034 0.210512 0.362479 0.2146289 0.361429 0.211134 0.357268 0.21143 0.362479 0.2146289 0.367228 0.214214 0.361429 0.211134 0.362479 0.2146289 0.357268 0.21143 0.357612 0.2124879 0.34285 0.2123219 0.357612 0.2124879 0.357268 0.21143 0.358214 0.214814 0.362479 0.2146289 0.357612 0.2124879 0.34285 0.2123219 0.358214 0.214814 0.357612 0.2124879 0.384287 0.216834 0.383203 0.211762 0.377712 0.212763 0.378663 0.217344 0.377712 0.212763 0.372345 0.213587 0.378663 0.217344 0.384287 0.216834 0.377712 0.212763 0.373174 0.2177619 0.372345 0.213587 0.367228 0.214214 0.373174 0.2177619 0.378663 0.217344 0.372345 0.213587 0.367948 0.218079 0.367228 0.214214 0.362479 0.2146289 0.367948 0.218079 0.373174 0.2177619 0.367228 0.214214 0.363111 0.218286 0.362479 0.2146289 0.358214 0.214814 0.363111 0.218286 0.367948 0.218079 0.362479 0.2146289 0.363111 0.218286 0.358214 0.214814 0.358626 0.217118 0.344381 0.21703 0.358626 0.217118 0.358214 0.214814 0.34285 0.2123219 0.344381 0.21703 0.358214 0.214814 0.358782 0.218369 0.363111 0.218286 0.358626 0.217118 0.344381 0.21703 0.358782 0.218369 0.358626 0.217118 0.383527 0.222023 0.384287 0.216834 0.378663 0.217344 0.376754 0.222023 0.378663 0.217344 0.373174 0.2177619 0.376754 0.222023 0.383527 0.222023 0.378663 0.217344 0.370248 0.222023 0.373174 0.2177619 0.367948 0.218079 0.370248 0.222023 0.376754 0.222023 0.373174 0.2177619 0.364247 0.222023 0.367948 0.218079 0.363111 0.218286 0.364247 0.222023 0.370248 0.222023 0.367948 0.218079 0.364247 0.222023 0.363111 0.218286 0.358782 0.218369 0.364247 0.222023 0.358782 0.218369 0.35897 0.222023 0.344905 0.221984 0.35897 0.222023 0.358782 0.218369 0.344381 0.21703 0.344905 0.221984 0.358782 0.218369 0.362947 0.226994 0.364247 0.222023 0.35897 0.222023 0.344396 0.226947 0.358634 0.22687 0.35897 0.222023 0.362947 0.226994 0.35897 0.222023 0.358634 0.22687 0.344905 0.221984 0.344396 0.226947 0.35897 0.222023 0.378415 0.228248 0.383527 0.222023 0.376754 0.222023 0.378415 0.228248 0.384004 0.228925 0.383527 0.222023 0.372958 0.227692 0.376754 0.222023 0.370248 0.222023 0.372958 0.227692 0.378415 0.228248 0.376754 0.222023 0.367761 0.22727 0.370248 0.222023 0.364247 0.222023 0.367761 0.22727 0.372958 0.227692 0.370248 0.222023 0.362947 0.226994 0.367761 0.22727 0.364247 0.222023 0.34285 0.2123219 0.348244 0.208151 0.340359 0.208005 0.355462 0.207275 0.340359 0.208005 0.348244 0.208151 0.334048 0.213281 0.34285 0.2123219 0.340359 0.208005 0.340239 0.207849 0.340359 0.208005 0.355462 0.207275 0.340129 0.207693 0.340359 0.208005 0.340239 0.207849 0.336047 0.207723 0.340359 0.208005 0.340129 0.207693 0.336248 0.208065 0.334048 0.213281 0.340359 0.208005 0.336248 0.208065 0.340359 0.208005 0.336047 0.207723 0.342868 0.231682 0.357625 0.231512 0.358634 0.22687 0.361822 0.231777 0.358634 0.22687 0.357625 0.231512 0.344396 0.226947 0.342868 0.231682 0.358634 0.22687 0.361822 0.231777 0.362947 0.226994 0.358634 0.22687 0.348244 0.235895 0.355961 0.235758 0.357625 0.231512 0.36081 0.236318 0.357625 0.231512 0.355961 0.235758 0.340359 0.236041 0.348244 0.235895 0.357625 0.231512 0.342868 0.231682 0.340359 0.236041 0.357625 0.231512 0.361822 0.231777 0.357625 0.231512 0.36081 0.236318 0.340239 0.2361969 0.355961 0.235758 0.348244 0.235895 0.340129 0.236353 0.355961 0.235758 0.340239 0.2361969 0.339868 0.236832 0.355961 0.235758 0.340129 0.236353 0.339868 0.236832 0.355522 0.236652 0.355961 0.235758 0.359746 0.238272 0.355961 0.235758 0.355522 0.236652 0.359746 0.238272 0.36081 0.236318 0.355961 0.235758 0.340239 0.2361969 0.348244 0.235895 0.340359 0.236041 0.336248 0.235981 0.340359 0.236041 0.342868 0.231682 0.336047 0.2363229 0.340359 0.236041 0.336248 0.235981 0.340129 0.236353 0.340239 0.2361969 0.340359 0.236041 0.336047 0.2363229 0.340129 0.236353 0.340359 0.236041 0.334049 0.230758 0.342868 0.231682 0.344396 0.226947 0.332162 0.235967 0.342868 0.231682 0.334049 0.230758 0.336248 0.235981 0.342868 0.231682 0.332162 0.235967 0.334995 0.2249619 0.344396 0.226947 0.344905 0.221984 0.334049 0.230758 0.344396 0.226947 0.334995 0.2249619 0.334991 0.2190459 0.344905 0.221984 0.344381 0.21703 0.334995 0.2249619 0.344905 0.221984 0.334991 0.2190459 0.334048 0.213281 0.344381 0.21703 0.34285 0.2123219 0.334991 0.2190459 0.344381 0.21703 0.334048 0.213281 0.340551 0.206232 0.348012 0.20627 0.340871 0.206133 0.349877 0.195522 0.340871 0.206133 0.348012 0.20627 0.330272 0.203451 0.340551 0.206232 0.340871 0.206133 0.349877 0.195522 0.34194 0.2035199 0.340871 0.206133 0.335527 0.204542 0.340871 0.206133 0.34194 0.2035199 0.330272 0.203451 0.340871 0.206133 0.335527 0.204542 0.340551 0.206232 0.355014 0.2064 0.348012 0.20627 0.349877 0.195522 0.348012 0.20627 0.355014 0.2064 0.339738 0.206742 0.355462 0.207275 0.355014 0.2064 0.339787 0.206614 0.339738 0.206742 0.355014 0.2064 0.339892 0.206522 0.339787 0.206614 0.355014 0.2064 0.339991 0.2064599 0.339892 0.206522 0.355014 0.2064 0.340126 0.206392 0.339991 0.2064599 0.355014 0.2064 0.340319 0.206313 0.340126 0.206392 0.355014 0.2064 0.340551 0.206232 0.340319 0.206313 0.355014 0.2064 0.359746 0.2057729 0.349877 0.195522 0.355014 0.2064 0.340129 0.207693 0.340239 0.207849 0.355462 0.207275 0.339875 0.2072319 0.340129 0.207693 0.355462 0.207275 0.339738 0.206742 0.339875 0.2072319 0.355462 0.207275 0.336047 0.207723 0.340129 0.207693 0.339875 0.2072319 0.331727 0.207085 0.339875 0.2072319 0.339738 0.206742 0.331979 0.207714 0.339875 0.2072319 0.331727 0.207085 0.336047 0.207723 0.339875 0.2072319 0.331979 0.207714 0.335613 0.206634 0.339738 0.206742 0.339787 0.206614 0.331727 0.207085 0.339738 0.206742 0.335613 0.206634 0.330822 0.2052569 0.339787 0.206614 0.339892 0.206522 0.331521 0.206466 0.335613 0.206634 0.339787 0.206614 0.331134 0.205865 0.331521 0.206466 0.339787 0.206614 0.330822 0.2052569 0.331134 0.205865 0.339787 0.206614 0.330822 0.2052569 0.339892 0.206522 0.339991 0.2064599 0.330576 0.204648 0.339991 0.2064599 0.340126 0.206392 0.330576 0.204648 0.330822 0.2052569 0.339991 0.2064599 0.330392 0.204044 0.340126 0.206392 0.340319 0.206313 0.330392 0.204044 0.330576 0.204648 0.340126 0.206392 0.330272 0.203451 0.340319 0.206313 0.340551 0.206232 0.330272 0.203451 0.330392 0.204044 0.340319 0.206313 0.349877 0.195522 0.342727 0.200394 0.34194 0.2035199 0.335871 0.200833 0.34194 0.2035199 0.342727 0.200394 0.335527 0.204542 0.34194 0.2035199 0.335871 0.200833 0.349877 0.195522 0.343225 0.196671 0.342727 0.200394 0.335364 0.196795 0.342727 0.200394 0.343225 0.196671 0.335871 0.200833 0.342727 0.200394 0.335364 0.196795 0.349877 0.195522 0.343406 0.192715 0.343225 0.196671 0.334289 0.1926389 0.343225 0.196671 0.343406 0.192715 0.335364 0.196795 0.343225 0.196671 0.334289 0.1926389 0.347414 0.190295 0.343255 0.188977 0.343406 0.192715 0.332821 0.188458 0.343406 0.192715 0.343255 0.188977 0.349877 0.195522 0.347414 0.190295 0.343406 0.192715 0.334289 0.1926389 0.343406 0.192715 0.332821 0.188458 0.345065 0.185276 0.342769 0.185021 0.343255 0.188977 0.332821 0.188458 0.343255 0.188977 0.342769 0.185021 0.347414 0.190295 0.345065 0.185276 0.343255 0.188977 0.345065 0.185276 0.342245 0.182085 0.342769 0.185021 0.331079 0.184307 0.342769 0.185021 0.342245 0.182085 0.332821 0.188458 0.342769 0.185021 0.331079 0.184307 0.345065 0.185276 0.341554 0.178986 0.342245 0.182085 0.32914 0.180218 0.342245 0.182085 0.341554 0.178986 0.331079 0.184307 0.342245 0.182085 0.32914 0.180218 0.345065 0.185276 0.340688 0.175741 0.341554 0.178986 0.327047 0.176208 0.341554 0.178986 0.340688 0.175741 0.32914 0.180218 0.341554 0.178986 0.327047 0.176208 0.351114 0.1902599 0.340688 0.175741 0.345065 0.185276 0.327047 0.176208 0.340688 0.175741 0.324829 0.17229 0.339198 0.172493 0.324829 0.17229 0.340688 0.175741 0.343219 0.17598 0.339198 0.172493 0.340688 0.175741 0.351114 0.1902599 0.343219 0.17598 0.340688 0.175741 0.351114 0.1902599 0.345065 0.185276 0.347414 0.190295 0.359746 0.2057729 0.347414 0.190295 0.349877 0.195522 0.359746 0.2057729 0.351114 0.1902599 0.347414 0.190295 0.27819 0.135239 0.299214 0.139927 0.296597 0.137521 0.319125 0.141734 0.296597 0.137521 0.299214 0.139927 0.319125 0.141734 0.316413 0.139415 0.296597 0.137521 0.280601 0.13763 0.301863 0.1425 0.299214 0.139927 0.321723 0.144185 0.299214 0.139927 0.301863 0.1425 0.27819 0.135239 0.280601 0.13763 0.299214 0.139927 0.321723 0.144185 0.319125 0.141734 0.299214 0.139927 0.283018 0.140076 0.304528 0.145238 0.301863 0.1425 0.324212 0.14676 0.301863 0.1425 0.304528 0.145238 0.280601 0.13763 0.283018 0.140076 0.301863 0.1425 0.324212 0.14676 0.321723 0.144185 0.301863 0.1425 0.285437 0.142558 0.307194 0.148133 0.304528 0.145238 0.326584 0.149455 0.304528 0.145238 0.307194 0.148133 0.283018 0.140076 0.285437 0.142558 0.304528 0.145238 0.326584 0.149455 0.324212 0.14676 0.304528 0.145238 0.290135 0.147539 0.309847 0.151181 0.307194 0.148133 0.328815 0.152258 0.307194 0.148133 0.309847 0.151181 0.287807 0.145053 0.290135 0.147539 0.307194 0.148133 0.285437 0.142558 0.287807 0.145053 0.307194 0.148133 0.328815 0.152258 0.326584 0.149455 0.307194 0.148133 0.292426 0.150037 0.312475 0.154374 0.309847 0.151181 0.330897 0.15516 0.309847 0.151181 0.312475 0.154374 0.290135 0.147539 0.292426 0.150037 0.309847 0.151181 0.330897 0.15516 0.328815 0.152258 0.309847 0.151181 0.296907 0.155045 0.315066 0.157707 0.312475 0.154374 0.332835 0.158155 0.312475 0.154374 0.315066 0.157707 0.29469 0.152546 0.296907 0.155045 0.312475 0.154374 0.292426 0.150037 0.29469 0.152546 0.312475 0.154374 0.332835 0.158155 0.330897 0.15516 0.312475 0.154374 0.299069 0.157524 0.317609 0.161172 0.315066 0.157707 0.33463 0.161242 0.315066 0.157707 0.317609 0.161172 0.296907 0.155045 0.299069 0.157524 0.315066 0.157707 0.33463 0.161242 0.332835 0.158155 0.315066 0.157707 0.303192 0.16236 0.320092 0.164763 0.317609 0.161172 0.335445 0.163494 0.317609 0.161172 0.320092 0.164763 0.301172 0.15997 0.303192 0.16236 0.317609 0.161172 0.299069 0.157524 0.301172 0.15997 0.317609 0.161172 0.335445 0.163494 0.33463 0.161242 0.317609 0.161172 0.305137 0.164689 0.322505 0.168471 0.320092 0.164763 0.336438 0.16604 0.320092 0.164763 0.322505 0.168471 0.303192 0.16236 0.305137 0.164689 0.320092 0.164763 0.336438 0.16604 0.335445 0.163494 0.320092 0.164763 0.308803 0.169176 0.324829 0.17229 0.322505 0.168471 0.339198 0.172493 0.322505 0.168471 0.324829 0.17229 0.307007 0.1669639 0.308803 0.169176 0.322505 0.168471 0.305137 0.164689 0.307007 0.1669639 0.322505 0.168471 0.337352 0.168258 0.336438 0.16604 0.322505 0.168471 0.337512 0.168636 0.337352 0.168258 0.322505 0.168471 0.339198 0.172493 0.337512 0.168636 0.322505 0.168471 0.310527 0.171333 0.327047 0.176208 0.324829 0.17229 0.308803 0.169176 0.310527 0.171333 0.324829 0.17229 0.313765 0.1754699 0.32914 0.180218 0.327047 0.176208 0.310527 0.171333 0.313765 0.1754699 0.327047 0.176208 0.316874 0.179567 0.331079 0.184307 0.32914 0.180218 0.313765 0.1754699 0.316874 0.179567 0.32914 0.180218 0.322347 0.187194 0.332821 0.188458 0.331079 0.184307 0.319762 0.183511 0.322347 0.187194 0.331079 0.184307 0.316874 0.179567 0.319762 0.183511 0.331079 0.184307 0.324731 0.190794 0.334289 0.1926389 0.332821 0.188458 0.322347 0.187194 0.324731 0.190794 0.332821 0.188458 0.3269 0.194376 0.335364 0.196795 0.334289 0.1926389 0.324731 0.190794 0.3269 0.194376 0.334289 0.1926389 0.328653 0.1977249 0.335871 0.200833 0.335364 0.196795 0.3269 0.194376 0.328653 0.1977249 0.335364 0.196795 0.330215 0.202867 0.335527 0.204542 0.335871 0.200833 0.329774 0.200572 0.330215 0.202867 0.335871 0.200833 0.328653 0.1977249 0.329774 0.200572 0.335871 0.200833 0.330272 0.203451 0.335527 0.204542 0.330215 0.202867 0.286184 0.2066929 0.330215 0.202867 0.329774 0.200572 0.286184 0.2066929 0.330272 0.203451 0.330215 0.202867 0.286184 0.2066929 0.329774 0.200572 0.328653 0.1977249 0.286184 0.2066929 0.328653 0.1977249 0.3269 0.194376 0.281166 0.1908479 0.3269 0.194376 0.324731 0.190794 0.281166 0.1908479 0.286184 0.2066929 0.3269 0.194376 0.281166 0.1908479 0.324731 0.190794 0.322347 0.187194 0.281166 0.1908479 0.322347 0.187194 0.319762 0.183511 0.281166 0.1908479 0.319762 0.183511 0.316874 0.179567 0.276528 0.176354 0.316874 0.179567 0.313765 0.1754699 0.276528 0.176354 0.281166 0.1908479 0.316874 0.179567 0.276528 0.176354 0.313765 0.1754699 0.310527 0.171333 0.276528 0.176354 0.310527 0.171333 0.308803 0.169176 0.276528 0.176354 0.308803 0.169176 0.307007 0.1669639 0.276528 0.176354 0.307007 0.1669639 0.305137 0.164689 0.272612 0.163482 0.305137 0.164689 0.303192 0.16236 0.272612 0.163482 0.276528 0.176354 0.305137 0.164689 0.272612 0.163482 0.303192 0.16236 0.301172 0.15997 0.272612 0.163482 0.301172 0.15997 0.299069 0.157524 0.272612 0.163482 0.299069 0.157524 0.296907 0.155045 0.269741 0.1526679 0.296907 0.155045 0.29469 0.152546 0.269741 0.1526679 0.272612 0.163482 0.296907 0.155045 0.269741 0.1526679 0.29469 0.152546 0.292426 0.150037 0.269741 0.1526679 0.292426 0.150037 0.290135 0.147539 0.268093 0.143941 0.290135 0.147539 0.287807 0.145053 0.268093 0.143941 0.269741 0.1526679 0.290135 0.147539 0.268093 0.143941 0.287807 0.145053 0.285437 0.142558 0.267723 0.140268 0.285437 0.142558 0.283018 0.140076 0.267723 0.140268 0.268093 0.143941 0.285437 0.142558 0.267639 0.1370429 0.283018 0.140076 0.280601 0.13763 0.267639 0.1370429 0.267723 0.140268 0.283018 0.140076 0.267639 0.1370429 0.280601 0.13763 0.27819 0.135239 0.267842 0.134246 0.267639 0.1370429 0.27819 0.135239 0.336292 0.140258 0.316413 0.139415 0.319125 0.141734 0.333368 0.142488 0.319125 0.141734 0.321723 0.144185 0.334695 0.141238 0.336292 0.140258 0.319125 0.141734 0.333368 0.142488 0.334695 0.141238 0.319125 0.141734 0.331767 0.1459079 0.321723 0.144185 0.324212 0.14676 0.332374 0.144035 0.333368 0.142488 0.321723 0.144185 0.331767 0.1459079 0.332374 0.144035 0.321723 0.144185 0.331549 0.148147 0.324212 0.14676 0.326584 0.149455 0.331549 0.148147 0.331767 0.1459079 0.324212 0.14676 0.331744 0.15081 0.326584 0.149455 0.328815 0.152258 0.331744 0.15081 0.331549 0.148147 0.326584 0.149455 0.33233 0.153883 0.328815 0.152258 0.330897 0.15516 0.33233 0.153883 0.331744 0.15081 0.328815 0.152258 0.333295 0.157342 0.330897 0.15516 0.332835 0.158155 0.333295 0.157342 0.33233 0.153883 0.330897 0.15516 0.333295 0.157342 0.332835 0.158155 0.33463 0.161242 0.341215 0.1687059 0.33463 0.161242 0.335445 0.163494 0.338783 0.157644 0.333295 0.157342 0.33463 0.161242 0.337591 0.161729 0.338783 0.157644 0.33463 0.161242 0.341215 0.1687059 0.337591 0.161729 0.33463 0.161242 0.341215 0.1687059 0.335445 0.163494 0.336438 0.16604 0.341215 0.1687059 0.336438 0.16604 0.337352 0.168258 0.343219 0.17598 0.337352 0.168258 0.337512 0.168636 0.343219 0.17598 0.341215 0.1687059 0.337352 0.168258 0.343219 0.17598 0.337512 0.168636 0.339198 0.172493 0.338727 0.142203 0.336292 0.140258 0.334695 0.141238 0.338727 0.142203 0.341617 0.140718 0.336292 0.140258 0.338727 0.142203 0.334695 0.141238 0.333368 0.142488 0.336979 0.144291 0.333368 0.142488 0.332374 0.144035 0.336979 0.144291 0.338727 0.142203 0.333368 0.142488 0.336282 0.1469399 0.332374 0.144035 0.331767 0.1459079 0.336282 0.1469399 0.336979 0.144291 0.332374 0.144035 0.336282 0.1469399 0.331767 0.1459079 0.331549 0.148147 0.336464 0.1500869 0.331549 0.148147 0.331744 0.15081 0.336464 0.1500869 0.336282 0.1469399 0.331549 0.148147 0.337351 0.153672 0.331744 0.15081 0.33233 0.153883 0.337351 0.153672 0.336464 0.1500869 0.331744 0.15081 0.338783 0.157644 0.33233 0.153883 0.333295 0.157342 0.338783 0.157644 0.337351 0.153672 0.33233 0.153883 0.341617 0.140718 0.342821 0.13974 0.340463 0.139644 0.340058 0.139149 0.340463 0.139644 0.342821 0.13974 0.341617 0.140718 0.345555 0.139837 0.342821 0.13974 0.343314 0.139402 0.342821 0.13974 0.345555 0.139837 0.340058 0.139149 0.342821 0.13974 0.343314 0.139402 0.346136 0.141176 0.345555 0.139837 0.341617 0.140718 0.35032 0.140447 0.347833 0.139916 0.345555 0.139837 0.346666 0.13964 0.345555 0.139837 0.347833 0.139916 0.346136 0.141176 0.35032 0.140447 0.345555 0.139837 0.343314 0.139402 0.345555 0.139837 0.346666 0.13964 0.343122 0.142496 0.341617 0.140718 0.338727 0.142203 0.343122 0.142496 0.346136 0.141176 0.341617 0.140718 0.341402 0.1444399 0.338727 0.142203 0.336979 0.144291 0.341402 0.1444399 0.343122 0.142496 0.338727 0.142203 0.340895 0.146972 0.336979 0.144291 0.336282 0.1469399 0.340895 0.146972 0.341402 0.1444399 0.336979 0.144291 0.341393 0.15002 0.336282 0.1469399 0.336464 0.1500869 0.341393 0.15002 0.340895 0.146972 0.336282 0.1469399 0.342688 0.153522 0.336464 0.1500869 0.337351 0.153672 0.342688 0.153522 0.341393 0.15002 0.336464 0.1500869 0.344588 0.1574169 0.337351 0.153672 0.338783 0.157644 0.344588 0.1574169 0.342688 0.153522 0.337351 0.153672 0.337591 0.161729 0.340651 0.161967 0.338783 0.157644 0.344588 0.1574169 0.338783 0.157644 0.340651 0.161967 0.341215 0.1687059 0.340651 0.161967 0.337591 0.161729 0.343786 0.161945 0.344588 0.1574169 0.340651 0.161967 0.345257 0.168721 0.343786 0.161945 0.340651 0.161967 0.341215 0.1687059 0.345257 0.168721 0.340651 0.161967 0.35032 0.140447 0.350525 0.140017 0.347833 0.139916 0.346666 0.13964 0.347833 0.139916 0.350525 0.140017 0.35032 0.140447 0.353354 0.1401309 0.350525 0.140017 0.350113 0.139863 0.350525 0.140017 0.353354 0.1401309 0.346666 0.13964 0.350525 0.140017 0.350113 0.139863 0.35032 0.140447 0.355389 0.1402159 0.353354 0.1401309 0.353652 0.140074 0.353354 0.1401309 0.355389 0.1402159 0.350113 0.139863 0.353354 0.1401309 0.353652 0.140074 0.357278 0.140275 0.355389 0.1402159 0.359321 0.140385 0.353652 0.140074 0.355389 0.1402159 0.357278 0.140275 0.343786 0.161945 0.346963 0.161665 0.344588 0.1574169 0.349413 0.1683 0.346963 0.161665 0.343786 0.161945 0.353618 0.16745 0.35015 0.1611289 0.346963 0.161665 0.349413 0.1683 0.353618 0.16745 0.346963 0.161665 0.345257 0.168721 0.349413 0.1683 0.343786 0.161945 0.36098 0.140466 0.359321 0.140385 0.362431 0.140523 0.357278 0.140275 0.359321 0.140385 0.36098 0.140466 0.364745 0.140649 0.362431 0.140523 0.365642 0.140669 0.36098 0.140466 0.362431 0.140523 0.364745 0.140649 0.368559 0.140826 0.365642 0.140669 0.368953 0.140825 0.364745 0.140649 0.365642 0.140669 0.368559 0.140826 0.343314 0.139402 0.342712 0.139411 0.339521 0.139158 0.307214 0.137432 0.339521 0.139158 0.342712 0.139411 0.340058 0.139149 0.343314 0.139402 0.339521 0.139158 0.343314 0.139402 0.345691 0.139627 0.342712 0.139411 0.307214 0.137432 0.342712 0.139411 0.345691 0.139627 0.346666 0.13964 0.349774 0.139894 0.345691 0.139627 0.307214 0.137432 0.345691 0.139627 0.349774 0.139894 0.343314 0.139402 0.346666 0.13964 0.345691 0.139627 0.353652 0.140074 0.353444 0.14011 0.349774 0.139894 0.350113 0.139863 0.353652 0.140074 0.349774 0.139894 0.346666 0.13964 0.350113 0.139863 0.349774 0.139894 0.357278 0.140275 0.35675 0.140289 0.353444 0.14011 0.353652 0.140074 0.357278 0.140275 0.353444 0.14011 0.357278 0.140275 0.359728 0.14044 0.35675 0.140289 0.36098 0.140466 0.362407 0.140568 0.359728 0.14044 0.357278 0.140275 0.36098 0.140466 0.359728 0.14044 0.364745 0.140649 0.364816 0.140677 0.362407 0.140568 0.36098 0.140466 0.364745 0.140649 0.362407 0.140568 0.368559 0.140826 0.36895 0.140855 0.364816 0.140677 0.364745 0.140649 0.368559 0.140826 0.364816 0.140677 0.27955 0.134054 0.253855 0.129788 0.281001 0.133707 0.25202 0.130309 0.249041 0.1290799 0.253855 0.129788 0.25202 0.130309 0.253855 0.129788 0.27955 0.134054 0.305789 0.137768 0.281001 0.133707 0.294212 0.135592 0.305789 0.137768 0.27955 0.134054 0.281001 0.133707 0.305789 0.137768 0.294212 0.135592 0.307214 0.137432 0.305789 0.137768 0.307214 0.137432 0.330746 0.141438 0.100785 0.0191999 0.104487 0.01756298 0.105418 0.01844096 0.100785 0.0191999 0.105418 0.01844096 0.134935 0.04589688 0.1360819 0.0512579 0.134935 0.04589688 0.158903 0.06760597 0.100785 0.0191999 0.134935 0.04589688 0.1360819 0.0512579 0.163763 0.07559198 0.158903 0.06760597 0.178961 0.08517599 0.1360819 0.0512579 0.158903 0.06760597 0.163763 0.07559198 0.186374 0.09465497 0.178961 0.08517599 0.196161 0.09967195 0.163763 0.07559198 0.178961 0.08517599 0.186374 0.09465497 0.205442 0.109975 0.196161 0.09967195 0.211212 0.111828 0.186374 0.09465497 0.196161 0.09967195 0.205442 0.109975 0.205442 0.109975 0.211212 0.111828 0.224607 0.122168 0.221948 0.122553 0.224607 0.122168 0.225874 0.123079 0.205442 0.109975 0.224607 0.122168 0.221948 0.122553 0.224278 0.124054 0.225874 0.123079 0.227407 0.123946 0.224278 0.124054 0.221948 0.122553 0.225874 0.123079 0.224278 0.124054 0.227407 0.123946 0.22916 0.124772 0.227313 0.1254619 0.22916 0.124772 0.231253 0.125553 0.224278 0.124054 0.22916 0.124772 0.227313 0.1254619 0.231423 0.126732 0.231253 0.125553 0.233767 0.126272 0.227313 0.1254619 0.231253 0.125553 0.231423 0.126732 0.231423 0.126732 0.233767 0.126272 0.236779 0.126968 0.237037 0.127928 0.236779 0.126968 0.240449 0.127671 0.231423 0.126732 0.236779 0.126968 0.237037 0.127928 0.237037 0.127928 0.240449 0.127671 0.244586 0.1283749 0.244129 0.129126 0.244586 0.1283749 0.249041 0.1290799 0.237037 0.127928 0.244586 0.1283749 0.244129 0.129126 0.244129 0.129126 0.249041 0.1290799 0.25202 0.130309 0.248925 0.1333079 0.27519 0.139311 0.247927 0.135523 0.281667 0.140202 0.247927 0.135523 0.27519 0.139311 0.240878 0.132133 0.248925 0.1333079 0.247927 0.135523 0.278785 0.1508769 0.247927 0.135523 0.281667 0.140202 0.239805 0.134356 0.247927 0.135523 0.23949 0.1343089 0.233759 0.15535 0.23949 0.1343089 0.247927 0.135523 0.240878 0.132133 0.247927 0.135523 0.239805 0.134356 0.278459 0.151001 0.247927 0.135523 0.278785 0.1508769 0.268166 0.157464 0.242559 0.15628 0.247927 0.135523 0.233759 0.15535 0.247927 0.135523 0.242559 0.15628 0.273205 0.153654 0.268166 0.157464 0.247927 0.135523 0.278459 0.151001 0.273205 0.153654 0.247927 0.135523 0.248925 0.1333079 0.275932 0.137546 0.27519 0.139311 0.281667 0.140202 0.27519 0.139311 0.275932 0.137546 0.248925 0.1333079 0.276945 0.136027 0.275932 0.137546 0.302243 0.141184 0.275932 0.137546 0.276945 0.136027 0.30152 0.142912 0.275932 0.137546 0.302243 0.141184 0.288459 0.141133 0.275932 0.137546 0.30152 0.142912 0.281667 0.140202 0.275932 0.137546 0.288459 0.141133 0.250327 0.131515 0.278172 0.134842 0.276945 0.136027 0.303233 0.139697 0.276945 0.136027 0.278172 0.134842 0.248925 0.1333079 0.250327 0.131515 0.276945 0.136027 0.302243 0.141184 0.276945 0.136027 0.303233 0.139697 0.25202 0.130309 0.27955 0.134054 0.278172 0.134842 0.304436 0.138537 0.278172 0.134842 0.27955 0.134054 0.250327 0.131515 0.25202 0.130309 0.278172 0.134842 0.303233 0.139697 0.278172 0.134842 0.304436 0.138537 0.304436 0.138537 0.27955 0.134054 0.305789 0.137768 0.244129 0.129126 0.25202 0.130309 0.250327 0.131515 0.2423509 0.1303319 0.250327 0.131515 0.248925 0.1333079 0.244129 0.129126 0.250327 0.131515 0.2423509 0.1303319 0.2423509 0.1303319 0.248925 0.1333079 0.240878 0.132133 0.302243 0.141184 0.32783 0.144248 0.32691 0.146327 0.33603 0.14638 0.32691 0.146327 0.32783 0.144248 0.314194 0.1446239 0.302243 0.141184 0.32691 0.146327 0.331593 0.147248 0.314194 0.1446239 0.32691 0.146327 0.33603 0.14638 0.331593 0.147248 0.32691 0.146327 0.303233 0.139697 0.329146 0.142565 0.32783 0.144248 0.337422 0.144803 0.32783 0.144248 0.329146 0.142565 0.302243 0.141184 0.303233 0.139697 0.32783 0.144248 0.337422 0.144803 0.33603 0.14638 0.32783 0.144248 0.304436 0.138537 0.330746 0.141438 0.329146 0.142565 0.339049 0.1437 0.329146 0.142565 0.330746 0.141438 0.303233 0.139697 0.304436 0.138537 0.329146 0.142565 0.339049 0.1437 0.337422 0.144803 0.329146 0.142565 0.304436 0.138537 0.305789 0.137768 0.330746 0.141438 0.314194 0.1446239 0.30152 0.142912 0.302243 0.141184 0.288715 0.149456 0.30152 0.142912 0.314194 0.1446239 0.288715 0.149456 0.288459 0.141133 0.30152 0.142912 0.335931 0.148658 0.314194 0.1446239 0.331593 0.147248 0.339943 0.150564 0.314194 0.1446239 0.335931 0.148658 0.343628 0.152938 0.314194 0.1446239 0.339943 0.150564 0.344162 0.153339 0.314194 0.1446239 0.343628 0.152938 0.312242 0.151823 0.314194 0.1446239 0.344162 0.153339 0.306665 0.151265 0.314194 0.1446239 0.312242 0.151823 0.306665 0.151265 0.288715 0.149456 0.314194 0.1446239 0.288715 0.149456 0.281667 0.140202 0.288459 0.141133 0.28372 0.14959 0.278785 0.1508769 0.281667 0.140202 0.288715 0.149456 0.28372 0.14959 0.281667 0.140202 0.21748 0.125496 0.218507 0.129257 0.216064 0.127788 0.2116529 0.138921 0.216064 0.127788 0.218507 0.129257 0.216033 0.127771 0.21748 0.125496 0.216064 0.127788 0.2116529 0.138921 0.216033 0.127771 0.216064 0.127788 0.219909 0.1269879 0.218628 0.129319 0.218507 0.129257 0.2116529 0.138921 0.218507 0.129257 0.218628 0.129319 0.21748 0.125496 0.219909 0.1269879 0.218507 0.129257 0.22311 0.128407 0.221759 0.130661 0.218628 0.129319 0.210686 0.151289 0.218628 0.129319 0.221759 0.130661 0.219909 0.1269879 0.22311 0.128407 0.218628 0.129319 0.210686 0.151289 0.2116529 0.138921 0.218628 0.129319 0.22311 0.128407 0.22193 0.130721 0.221759 0.130661 0.210686 0.151289 0.221759 0.130661 0.22193 0.130721 0.227523 0.129708 0.226256 0.131954 0.22193 0.130721 0.214357 0.1524209 0.22193 0.130721 0.226256 0.131954 0.22311 0.128407 0.227523 0.129708 0.22193 0.130721 0.210686 0.151289 0.22193 0.130721 0.214357 0.1524209 0.227523 0.129708 0.232055 0.133116 0.226256 0.131954 0.219263 0.153441 0.226256 0.131954 0.232055 0.133116 0.214357 0.1524209 0.226256 0.131954 0.219263 0.153441 0.23949 0.1343089 0.232055 0.133116 0.232313 0.133162 0.233514 0.13093 0.232313 0.133162 0.232055 0.133116 0.225764 0.154398 0.232055 0.133116 0.23949 0.1343089 0.227523 0.129708 0.233514 0.13093 0.232055 0.133116 0.219263 0.153441 0.232055 0.133116 0.225764 0.154398 0.233514 0.13093 0.23949 0.1343089 0.232313 0.133162 0.240878 0.132133 0.239805 0.134356 0.23949 0.1343089 0.233514 0.13093 0.240878 0.132133 0.23949 0.1343089 0.225764 0.154398 0.23949 0.1343089 0.233759 0.15535 0.235109 0.129126 0.240878 0.132133 0.233514 0.13093 0.235109 0.129126 0.2423509 0.1303319 0.240878 0.132133 0.229287 0.127909 0.233514 0.13093 0.227523 0.129708 0.229287 0.127909 0.235109 0.129126 0.233514 0.13093 0.22501 0.126615 0.227523 0.129708 0.22311 0.128407 0.22501 0.126615 0.229287 0.127909 0.227523 0.129708 0.2218829 0.125194 0.22311 0.128407 0.219909 0.1269879 0.2218829 0.125194 0.22501 0.126615 0.22311 0.128407 0.219499 0.123692 0.219909 0.1269879 0.21748 0.125496 0.2218829 0.125194 0.219909 0.1269879 0.219499 0.123692 0.200554 0.113164 0.219499 0.123692 0.21748 0.125496 0.20197 0.117821 0.21748 0.125496 0.216033 0.127771 0.20197 0.117821 0.200554 0.113164 0.21748 0.125496 0.221948 0.122553 0.2218829 0.125194 0.219499 0.123692 0.202768 0.111211 0.221948 0.122553 0.219499 0.123692 0.202768 0.111211 0.219499 0.123692 0.200554 0.113164 0.237037 0.127928 0.2423509 0.1303319 0.235109 0.129126 0.237037 0.127928 0.244129 0.129126 0.2423509 0.1303319 0.231423 0.126732 0.235109 0.129126 0.229287 0.127909 0.231423 0.126732 0.237037 0.127928 0.235109 0.129126 0.227313 0.1254619 0.229287 0.127909 0.22501 0.126615 0.227313 0.1254619 0.231423 0.126732 0.229287 0.127909 0.224278 0.124054 0.22501 0.126615 0.2218829 0.125194 0.224278 0.124054 0.227313 0.1254619 0.22501 0.126615 0.224278 0.124054 0.2218829 0.125194 0.221948 0.122553 0.205442 0.109975 0.221948 0.122553 0.202768 0.111211 0.20197 0.117821 0.216033 0.127771 0.198982 0.115652 0.2116529 0.138921 0.198982 0.115652 0.216033 0.127771 0.186137 0.106128 0.180972 0.098149 0.200554 0.113164 0.202768 0.111211 0.200554 0.113164 0.180972 0.098149 0.198982 0.115652 0.186137 0.106128 0.200554 0.113164 0.20197 0.117821 0.198982 0.115652 0.200554 0.113164 0.1680099 0.09219497 0.157725 0.07946997 0.180972 0.098149 0.1834239 0.09601098 0.180972 0.098149 0.157725 0.07946997 0.1791869 0.100849 0.1680099 0.09219497 0.180972 0.098149 0.186137 0.106128 0.1791869 0.100849 0.180972 0.098149 0.1834239 0.09601098 0.202768 0.111211 0.180972 0.098149 0.146833 0.07531797 0.129233 0.055637 0.157725 0.07946997 0.160472 0.07710099 0.157725 0.07946997 0.129233 0.055637 0.155676 0.08243399 0.146833 0.07531797 0.157725 0.07946997 0.1680099 0.09219497 0.155676 0.08243399 0.157725 0.07946997 0.160472 0.07710099 0.1834239 0.09601098 0.157725 0.07946997 0.09022498 0.02814197 0.09287297 0.02425789 0.129233 0.055637 0.132356 0.05296891 0.129233 0.055637 0.09287297 0.02425789 0.121483 0.05447489 0.09022498 0.02814197 0.129233 0.055637 0.126841 0.05892795 0.121483 0.05447489 0.129233 0.055637 0.146833 0.07531797 0.126841 0.05892795 0.129233 0.055637 0.132356 0.05296891 0.160472 0.07710099 0.129233 0.055637 0.09091097 0.02253198 0.09287297 0.02425789 0.09022498 0.02814197 0.09648895 0.02119195 0.132356 0.05296891 0.09287297 0.02425789 0.09091097 0.02253198 0.09648895 0.02119195 0.09287297 0.02425789 0.126841 0.05892795 0.09022498 0.02814197 0.121483 0.05447489 0.085581 0.03793191 0.09022498 0.02814197 0.126841 0.05892795 0.08922696 0.02729195 0.09022498 0.02814197 0.085581 0.03793191 0.09091097 0.02253198 0.09022498 0.02814197 0.08922696 0.02729195 0.155676 0.08243399 0.126841 0.05892795 0.146833 0.07531797 0.115217 0.08621895 0.126841 0.05892795 0.155676 0.08243399 0.114956 0.08188599 0.126841 0.05892795 0.115217 0.08621895 0.1123329 0.07528597 0.085581 0.03793191 0.126841 0.05892795 0.113995 0.07779699 0.1123329 0.07528597 0.126841 0.05892795 0.114956 0.08188599 0.113995 0.07779699 0.126841 0.05892795 0.1791869 0.100849 0.155676 0.08243399 0.1680099 0.09219497 0.171461 0.119771 0.155676 0.08243399 0.1791869 0.100849 0.115217 0.08621895 0.155676 0.08243399 0.143691 0.112066 0.171461 0.119771 0.143691 0.112066 0.155676 0.08243399 0.198982 0.115652 0.1791869 0.100849 0.186137 0.106128 0.171461 0.119771 0.1791869 0.100849 0.198982 0.115652 0.189772 0.139926 0.171461 0.119771 0.198982 0.115652 0.189772 0.139926 0.198982 0.115652 0.2116529 0.138921 0.205442 0.109975 0.202768 0.111211 0.1834239 0.09601098 0.186374 0.09465497 0.1834239 0.09601098 0.160472 0.07710099 0.186374 0.09465497 0.205442 0.109975 0.1834239 0.09601098 0.163763 0.07559198 0.160472 0.07710099 0.132356 0.05296891 0.163763 0.07559198 0.186374 0.09465497 0.160472 0.07710099 0.1360819 0.0512579 0.132356 0.05296891 0.09648895 0.02119195 0.1360819 0.0512579 0.163763 0.07559198 0.132356 0.05296891 0.100785 0.0191999 0.1360819 0.0512579 0.09648895 0.02119195 0.09455597 0.01944392 0.100785 0.0191999 0.09648895 0.02119195 0.09091097 0.02253198 0.09455597 0.01944392 0.09648895 0.02119195 0.09455597 0.01944392 0.09888899 0.01744395 0.100785 0.0191999 0.128587 0.269892 0.1094869 0.275187 0.111806 0.242473 0.148485 0.242624 0.111806 0.242473 0.1094869 0.275187 0.125551 0.238029 0.128587 0.269892 0.111806 0.242473 0.112381 0.23609 0.125551 0.238029 0.111806 0.242473 0.149217 0.234827 0.112381 0.23609 0.111806 0.242473 0.149217 0.234827 0.111806 0.242473 0.148485 0.242624 0.134644 0.301308 0.110109 0.308641 0.1094869 0.275187 0.148485 0.242624 0.1094869 0.275187 0.110109 0.308641 0.128587 0.269892 0.134644 0.301308 0.1094869 0.275187 0.134644 0.301308 0.113794 0.34244 0.110109 0.308641 0.148485 0.242624 0.110109 0.308641 0.113794 0.34244 0.14369 0.331978 0.114808 0.350214 0.113794 0.34244 0.136026 0.342987 0.113794 0.34244 0.114808 0.350214 0.134644 0.301308 0.14369 0.331978 0.113794 0.34244 0.136026 0.342987 0.148485 0.242624 0.113794 0.34244 0.155676 0.361612 0.1152099 0.356755 0.114808 0.350214 0.134587 0.352251 0.114808 0.350214 0.1152099 0.356755 0.14369 0.331978 0.155676 0.361612 0.114808 0.350214 0.134587 0.352251 0.136026 0.342987 0.114808 0.350214 0.155676 0.361612 0.115217 0.357827 0.1152099 0.356755 0.134587 0.352251 0.1152099 0.356755 0.115217 0.357827 0.146834 0.368728 0.126843 0.385116 0.115217 0.357827 0.114955 0.362165 0.115217 0.357827 0.126843 0.385116 0.155676 0.361612 0.146834 0.368728 0.115217 0.357827 0.13279 0.359973 0.115217 0.357827 0.114955 0.362165 0.13279 0.359973 0.134587 0.352251 0.115217 0.357827 0.1292099 0.388429 0.126843 0.385116 0.146834 0.368728 0.113994 0.366251 0.114955 0.362165 0.126843 0.385116 0.1123329 0.36876 0.113994 0.366251 0.126843 0.385116 0.09761798 0.381632 0.1123329 0.36876 0.126843 0.385116 0.08118599 0.396202 0.09761798 0.381632 0.126843 0.385116 0.08557999 0.406112 0.08118599 0.396202 0.126843 0.385116 0.09022498 0.415903 0.08557999 0.406112 0.126843 0.385116 0.09287697 0.419786 0.09022498 0.415903 0.126843 0.385116 0.1292099 0.388429 0.09287697 0.419786 0.126843 0.385116 0.1292099 0.388429 0.146834 0.368728 0.155676 0.361612 0.179188 0.343197 0.155676 0.361612 0.14369 0.331978 0.157709 0.364589 0.155676 0.361612 0.179188 0.343197 0.157709 0.364589 0.1292099 0.388429 0.155676 0.361612 0.1650789 0.304856 0.14369 0.331978 0.134644 0.301308 0.171461 0.324274 0.179188 0.343197 0.14369 0.331978 0.1650789 0.304856 0.171461 0.324274 0.14369 0.331978 0.1489779 0.286467 0.134644 0.301308 0.128587 0.269892 0.160301 0.285223 0.1650789 0.304856 0.134644 0.301308 0.151162 0.28698 0.160301 0.285223 0.134644 0.301308 0.150102 0.286945 0.151162 0.28698 0.134644 0.301308 0.1489779 0.286467 0.150102 0.286945 0.134644 0.301308 0.139273 0.267608 0.128587 0.269892 0.125551 0.238029 0.146547 0.284157 0.1489779 0.286467 0.128587 0.269892 0.144014 0.280131 0.146547 0.284157 0.128587 0.269892 0.141519 0.274508 0.144014 0.280131 0.128587 0.269892 0.139273 0.267608 0.141519 0.274508 0.128587 0.269892 0.11238 0.2079499 0.125551 0.206015 0.125551 0.238029 0.133935 0.222016 0.125551 0.238029 0.125551 0.206015 0.112716 0.214861 0.11238 0.2079499 0.125551 0.238029 0.112825 0.222015 0.112716 0.214861 0.125551 0.238029 0.112716 0.229175 0.112825 0.222015 0.125551 0.238029 0.112381 0.23609 0.112716 0.229175 0.125551 0.238029 0.137383 0.259436 0.139273 0.267608 0.125551 0.238029 0.134809 0.241041 0.137383 0.259436 0.125551 0.238029 0.133935 0.222016 0.134809 0.241041 0.125551 0.238029 0.111806 0.201573 0.128587 0.174152 0.125551 0.206015 0.134807 0.203021 0.125551 0.206015 0.128587 0.174152 0.11238 0.2079499 0.111806 0.201573 0.125551 0.206015 0.134807 0.203021 0.133935 0.222016 0.125551 0.206015 0.110109 0.135405 0.134645 0.142737 0.128587 0.174152 0.141531 0.169506 0.128587 0.174152 0.134645 0.142737 0.1094869 0.168859 0.110109 0.135405 0.128587 0.174152 0.111806 0.201573 0.1094869 0.168859 0.128587 0.174152 0.137383 0.18461 0.134807 0.203021 0.128587 0.174152 0.139275 0.176431 0.137383 0.18461 0.128587 0.174152 0.141531 0.169506 0.139275 0.176431 0.128587 0.174152 0.113794 0.101606 0.143691 0.112066 0.134645 0.142737 0.1650789 0.139189 0.134645 0.142737 0.143691 0.112066 0.110109 0.135405 0.113794 0.101606 0.134645 0.142737 0.144039 0.163869 0.141531 0.169506 0.134645 0.142737 0.146577 0.159852 0.144039 0.163869 0.134645 0.142737 0.148998 0.157567 0.146577 0.159852 0.134645 0.142737 0.1501139 0.157096 0.148998 0.157567 0.134645 0.142737 0.151162 0.157066 0.1501139 0.157096 0.134645 0.142737 0.160301 0.158822 0.151162 0.157066 0.134645 0.142737 0.1650789 0.139189 0.160301 0.158822 0.134645 0.142737 0.1152099 0.08729797 0.115217 0.08621895 0.143691 0.112066 0.114807 0.09383797 0.1152099 0.08729797 0.143691 0.112066 0.113794 0.101606 0.114807 0.09383797 0.143691 0.112066 0.171461 0.119771 0.1650789 0.139189 0.143691 0.112066 0.13279 0.08407199 0.115217 0.08621895 0.1152099 0.08729797 0.13279 0.08407199 0.114956 0.08188599 0.115217 0.08621895 0.134587 0.09179395 0.1152099 0.08729797 0.114807 0.09383797 0.134587 0.09179395 0.13279 0.08407199 0.1152099 0.08729797 0.134587 0.09179395 0.114807 0.09383797 0.113794 0.101606 0.136026 0.101058 0.113794 0.101606 0.110109 0.135405 0.134587 0.09179395 0.113794 0.101606 0.136026 0.101058 0.136026 0.101058 0.110109 0.135405 0.1094869 0.168859 0.136026 0.101058 0.1094869 0.168859 0.111806 0.201573 0.148485 0.201422 0.111806 0.201573 0.11238 0.2079499 0.136026 0.101058 0.111806 0.201573 0.148485 0.201422 0.149217 0.209218 0.11238 0.2079499 0.112716 0.214861 0.149217 0.209218 0.148485 0.201422 0.11238 0.2079499 0.149591 0.21768 0.112716 0.214861 0.112825 0.222015 0.149591 0.21768 0.149217 0.209218 0.112716 0.214861 0.149591 0.226365 0.112825 0.222015 0.112716 0.229175 0.149591 0.226365 0.149591 0.21768 0.112825 0.222015 0.149217 0.234827 0.112716 0.229175 0.112381 0.23609 0.149217 0.234827 0.149591 0.226365 0.112716 0.229175 0.130711 0.365752 0.114955 0.362165 0.113994 0.366251 0.130711 0.365752 0.13279 0.359973 0.114955 0.362165 0.130711 0.365752 0.113994 0.366251 0.1123329 0.36876 0.128442 0.369252 0.1123329 0.36876 0.09761798 0.381632 0.130711 0.365752 0.1123329 0.36876 0.128442 0.369252 0.128442 0.369252 0.09761798 0.381632 0.08118599 0.396202 0.08029198 0.396954 0.08118599 0.396202 0.08557999 0.406112 0.08029198 0.396954 0.09982496 0.396975 0.08118599 0.396202 0.128442 0.369252 0.08118599 0.396202 0.09982496 0.396975 0.083682 0.407678 0.08557999 0.406112 0.09022498 0.415903 0.08029198 0.396954 0.08557999 0.406112 0.07938295 0.397628 0.083682 0.407678 0.07938295 0.397628 0.08557999 0.406112 0.08922499 0.416758 0.083682 0.407678 0.09022498 0.415903 0.09287697 0.419786 0.08922499 0.416758 0.09022498 0.415903 0.186137 0.337918 0.179188 0.343197 0.171461 0.324274 0.180965 0.345903 0.179188 0.343197 0.186137 0.337918 0.180965 0.345903 0.157709 0.364589 0.179188 0.343197 0.189772 0.304118 0.171461 0.324274 0.1650789 0.304856 0.198982 0.328394 0.186137 0.337918 0.171461 0.324274 0.189772 0.304118 0.198982 0.328394 0.171461 0.324274 0.173123 0.282237 0.1650789 0.304856 0.160301 0.285223 0.173123 0.282237 0.189772 0.304118 0.1650789 0.304856 0.162071 0.283495 0.160301 0.285223 0.151162 0.28698 0.172246 0.281266 0.173123 0.282237 0.160301 0.285223 0.162071 0.283495 0.172246 0.281266 0.160301 0.285223 0.151011 0.285501 0.151162 0.28698 0.150102 0.286945 0.162071 0.283495 0.151162 0.28698 0.151011 0.285501 0.148974 0.285 0.150102 0.286945 0.1489779 0.286467 0.148974 0.285 0.151011 0.285501 0.150102 0.286945 0.146685 0.282783 0.1489779 0.286467 0.146547 0.284157 0.146685 0.282783 0.148974 0.285 0.1489779 0.286467 0.144279 0.278859 0.146547 0.284157 0.144014 0.280131 0.144279 0.278859 0.146685 0.282783 0.146547 0.284157 0.141915 0.273378 0.144014 0.280131 0.141519 0.274508 0.141915 0.273378 0.144279 0.278859 0.144014 0.280131 0.139778 0.266611 0.141519 0.274508 0.139273 0.267608 0.139778 0.266611 0.141915 0.273378 0.141519 0.274508 0.138014 0.258775 0.139273 0.267608 0.137383 0.259436 0.138014 0.258775 0.139778 0.266611 0.139273 0.267608 0.138014 0.258775 0.137383 0.259436 0.134809 0.241041 0.1354539 0.240661 0.134809 0.241041 0.133935 0.222016 0.1354539 0.240661 0.138014 0.258775 0.134809 0.241041 0.135453 0.2034 0.133935 0.222016 0.134807 0.203021 0.134596 0.222034 0.1354539 0.240661 0.133935 0.222016 0.135453 0.2034 0.134596 0.222034 0.133935 0.222016 0.135453 0.2034 0.134807 0.203021 0.137383 0.18461 0.138014 0.185271 0.137383 0.18461 0.139275 0.176431 0.138014 0.185271 0.135453 0.2034 0.137383 0.18461 0.139777 0.177438 0.139275 0.176431 0.141531 0.169506 0.139777 0.177438 0.138014 0.185271 0.139275 0.176431 0.141914 0.1706719 0.141531 0.169506 0.144039 0.163869 0.141914 0.1706719 0.139777 0.177438 0.141531 0.169506 0.144277 0.16519 0.144039 0.163869 0.146577 0.159852 0.144277 0.16519 0.141914 0.1706719 0.144039 0.163869 0.146684 0.161265 0.146577 0.159852 0.148998 0.157567 0.146684 0.161265 0.144277 0.16519 0.146577 0.159852 0.148972 0.159047 0.148998 0.157567 0.1501139 0.157096 0.148972 0.159047 0.146684 0.161265 0.148998 0.157567 0.148972 0.159047 0.1501139 0.157096 0.151162 0.157066 0.151011 0.158544 0.151162 0.157066 0.160301 0.158822 0.151011 0.158544 0.148972 0.159047 0.151162 0.157066 0.173123 0.161809 0.160301 0.158822 0.1650789 0.139189 0.162071 0.1605499 0.160301 0.158822 0.173123 0.161809 0.162071 0.1605499 0.151011 0.158544 0.160301 0.158822 0.189772 0.139926 0.1650789 0.139189 0.171461 0.119771 0.1832219 0.164766 0.1650789 0.139189 0.189772 0.139926 0.173123 0.161809 0.1650789 0.139189 0.1832219 0.164766 0.180965 0.345903 0.186137 0.337918 0.198982 0.328394 0.216033 0.316274 0.198982 0.328394 0.189772 0.304118 0.200549 0.330885 0.198982 0.328394 0.216033 0.316274 0.200549 0.330885 0.180965 0.345903 0.198982 0.328394 0.173123 0.282237 0.1832219 0.27928 0.189772 0.304118 0.207732 0.293547 0.189772 0.304118 0.1832219 0.27928 0.216064 0.316258 0.216033 0.316274 0.189772 0.304118 0.21161 0.305008 0.216064 0.316258 0.189772 0.304118 0.207732 0.293547 0.21161 0.305008 0.189772 0.304118 0.181622 0.278741 0.1832219 0.27928 0.173123 0.282237 0.190393 0.276717 0.207732 0.293547 0.1832219 0.27928 0.1902649 0.275836 0.190393 0.276717 0.1832219 0.27928 0.181622 0.278741 0.1902649 0.275836 0.1832219 0.27928 0.172246 0.281266 0.181622 0.278741 0.173123 0.282237 0.217481 0.31855 0.216033 0.316274 0.216064 0.316258 0.200549 0.330885 0.216033 0.316274 0.217481 0.31855 0.2184669 0.314809 0.216064 0.316258 0.21161 0.305008 0.217481 0.31855 0.216064 0.316258 0.2184669 0.314809 0.210686 0.292757 0.21161 0.305008 0.207732 0.293547 0.218626 0.314727 0.21161 0.305008 0.210686 0.292757 0.2184669 0.314809 0.21161 0.305008 0.218626 0.314727 0.192595 0.272974 0.201734 0.27011 0.207732 0.293547 0.204849 0.269773 0.207732 0.293547 0.201734 0.27011 0.1917 0.275447 0.192595 0.272974 0.207732 0.293547 0.1911 0.276232 0.1917 0.275447 0.207732 0.293547 0.190393 0.276717 0.1911 0.276232 0.207732 0.293547 0.210686 0.292757 0.207732 0.293547 0.204849 0.269773 0.1931329 0.252923 0.198118 0.246186 0.201734 0.27011 0.201286 0.246078 0.201734 0.27011 0.198118 0.246186 0.193354 0.25928 0.1931329 0.252923 0.201734 0.27011 0.1933709 0.264744 0.193354 0.25928 0.201734 0.27011 0.1931329 0.269352 0.1933709 0.264744 0.201734 0.27011 0.192595 0.272974 0.1931329 0.269352 0.201734 0.27011 0.204849 0.269773 0.201734 0.27011 0.201286 0.246078 0.192332 0.222017 0.19691 0.222018 0.198118 0.246186 0.200083 0.222023 0.198118 0.246186 0.19691 0.222018 0.1924369 0.232707 0.192332 0.222017 0.198118 0.246186 0.192727 0.243172 0.1924369 0.232707 0.198118 0.246186 0.1931329 0.252923 0.192727 0.243172 0.198118 0.246186 0.201286 0.246078 0.198118 0.246186 0.200083 0.222023 0.1924369 0.211313 0.19691 0.221523 0.19691 0.222018 0.200083 0.222023 0.19691 0.222018 0.19691 0.221523 0.192332 0.222017 0.1924369 0.211313 0.19691 0.222018 0.1924369 0.211313 0.196912 0.221029 0.19691 0.221523 0.200083 0.222023 0.19691 0.221523 0.196912 0.221029 0.192727 0.2008669 0.198194 0.197114 0.196912 0.221029 0.201286 0.197968 0.196912 0.221029 0.198194 0.197114 0.1924369 0.211313 0.192727 0.2008669 0.196912 0.221029 0.200083 0.222023 0.196912 0.221029 0.201286 0.197968 0.193139 0.174745 0.201834 0.1734459 0.198194 0.197114 0.204849 0.174273 0.198194 0.197114 0.201834 0.1734459 0.193372 0.179381 0.193139 0.174745 0.198194 0.197114 0.1933529 0.184853 0.193372 0.179381 0.198194 0.197114 0.1931329 0.191123 0.1933529 0.184853 0.198194 0.197114 0.192727 0.2008669 0.1931329 0.191123 0.198194 0.197114 0.201286 0.197968 0.198194 0.197114 0.204849 0.174273 0.190393 0.167329 0.207806 0.15026 0.201834 0.1734459 0.210686 0.151289 0.201834 0.1734459 0.207806 0.15026 0.1910949 0.1677989 0.190393 0.167329 0.201834 0.1734459 0.191694 0.168581 0.1910949 0.1677989 0.201834 0.1734459 0.192193 0.169679 0.191694 0.168581 0.201834 0.1734459 0.192597 0.1710889 0.192193 0.169679 0.201834 0.1734459 0.193139 0.174745 0.192597 0.1710889 0.201834 0.1734459 0.204849 0.174273 0.201834 0.1734459 0.210686 0.151289 0.189772 0.139926 0.2116529 0.138921 0.207806 0.15026 0.210686 0.151289 0.207806 0.15026 0.2116529 0.138921 0.1832219 0.164766 0.189772 0.139926 0.207806 0.15026 0.190393 0.167329 0.1832219 0.164766 0.207806 0.15026 0.181622 0.165302 0.1832219 0.164766 0.190393 0.167329 0.181622 0.165302 0.173123 0.161809 0.1832219 0.164766 0.1902649 0.168208 0.190393 0.167329 0.1910949 0.1677989 0.1902649 0.168208 0.181622 0.165302 0.190393 0.167329 0.191488 0.169333 0.1910949 0.1677989 0.191694 0.168581 0.191488 0.169333 0.1902649 0.168208 0.1910949 0.1677989 0.191488 0.169333 0.191694 0.168581 0.192193 0.169679 0.192381 0.171692 0.192193 0.169679 0.192597 0.1710889 0.192381 0.171692 0.191488 0.169333 0.192193 0.169679 0.192939 0.17524 0.192597 0.1710889 0.193139 0.174745 0.192939 0.17524 0.192381 0.171692 0.192597 0.1710889 0.193192 0.179843 0.193139 0.174745 0.193372 0.179381 0.193192 0.179843 0.192939 0.17524 0.193139 0.174745 0.19319 0.1853049 0.193372 0.179381 0.1933529 0.184853 0.19319 0.1853049 0.193192 0.179843 0.193372 0.179381 0.192984 0.1914809 0.1933529 0.184853 0.1931329 0.191123 0.192984 0.1914809 0.19319 0.1853049 0.1933529 0.184853 0.192984 0.1914809 0.1931329 0.191123 0.192727 0.2008669 0.192522 0.203381 0.192727 0.2008669 0.1924369 0.211313 0.192522 0.203381 0.192984 0.1914809 0.192727 0.2008669 0.1922529 0.215773 0.1924369 0.211313 0.192332 0.222017 0.1922529 0.215773 0.192522 0.203381 0.1924369 0.211313 0.1922529 0.228244 0.192332 0.222017 0.1924369 0.232707 0.1922529 0.228244 0.1922529 0.215773 0.192332 0.222017 0.192522 0.2406589 0.1924369 0.232707 0.192727 0.243172 0.192522 0.2406589 0.1922529 0.228244 0.1924369 0.232707 0.192522 0.2406589 0.192727 0.243172 0.1931329 0.252923 0.192984 0.252564 0.1931329 0.252923 0.193354 0.25928 0.192984 0.252564 0.192522 0.2406589 0.1931329 0.252923 0.19319 0.25874 0.193354 0.25928 0.1933709 0.264744 0.19319 0.25874 0.192984 0.252564 0.193354 0.25928 0.193192 0.264201 0.1933709 0.264744 0.1931329 0.269352 0.193192 0.264201 0.19319 0.25874 0.1933709 0.264744 0.192938 0.268805 0.1931329 0.269352 0.192595 0.272974 0.192938 0.268805 0.193192 0.264201 0.1931329 0.269352 0.192381 0.272352 0.192595 0.272974 0.1917 0.275447 0.192381 0.272352 0.192938 0.268805 0.192595 0.272974 0.191487 0.274711 0.1917 0.275447 0.1911 0.276232 0.191487 0.274711 0.192381 0.272352 0.1917 0.275447 0.191487 0.274711 0.1911 0.276232 0.190393 0.276717 0.1902649 0.275836 0.191487 0.274711 0.190393 0.276717 0.172246 0.162779 0.162071 0.1605499 0.173123 0.161809 0.181622 0.165302 0.172246 0.162779 0.173123 0.161809 0.1123329 0.07528597 0.08118599 0.04784291 0.085581 0.03793191 0.08029597 0.0470969 0.085581 0.03793191 0.08118599 0.04784291 0.07937699 0.046422 0.085581 0.03793191 0.08029597 0.0470969 0.08368098 0.03637492 0.085581 0.03793191 0.07937699 0.046422 0.08823496 0.02644091 0.085581 0.03793191 0.08368098 0.03637492 0.08922696 0.02729195 0.085581 0.03793191 0.08823496 0.02644091 0.1123329 0.07528597 0.09761697 0.06241291 0.08118599 0.04784291 0.09982496 0.04707098 0.08118599 0.04784291 0.09761697 0.06241291 0.09877097 0.04611599 0.08118599 0.04784291 0.09982496 0.04707098 0.08029597 0.0470969 0.08118599 0.04784291 0.09877097 0.04611599 0.09982496 0.04707098 0.09761697 0.06241291 0.1123329 0.07528597 0.128442 0.07479399 0.1123329 0.07528597 0.113995 0.07779699 0.09982496 0.04707098 0.1123329 0.07528597 0.128442 0.07479399 0.130711 0.07829397 0.113995 0.07779699 0.114956 0.08188599 0.130711 0.07829397 0.128442 0.07479399 0.113995 0.07779699 0.13279 0.08407199 0.130711 0.07829397 0.114956 0.08188599 0.148485 0.201422 0.148485 0.242624 0.136026 0.342987 0.149217 0.209218 0.148485 0.242624 0.148485 0.201422 0.149217 0.234827 0.148485 0.242624 0.149217 0.209218 0.136026 0.101058 0.148485 0.201422 0.136026 0.342987 0.134587 0.352251 0.136026 0.101058 0.136026 0.342987 0.149217 0.234827 0.149217 0.209218 0.149591 0.21768 0.149217 0.234827 0.149591 0.21768 0.149591 0.226365 0.134587 0.352251 0.134587 0.09179395 0.136026 0.101058 0.128442 0.369252 0.128442 0.07479399 0.130711 0.07829397 0.09982496 0.396975 0.09982496 0.04707098 0.128442 0.07479399 0.128442 0.369252 0.09982496 0.396975 0.128442 0.07479399 0.130711 0.365752 0.130711 0.07829397 0.13279 0.08407199 0.130711 0.365752 0.128442 0.369252 0.130711 0.07829397 0.13279 0.359973 0.13279 0.08407199 0.134587 0.09179395 0.130711 0.365752 0.13279 0.08407199 0.13279 0.359973 0.13279 0.359973 0.134587 0.09179395 0.134587 0.352251 0.09877097 0.397929 0.09982496 0.04707098 0.09982496 0.396975 0.09877097 0.04611599 0.09982496 0.04707098 0.09877097 0.397929 0.08029198 0.396954 0.09877097 0.397929 0.09982496 0.396975 0.09877097 0.04611599 0.09877097 0.397929 0.09770798 0.398773 0.07886099 0.397977 0.09770798 0.398773 0.09877097 0.397929 0.07912296 0.397805 0.07886099 0.397977 0.09877097 0.397929 0.07938295 0.397628 0.07912296 0.397805 0.09877097 0.397929 0.08029198 0.396954 0.07938295 0.397628 0.09877097 0.397929 0.09770798 0.04527288 0.09770798 0.398773 0.09406197 0.400773 0.07060796 0.400526 0.09406197 0.400773 0.09770798 0.398773 0.09877097 0.04611599 0.09770798 0.398773 0.09770798 0.04527288 0.07886099 0.397977 0.07060796 0.400526 0.09770798 0.398773 0.090406 0.04260092 0.09406197 0.400773 0.09036397 0.401445 0.07060796 0.400526 0.09036397 0.401445 0.09406197 0.400773 0.09408497 0.04327899 0.09406197 0.400773 0.090406 0.04260092 0.09770798 0.04527288 0.09406197 0.400773 0.09408497 0.04327899 0.08665698 0.04330599 0.09036397 0.401445 0.08659797 0.400717 0.06584495 0.400052 0.08659797 0.400717 0.09036397 0.401445 0.090406 0.04260092 0.09036397 0.401445 0.08665698 0.04330599 0.07060796 0.400526 0.06584495 0.400052 0.09036397 0.401445 0.08286798 0.045448 0.08659797 0.400717 0.08279597 0.398542 0.06069391 0.398303 0.08279597 0.398542 0.08659797 0.400717 0.08665698 0.04330599 0.08659797 0.400717 0.08286798 0.045448 0.06584495 0.400052 0.06069391 0.398303 0.08659797 0.400717 0.07909995 0.0490809 0.08279597 0.398542 0.07902097 0.394871 0.05529391 0.39522 0.07902097 0.394871 0.08279597 0.398542 0.08286798 0.045448 0.08279597 0.398542 0.07909995 0.0490809 0.06069391 0.398303 0.05529391 0.39522 0.08279597 0.398542 0.07536399 0.0542519 0.07902097 0.394871 0.07528096 0.389661 0.049649 0.390746 0.07528096 0.389661 0.07902097 0.394871 0.07909995 0.0490809 0.07902097 0.394871 0.07536399 0.0542519 0.05529391 0.39522 0.049649 0.390746 0.07902097 0.394871 0.07173401 0.0609219 0.07528096 0.389661 0.07165497 0.38296 0.04396498 0.384903 0.07165497 0.38296 0.07528096 0.389661 0.07536399 0.0542519 0.07528096 0.389661 0.07173401 0.0609219 0.049649 0.390746 0.04396498 0.384903 0.07528096 0.389661 0.068219 0.06915599 0.07165497 0.38296 0.06814897 0.374704 0.03828191 0.377728 0.06814897 0.374704 0.07165497 0.38296 0.07173401 0.0609219 0.07165497 0.38296 0.068219 0.06915599 0.04396498 0.384903 0.03828191 0.377728 0.07165497 0.38296 0.06486296 0.07895195 0.06814897 0.374704 0.06480497 0.364908 0.03270792 0.369144 0.06480497 0.364908 0.06814897 0.374704 0.068219 0.06915599 0.06814897 0.374704 0.06486296 0.07895195 0.03828191 0.377728 0.03270792 0.369144 0.06814897 0.374704 0.06167888 0.09035998 0.06480497 0.364908 0.06163793 0.353525 0.02729696 0.359065 0.06163793 0.353525 0.06480497 0.364908 0.06486296 0.07895195 0.06480497 0.364908 0.06167888 0.09035998 0.03270792 0.369144 0.02729696 0.359065 0.06480497 0.364908 0.05875897 0.10317 0.06163793 0.353525 0.0587359 0.340762 0.02219092 0.347582 0.0587359 0.340762 0.06163793 0.353525 0.06167888 0.09035998 0.06163793 0.353525 0.05875897 0.10317 0.02729696 0.359065 0.02219092 0.347582 0.06163793 0.353525 0.05612289 0.1174049 0.0587359 0.340762 0.05611598 0.326601 0.01761299 0.334823 0.05611598 0.326601 0.0587359 0.340762 0.05875897 0.10317 0.0587359 0.340762 0.05612289 0.1174049 0.02219092 0.347582 0.01761299 0.334823 0.0587359 0.340762 0.05612289 0.1174049 0.05611598 0.326601 0.05383199 0.311279 0.01352393 0.320865 0.05383199 0.311279 0.05611598 0.326601 0.01761299 0.334823 0.01352393 0.320865 0.05611598 0.326601 0.05382692 0.132811 0.05383199 0.311279 0.051907 0.294825 0.009817957 0.305878 0.051907 0.294825 0.05383199 0.311279 0.05612289 0.1174049 0.05383199 0.311279 0.05382692 0.132811 0.01352393 0.320865 0.009817957 0.305878 0.05383199 0.311279 0.05189293 0.149357 0.051907 0.294825 0.05037695 0.277523 0.006551921 0.290005 0.05037695 0.277523 0.051907 0.294825 0.05382692 0.132811 0.051907 0.294825 0.05189293 0.149357 0.009817957 0.305878 0.006551921 0.290005 0.051907 0.294825 0.05035996 0.16674 0.05037695 0.277523 0.049263 0.259472 0.003858983 0.273371 0.049263 0.259472 0.05037695 0.277523 0.05189293 0.149357 0.05037695 0.277523 0.05035996 0.16674 0.006551921 0.290005 0.003858983 0.273371 0.05037695 0.277523 0.04924899 0.184855 0.049263 0.259472 0.04858398 0.240968 0.001726925 0.256107 0.04858398 0.240968 0.049263 0.259472 0.05035996 0.16674 0.049263 0.259472 0.04924899 0.184855 0.003858983 0.273371 0.001726925 0.256107 0.049263 0.259472 0.04857695 0.203401 0.04858398 0.240968 0.04835593 0.222191 4.11e-4 0.238641 0.04835593 0.222191 0.04858398 0.240968 0.04924899 0.184855 0.04858398 0.240968 0.04857695 0.203401 0.001726925 0.256107 4.11e-4 0.238641 0.04858398 0.240968 4.35e-4 0.204153 0.04857695 0.203401 0.04835593 0.222191 0 0.221364 4.35e-4 0.204153 0.04835593 0.222191 4.11e-4 0.238641 0 0.221364 0.04835593 0.222191 0.0017879 0.186892 0.04924899 0.184855 0.04857695 0.203401 4.35e-4 0.204153 0.0017879 0.186892 0.04857695 0.203401 0.003942966 0.169941 0.05035996 0.16674 0.04924899 0.184855 0.0017879 0.186892 0.003942966 0.169941 0.04924899 0.184855 0.006614983 0.153665 0.05189293 0.149357 0.05035996 0.16674 0.003942966 0.169941 0.006614983 0.153665 0.05035996 0.16674 0.009814977 0.1381829 0.05382692 0.132811 0.05189293 0.149357 0.006614983 0.153665 0.009814977 0.1381829 0.05189293 0.149357 0.01342797 0.123552 0.05612289 0.1174049 0.05382692 0.132811 0.009814977 0.1381829 0.01342797 0.123552 0.05382692 0.132811 0.01739192 0.109911 0.05875897 0.10317 0.05612289 0.1174049 0.01342797 0.123552 0.01739192 0.109911 0.05612289 0.1174049 0.02184891 0.09736096 0.06167888 0.09035998 0.05875897 0.10317 0.01739192 0.109911 0.02184891 0.09736096 0.05875897 0.10317 0.026847 0.08598196 0.06486296 0.07895195 0.06167888 0.09035998 0.02184891 0.09736096 0.026847 0.08598196 0.06167888 0.09035998 0.03217893 0.07589197 0.068219 0.06915599 0.06486296 0.07895195 0.026847 0.08598196 0.03217893 0.07589197 0.06486296 0.07895195 0.03772497 0.06718599 0.07173401 0.0609219 0.068219 0.06915599 0.03217893 0.07589197 0.03772497 0.06718599 0.068219 0.06915599 0.04341799 0.05983191 0.07536399 0.0542519 0.07173401 0.0609219 0.03772497 0.06718599 0.04341799 0.05983191 0.07173401 0.0609219 0.0491259 0.05378997 0.07909995 0.0490809 0.07536399 0.0542519 0.04341799 0.05983191 0.0491259 0.05378997 0.07536399 0.0542519 0.05481588 0.0491259 0.08286798 0.045448 0.07909995 0.0490809 0.0491259 0.05378997 0.05481588 0.0491259 0.07909995 0.0490809 0.0602889 0.04589295 0.08665698 0.04330599 0.08286798 0.045448 0.05481588 0.0491259 0.0602889 0.04589295 0.08286798 0.045448 0.065539 0.04404091 0.090406 0.04260092 0.08665698 0.04330599 0.0602889 0.04589295 0.065539 0.04404091 0.08665698 0.04330599 0.07040399 0.04352295 0.09408497 0.04327899 0.090406 0.04260092 0.065539 0.04404091 0.07040399 0.04352295 0.090406 0.04260092 0.07884496 0.04606992 0.09770798 0.04527288 0.09408497 0.04327899 0.07483297 0.04423499 0.07884496 0.04606992 0.09408497 0.04327899 0.07040399 0.04352295 0.07483297 0.04423499 0.09408497 0.04327899 0.07937699 0.046422 0.09877097 0.04611599 0.09770798 0.04527288 0.07911396 0.0462439 0.07937699 0.046422 0.09770798 0.04527288 0.07884496 0.04606992 0.07911396 0.0462439 0.09770798 0.04527288 0.07937699 0.046422 0.08029597 0.0470969 0.09877097 0.04611599 0.08368098 0.03637492 0.07937699 0.046422 0.07911396 0.0462439 0.08823496 0.02644091 0.07911396 0.0462439 0.07884496 0.04606992 0.08823496 0.02644091 0.08368098 0.03637492 0.07911396 0.0462439 0.08823496 0.02644091 0.07884496 0.04606992 0.07483297 0.04423499 0.080343 0.02239799 0.07483297 0.04423499 0.07040399 0.04352295 0.080343 0.02239799 0.08823496 0.02644091 0.07483297 0.04423499 0.080343 0.02239799 0.07040399 0.04352295 0.065539 0.04404091 0.07076096 0.02267789 0.065539 0.04404091 0.0602889 0.04589295 0.07076096 0.02267789 0.080343 0.02239799 0.065539 0.04404091 0.06415599 0.02532196 0.0602889 0.04589295 0.05481588 0.0491259 0.07034999 0.022789 0.07076096 0.02267789 0.0602889 0.04589295 0.06992596 0.02291095 0.07034999 0.022789 0.0602889 0.04589295 0.06415599 0.02532196 0.06992596 0.02291095 0.0602889 0.04589295 0.05815088 0.02924299 0.05481588 0.0491259 0.0491259 0.05378997 0.05815088 0.02924299 0.06415599 0.02532196 0.05481588 0.0491259 0.05199992 0.03471297 0.0491259 0.05378997 0.04341799 0.05983191 0.0580089 0.02935296 0.05815088 0.02924299 0.0491259 0.05378997 0.05786591 0.029464 0.0580089 0.02935296 0.0491259 0.05378997 0.05199992 0.03471297 0.05786591 0.029464 0.0491259 0.05378997 0.04612499 0.04139596 0.04341799 0.05983191 0.03772497 0.06718599 0.04612499 0.04139596 0.05199992 0.03471297 0.04341799 0.05983191 0.043401 0.04500198 0.03772497 0.06718599 0.03217893 0.07589197 0.044761 0.04315888 0.04612499 0.04139596 0.03772497 0.06718599 0.043401 0.04500198 0.044761 0.04315888 0.03772497 0.06718599 0.03330993 0.06173795 0.03217893 0.07589197 0.026847 0.08598196 0.03330993 0.06173795 0.043401 0.04500198 0.03217893 0.07589197 0.03330993 0.06173795 0.026847 0.08598196 0.02184891 0.09736096 0.02429795 0.082969 0.02184891 0.09736096 0.01739192 0.109911 0.02429795 0.082969 0.03330993 0.06173795 0.02184891 0.09736096 0.01670897 0.108589 0.01739192 0.109911 0.01342797 0.123552 0.01670897 0.108589 0.02429795 0.082969 0.01739192 0.109911 0.01670897 0.108589 0.01342797 0.123552 0.009814977 0.1381829 0.01106894 0.134775 0.009814977 0.1381829 0.006614983 0.153665 0.01106894 0.134775 0.01670897 0.108589 0.009814977 0.1381829 0.01106894 0.134775 0.006614983 0.153665 0.003942966 0.169941 0.006688952 0.162952 0.003942966 0.169941 0.0017879 0.186892 0.006688952 0.162952 0.01106894 0.134775 0.003942966 0.169941 0.003850996 0.192369 0.0017879 0.186892 4.35e-4 0.204153 0.003850996 0.192369 0.006688952 0.162952 0.0017879 0.186892 0.003850996 0.192369 4.35e-4 0.204153 0 0.221364 0.002899885 0.222095 0 0.221364 4.11e-4 0.238641 0.002899885 0.222095 0.003850996 0.192369 0 0.221364 0.003890991 0.251672 4.11e-4 0.238641 0.001726925 0.256107 0.003890991 0.251672 0.002899885 0.222095 4.11e-4 0.238641 0.006687939 0.280876 0.001726925 0.256107 0.003858983 0.273371 0.006687939 0.280876 0.003890991 0.251672 0.001726925 0.256107 0.006687939 0.280876 0.003858983 0.273371 0.006551921 0.290005 0.01100796 0.308865 0.006551921 0.290005 0.009817957 0.305878 0.01100796 0.308865 0.006687939 0.280876 0.006551921 0.290005 0.01657193 0.334906 0.009817957 0.305878 0.01352393 0.320865 0.01657193 0.334906 0.01100796 0.308865 0.009817957 0.305878 0.01676696 0.335691 0.01352393 0.320865 0.01761299 0.334823 0.01676696 0.335691 0.01657193 0.334906 0.01352393 0.320865 0.02555888 0.364591 0.01761299 0.334823 0.02219092 0.347582 0.016963 0.336474 0.01676696 0.335691 0.01761299 0.334823 0.021025 0.351164 0.016963 0.336474 0.01761299 0.334823 0.02555888 0.364591 0.021025 0.351164 0.01761299 0.334823 0.03055089 0.376663 0.02219092 0.347582 0.02729696 0.359065 0.03055089 0.376663 0.02555888 0.364591 0.02219092 0.347582 0.03592795 0.387335 0.02729696 0.359065 0.03270792 0.369144 0.03592795 0.387335 0.03055089 0.376663 0.02729696 0.359065 0.04159688 0.39657 0.03270792 0.369144 0.03828191 0.377728 0.04159688 0.39657 0.03592795 0.387335 0.03270792 0.369144 0.04744988 0.404356 0.03828191 0.377728 0.04396498 0.384903 0.04744988 0.404356 0.04159688 0.39657 0.03828191 0.377728 0.05338388 0.410712 0.04396498 0.384903 0.049649 0.390746 0.05338388 0.410712 0.04744988 0.404356 0.04396498 0.384903 0.059264 0.415622 0.049649 0.390746 0.05529391 0.39522 0.059264 0.415622 0.05338388 0.410712 0.049649 0.390746 0.06498396 0.419121 0.05529391 0.39522 0.06069391 0.398303 0.06498396 0.419121 0.059264 0.415622 0.05529391 0.39522 0.07043695 0.421262 0.06069391 0.398303 0.06584495 0.400052 0.07043695 0.421262 0.06498396 0.419121 0.06069391 0.398303 0.07553899 0.422108 0.06584495 0.400052 0.07060796 0.400526 0.07553899 0.422108 0.07043695 0.421262 0.06584495 0.400052 0.08023697 0.421721 0.07060796 0.400526 0.07886099 0.397977 0.08023697 0.421721 0.07553899 0.422108 0.07060796 0.400526 0.08023697 0.421721 0.07886099 0.397977 0.07912296 0.397805 0.08023697 0.421721 0.07912296 0.397805 0.07938295 0.397628 0.08023697 0.421721 0.07938295 0.397628 0.083682 0.407678 0.08922499 0.416758 0.08823597 0.417615 0.083682 0.407678 0.08023697 0.421721 0.083682 0.407678 0.08823597 0.417615 0.09287697 0.419786 0.08823597 0.417615 0.08922499 0.416758 0.08287698 0.425733 0.08023697 0.421721 0.08823597 0.417615 0.09090995 0.421525 0.08287698 0.425733 0.08823597 0.417615 0.09287697 0.419786 0.09090995 0.421525 0.08823597 0.417615 0.09091097 0.02253198 0.08823496 0.02644091 0.080343 0.02239799 0.09091097 0.02253198 0.08922696 0.02729195 0.08823496 0.02644091 0.08275896 0.018332 0.080343 0.02239799 0.07076096 0.02267789 0.08275896 0.018332 0.09091097 0.02253198 0.080343 0.02239799 0.07329499 0.01847696 0.07076096 0.02267789 0.07034999 0.022789 0.07329499 0.01847696 0.08275896 0.018332 0.07076096 0.02267789 0.07329499 0.01847696 0.07034999 0.022789 0.06992596 0.02291095 0.07329499 0.01847696 0.06992596 0.02291095 0.06415599 0.02532196 0.06289899 0.02320796 0.06415599 0.02532196 0.05815088 0.02924299 0.06289899 0.02320796 0.07329499 0.01847696 0.06415599 0.02532196 0.06289899 0.02320796 0.05815088 0.02924299 0.0580089 0.02935296 0.06289899 0.02320796 0.0580089 0.02935296 0.05786591 0.029464 0.06289899 0.02320796 0.05786591 0.029464 0.05199992 0.03471297 0.05196493 0.03276991 0.05199992 0.03471297 0.04612499 0.04139596 0.05196493 0.03276991 0.06289899 0.02320796 0.05199992 0.03471297 0.05196493 0.03276991 0.04612499 0.04139596 0.044761 0.04315888 0.05196493 0.03276991 0.044761 0.04315888 0.043401 0.04500198 0.04104799 0.04733192 0.043401 0.04500198 0.03330993 0.06173795 0.04104799 0.04733192 0.05196493 0.03276991 0.043401 0.04500198 0.03086799 0.06685298 0.03330993 0.06173795 0.02429795 0.082969 0.03086799 0.06685298 0.04104799 0.04733192 0.03330993 0.06173795 0.022143 0.09101498 0.02429795 0.082969 0.01670897 0.108589 0.022143 0.09101498 0.03086799 0.06685298 0.02429795 0.082969 0.01499599 0.11935 0.01670897 0.108589 0.01106894 0.134775 0.01499599 0.11935 0.022143 0.09101498 0.01670897 0.108589 0.009329974 0.151295 0.01106894 0.134775 0.006688952 0.162952 0.009329974 0.151295 0.01499599 0.11935 0.01106894 0.134775 0.005477905 0.185976 0.006688952 0.162952 0.003850996 0.192369 0.005477905 0.185976 0.009329974 0.151295 0.006688952 0.162952 0.004121959 0.222055 0.003850996 0.192369 0.002899885 0.222095 0.004121959 0.222055 0.005477905 0.185976 0.003850996 0.192369 0.004121959 0.222055 0.002899885 0.222095 0.003890991 0.251672 0.005523979 0.258143 0.003890991 0.251672 0.006687939 0.280876 0.005523979 0.258143 0.004121959 0.222055 0.003890991 0.251672 0.009352982 0.292821 0.006687939 0.280876 0.01100796 0.308865 0.009352982 0.292821 0.005523979 0.258143 0.006687939 0.280876 0.01502794 0.324784 0.01100796 0.308865 0.01657193 0.334906 0.01502794 0.324784 0.009352982 0.292821 0.01100796 0.308865 0.01502794 0.324784 0.01657193 0.334906 0.01676696 0.335691 0.01502794 0.324784 0.01676696 0.335691 0.016963 0.336474 0.02214795 0.353096 0.016963 0.336474 0.021025 0.351164 0.02214795 0.353096 0.01502794 0.324784 0.016963 0.336474 0.02214795 0.353096 0.021025 0.351164 0.02555888 0.364591 0.03086698 0.377253 0.02555888 0.364591 0.03055089 0.376663 0.03086698 0.377253 0.02214795 0.353096 0.02555888 0.364591 0.03086698 0.377253 0.03055089 0.376663 0.03592795 0.387335 0.04100793 0.396764 0.03592795 0.387335 0.04159688 0.39657 0.04100793 0.396764 0.03086698 0.377253 0.03592795 0.387335 0.04100793 0.396764 0.04159688 0.39657 0.04744988 0.404356 0.05194389 0.411307 0.04744988 0.404356 0.05338388 0.410712 0.05194389 0.411307 0.04100793 0.396764 0.04744988 0.404356 0.05194389 0.411307 0.05338388 0.410712 0.059264 0.415622 0.06296098 0.420855 0.059264 0.415622 0.06498396 0.419121 0.06296098 0.420855 0.05194389 0.411307 0.059264 0.415622 0.06296098 0.420855 0.06498396 0.419121 0.07043695 0.421262 0.073435 0.425585 0.07043695 0.421262 0.07553899 0.422108 0.073435 0.425585 0.06296098 0.420855 0.07043695 0.421262 0.073435 0.425585 0.07553899 0.422108 0.08023697 0.421721 0.08287698 0.425733 0.073435 0.425585 0.08023697 0.421721 0.08622097 0.01507896 0.09888899 0.01744395 0.09455597 0.01944392 0.09041899 0.0128979 0.09888899 0.01744395 0.08622097 0.01507896 0.08275896 0.018332 0.09455597 0.01944392 0.09091097 0.02253198 0.08622097 0.01507896 0.09455597 0.01944392 0.08275896 0.018332 0.08622097 0.01507896 0.08275896 0.018332 0.07329499 0.01847696 0.076568 0.01512789 0.07329499 0.01847696 0.06289899 0.02320796 0.076568 0.01512789 0.08622097 0.01507896 0.07329499 0.01847696 0.06597 0.01988291 0.06289899 0.02320796 0.05196493 0.03276991 0.06597 0.01988291 0.076568 0.01512789 0.06289899 0.02320796 0.05483597 0.02959597 0.05196493 0.03276991 0.04104799 0.04733192 0.05483597 0.02959597 0.06597 0.01988291 0.05196493 0.03276991 0.04373997 0.04441791 0.04104799 0.04733192 0.03086799 0.06685298 0.04373997 0.04441791 0.05483597 0.02959597 0.04104799 0.04733192 0.03341192 0.06427299 0.03086799 0.06685298 0.022143 0.09101498 0.03341192 0.06427299 0.04373997 0.04441791 0.03086799 0.06685298 0.0245639 0.08883297 0.022143 0.09101498 0.01499599 0.11935 0.0245639 0.08883297 0.03341192 0.06427299 0.022143 0.09101498 0.01730698 0.117693 0.01499599 0.11935 0.009329974 0.151295 0.01730698 0.117693 0.0245639 0.08883297 0.01499599 0.11935 0.011554 0.150258 0.009329974 0.151295 0.005477905 0.185976 0.011554 0.150258 0.01730698 0.117693 0.009329974 0.151295 0.007659912 0.185499 0.005477905 0.185976 0.004121959 0.222055 0.007659912 0.185499 0.011554 0.150258 0.005477905 0.185976 0.006293952 0.222051 0.004121959 0.222055 0.005523979 0.258143 0.006293952 0.222051 0.007659912 0.185499 0.004121959 0.222055 0.00770694 0.25862 0.005523979 0.258143 0.009352982 0.292821 0.00770694 0.25862 0.006293952 0.222051 0.005523979 0.258143 0.01157891 0.293867 0.009352982 0.292821 0.01502794 0.324784 0.01157891 0.293867 0.00770694 0.25862 0.009352982 0.292821 0.01733595 0.32644 0.01502794 0.324784 0.02214795 0.353096 0.01733595 0.32644 0.01157891 0.293867 0.01502794 0.324784 0.02456992 0.355282 0.02214795 0.353096 0.03086698 0.377253 0.02456992 0.355282 0.01733595 0.32644 0.02214795 0.353096 0.03341299 0.379839 0.03086698 0.377253 0.04100793 0.396764 0.03341299 0.379839 0.02456992 0.355282 0.03086698 0.377253 0.04370188 0.399681 0.04100793 0.396764 0.05194389 0.411307 0.04370188 0.399681 0.03341299 0.379839 0.04100793 0.396764 0.05481195 0.414478 0.05194389 0.411307 0.06296098 0.420855 0.05481195 0.414478 0.04370188 0.399681 0.05194389 0.411307 0.06602698 0.424176 0.06296098 0.420855 0.073435 0.425585 0.06602698 0.424176 0.05481195 0.414478 0.06296098 0.420855 0.07670599 0.428931 0.073435 0.425585 0.08287698 0.425733 0.07670599 0.428931 0.06602698 0.424176 0.073435 0.425585 0.08634197 0.428981 0.08287698 0.425733 0.09090995 0.421525 0.08634197 0.428981 0.07670599 0.428931 0.08287698 0.425733 0.09456098 0.424609 0.08634197 0.428981 0.09090995 0.421525 0.09648996 0.422854 0.09456098 0.424609 0.09090995 0.421525 0.09287697 0.419786 0.09648996 0.422854 0.09090995 0.421525 0.09041899 0.0128979 0.08622097 0.01507896 0.076568 0.01512789 0.08063697 0.01283293 0.076568 0.01512789 0.06597 0.01988291 0.08063697 0.01283293 0.09041899 0.0128979 0.076568 0.01512789 0.06989198 0.01757198 0.06597 0.01988291 0.05483597 0.02959597 0.06989198 0.01757198 0.08063697 0.01283293 0.06597 0.01988291 0.05859988 0.0273739 0.05483597 0.02959597 0.04373997 0.04441791 0.05859988 0.0273739 0.06989198 0.01757198 0.05483597 0.02959597 0.04735893 0.04236495 0.04373997 0.04441791 0.03341192 0.06427299 0.04735893 0.04236495 0.05859988 0.0273739 0.04373997 0.04441791 0.03690499 0.06243598 0.03341192 0.06427299 0.0245639 0.08883297 0.03690499 0.06243598 0.04735893 0.04236495 0.03341192 0.06427299 0.02794295 0.08725696 0.0245639 0.08883297 0.01730698 0.117693 0.02794295 0.08725696 0.03690499 0.06243598 0.0245639 0.08883297 0.020563 0.116497 0.01730698 0.117693 0.011554 0.150258 0.020563 0.116497 0.02794295 0.08725696 0.01730698 0.117693 0.01469093 0.149532 0.011554 0.150258 0.007659912 0.185499 0.01469093 0.149532 0.020563 0.116497 0.011554 0.150258 0.01071697 0.185176 0.007659912 0.185499 0.006293952 0.222051 0.01071697 0.185176 0.01469093 0.149532 0.007659912 0.185499 0.009323954 0.222046 0.006293952 0.222051 0.00770694 0.25862 0.009323954 0.222046 0.01071697 0.185176 0.006293952 0.222051 0.01076591 0.258943 0.00770694 0.25862 0.01157891 0.293867 0.01076591 0.258943 0.009323954 0.222046 0.00770694 0.25862 0.01471793 0.294602 0.01157891 0.293867 0.01733595 0.32644 0.01471793 0.294602 0.01076591 0.258943 0.01157891 0.293867 0.02059292 0.327634 0.01733595 0.32644 0.02456992 0.355282 0.02059292 0.327634 0.01471793 0.294602 0.01733595 0.32644 0.027951 0.356862 0.02456992 0.355282 0.03341299 0.379839 0.027951 0.356862 0.02059292 0.327634 0.02456992 0.355282 0.03690797 0.381681 0.03341299 0.379839 0.04370188 0.399681 0.03690797 0.381681 0.027951 0.356862 0.03341299 0.379839 0.04732197 0.401737 0.04370188 0.399681 0.05481195 0.414478 0.04732197 0.401737 0.03690797 0.381681 0.04370188 0.399681 0.05857288 0.416697 0.05481195 0.414478 0.06602698 0.424176 0.05857288 0.416697 0.04732197 0.401737 0.05481195 0.414478 0.06994098 0.426483 0.06602698 0.424176 0.07670599 0.428931 0.06994098 0.426483 0.05857288 0.416697 0.06602698 0.424176 0.08077096 0.431224 0.07670599 0.428931 0.08634197 0.428981 0.08077096 0.431224 0.06994098 0.426483 0.07670599 0.428931 0.09054195 0.431158 0.08634197 0.428981 0.09456098 0.424609 0.09054195 0.431158 0.08077096 0.431224 0.08634197 0.428981 0.09889596 0.42661 0.09054195 0.431158 0.09456098 0.424609 0.100786 0.424842 0.09889596 0.42661 0.09456098 0.424609 0.09648996 0.422854 0.100786 0.424842 0.09456098 0.424609 0.105418 0.425604 0.10449 0.426483 0.09889596 0.42661 0.100786 0.424842 0.105418 0.425604 0.09889596 0.42661 0.202718 0.433126 0.10449 0.426483 0.105418 0.425604 0.202718 0.433126 0.205032 0.433806 0.10449 0.426483 0.136059 0.392808 0.105418 0.425604 0.100786 0.424842 0.166342 0.41854 0.105418 0.425604 0.134935 0.398149 0.136059 0.392808 0.134935 0.398149 0.105418 0.425604 0.200467 0.43245 0.202718 0.433126 0.105418 0.425604 0.198281 0.431776 0.200467 0.43245 0.105418 0.425604 0.196157 0.431104 0.198281 0.431776 0.105418 0.425604 0.194095 0.430436 0.196157 0.431104 0.105418 0.425604 0.192095 0.429771 0.194095 0.430436 0.105418 0.425604 0.190156 0.429109 0.192095 0.429771 0.105418 0.425604 0.188278 0.42845 0.190156 0.429109 0.105418 0.425604 0.186459 0.427794 0.188278 0.42845 0.105418 0.425604 0.1847 0.427141 0.186459 0.427794 0.105418 0.425604 0.182829 0.426426 0.1847 0.427141 0.105418 0.425604 0.181024 0.425712 0.182829 0.426426 0.105418 0.425604 0.179285 0.425 0.181024 0.425712 0.105418 0.425604 0.177615 0.424293 0.179285 0.425 0.105418 0.425604 0.176014 0.42359 0.177615 0.424293 0.105418 0.425604 0.174484 0.422892 0.176014 0.42359 0.105418 0.425604 0.173027 0.422201 0.174484 0.422892 0.105418 0.425604 0.171642 0.421516 0.173027 0.422201 0.105418 0.425604 0.170332 0.42084 0.171642 0.421516 0.105418 0.425604 0.169097 0.420172 0.170332 0.42084 0.105418 0.425604 0.167662 0.41935 0.169097 0.420172 0.105418 0.425604 0.166342 0.41854 0.167662 0.41935 0.105418 0.425604 0.132332 0.391098 0.100786 0.424842 0.09648996 0.422854 0.136059 0.392808 0.100786 0.424842 0.132332 0.391098 0.1292099 0.388429 0.09648996 0.422854 0.09287697 0.419786 0.132332 0.391098 0.09648996 0.422854 0.1292099 0.388429 0.279553 0.309991 0.307215 0.306614 0.294213 0.308454 0.279553 0.309991 0.305789 0.306278 0.307215 0.306614 0.279553 0.309991 0.294213 0.308454 0.281002 0.310339 0.25202 0.313737 0.281002 0.310339 0.253855 0.314258 0.279553 0.309991 0.281002 0.310339 0.25202 0.313737 0.25202 0.313737 0.253855 0.314258 0.249117 0.314954 0.244105 0.314924 0.249117 0.314954 0.244715 0.31565 0.244105 0.314924 0.25202 0.313737 0.249117 0.314954 0.244105 0.314924 0.244715 0.31565 0.240607 0.316346 0.23702 0.316121 0.240607 0.316346 0.2369419 0.317044 0.23702 0.316121 0.244105 0.314924 0.240607 0.316346 0.23702 0.316121 0.2369419 0.317044 0.233912 0.317737 0.231409 0.317317 0.233912 0.317737 0.231367 0.318456 0.231409 0.317317 0.23702 0.316121 0.233912 0.317737 0.227309 0.318586 0.231367 0.318456 0.2292439 0.319239 0.227309 0.318586 0.231409 0.317317 0.231367 0.318456 0.227309 0.318586 0.2292439 0.319239 0.227461 0.320072 0.224276 0.319993 0.227461 0.320072 0.225901 0.32095 0.224276 0.319993 0.227309 0.318586 0.227461 0.320072 0.224276 0.319993 0.225901 0.32095 0.224606 0.321878 0.221948 0.321493 0.224606 0.321878 0.211212 0.332217 0.221948 0.321493 0.224276 0.319993 0.224606 0.321878 0.205438 0.334074 0.211212 0.332217 0.196161 0.344374 0.205438 0.334074 0.221948 0.321493 0.211212 0.332217 0.186367 0.349397 0.196161 0.344374 0.178961 0.35887 0.205438 0.334074 0.196161 0.344374 0.186367 0.349397 0.163748 0.368467 0.178961 0.35887 0.158903 0.376439 0.186367 0.349397 0.178961 0.35887 0.163748 0.368467 0.136059 0.392808 0.158903 0.376439 0.134935 0.398149 0.163748 0.368467 0.158903 0.376439 0.136059 0.392808 0.1651329 0.417741 0.166342 0.41854 0.134935 0.398149 0.164027 0.416951 0.1651329 0.417741 0.134935 0.398149 0.163018 0.41617 0.164027 0.416951 0.134935 0.398149 0.1621 0.415396 0.163018 0.41617 0.134935 0.398149 0.161267 0.414628 0.1621 0.415396 0.134935 0.398149 0.1605139 0.413865 0.161267 0.414628 0.134935 0.398149 0.159841 0.413107 0.1605139 0.413865 0.134935 0.398149 0.159254 0.412356 0.159841 0.413107 0.134935 0.398149 0.158751 0.411611 0.159254 0.412356 0.134935 0.398149 0.158331 0.410873 0.158751 0.411611 0.134935 0.398149 0.157995 0.410141 0.158331 0.410873 0.134935 0.398149 0.1577399 0.409416 0.157995 0.410141 0.134935 0.398149 0.1575649 0.408696 0.1577399 0.409416 0.134935 0.398149 0.157471 0.407983 0.1575649 0.408696 0.134935 0.398149 0.156268 0.394814 0.157471 0.407983 0.134935 0.398149 0.203145 0.433119 0.205032 0.433806 0.202718 0.433126 0.221898 0.16624 0.218131 0.304213 0.221928 0.277544 0.201061 0.432429 0.202718 0.433126 0.200467 0.43245 0.201061 0.432429 0.203145 0.433119 0.202718 0.433126 0.199009 0.431733 0.200467 0.43245 0.198281 0.431776 0.199009 0.431733 0.201061 0.432429 0.200467 0.43245 0.196994 0.431033 0.198281 0.431776 0.196157 0.431104 0.196994 0.431033 0.199009 0.431733 0.198281 0.431776 0.195022 0.430331 0.196157 0.431104 0.194095 0.430436 0.195022 0.430331 0.196994 0.431033 0.196157 0.431104 0.193093 0.429625 0.194095 0.430436 0.192095 0.429771 0.193093 0.429625 0.195022 0.430331 0.194095 0.430436 0.191207 0.428915 0.192095 0.429771 0.190156 0.429109 0.191207 0.428915 0.193093 0.429625 0.192095 0.429771 0.191207 0.428915 0.190156 0.429109 0.188278 0.42845 0.189366 0.428202 0.188278 0.42845 0.186459 0.427794 0.189366 0.428202 0.191207 0.428915 0.188278 0.42845 0.18757 0.427485 0.186459 0.427794 0.1847 0.427141 0.18757 0.427485 0.189366 0.428202 0.186459 0.427794 0.18582 0.426763 0.1847 0.427141 0.182829 0.426426 0.18582 0.426763 0.18757 0.427485 0.1847 0.427141 0.184119 0.426037 0.182829 0.426426 0.181024 0.425712 0.184119 0.426037 0.18582 0.426763 0.182829 0.426426 0.1824679 0.425306 0.181024 0.425712 0.179285 0.425 0.1824679 0.425306 0.184119 0.426037 0.181024 0.425712 0.180867 0.424571 0.179285 0.425 0.177615 0.424293 0.180867 0.424571 0.1824679 0.425306 0.179285 0.425 0.179319 0.42383 0.177615 0.424293 0.176014 0.42359 0.179319 0.42383 0.180867 0.424571 0.177615 0.424293 0.177825 0.423084 0.176014 0.42359 0.174484 0.422892 0.177825 0.423084 0.179319 0.42383 0.176014 0.42359 0.1763859 0.422333 0.174484 0.422892 0.173027 0.422201 0.1763859 0.422333 0.177825 0.423084 0.174484 0.422892 0.175004 0.421577 0.173027 0.422201 0.171642 0.421516 0.175004 0.421577 0.1763859 0.422333 0.173027 0.422201 0.173681 0.420815 0.171642 0.421516 0.170332 0.42084 0.173681 0.420815 0.175004 0.421577 0.171642 0.421516 0.17242 0.420047 0.170332 0.42084 0.169097 0.420172 0.17242 0.420047 0.173681 0.420815 0.170332 0.42084 0.171221 0.419275 0.169097 0.420172 0.167662 0.41935 0.171221 0.419275 0.17242 0.420047 0.169097 0.420172 0.1700879 0.418497 0.167662 0.41935 0.166342 0.41854 0.1700879 0.418497 0.171221 0.419275 0.167662 0.41935 0.169021 0.417714 0.166342 0.41854 0.1651329 0.417741 0.169021 0.417714 0.1700879 0.418497 0.166342 0.41854 0.168023 0.416926 0.1651329 0.417741 0.164027 0.416951 0.168023 0.416926 0.169021 0.417714 0.1651329 0.417741 0.167096 0.416134 0.164027 0.416951 0.163018 0.41617 0.167096 0.416134 0.168023 0.416926 0.164027 0.416951 0.166242 0.415336 0.163018 0.41617 0.1621 0.415396 0.166242 0.415336 0.167096 0.416134 0.163018 0.41617 0.165462 0.414534 0.1621 0.415396 0.161267 0.414628 0.165462 0.414534 0.166242 0.415336 0.1621 0.415396 0.164759 0.413727 0.161267 0.414628 0.1605139 0.413865 0.164759 0.413727 0.165462 0.414534 0.161267 0.414628 0.164135 0.412917 0.1605139 0.413865 0.159841 0.413107 0.164135 0.412917 0.164759 0.413727 0.1605139 0.413865 0.163592 0.412102 0.159841 0.413107 0.159254 0.412356 0.163592 0.412102 0.164135 0.412917 0.159841 0.413107 0.1631309 0.411284 0.159254 0.412356 0.158751 0.411611 0.1631309 0.411284 0.163592 0.412102 0.159254 0.412356 0.162755 0.410463 0.158751 0.411611 0.158331 0.410873 0.162755 0.410463 0.1631309 0.411284 0.158751 0.411611 0.162465 0.409638 0.158331 0.410873 0.157995 0.410141 0.162465 0.409638 0.162755 0.410463 0.158331 0.410873 0.162263 0.408812 0.157995 0.410141 0.1577399 0.409416 0.162263 0.408812 0.162465 0.409638 0.157995 0.410141 0.16215 0.407983 0.1577399 0.409416 0.1575649 0.408696 0.16215 0.407983 0.162263 0.408812 0.1577399 0.409416 0.16215 0.407983 0.1575649 0.408696 0.157471 0.407983 0.162227 0.40712 0.16215 0.407983 0.157471 0.407983 0.32783 0.299798 0.314194 0.299421 0.32691 0.297718 0.312242 0.292223 0.32691 0.297718 0.314194 0.299421 0.331592 0.296798 0.32783 0.299798 0.32691 0.297718 0.312242 0.292223 0.331592 0.296798 0.32691 0.297718 0.32783 0.299798 0.301521 0.301133 0.314194 0.299421 0.283756 0.294461 0.314194 0.299421 0.301521 0.301133 0.283756 0.294461 0.288715 0.294589 0.314194 0.299421 0.306665 0.292781 0.314194 0.299421 0.288715 0.294589 0.306665 0.292781 0.312242 0.292223 0.314194 0.299421 0.32783 0.299798 0.302243 0.302861 0.301521 0.301133 0.288459 0.302912 0.301521 0.301133 0.302243 0.302861 0.278787 0.293169 0.301521 0.301133 0.288459 0.302912 0.278787 0.293169 0.283756 0.294461 0.301521 0.301133 0.32783 0.299798 0.303233 0.304349 0.302243 0.302861 0.275935 0.306499 0.302243 0.302861 0.303233 0.304349 0.275191 0.304734 0.302243 0.302861 0.275935 0.306499 0.281667 0.303843 0.302243 0.302861 0.275191 0.304734 0.288459 0.302912 0.302243 0.302861 0.281667 0.303843 0.329146 0.301481 0.304436 0.305509 0.303233 0.304349 0.276948 0.308018 0.303233 0.304349 0.304436 0.305509 0.32783 0.299798 0.329146 0.301481 0.303233 0.304349 0.275935 0.306499 0.303233 0.304349 0.276948 0.308018 0.330746 0.302607 0.305789 0.306278 0.304436 0.305509 0.278175 0.309204 0.304436 0.305509 0.305789 0.306278 0.329146 0.301481 0.330746 0.302607 0.304436 0.305509 0.276948 0.308018 0.304436 0.305509 0.278175 0.309204 0.278175 0.309204 0.305789 0.306278 0.279553 0.309991 0.337422 0.299242 0.330746 0.302607 0.329146 0.301481 0.33905 0.300346 0.330746 0.302607 0.337422 0.299242 0.33603 0.297666 0.329146 0.301481 0.32783 0.299798 0.337422 0.299242 0.329146 0.301481 0.33603 0.297666 0.33603 0.297666 0.32783 0.299798 0.331592 0.296798 0.275935 0.306499 0.248925 0.310737 0.247927 0.308523 0.240854 0.311916 0.247927 0.308523 0.248925 0.310737 0.275191 0.304734 0.275935 0.306499 0.247927 0.308523 0.242559 0.287766 0.275191 0.304734 0.247927 0.308523 0.2337599 0.288697 0.242559 0.287766 0.247927 0.308523 0.243758 0.309113 0.2337599 0.288697 0.247927 0.308523 0.240854 0.311916 0.243758 0.309113 0.247927 0.308523 0.276948 0.308018 0.250327 0.312531 0.248925 0.310737 0.242327 0.313718 0.248925 0.310737 0.250327 0.312531 0.275935 0.306499 0.276948 0.308018 0.248925 0.310737 0.240854 0.311916 0.248925 0.310737 0.242327 0.313718 0.278175 0.309204 0.25202 0.313737 0.250327 0.312531 0.244105 0.314924 0.250327 0.312531 0.25202 0.313737 0.276948 0.308018 0.278175 0.309204 0.250327 0.312531 0.242327 0.313718 0.250327 0.312531 0.244105 0.314924 0.278175 0.309204 0.279553 0.309991 0.25202 0.313737 0.242559 0.287766 0.281667 0.303843 0.275191 0.304734 0.278787 0.293169 0.288459 0.302912 0.281667 0.303843 0.242559 0.287766 0.278787 0.293169 0.281667 0.303843 0.33603 0.14638 0.335931 0.148658 0.331593 0.147248 0.343392 0.150224 0.339943 0.150564 0.335931 0.148658 0.33603 0.14638 0.343392 0.150224 0.335931 0.148658 0.343392 0.150224 0.343628 0.152938 0.339943 0.150564 0.349783 0.155768 0.344162 0.153339 0.343628 0.152938 0.343392 0.150224 0.349783 0.155768 0.343628 0.152938 0.350003 0.158959 0.344162 0.153339 0.346973 0.155736 0.349783 0.155768 0.346973 0.155736 0.344162 0.153339 0.342256 0.161375 0.344162 0.153339 0.350003 0.158959 0.338665 0.158423 0.344162 0.153339 0.342256 0.161375 0.324199 0.153012 0.312242 0.151823 0.344162 0.153339 0.331765 0.1547549 0.324199 0.153012 0.344162 0.153339 0.338665 0.158423 0.331765 0.1547549 0.344162 0.153339 0.349783 0.155768 0.350003 0.158959 0.346973 0.155736 0.355137 0.162917 0.35273 0.162577 0.350003 0.158959 0.342256 0.161375 0.350003 0.158959 0.35273 0.162577 0.349783 0.155768 0.355137 0.162917 0.350003 0.158959 0.355137 0.162917 0.355174 0.166592 0.35273 0.162577 0.344767 0.163985 0.35273 0.162577 0.355174 0.166592 0.344767 0.163985 0.342256 0.161375 0.35273 0.162577 0.359436 0.171532 0.357334 0.1709589 0.355174 0.166592 0.344767 0.163985 0.355174 0.166592 0.357334 0.1709589 0.355137 0.162917 0.359436 0.171532 0.355174 0.166592 0.359436 0.171532 0.359233 0.175686 0.357334 0.1709589 0.34979 0.171048 0.357334 0.1709589 0.359233 0.175686 0.34979 0.171048 0.344767 0.163985 0.357334 0.1709589 0.36273 0.1814 0.36087 0.1807129 0.359233 0.175686 0.353868 0.179536 0.359233 0.175686 0.36087 0.1807129 0.359436 0.171532 0.36273 0.1814 0.359233 0.175686 0.353868 0.179536 0.34979 0.171048 0.359233 0.175686 0.36273 0.1814 0.362267 0.186051 0.36087 0.1807129 0.353868 0.179536 0.36087 0.1807129 0.362267 0.186051 0.365097 0.1922709 0.363425 0.1916249 0.362267 0.186051 0.356975 0.189115 0.362267 0.186051 0.363425 0.1916249 0.36273 0.1814 0.365097 0.1922709 0.362267 0.186051 0.356975 0.189115 0.353868 0.179536 0.362267 0.186051 0.365097 0.1922709 0.36436 0.1974419 0.363425 0.1916249 0.356975 0.189115 0.363425 0.1916249 0.36436 0.1974419 0.36662 0.203874 0.365077 0.203419 0.36436 0.1974419 0.359189 0.199717 0.36436 0.1974419 0.365077 0.203419 0.365097 0.1922709 0.36662 0.203874 0.36436 0.1974419 0.359189 0.199717 0.356975 0.189115 0.36436 0.1974419 0.36662 0.203874 0.365583 0.209549 0.365077 0.203419 0.359189 0.199717 0.365077 0.203419 0.365583 0.209549 0.367363 0.215924 0.365886 0.215759 0.365583 0.209549 0.360481 0.210782 0.365583 0.209549 0.365886 0.215759 0.36662 0.203874 0.367363 0.215924 0.365583 0.209549 0.360481 0.210782 0.359189 0.199717 0.365583 0.209549 0.367363 0.215924 0.365985 0.22202 0.365886 0.215759 0.360481 0.210782 0.365886 0.215759 0.365985 0.22202 0.367363 0.228121 0.365886 0.228282 0.365985 0.22202 0.360903 0.222023 0.365985 0.22202 0.365886 0.228282 0.367363 0.215924 0.367363 0.228121 0.365985 0.22202 0.360903 0.222023 0.360481 0.210782 0.365985 0.22202 0.36662 0.240171 0.365584 0.234492 0.365886 0.228282 0.360495 0.233071 0.365886 0.228282 0.365584 0.234492 0.367363 0.228121 0.36662 0.240171 0.365886 0.228282 0.360495 0.233071 0.360903 0.222023 0.365886 0.228282 0.36662 0.240171 0.365078 0.240622 0.365584 0.234492 0.360495 0.233071 0.365584 0.234492 0.365078 0.240622 0.365097 0.251774 0.364361 0.246599 0.365078 0.240622 0.359239 0.244018 0.365078 0.240622 0.364361 0.246599 0.36662 0.240171 0.365097 0.251774 0.365078 0.240622 0.359239 0.244018 0.360495 0.233071 0.365078 0.240622 0.365097 0.251774 0.363426 0.252416 0.364361 0.246599 0.359239 0.244018 0.364361 0.246599 0.363426 0.252416 0.36273 0.262645 0.362268 0.25799 0.363426 0.252416 0.357065 0.254585 0.363426 0.252416 0.362268 0.25799 0.365097 0.251774 0.36273 0.262645 0.363426 0.252416 0.357065 0.254585 0.359239 0.244018 0.363426 0.252416 0.36273 0.262645 0.360872 0.263328 0.362268 0.25799 0.357065 0.254585 0.362268 0.25799 0.360872 0.263328 0.359436 0.272513 0.359235 0.268355 0.360872 0.263328 0.353997 0.264182 0.360872 0.263328 0.359235 0.268355 0.36273 0.262645 0.359436 0.272513 0.360872 0.263328 0.353997 0.264182 0.357065 0.254585 0.360872 0.263328 0.359436 0.272513 0.357336 0.273083 0.359235 0.268355 0.349943 0.272734 0.359235 0.268355 0.357336 0.273083 0.349943 0.272734 0.353997 0.264182 0.359235 0.268355 0.355137 0.281129 0.355175 0.277451 0.357336 0.273083 0.349943 0.272734 0.357336 0.273083 0.355175 0.277451 0.359436 0.272513 0.355137 0.281129 0.357336 0.273083 0.355137 0.281129 0.352731 0.281467 0.355175 0.277451 0.344921 0.279883 0.355175 0.277451 0.352731 0.281467 0.344921 0.279883 0.349943 0.272734 0.355175 0.277451 0.349783 0.288277 0.350004 0.285085 0.352731 0.281467 0.342259 0.282668 0.352731 0.281467 0.350004 0.285085 0.355137 0.281129 0.349783 0.288277 0.352731 0.281467 0.344921 0.279883 0.352731 0.281467 0.342259 0.282668 0.349783 0.288277 0.346975 0.288309 0.350004 0.285085 0.342259 0.282668 0.350004 0.285085 0.346975 0.288309 0.343393 0.293822 0.344162 0.290706 0.346975 0.288309 0.342259 0.282668 0.346975 0.288309 0.344162 0.290706 0.349783 0.288277 0.343393 0.293822 0.346975 0.288309 0.343393 0.293822 0.343628 0.291107 0.344162 0.290706 0.312242 0.292223 0.344162 0.290706 0.343628 0.291107 0.324199 0.291034 0.344162 0.290706 0.312242 0.292223 0.338798 0.285528 0.342259 0.282668 0.344162 0.290706 0.331843 0.289261 0.338798 0.285528 0.344162 0.290706 0.324199 0.291034 0.331843 0.289261 0.344162 0.290706 0.343393 0.293822 0.339942 0.293482 0.343628 0.291107 0.312242 0.292223 0.343628 0.291107 0.339942 0.293482 0.33603 0.297666 0.335929 0.295388 0.339942 0.293482 0.312242 0.292223 0.339942 0.293482 0.335929 0.295388 0.343393 0.293822 0.33603 0.297666 0.339942 0.293482 0.33603 0.297666 0.331592 0.296798 0.335929 0.295388 0.312242 0.292223 0.335929 0.295388 0.331592 0.296798 0.337422 0.299242 0.33603 0.297666 0.343393 0.293822 0.344853 0.295272 0.343393 0.293822 0.349783 0.288277 0.344853 0.295272 0.337422 0.299242 0.343393 0.293822 0.351305 0.289582 0.349783 0.288277 0.355137 0.281129 0.351305 0.289582 0.344853 0.295272 0.349783 0.288277 0.356713 0.282271 0.355137 0.281129 0.359436 0.272513 0.356713 0.282271 0.351305 0.289582 0.355137 0.281129 0.361059 0.273475 0.359436 0.272513 0.36273 0.262645 0.361059 0.273475 0.356713 0.282271 0.359436 0.272513 0.364393 0.263412 0.36273 0.262645 0.365097 0.251774 0.364393 0.263412 0.361059 0.273475 0.36273 0.262645 0.366791 0.252333 0.365097 0.251774 0.36662 0.240171 0.366791 0.252333 0.364393 0.263412 0.365097 0.251774 0.368334 0.24051 0.36662 0.240171 0.367363 0.228121 0.368334 0.24051 0.366791 0.252333 0.36662 0.240171 0.369088 0.228235 0.367363 0.228121 0.367363 0.215924 0.369088 0.228235 0.368334 0.24051 0.367363 0.228121 0.369088 0.21581 0.367363 0.215924 0.36662 0.203874 0.369088 0.21581 0.369088 0.228235 0.367363 0.215924 0.368334 0.203535 0.36662 0.203874 0.365097 0.1922709 0.368334 0.203535 0.369088 0.21581 0.36662 0.203874 0.366791 0.191713 0.365097 0.1922709 0.36273 0.1814 0.366791 0.191713 0.368334 0.203535 0.365097 0.1922709 0.364392 0.180633 0.36273 0.1814 0.359436 0.171532 0.364392 0.180633 0.366791 0.191713 0.36273 0.1814 0.361059 0.17057 0.359436 0.171532 0.355137 0.162917 0.361059 0.17057 0.364392 0.180633 0.359436 0.171532 0.356713 0.1617749 0.355137 0.162917 0.349783 0.155768 0.356713 0.1617749 0.361059 0.17057 0.355137 0.162917 0.351304 0.154464 0.349783 0.155768 0.343392 0.150224 0.351304 0.154464 0.356713 0.1617749 0.349783 0.155768 0.344853 0.148773 0.343392 0.150224 0.33603 0.14638 0.344853 0.148773 0.351304 0.154464 0.343392 0.150224 0.337422 0.144803 0.344853 0.148773 0.33603 0.14638 0.33905 0.300346 0.337422 0.299242 0.344853 0.295272 0.346514 0.296321 0.344853 0.295272 0.351305 0.289582 0.346514 0.296321 0.33905 0.300346 0.344853 0.295272 0.353003 0.290545 0.351305 0.289582 0.356713 0.282271 0.353003 0.290545 0.346514 0.296321 0.351305 0.289582 0.358451 0.283123 0.356713 0.282271 0.361059 0.273475 0.358451 0.283123 0.353003 0.290545 0.356713 0.282271 0.362836 0.274196 0.361059 0.273475 0.364393 0.263412 0.362836 0.274196 0.358451 0.283123 0.361059 0.273475 0.366203 0.263986 0.364393 0.263412 0.366791 0.252333 0.366203 0.263986 0.362836 0.274196 0.364393 0.263412 0.36863 0.252749 0.366791 0.252333 0.368334 0.24051 0.36863 0.252749 0.366203 0.263986 0.366791 0.252333 0.370193 0.2407619 0.368334 0.24051 0.369088 0.228235 0.370193 0.2407619 0.36863 0.252749 0.368334 0.24051 0.370958 0.22832 0.369088 0.228235 0.369088 0.21581 0.370958 0.22832 0.370193 0.2407619 0.369088 0.228235 0.370958 0.215725 0.369088 0.21581 0.368334 0.203535 0.370958 0.215725 0.370958 0.22832 0.369088 0.21581 0.370193 0.203283 0.368334 0.203535 0.366791 0.191713 0.370193 0.203283 0.370958 0.215725 0.368334 0.203535 0.36863 0.191296 0.366791 0.191713 0.364392 0.180633 0.36863 0.191296 0.370193 0.203283 0.366791 0.191713 0.366203 0.180059 0.364392 0.180633 0.361059 0.17057 0.366203 0.180059 0.36863 0.191296 0.364392 0.180633 0.362835 0.169849 0.361059 0.17057 0.356713 0.1617749 0.362835 0.169849 0.366203 0.180059 0.361059 0.17057 0.358451 0.160922 0.356713 0.1617749 0.351304 0.154464 0.358451 0.160922 0.362835 0.169849 0.356713 0.1617749 0.353003 0.1535 0.351304 0.154464 0.344853 0.148773 0.353003 0.1535 0.358451 0.160922 0.351304 0.154464 0.346514 0.147725 0.344853 0.148773 0.337422 0.144803 0.346514 0.147725 0.353003 0.1535 0.344853 0.148773 0.339049 0.1437 0.346514 0.147725 0.337422 0.144803 0.293788 0.294954 0.288715 0.294589 0.283756 0.294461 0.329613 0.291378 0.306665 0.292781 0.288715 0.294589 0.329613 0.291378 0.288715 0.294589 0.293788 0.294954 0.28876 0.294814 0.283756 0.294461 0.278787 0.293169 0.28876 0.294814 0.293788 0.294954 0.283756 0.294461 0.242559 0.287766 0.278514 0.293066 0.278787 0.293169 0.28876 0.294814 0.278787 0.293169 0.278514 0.293066 0.329613 0.291378 0.312242 0.292223 0.306665 0.292781 0.329613 0.291378 0.324199 0.291034 0.312242 0.292223 0.242559 0.287766 0.273256 0.290424 0.278514 0.293066 0.283841 0.293411 0.278514 0.293066 0.273256 0.290424 0.283841 0.293411 0.28876 0.294814 0.278514 0.293066 0.242559 0.287766 0.268198 0.286611 0.273256 0.290424 0.279172 0.290771 0.273256 0.290424 0.268198 0.286611 0.279172 0.290771 0.283841 0.293411 0.273256 0.290424 0.242559 0.287766 0.265768 0.284253 0.268198 0.286611 0.274911 0.286967 0.268198 0.286611 0.265768 0.284253 0.274911 0.286967 0.279172 0.290771 0.268198 0.286611 0.23869 0.266606 0.263435 0.281604 0.265768 0.284253 0.274911 0.286967 0.265768 0.284253 0.263435 0.281604 0.242559 0.287766 0.23869 0.266606 0.265768 0.284253 0.23869 0.266606 0.249537 0.263738 0.263435 0.281604 0.271193 0.282085 0.263435 0.281604 0.249537 0.263738 0.271193 0.282085 0.274911 0.286967 0.263435 0.281604 0.23869 0.266606 0.236325 0.245176 0.249537 0.263738 0.271193 0.282085 0.249537 0.263738 0.236325 0.245176 0.2295809 0.266908 0.236325 0.245176 0.23869 0.266606 0.234624 0.242649 0.271193 0.282085 0.236325 0.245176 0.227041 0.244597 0.234624 0.242649 0.236325 0.245176 0.2295809 0.266908 0.227041 0.244597 0.236325 0.245176 0.2295809 0.266908 0.23869 0.266606 0.242559 0.287766 0.2337599 0.288697 0.2295809 0.266908 0.242559 0.287766 0.345203 0.285768 0.342259 0.282668 0.338798 0.285528 0.352185 0.280215 0.344921 0.279883 0.342259 0.282668 0.345203 0.285768 0.352185 0.280215 0.342259 0.282668 0.337615 0.289542 0.338798 0.285528 0.331843 0.289261 0.337615 0.289542 0.345203 0.285768 0.338798 0.285528 0.337615 0.289542 0.331843 0.289261 0.324199 0.291034 0.337615 0.289542 0.324199 0.291034 0.329613 0.291378 0.345202 0.158277 0.342256 0.161375 0.344767 0.163985 0.345202 0.158277 0.338665 0.158423 0.342256 0.161375 0.352184 0.16383 0.344767 0.163985 0.34979 0.171048 0.352184 0.16383 0.345202 0.158277 0.344767 0.163985 0.358386 0.170966 0.34979 0.171048 0.353868 0.179536 0.358386 0.170966 0.352184 0.16383 0.34979 0.171048 0.363662 0.1794649 0.353868 0.179536 0.356975 0.189115 0.363662 0.1794649 0.358386 0.170966 0.353868 0.179536 0.367894 0.1890839 0.356975 0.189115 0.359189 0.199717 0.367894 0.1890839 0.363662 0.1794649 0.356975 0.189115 0.370988 0.1995649 0.359189 0.199717 0.360481 0.210782 0.370988 0.1995649 0.367894 0.1890839 0.359189 0.199717 0.372874 0.210635 0.360481 0.210782 0.360903 0.222023 0.372874 0.210635 0.370988 0.1995649 0.360481 0.210782 0.37351 0.222023 0.360903 0.222023 0.360495 0.233071 0.37351 0.222023 0.372874 0.210635 0.360903 0.222023 0.372874 0.233411 0.360495 0.233071 0.359239 0.244018 0.372874 0.233411 0.37351 0.222023 0.360495 0.233071 0.370988 0.24448 0.359239 0.244018 0.357065 0.254585 0.370988 0.24448 0.372874 0.233411 0.359239 0.244018 0.367894 0.254961 0.357065 0.254585 0.353997 0.264182 0.367894 0.254961 0.370988 0.24448 0.357065 0.254585 0.363663 0.26458 0.353997 0.264182 0.349943 0.272734 0.363663 0.26458 0.367894 0.254961 0.353997 0.264182 0.352185 0.280215 0.349943 0.272734 0.344921 0.279883 0.358387 0.273079 0.363663 0.26458 0.349943 0.272734 0.352185 0.280215 0.358387 0.273079 0.349943 0.272734 0.293788 0.149092 0.312242 0.151823 0.324199 0.153012 0.293788 0.149092 0.306665 0.151265 0.312242 0.151823 0.329613 0.1526679 0.324199 0.153012 0.331765 0.1547549 0.293788 0.149092 0.324199 0.153012 0.329613 0.1526679 0.337614 0.154504 0.331765 0.1547549 0.338665 0.158423 0.337614 0.154504 0.329613 0.1526679 0.331765 0.1547549 0.345202 0.158277 0.337614 0.154504 0.338665 0.158423 0.28876 0.149231 0.278785 0.1508769 0.28372 0.14959 0.283841 0.150635 0.278459 0.151001 0.278785 0.1508769 0.28876 0.149231 0.283841 0.150635 0.278785 0.1508769 0.28876 0.149231 0.28372 0.14959 0.288715 0.149456 0.293788 0.149092 0.288715 0.149456 0.306665 0.151265 0.28876 0.149231 0.288715 0.149456 0.293788 0.149092 0.263434 0.162442 0.23869 0.177439 0.242559 0.15628 0.233759 0.15535 0.242559 0.15628 0.23869 0.177439 0.265751 0.159811 0.263434 0.162442 0.242559 0.15628 0.268166 0.157464 0.265751 0.159811 0.242559 0.15628 0.249537 0.1803089 0.236325 0.19887 0.23869 0.177439 0.2295809 0.177139 0.23869 0.177439 0.236325 0.19887 0.263434 0.162442 0.249537 0.1803089 0.23869 0.177439 0.2295809 0.177139 0.233759 0.15535 0.23869 0.177439 0.244881 0.203657 0.236325 0.19887 0.249537 0.1803089 0.234624 0.201397 0.236325 0.19887 0.244881 0.203657 0.227041 0.19945 0.236325 0.19887 0.234624 0.201397 0.227041 0.19945 0.2295809 0.177139 0.236325 0.19887 0.244881 0.203657 0.249537 0.1803089 0.263434 0.162442 0.271193 0.161961 0.263434 0.162442 0.265751 0.159811 0.244881 0.203657 0.263434 0.162442 0.271193 0.161961 0.274911 0.157079 0.265751 0.159811 0.268166 0.157464 0.274911 0.157079 0.271193 0.161961 0.265751 0.159811 0.279172 0.153275 0.268166 0.157464 0.273205 0.153654 0.279172 0.153275 0.274911 0.157079 0.268166 0.157464 0.283841 0.150635 0.273205 0.153654 0.278459 0.151001 0.283841 0.150635 0.279172 0.153275 0.273205 0.153654 0.293788 0.149092 0.293788 0.294954 0.28876 0.294814 0.329613 0.1526679 0.329613 0.291378 0.293788 0.294954 0.293788 0.149092 0.329613 0.1526679 0.293788 0.294954 0.28876 0.149231 0.28876 0.294814 0.283841 0.293411 0.28876 0.149231 0.293788 0.149092 0.28876 0.294814 0.283841 0.150635 0.283841 0.293411 0.279172 0.290771 0.28876 0.149231 0.283841 0.293411 0.283841 0.150635 0.279172 0.153275 0.279172 0.290771 0.274911 0.286967 0.283841 0.150635 0.279172 0.290771 0.279172 0.153275 0.274911 0.157079 0.274911 0.286967 0.271193 0.282085 0.279172 0.153275 0.274911 0.286967 0.274911 0.157079 0.274911 0.157079 0.271193 0.282085 0.271193 0.161961 0.244881 0.240389 0.271193 0.161961 0.271193 0.282085 0.232969 0.24015 0.271193 0.282085 0.234624 0.242649 0.244881 0.240389 0.271193 0.282085 0.232969 0.24015 0.337614 0.154504 0.329613 0.291378 0.329613 0.1526679 0.337615 0.289542 0.329613 0.291378 0.337614 0.154504 0.337615 0.289542 0.337614 0.154504 0.345202 0.158277 0.345203 0.285768 0.345202 0.158277 0.352184 0.16383 0.337615 0.289542 0.345202 0.158277 0.345203 0.285768 0.352185 0.280215 0.352184 0.16383 0.358386 0.170966 0.345203 0.285768 0.352184 0.16383 0.352185 0.280215 0.358387 0.273079 0.358386 0.170966 0.363662 0.1794649 0.352185 0.280215 0.358386 0.170966 0.358387 0.273079 0.363663 0.26458 0.363662 0.1794649 0.367894 0.1890839 0.358387 0.273079 0.363662 0.1794649 0.363663 0.26458 0.367894 0.254961 0.367894 0.1890839 0.370988 0.1995649 0.363663 0.26458 0.367894 0.1890839 0.367894 0.254961 0.370988 0.24448 0.370988 0.1995649 0.372874 0.210635 0.367894 0.254961 0.370988 0.1995649 0.370988 0.24448 0.372874 0.233411 0.372874 0.210635 0.37351 0.222023 0.370988 0.24448 0.372874 0.210635 0.372874 0.233411 0.244881 0.240389 0.244881 0.203657 0.271193 0.161961 0.234624 0.201397 0.244881 0.203657 0.2329699 0.203896 0.242174 0.209159 0.2329699 0.203896 0.244881 0.203657 0.227041 0.19945 0.234624 0.201397 0.2329699 0.203896 0.227041 0.19945 0.2329699 0.203896 0.23018 0.209341 0.242174 0.209159 0.23018 0.209341 0.2329699 0.203896 0.242174 0.234887 0.244881 0.203657 0.244881 0.240389 0.242174 0.234887 0.242174 0.209159 0.244881 0.203657 0.227041 0.244597 0.232969 0.24015 0.234624 0.242649 0.227041 0.244597 0.23018 0.234705 0.232969 0.24015 0.244881 0.240389 0.232969 0.24015 0.23018 0.234705 0.226184 0.222023 0.228442 0.228547 0.23018 0.234705 0.240481 0.228645 0.23018 0.234705 0.228442 0.228547 0.227041 0.244597 0.226184 0.222023 0.23018 0.234705 0.242174 0.234887 0.244881 0.240389 0.23018 0.234705 0.242174 0.234887 0.23018 0.234705 0.240481 0.228645 0.226184 0.222023 0.227851 0.222023 0.228442 0.228547 0.240481 0.228645 0.228442 0.228547 0.227851 0.222023 0.227041 0.19945 0.228442 0.215499 0.227851 0.222023 0.2399049 0.222023 0.227851 0.222023 0.228442 0.215499 0.226184 0.222023 0.227041 0.19945 0.227851 0.222023 0.240481 0.228645 0.227851 0.222023 0.2399049 0.222023 0.227041 0.19945 0.23018 0.209341 0.228442 0.215499 0.240481 0.2154 0.228442 0.215499 0.23018 0.209341 0.2399049 0.222023 0.228442 0.215499 0.240481 0.2154 0.240481 0.2154 0.23018 0.209341 0.242174 0.209159 0.22117 0.176476 0.233759 0.15535 0.2295809 0.177139 0.22117 0.176476 0.225764 0.154398 0.233759 0.15535 0.218376 0.199109 0.2295809 0.177139 0.227041 0.19945 0.218376 0.199109 0.22117 0.176476 0.2295809 0.177139 0.218376 0.199109 0.227041 0.19945 0.226184 0.222023 0.217434 0.222023 0.226184 0.222023 0.227041 0.244597 0.217434 0.222023 0.218376 0.199109 0.226184 0.222023 0.218376 0.244937 0.227041 0.244597 0.2295809 0.266908 0.218376 0.244937 0.217434 0.222023 0.227041 0.244597 0.22117 0.267571 0.2295809 0.266908 0.2337599 0.288697 0.22117 0.267571 0.218376 0.244937 0.2295809 0.266908 0.239675 0.309709 0.239487 0.309737 0.2337599 0.288697 0.225764 0.289649 0.2337599 0.288697 0.239487 0.309737 0.243758 0.309113 0.239675 0.309709 0.2337599 0.288697 0.225764 0.289649 0.22117 0.267571 0.2337599 0.288697 0.233496 0.313119 0.239487 0.309737 0.239675 0.309709 0.232145 0.310913 0.225764 0.289649 0.239487 0.309737 0.233496 0.313119 0.232145 0.310913 0.239487 0.309737 0.240854 0.311916 0.239675 0.309709 0.243758 0.309113 0.233496 0.313119 0.239675 0.309709 0.240854 0.311916 0.214144 0.175795 0.225764 0.154398 0.22117 0.176476 0.214144 0.175795 0.219263 0.153441 0.225764 0.154398 0.211026 0.198756 0.22117 0.176476 0.218376 0.199109 0.211026 0.198756 0.214144 0.175795 0.22117 0.176476 0.209974 0.222023 0.218376 0.199109 0.217434 0.222023 0.209974 0.222023 0.211026 0.198756 0.218376 0.199109 0.209974 0.222023 0.217434 0.222023 0.218376 0.244937 0.211026 0.24529 0.218376 0.244937 0.22117 0.267571 0.211026 0.24529 0.209974 0.222023 0.218376 0.244937 0.214144 0.26825 0.22117 0.267571 0.225764 0.289649 0.214144 0.26825 0.211026 0.24529 0.22117 0.267571 0.232145 0.310913 0.232051 0.31093 0.225764 0.289649 0.219263 0.290605 0.225764 0.289649 0.232051 0.31093 0.219263 0.290605 0.214144 0.26825 0.225764 0.289649 0.227509 0.314341 0.232051 0.31093 0.232145 0.310913 0.2262589 0.312091 0.219263 0.290605 0.232051 0.31093 0.227509 0.314341 0.2262589 0.312091 0.232051 0.31093 0.227509 0.314341 0.232145 0.310913 0.233496 0.313119 0.208799 0.175067 0.219263 0.153441 0.214144 0.175795 0.208799 0.175067 0.214357 0.1524209 0.219263 0.153441 0.20541 0.198377 0.214144 0.175795 0.211026 0.198756 0.20541 0.198377 0.208799 0.175067 0.214144 0.175795 0.20541 0.198377 0.211026 0.198756 0.209974 0.222023 0.2042649 0.222023 0.209974 0.222023 0.211026 0.24529 0.2042649 0.222023 0.20541 0.198377 0.209974 0.222023 0.20541 0.245669 0.211026 0.24529 0.214144 0.26825 0.20541 0.245669 0.2042649 0.222023 0.211026 0.24529 0.208799 0.268978 0.214144 0.26825 0.219263 0.290605 0.208799 0.268978 0.20541 0.245669 0.214144 0.26825 0.214357 0.291625 0.219263 0.290605 0.2262589 0.312091 0.214357 0.291625 0.208799 0.268978 0.219263 0.290605 0.226097 0.312129 0.214357 0.291625 0.2262589 0.312091 0.223105 0.315641 0.226097 0.312129 0.2262589 0.312091 0.223105 0.315641 0.2262589 0.312091 0.227509 0.314341 0.204849 0.174273 0.214357 0.1524209 0.208799 0.175067 0.204849 0.174273 0.210686 0.151289 0.214357 0.1524209 0.201286 0.197968 0.208799 0.175067 0.20541 0.198377 0.201286 0.197968 0.204849 0.174273 0.208799 0.175067 0.201286 0.197968 0.20541 0.198377 0.2042649 0.222023 0.200083 0.222023 0.2042649 0.222023 0.20541 0.245669 0.200083 0.222023 0.201286 0.197968 0.2042649 0.222023 0.201286 0.246078 0.20541 0.245669 0.208799 0.268978 0.201286 0.246078 0.200083 0.222023 0.20541 0.245669 0.204849 0.269773 0.208799 0.268978 0.214357 0.291625 0.204849 0.269773 0.201286 0.246078 0.208799 0.268978 0.226097 0.312129 0.221927 0.313326 0.214357 0.291625 0.210686 0.292757 0.214357 0.291625 0.221927 0.313326 0.210686 0.292757 0.204849 0.269773 0.214357 0.291625 0.223105 0.315641 0.221927 0.313326 0.226097 0.312129 0.221671 0.313416 0.210686 0.292757 0.221927 0.313326 0.223105 0.315641 0.221671 0.313416 0.221927 0.313326 0.221671 0.313416 0.218626 0.314727 0.210686 0.292757 0.2199079 0.317059 0.218626 0.314727 0.221671 0.313416 0.2199079 0.317059 0.2184669 0.314809 0.218626 0.314727 0.2199079 0.317059 0.221671 0.313416 0.223105 0.315641 0.217481 0.31855 0.2184669 0.314809 0.2199079 0.317059 0.240481 0.228645 0.240481 0.2154 0.242174 0.209159 0.242174 0.234887 0.240481 0.228645 0.242174 0.209159 0.240481 0.228645 0.2399049 0.222023 0.240481 0.2154 0.242327 0.313718 0.244105 0.314924 0.23702 0.316121 0.235092 0.314923 0.23702 0.316121 0.231409 0.317317 0.235092 0.314923 0.242327 0.313718 0.23702 0.316121 0.229273 0.31614 0.231409 0.317317 0.227309 0.318586 0.229273 0.31614 0.235092 0.314923 0.231409 0.317317 0.225005 0.317433 0.227309 0.318586 0.224276 0.319993 0.225005 0.317433 0.229273 0.31614 0.227309 0.318586 0.221882 0.318853 0.224276 0.319993 0.221948 0.321493 0.221882 0.318853 0.225005 0.317433 0.224276 0.319993 0.219499 0.320354 0.221882 0.318853 0.221948 0.321493 0.205438 0.334074 0.219499 0.320354 0.221948 0.321493 0.240854 0.311916 0.242327 0.313718 0.235092 0.314923 0.233496 0.313119 0.235092 0.314923 0.229273 0.31614 0.233496 0.313119 0.240854 0.311916 0.235092 0.314923 0.227509 0.314341 0.229273 0.31614 0.225005 0.317433 0.227509 0.314341 0.233496 0.313119 0.229273 0.31614 0.223105 0.315641 0.225005 0.317433 0.221882 0.318853 0.223105 0.315641 0.227509 0.314341 0.225005 0.317433 0.2199079 0.317059 0.221882 0.318853 0.219499 0.320354 0.2199079 0.317059 0.223105 0.315641 0.221882 0.318853 0.217481 0.31855 0.2199079 0.317059 0.219499 0.320354 0.202764 0.332838 0.217481 0.31855 0.219499 0.320354 0.205438 0.334074 0.202764 0.332838 0.219499 0.320354 0.202764 0.332838 0.200549 0.330885 0.217481 0.31855 0.132332 0.391098 0.1292099 0.388429 0.157709 0.364589 0.160456 0.366959 0.157709 0.364589 0.180965 0.345903 0.160456 0.366959 0.132332 0.391098 0.157709 0.364589 0.183417 0.348041 0.180965 0.345903 0.200549 0.330885 0.183417 0.348041 0.160456 0.366959 0.180965 0.345903 0.202764 0.332838 0.183417 0.348041 0.200549 0.330885 0.136059 0.392808 0.132332 0.391098 0.160456 0.366959 0.163748 0.368467 0.160456 0.366959 0.183417 0.348041 0.163748 0.368467 0.136059 0.392808 0.160456 0.366959 0.186367 0.349397 0.183417 0.348041 0.202764 0.332838 0.186367 0.349397 0.163748 0.368467 0.183417 0.348041 0.205438 0.334074 0.186367 0.349397 0.202764 0.332838 0.205373 0.433779 0.205032 0.433806 0.203145 0.433119 0.203388 0.433068 0.203145 0.433119 0.201061 0.432429 0.203388 0.433068 0.205373 0.433779 0.203145 0.433119 0.201427 0.432348 0.201061 0.432429 0.199009 0.431733 0.201427 0.432348 0.203388 0.433068 0.201061 0.432429 0.1995 0.43162 0.199009 0.431733 0.196994 0.431033 0.1995 0.43162 0.201427 0.432348 0.199009 0.431733 0.197611 0.430884 0.196994 0.431033 0.195022 0.430331 0.197611 0.430884 0.1995 0.43162 0.196994 0.431033 0.195766 0.430144 0.195022 0.430331 0.193093 0.429625 0.195766 0.430144 0.197611 0.430884 0.195022 0.430331 0.193964 0.429397 0.193093 0.429625 0.191207 0.428915 0.193964 0.429397 0.195766 0.430144 0.193093 0.429625 0.192206 0.428645 0.191207 0.428915 0.189366 0.428202 0.192206 0.428645 0.193964 0.429397 0.191207 0.428915 0.190493 0.427886 0.189366 0.428202 0.18757 0.427485 0.190493 0.427886 0.192206 0.428645 0.189366 0.428202 0.188826 0.427121 0.18757 0.427485 0.18582 0.426763 0.188826 0.427121 0.190493 0.427886 0.18757 0.427485 0.187206 0.426349 0.18582 0.426763 0.184119 0.426037 0.187206 0.426349 0.188826 0.427121 0.18582 0.426763 0.185635 0.42557 0.184119 0.426037 0.1824679 0.425306 0.185635 0.42557 0.187206 0.426349 0.184119 0.426037 0.184113 0.424785 0.1824679 0.425306 0.180867 0.424571 0.184113 0.424785 0.185635 0.42557 0.1824679 0.425306 0.1826429 0.423993 0.180867 0.424571 0.179319 0.42383 0.1826429 0.423993 0.184113 0.424785 0.180867 0.424571 0.181225 0.423194 0.179319 0.42383 0.177825 0.423084 0.181225 0.423194 0.1826429 0.423993 0.179319 0.42383 0.1798599 0.422388 0.177825 0.423084 0.1763859 0.422333 0.1798599 0.422388 0.181225 0.423194 0.177825 0.423084 0.17855 0.421575 0.1763859 0.422333 0.175004 0.421577 0.17855 0.421575 0.1798599 0.422388 0.1763859 0.422333 0.177296 0.420755 0.175004 0.421577 0.173681 0.420815 0.177296 0.420755 0.17855 0.421575 0.175004 0.421577 0.176101 0.419928 0.173681 0.420815 0.17242 0.420047 0.176101 0.419928 0.177296 0.420755 0.173681 0.420815 0.174966 0.419095 0.17242 0.420047 0.171221 0.419275 0.174966 0.419095 0.176101 0.419928 0.17242 0.420047 0.173892 0.418255 0.171221 0.419275 0.1700879 0.418497 0.173892 0.418255 0.174966 0.419095 0.171221 0.419275 0.172882 0.417408 0.1700879 0.418497 0.169021 0.417714 0.172882 0.417408 0.173892 0.418255 0.1700879 0.418497 0.171937 0.416555 0.169021 0.417714 0.168023 0.416926 0.171937 0.416555 0.172882 0.417408 0.169021 0.417714 0.1710579 0.415696 0.168023 0.416926 0.167096 0.416134 0.1710579 0.415696 0.171937 0.416555 0.168023 0.416926 0.170248 0.414831 0.167096 0.416134 0.166242 0.415336 0.170248 0.414831 0.1710579 0.415696 0.167096 0.416134 0.169508 0.413961 0.166242 0.415336 0.165462 0.414534 0.169508 0.413961 0.170248 0.414831 0.166242 0.415336 0.168839 0.413085 0.165462 0.414534 0.164759 0.413727 0.168839 0.413085 0.169508 0.413961 0.165462 0.414534 0.168245 0.412204 0.164759 0.413727 0.164135 0.412917 0.168245 0.412204 0.168839 0.413085 0.164759 0.413727 0.167726 0.411319 0.164135 0.412917 0.163592 0.412102 0.167726 0.411319 0.168245 0.412204 0.164135 0.412917 0.1672829 0.410429 0.163592 0.412102 0.1631309 0.411284 0.1672829 0.410429 0.167726 0.411319 0.163592 0.412102 0.16692 0.409534 0.1631309 0.411284 0.162755 0.410463 0.16692 0.409534 0.1672829 0.410429 0.1631309 0.411284 0.166636 0.408636 0.162755 0.410463 0.162465 0.409638 0.166636 0.408636 0.16692 0.409534 0.162755 0.410463 0.166435 0.407735 0.162465 0.409638 0.162263 0.408812 0.166435 0.407735 0.166636 0.408636 0.162465 0.409638 0.166317 0.406831 0.162263 0.408812 0.16215 0.407983 0.166317 0.406831 0.166435 0.407735 0.162263 0.408812 0.166283 0.405924 0.16215 0.407983 0.162227 0.40712 0.166283 0.405924 0.166317 0.406831 0.16215 0.407983 0.165331 0.02667999 0.177215 0.406904 0.177328 0.03726589 0.166499 0.404899 0.166283 0.405924 0.162227 0.40712 0.204338 0.433297 0.205373 0.433779 0.203388 0.433068 0.204338 0.433297 0.205853 0.433893 0.205373 0.433779 0.202285 0.432462 0.203388 0.433068 0.201427 0.432348 0.224198 0.193901 0.221928 0.277544 0.224207 0.249981 0.204155 0.433224 0.204338 0.433297 0.203388 0.433068 0.202285 0.432462 0.204155 0.433224 0.203388 0.433068 0.200432 0.431659 0.201427 0.432348 0.1995 0.43162 0.200432 0.431659 0.202285 0.432462 0.201427 0.432348 0.198703 0.430894 0.1995 0.43162 0.197611 0.430884 0.198703 0.430894 0.200432 0.431659 0.1995 0.43162 0.196921 0.43011 0.197611 0.430884 0.195766 0.430144 0.196921 0.43011 0.198703 0.430894 0.197611 0.430884 0.195219 0.429304 0.195766 0.430144 0.193964 0.429397 0.195219 0.429304 0.196921 0.43011 0.195766 0.430144 0.193562 0.428488 0.193964 0.429397 0.192206 0.428645 0.193562 0.428488 0.195219 0.429304 0.193964 0.429397 0.19195 0.42766 0.192206 0.428645 0.190493 0.427886 0.19195 0.42766 0.193562 0.428488 0.192206 0.428645 0.190383 0.426822 0.190493 0.427886 0.188826 0.427121 0.190383 0.426822 0.19195 0.42766 0.190493 0.427886 0.188929 0.425927 0.188826 0.427121 0.187206 0.426349 0.188929 0.425927 0.190383 0.426822 0.188826 0.427121 0.187393 0.425112 0.187206 0.426349 0.185635 0.42557 0.187393 0.425112 0.188929 0.425927 0.187206 0.426349 0.18597 0.42424 0.185635 0.42557 0.184113 0.424785 0.18597 0.42424 0.187393 0.425112 0.185635 0.42557 0.184598 0.423359 0.184113 0.424785 0.1826429 0.423993 0.184598 0.423359 0.18597 0.42424 0.184113 0.424785 0.183396 0.422414 0.1826429 0.423993 0.181225 0.423194 0.183396 0.422414 0.184598 0.423359 0.1826429 0.423993 0.182008 0.421563 0.181225 0.423194 0.1798599 0.422388 0.182008 0.421563 0.183396 0.422414 0.181225 0.423194 0.180792 0.420649 0.1798599 0.422388 0.17855 0.421575 0.180792 0.420649 0.182008 0.421563 0.1798599 0.422388 0.1796309 0.419725 0.17855 0.421575 0.177296 0.420755 0.1796309 0.419725 0.180792 0.420649 0.17855 0.421575 0.178526 0.418791 0.177296 0.420755 0.176101 0.419928 0.178526 0.418791 0.1796309 0.419725 0.177296 0.420755 0.177478 0.417848 0.176101 0.419928 0.174966 0.419095 0.177478 0.417848 0.178526 0.418791 0.176101 0.419928 0.1764889 0.416895 0.174966 0.419095 0.173892 0.418255 0.1764889 0.416895 0.177478 0.417848 0.174966 0.419095 0.1755599 0.415934 0.173892 0.418255 0.172882 0.417408 0.1755599 0.415934 0.1764889 0.416895 0.173892 0.418255 0.174693 0.414963 0.172882 0.417408 0.171937 0.416555 0.174693 0.414963 0.1755599 0.415934 0.172882 0.417408 0.173888 0.413985 0.171937 0.416555 0.1710579 0.415696 0.173888 0.413985 0.174693 0.414963 0.171937 0.416555 0.173149 0.412999 0.1710579 0.415696 0.170248 0.414831 0.173149 0.412999 0.173888 0.413985 0.1710579 0.415696 0.172475 0.412005 0.170248 0.414831 0.169508 0.413961 0.172475 0.412005 0.173149 0.412999 0.170248 0.414831 0.171869 0.411005 0.169508 0.413961 0.168839 0.413085 0.171869 0.411005 0.172475 0.412005 0.169508 0.413961 0.171332 0.409998 0.168839 0.413085 0.168245 0.412204 0.171332 0.409998 0.171869 0.411005 0.168839 0.413085 0.1708649 0.408985 0.168245 0.412204 0.167726 0.411319 0.1708649 0.408985 0.171332 0.409998 0.168245 0.412204 0.170471 0.407966 0.167726 0.411319 0.1672829 0.410429 0.170471 0.407966 0.1708649 0.408985 0.167726 0.411319 0.17015 0.406942 0.1672829 0.410429 0.16692 0.409534 0.17015 0.406942 0.170471 0.407966 0.1672829 0.410429 0.1699039 0.405914 0.16692 0.409534 0.166636 0.408636 0.1699039 0.405914 0.17015 0.406942 0.16692 0.409534 0.169734 0.404881 0.166636 0.408636 0.166435 0.407735 0.169734 0.404881 0.1699039 0.405914 0.166636 0.408636 0.169642 0.403845 0.166435 0.407735 0.166317 0.406831 0.169642 0.403845 0.169734 0.404881 0.166435 0.407735 0.16963 0.402806 0.166317 0.406831 0.166283 0.405924 0.16963 0.402806 0.169642 0.403845 0.166317 0.406831 0.16963 0.402806 0.166283 0.405924 0.166499 0.404899 0.152405 0.020738 0.165178 0.417468 0.165331 0.02667999 0.1696979 0.401764 0.16963 0.402806 0.166499 0.404899 0.206154 0.433996 0.205853 0.433893 0.204338 0.433297 0.203212 0.432838 0.204155 0.433224 0.202285 0.432462 0.201961 0.432312 0.202285 0.432462 0.200432 0.431659 0.201961 0.432312 0.203212 0.432838 0.202285 0.432462 0.152405 0.020738 0.152242 0.42335 0.165178 0.417468 0.13882 0.02003395 0.152242 0.42335 0.152405 0.020738 0.124932 0.02512598 0.138685 0.423991 0.13882 0.02003395 0.13882 0.02003395 0.138685 0.423991 0.152242 0.42335 0.196727 0.429984 0.196921 0.43011 0.195219 0.429304 0.196727 0.429984 0.198703 0.430894 0.196921 0.43011 0.19442 0.428867 0.195219 0.429304 0.193562 0.428488 0.195488 0.429392 0.196727 0.429984 0.195219 0.429304 0.19442 0.428867 0.195488 0.429392 0.195219 0.429304 0.193005 0.428151 0.193562 0.428488 0.19195 0.42766 0.193005 0.428151 0.19442 0.428867 0.193562 0.428488 0.191465 0.42734 0.19195 0.42766 0.190383 0.426822 0.192358 0.427814 0.193005 0.428151 0.19195 0.42766 0.191465 0.42734 0.192358 0.427814 0.19195 0.42766 0.190107 0.426597 0.190383 0.426822 0.188929 0.425927 0.190107 0.426597 0.191465 0.42734 0.190383 0.426822 0.111195 0.03646188 0.12486 0.418879 0.124932 0.02512598 0.124932 0.02512598 0.12486 0.418879 0.138685 0.423991 0.186516 0.424477 0.187393 0.425112 0.18597 0.42424 0.187735 0.425224 0.188929 0.425927 0.187393 0.425112 0.186516 0.424477 0.187735 0.425224 0.187393 0.425112 0.185555 0.423867 0.18597 0.42424 0.184598 0.423359 0.185555 0.423867 0.186516 0.424477 0.18597 0.42424 0.184502 0.423173 0.184598 0.423359 0.183396 0.422414 0.184502 0.423173 0.185555 0.423867 0.184598 0.423359 0.182657 0.421888 0.183396 0.422414 0.182008 0.421563 0.09815096 0.05426889 0.09822797 0.389906 0.111195 0.03646188 0.111195 0.03646188 0.111204 0.407595 0.12486 0.418879 0.181199 0.420798 0.182008 0.421563 0.180792 0.420649 0.182217 0.421566 0.182657 0.421888 0.182008 0.421563 0.181199 0.420798 0.182217 0.421566 0.182008 0.421563 0.180052 0.419887 0.180792 0.420649 0.1796309 0.419725 0.180052 0.419887 0.181199 0.420798 0.180792 0.420649 0.1788769 0.418896 0.1796309 0.419725 0.178526 0.418791 0.1788769 0.418896 0.180052 0.419887 0.1796309 0.419725 0.177811 0.417935 0.178526 0.418791 0.177478 0.417848 0.177811 0.417935 0.1788769 0.418896 0.178526 0.418791 0.17696 0.41712 0.177478 0.417848 0.1764889 0.416895 0.17696 0.41712 0.177811 0.417935 0.177478 0.417848 0.176272 0.416423 0.1764889 0.416895 0.1755599 0.415934 0.176272 0.416423 0.17696 0.41712 0.1764889 0.416895 0.175485 0.415578 0.1755599 0.415934 0.174693 0.414963 0.176168 0.416315 0.176272 0.416423 0.1755599 0.415934 0.175485 0.415578 0.176168 0.416315 0.1755599 0.415934 0.174741 0.414722 0.174693 0.414963 0.173888 0.413985 0.174741 0.414722 0.175485 0.415578 0.174693 0.414963 0.173967 0.413757 0.173888 0.413985 0.173149 0.412999 0.173967 0.413757 0.174741 0.414722 0.173888 0.413985 0.1727409 0.412023 0.173149 0.412999 0.172475 0.412005 0.173352 0.412926 0.173967 0.413757 0.173149 0.412999 0.1727409 0.412023 0.173352 0.412926 0.173149 0.412999 0.172299 0.41131 0.172475 0.412005 0.171869 0.411005 0.172299 0.41131 0.1727409 0.412023 0.172475 0.412005 0.171581 0.410001 0.171869 0.411005 0.171332 0.409998 0.172142 0.411043 0.172299 0.41131 0.171869 0.411005 0.171581 0.410001 0.172142 0.411043 0.171869 0.411005 0.17106 0.408874 0.171332 0.409998 0.1708649 0.408985 0.17106 0.408874 0.171581 0.410001 0.171332 0.409998 0.170718 0.408002 0.1708649 0.408985 0.170471 0.407966 0.170718 0.408002 0.17106 0.408874 0.1708649 0.408985 0.170411 0.407066 0.170471 0.407966 0.17015 0.406942 0.170411 0.407066 0.170718 0.408002 0.170471 0.407966 0.17022 0.406363 0.17015 0.406942 0.1699039 0.405914 0.17022 0.406363 0.170411 0.407066 0.17015 0.406942 0.169955 0.405021 0.1699039 0.405914 0.169734 0.404881 0.170152 0.406072 0.17022 0.406363 0.1699039 0.405914 0.169955 0.405021 0.170152 0.406072 0.1699039 0.405914 0.169832 0.403915 0.169734 0.404881 0.169642 0.403845 0.169832 0.403915 0.169955 0.405021 0.169734 0.404881 0.169798 0.402753 0.169642 0.403845 0.16963 0.402806 0.169798 0.402753 0.169832 0.403915 0.169642 0.403845 0.169798 0.402753 0.16963 0.402806 0.1696979 0.401764 0.191705 0.418687 0.192358 0.427814 0.191465 0.42734 0.191705 0.418687 0.191465 0.42734 0.190107 0.426597 0.191705 0.418687 0.190107 0.426597 0.188929 0.425927 0.191705 0.418687 0.188929 0.425927 0.187735 0.425224 0.191705 0.418687 0.187735 0.425224 0.186516 0.424477 0.191705 0.418687 0.186516 0.424477 0.185555 0.423867 0.191705 0.418687 0.185555 0.423867 0.184502 0.423173 0.191705 0.418687 0.184502 0.423173 0.183396 0.422414 0.191705 0.418687 0.183396 0.422414 0.182657 0.421888 0.185142 0.410324 0.182657 0.421888 0.182217 0.421566 0.185142 0.410324 0.191705 0.418687 0.182657 0.421888 0.185142 0.410324 0.182217 0.421566 0.181199 0.420798 0.185142 0.410324 0.181199 0.420798 0.180052 0.419887 0.185142 0.410324 0.180052 0.419887 0.1788769 0.418896 0.185142 0.410324 0.1788769 0.418896 0.177811 0.417935 0.185142 0.410324 0.177811 0.417935 0.17696 0.41712 0.185142 0.410324 0.17696 0.41712 0.176272 0.416423 0.180783 0.403836 0.176272 0.416423 0.176168 0.416315 0.180783 0.403836 0.185142 0.410324 0.176272 0.416423 0.180783 0.403836 0.176168 0.416315 0.175485 0.415578 0.180783 0.403836 0.175485 0.415578 0.174741 0.414722 0.180783 0.403836 0.174741 0.414722 0.173967 0.413757 0.180783 0.403836 0.173967 0.413757 0.173352 0.412926 0.180783 0.403836 0.173352 0.412926 0.1727409 0.412023 0.180783 0.403836 0.1727409 0.412023 0.172299 0.41131 0.178822 0.396451 0.172299 0.41131 0.172142 0.411043 0.178822 0.396451 0.180783 0.403836 0.172299 0.41131 0.178822 0.396451 0.172142 0.411043 0.171581 0.410001 0.178822 0.396451 0.171581 0.410001 0.17106 0.408874 0.178822 0.396451 0.17106 0.408874 0.170718 0.408002 0.178822 0.396451 0.170718 0.408002 0.170411 0.407066 0.178822 0.396451 0.170411 0.407066 0.17022 0.406363 0.178688 0.389065 0.17022 0.406363 0.170152 0.406072 0.178822 0.396451 0.17022 0.406363 0.178688 0.389065 0.178688 0.389065 0.170152 0.406072 0.169955 0.405021 0.178688 0.389065 0.169955 0.405021 0.169832 0.403915 0.178688 0.389065 0.169832 0.403915 0.169798 0.402753 0.187018 0.380105 0.178688 0.389065 0.188655 0.370361 0.178822 0.396451 0.178688 0.389065 0.187018 0.380105 0.196482 0.362544 0.188655 0.370361 0.199632 0.35055 0.187018 0.380105 0.188655 0.370361 0.196482 0.362544 0.206799 0.344015 0.199632 0.35055 0.211179 0.329864 0.196482 0.362544 0.199632 0.35055 0.206799 0.344015 0.217592 0.324718 0.211179 0.329864 0.222921 0.308472 0.206799 0.344015 0.211179 0.329864 0.217592 0.324718 0.228542 0.304801 0.222921 0.308472 0.234544 0.286502 0.217592 0.324718 0.222921 0.308472 0.228542 0.304801 0.23938 0.284385 0.234544 0.286502 0.245798 0.264049 0.228542 0.304801 0.234544 0.286502 0.23938 0.284385 0.24989 0.26356 0.245798 0.264049 0.256474 0.241186 0.23938 0.284385 0.245798 0.264049 0.24989 0.26356 0.24989 0.26356 0.256474 0.241186 0.259891 0.242404 0.272602 0.2475759 0.28144 0.251348 0.270178 0.271482 0.261741 0.268413 0.270178 0.271482 0.258564 0.291199 0.261741 0.268413 0.272602 0.2475759 0.270178 0.271482 0.250446 0.288883 0.258564 0.291199 0.246834 0.310419 0.250446 0.288883 0.261741 0.268413 0.258564 0.291199 0.2389439 0.308891 0.246834 0.310419 0.235265 0.32905 0.2389439 0.308891 0.250446 0.288883 0.246834 0.310419 0.2275069 0.328327 0.235265 0.32905 0.224201 0.346964 0.2275069 0.328327 0.2389439 0.308891 0.235265 0.32905 0.216475 0.347045 0.224201 0.346964 0.214047 0.364001 0.216475 0.347045 0.2275069 0.328327 0.224201 0.346964 0.206251 0.364862 0.214047 0.364001 0.205269 0.37995 0.206251 0.364862 0.216475 0.347045 0.214047 0.364001 0.197302 0.381542 0.205269 0.37995 0.198356 0.394553 0.197302 0.381542 0.206251 0.364862 0.205269 0.37995 0.1901209 0.396795 0.198356 0.394553 0.193742 0.407543 0.1901209 0.396795 0.197302 0.381542 0.198356 0.394553 0.185142 0.410324 0.193742 0.407543 0.191705 0.418687 0.185142 0.410324 0.1901209 0.396795 0.193742 0.407543 0.265325 0.244556 0.272602 0.2475759 0.261741 0.268413 0.2454 0.283982 0.261741 0.268413 0.250446 0.288883 0.255583 0.264417 0.265325 0.244556 0.261741 0.268413 0.2454 0.283982 0.255583 0.264417 0.261741 0.268413 0.234943 0.303179 0.250446 0.288883 0.2389439 0.308891 0.234943 0.303179 0.2454 0.283982 0.250446 0.288883 0.224411 0.321921 0.2389439 0.308891 0.2275069 0.328327 0.224411 0.321921 0.234943 0.303179 0.2389439 0.308891 0.214051 0.340096 0.2275069 0.328327 0.216475 0.347045 0.214051 0.340096 0.224411 0.321921 0.2275069 0.328327 0.204152 0.35757 0.216475 0.347045 0.206251 0.364862 0.204152 0.35757 0.214051 0.340096 0.216475 0.347045 0.195056 0.374168 0.206251 0.364862 0.197302 0.381542 0.195056 0.374168 0.204152 0.35757 0.206251 0.364862 0.187142 0.389671 0.197302 0.381542 0.1901209 0.396795 0.187142 0.389671 0.195056 0.374168 0.197302 0.381542 0.180783 0.403836 0.1901209 0.396795 0.185142 0.410324 0.180783 0.403836 0.187142 0.389671 0.1901209 0.396795 0.259891 0.242404 0.265325 0.244556 0.255583 0.264417 0.24989 0.26356 0.255583 0.264417 0.2454 0.283982 0.24989 0.26356 0.259891 0.242404 0.255583 0.264417 0.23938 0.284385 0.2454 0.283982 0.234943 0.303179 0.23938 0.284385 0.24989 0.26356 0.2454 0.283982 0.228542 0.304801 0.234943 0.303179 0.224411 0.321921 0.228542 0.304801 0.23938 0.284385 0.234943 0.303179 0.217592 0.324718 0.224411 0.321921 0.214051 0.340096 0.217592 0.324718 0.228542 0.304801 0.224411 0.321921 0.206799 0.344015 0.214051 0.340096 0.204152 0.35757 0.206799 0.344015 0.217592 0.324718 0.214051 0.340096 0.196482 0.362544 0.204152 0.35757 0.195056 0.374168 0.196482 0.362544 0.206799 0.344015 0.204152 0.35757 0.187018 0.380105 0.195056 0.374168 0.187142 0.389671 0.187018 0.380105 0.196482 0.362544 0.195056 0.374168 0.178822 0.396451 0.187142 0.389671 0.180783 0.403836 0.178822 0.396451 0.187018 0.380105 0.187142 0.389671 0.151167 0.284033 0.151011 0.285501 0.148974 0.285 0.1627579 0.282077 0.151011 0.285501 0.151167 0.284033 0.1627579 0.282077 0.162071 0.283495 0.151011 0.285501 0.1492159 0.283502 0.148974 0.285 0.146685 0.282783 0.1492159 0.283502 0.151167 0.284033 0.148974 0.285 0.144881 0.277534 0.146685 0.282783 0.144279 0.278859 0.147088 0.281327 0.1492159 0.283502 0.146685 0.282783 0.144881 0.277534 0.147088 0.281327 0.146685 0.282783 0.142722 0.272258 0.144279 0.278859 0.141915 0.273378 0.142722 0.272258 0.144881 0.277534 0.144279 0.278859 0.140768 0.265763 0.141915 0.273378 0.139778 0.266611 0.140768 0.265763 0.142722 0.272258 0.141915 0.273378 0.1398929 0.262049 0.139778 0.266611 0.138014 0.258775 0.1398929 0.262049 0.140768 0.265763 0.139778 0.266611 0.1398929 0.262049 0.138014 0.258775 0.139111 0.258105 0.136527 0.24035 0.139111 0.258105 0.138014 0.258775 0.136527 0.24035 0.138014 0.258775 0.1354539 0.240661 0.148294 0.253512 0.1398929 0.262049 0.139111 0.258105 0.143453 0.25283 0.139111 0.258105 0.136527 0.24035 0.143453 0.25283 0.148294 0.253512 0.139111 0.258105 0.154223 0.269357 0.151167 0.284033 0.1492159 0.283502 0.164863 0.267029 0.1627579 0.282077 0.151167 0.284033 0.154223 0.269357 0.164863 0.267029 0.151167 0.284033 0.152846 0.268888 0.1492159 0.283502 0.147088 0.281327 0.153536 0.269313 0.154223 0.269357 0.1492159 0.283502 0.152846 0.268888 0.153536 0.269313 0.1492159 0.283502 0.151493 0.26691 0.147088 0.281327 0.144881 0.277534 0.152161 0.268082 0.152846 0.268888 0.147088 0.281327 0.151493 0.26691 0.152161 0.268082 0.147088 0.281327 0.150239 0.263546 0.144881 0.277534 0.142722 0.272258 0.150849 0.265393 0.151493 0.26691 0.144881 0.277534 0.150239 0.263546 0.150849 0.265393 0.144881 0.277534 0.149155 0.259021 0.142722 0.272258 0.140768 0.265763 0.149155 0.259021 0.150239 0.263546 0.142722 0.272258 0.148294 0.253512 0.140768 0.265763 0.1398929 0.262049 0.148294 0.253512 0.149155 0.259021 0.140768 0.265763 0.135667 0.222041 0.1354539 0.240661 0.134596 0.222034 0.135667 0.222041 0.136527 0.24035 0.1354539 0.240661 0.136524 0.2037259 0.134596 0.222034 0.135453 0.2034 0.136524 0.2037259 0.135667 0.222041 0.134596 0.222034 0.136524 0.2037259 0.135453 0.2034 0.138014 0.185271 0.136524 0.2037259 0.138014 0.185271 0.139111 0.18594 0.139777 0.177438 0.139111 0.18594 0.138014 0.185271 0.147864 0.209508 0.136524 0.2037259 0.139111 0.18594 0.139891 0.182005 0.139111 0.18594 0.139777 0.177438 0.143453 0.191215 0.139111 0.18594 0.139891 0.182005 0.143453 0.191215 0.147864 0.209508 0.139111 0.18594 0.147864 0.232931 0.136527 0.24035 0.135667 0.222041 0.143453 0.25283 0.136527 0.24035 0.147745 0.247598 0.147864 0.232931 0.147745 0.247598 0.136527 0.24035 0.147918 0.221107 0.135667 0.222041 0.136524 0.2037259 0.147864 0.232931 0.135667 0.222041 0.147918 0.221107 0.147918 0.221107 0.136524 0.2037259 0.147864 0.209508 0.140765 0.178293 0.139777 0.177438 0.141914 0.1706719 0.140765 0.178293 0.139891 0.182005 0.139777 0.177438 0.142719 0.171797 0.141914 0.1706719 0.144277 0.16519 0.1417109 0.174897 0.140765 0.178293 0.141914 0.1706719 0.142719 0.171797 0.1417109 0.174897 0.141914 0.1706719 0.144879 0.1665149 0.144277 0.16519 0.146684 0.161265 0.143783 0.168986 0.142719 0.171797 0.144277 0.16519 0.144879 0.1665149 0.143783 0.168986 0.144277 0.16519 0.147088 0.162719 0.146684 0.161265 0.148972 0.159047 0.145986 0.16442 0.144879 0.1665149 0.146684 0.161265 0.147088 0.162719 0.145986 0.16442 0.146684 0.161265 0.150219 0.160069 0.148972 0.159047 0.151011 0.158544 0.148169 0.161427 0.147088 0.162719 0.148972 0.159047 0.1492159 0.160544 0.148169 0.161427 0.148972 0.159047 0.150219 0.160069 0.1492159 0.160544 0.148972 0.159047 0.150219 0.160069 0.151011 0.158544 0.151167 0.160013 0.162071 0.1605499 0.151167 0.160013 0.151011 0.158544 0.153527 0.174736 0.150219 0.160069 0.151167 0.160013 0.1627579 0.161969 0.151167 0.160013 0.162071 0.1605499 0.154223 0.1746889 0.151167 0.160013 0.1627579 0.161969 0.154223 0.1746889 0.153527 0.174736 0.151167 0.160013 0.148292 0.19055 0.139891 0.182005 0.140765 0.178293 0.143453 0.191215 0.139891 0.182005 0.147745 0.196448 0.14798 0.193482 0.147745 0.196448 0.139891 0.182005 0.148292 0.19055 0.14798 0.193482 0.139891 0.182005 0.148683 0.187731 0.140765 0.178293 0.1417109 0.174897 0.148683 0.187731 0.148292 0.19055 0.140765 0.178293 0.149139 0.185108 0.1417109 0.174897 0.142719 0.171797 0.149139 0.185108 0.148683 0.187731 0.1417109 0.174897 0.149649 0.1827329 0.142719 0.171797 0.143783 0.168986 0.149649 0.1827329 0.149139 0.185108 0.142719 0.171797 0.150209 0.1806 0.143783 0.168986 0.144879 0.1665149 0.150209 0.1806 0.149649 0.1827329 0.143783 0.168986 0.1508229 0.178724 0.144879 0.1665149 0.145986 0.16442 0.1508229 0.178724 0.150209 0.1806 0.144879 0.1665149 0.151472 0.177179 0.145986 0.16442 0.147088 0.162719 0.151472 0.177179 0.1508229 0.178724 0.145986 0.16442 0.152142 0.175992 0.147088 0.162719 0.148169 0.161427 0.152142 0.175992 0.151472 0.177179 0.147088 0.162719 0.152829 0.175172 0.148169 0.161427 0.1492159 0.160544 0.152829 0.175172 0.152142 0.175992 0.148169 0.161427 0.153527 0.174736 0.1492159 0.160544 0.150219 0.160069 0.153527 0.174736 0.152829 0.175172 0.1492159 0.160544 0.1627579 0.161969 0.162071 0.1605499 0.172246 0.162779 0.173027 0.164113 0.172246 0.162779 0.181622 0.165302 0.173027 0.164113 0.1627579 0.161969 0.172246 0.162779 0.182151 0.166479 0.181622 0.165302 0.1902649 0.168208 0.182151 0.166479 0.173027 0.164113 0.181622 0.165302 0.182151 0.166479 0.1902649 0.168208 0.190271 0.169097 0.191488 0.169333 0.190271 0.169097 0.1902649 0.168208 0.183369 0.181087 0.182151 0.166479 0.190271 0.169097 0.190917 0.169488 0.190271 0.169097 0.191488 0.169333 0.191461 0.182874 0.190271 0.169097 0.190917 0.169488 0.183369 0.181087 0.190271 0.169097 0.191461 0.182874 0.174537 0.179141 0.1627579 0.161969 0.173027 0.164113 0.164863 0.177017 0.154223 0.1746889 0.1627579 0.161969 0.164863 0.177017 0.1627579 0.161969 0.174537 0.179141 0.183369 0.181087 0.173027 0.164113 0.182151 0.166479 0.174537 0.179141 0.173027 0.164113 0.183369 0.181087 0.191484 0.170209 0.191488 0.169333 0.192381 0.171692 0.191484 0.170209 0.190917 0.169488 0.191488 0.169333 0.19236 0.172541 0.192381 0.171692 0.192939 0.17524 0.191965 0.171237 0.191484 0.170209 0.192381 0.171692 0.19236 0.172541 0.191965 0.171237 0.192381 0.171692 0.193082 0.178112 0.192939 0.17524 0.193192 0.179843 0.1926749 0.174133 0.19236 0.172541 0.192939 0.17524 0.192914 0.175992 0.1926749 0.174133 0.192939 0.17524 0.193082 0.178112 0.192914 0.175992 0.192939 0.17524 0.193226 0.183001 0.193192 0.179843 0.19319 0.1853049 0.193185 0.180464 0.193082 0.178112 0.193192 0.179843 0.193226 0.183001 0.193185 0.180464 0.193192 0.179843 0.193146 0.188731 0.19319 0.1853049 0.192984 0.1914809 0.193212 0.1857579 0.193226 0.183001 0.19319 0.1853049 0.193146 0.188731 0.193212 0.1857579 0.19319 0.1853049 0.193146 0.188731 0.192984 0.1914809 0.1930299 0.191852 0.192582 0.203565 0.1930299 0.191852 0.192984 0.1914809 0.192582 0.203565 0.192984 0.1914809 0.192522 0.203381 0.19481 0.199635 0.193146 0.188731 0.1930299 0.191852 0.193909 0.196922 0.1930299 0.191852 0.192582 0.203565 0.193909 0.196922 0.19481 0.199635 0.1930299 0.191852 0.192364 0.1836889 0.190917 0.169488 0.191484 0.170209 0.191916 0.183131 0.191461 0.182874 0.190917 0.169488 0.191916 0.183131 0.190917 0.169488 0.192364 0.1836889 0.192797 0.184547 0.191484 0.170209 0.191965 0.171237 0.192364 0.1836889 0.191484 0.170209 0.192797 0.184547 0.192797 0.184547 0.191965 0.171237 0.19236 0.172541 0.1932049 0.185692 0.19236 0.172541 0.1926749 0.174133 0.192797 0.184547 0.19236 0.172541 0.1932049 0.185692 0.1935819 0.187108 0.1926749 0.174133 0.192914 0.175992 0.1932049 0.185692 0.1926749 0.174133 0.1935819 0.187108 0.193919 0.188773 0.192914 0.175992 0.193082 0.178112 0.1935819 0.187108 0.192914 0.175992 0.193919 0.188773 0.1942059 0.19064 0.193082 0.178112 0.193185 0.180464 0.193919 0.188773 0.193082 0.178112 0.1942059 0.19064 0.194442 0.192685 0.193185 0.180464 0.193226 0.183001 0.1942059 0.19064 0.193185 0.180464 0.194442 0.192685 0.194624 0.1948969 0.193226 0.183001 0.193212 0.1857579 0.194442 0.192685 0.193226 0.183001 0.194624 0.1948969 0.194748 0.197235 0.193212 0.1857579 0.193146 0.188731 0.194624 0.1948969 0.193212 0.1857579 0.194748 0.197235 0.194748 0.197235 0.193146 0.188731 0.19481 0.199635 0.192309 0.21583 0.192522 0.203381 0.1922529 0.215773 0.192309 0.21583 0.192582 0.203565 0.192522 0.203381 0.192309 0.228188 0.1922529 0.215773 0.1922529 0.228244 0.192309 0.228188 0.192309 0.21583 0.1922529 0.215773 0.192582 0.24047 0.1922529 0.228244 0.192522 0.2406589 0.192582 0.24047 0.192309 0.228188 0.1922529 0.228244 0.192582 0.24047 0.192522 0.2406589 0.192984 0.252564 0.192582 0.24047 0.192984 0.252564 0.1930299 0.252194 0.19319 0.25874 0.1930299 0.252194 0.192984 0.252564 0.19482 0.234089 0.192582 0.24047 0.1930299 0.252194 0.193211 0.258257 0.1930299 0.252194 0.19319 0.25874 0.193909 0.247123 0.1930299 0.252194 0.193211 0.258257 0.193909 0.247123 0.19482 0.234089 0.1930299 0.252194 0.194824 0.212444 0.192582 0.203565 0.192309 0.21583 0.194824 0.212444 0.1948119 0.20204 0.192582 0.203565 0.193909 0.196922 0.192582 0.203565 0.1948119 0.20204 0.194828 0.2214339 0.192309 0.21583 0.192309 0.228188 0.194824 0.212444 0.192309 0.21583 0.194828 0.2214339 0.194826 0.227398 0.192309 0.228188 0.192582 0.24047 0.194828 0.2214339 0.192309 0.228188 0.194826 0.227398 0.194826 0.227398 0.192582 0.24047 0.19482 0.234089 0.193211 0.258257 0.19319 0.25874 0.193192 0.264201 0.193186 0.263552 0.193192 0.264201 0.192938 0.268805 0.193186 0.263552 0.193211 0.258257 0.193192 0.264201 0.1923609 0.271501 0.192938 0.268805 0.192381 0.272352 0.192916 0.268037 0.193186 0.263552 0.192938 0.268805 0.1923609 0.271501 0.192916 0.268037 0.192938 0.268805 0.191483 0.273839 0.192381 0.272352 0.191487 0.274711 0.191483 0.273839 0.1923609 0.271501 0.192381 0.272352 0.190916 0.274559 0.191487 0.274711 0.1902649 0.275836 0.190916 0.274559 0.191483 0.273839 0.191487 0.274711 0.190916 0.274559 0.1902649 0.275836 0.190271 0.274951 0.181622 0.278741 0.190271 0.274951 0.1902649 0.275836 0.192356 0.260371 0.190916 0.274559 0.190271 0.274951 0.182151 0.277567 0.190271 0.274951 0.181622 0.278741 0.191461 0.261172 0.190271 0.274951 0.182151 0.277567 0.192356 0.260371 0.190271 0.274951 0.191461 0.261172 0.1944479 0.251306 0.193211 0.258257 0.193186 0.263552 0.194747 0.2468309 0.1948119 0.242005 0.193211 0.258257 0.193909 0.247123 0.193211 0.258257 0.1948119 0.242005 0.194747 0.2468309 0.193211 0.258257 0.1944479 0.251306 0.194207 0.253403 0.193186 0.263552 0.192916 0.268037 0.1944479 0.251306 0.193186 0.263552 0.194207 0.253403 0.19357 0.256989 0.192916 0.268037 0.1923609 0.271501 0.19391 0.25532 0.192916 0.268037 0.19357 0.256989 0.194207 0.253403 0.192916 0.268037 0.19391 0.25532 0.193192 0.258396 0.1923609 0.271501 0.191483 0.273839 0.19357 0.256989 0.1923609 0.271501 0.193192 0.258396 0.192356 0.260371 0.191483 0.273839 0.190916 0.274559 0.192785 0.259527 0.191483 0.273839 0.192356 0.260371 0.193192 0.258396 0.191483 0.273839 0.192785 0.259527 0.173026 0.279933 0.181622 0.278741 0.172246 0.281266 0.173026 0.279933 0.182151 0.277567 0.181622 0.278741 0.1627579 0.282077 0.172246 0.281266 0.162071 0.283495 0.1627579 0.282077 0.173026 0.279933 0.172246 0.281266 0.183369 0.262959 0.182151 0.277567 0.173026 0.279933 0.183369 0.262959 0.191461 0.261172 0.182151 0.277567 0.174537 0.264904 0.173026 0.279933 0.1627579 0.282077 0.174537 0.264904 0.183369 0.262959 0.173026 0.279933 0.164863 0.267029 0.174537 0.264904 0.1627579 0.282077 0.154336 0.268634 0.191461 0.261172 0.183369 0.262959 0.154375 0.267908 0.191461 0.261172 0.154336 0.268634 0.191478 0.260918 0.191461 0.261172 0.154375 0.267908 0.192348 0.259873 0.191461 0.261172 0.191478 0.260918 0.192356 0.260371 0.191461 0.261172 0.192348 0.259873 0.154336 0.268634 0.183369 0.262959 0.174537 0.264904 0.154336 0.268634 0.174537 0.264904 0.164863 0.267029 0.154336 0.268634 0.164863 0.267029 0.154223 0.269357 0.154336 0.268634 0.154223 0.269357 0.153536 0.269313 0.153234 0.268319 0.153536 0.269313 0.152846 0.268888 0.153234 0.268319 0.154336 0.268634 0.153536 0.269313 0.153234 0.268319 0.152846 0.268888 0.152161 0.268082 0.152181 0.266959 0.152161 0.268082 0.151493 0.26691 0.152181 0.266959 0.153234 0.268319 0.152161 0.268082 0.151217 0.26463 0.151493 0.26691 0.150849 0.265393 0.151217 0.26463 0.152181 0.266959 0.151493 0.26691 0.151217 0.26463 0.150849 0.265393 0.150239 0.263546 0.15037 0.261407 0.150239 0.263546 0.149155 0.259021 0.15037 0.261407 0.151217 0.26463 0.150239 0.263546 0.149678 0.257392 0.149155 0.259021 0.148294 0.253512 0.149678 0.257392 0.15037 0.261407 0.149155 0.259021 0.143453 0.25283 0.147745 0.247598 0.148294 0.253512 0.1491799 0.252723 0.148294 0.253512 0.147745 0.247598 0.1491799 0.252723 0.149678 0.257392 0.148294 0.253512 0.1489109 0.247526 0.1491799 0.252723 0.147745 0.247598 0.148909 0.196519 0.1489109 0.247526 0.147745 0.247598 0.147864 0.232931 0.148909 0.196519 0.147745 0.247598 0.154375 0.267908 0.154336 0.268634 0.153234 0.268319 0.153174 0.267435 0.153234 0.268319 0.152181 0.266959 0.153174 0.267435 0.154375 0.267908 0.153234 0.268319 0.152034 0.265546 0.152181 0.266959 0.151217 0.26463 0.152034 0.265546 0.153174 0.267435 0.152181 0.266959 0.151042 0.262342 0.151217 0.26463 0.15037 0.261407 0.151042 0.262342 0.152034 0.265546 0.151217 0.26463 0.150272 0.258038 0.15037 0.261407 0.149678 0.257392 0.150272 0.258038 0.151042 0.262342 0.15037 0.261407 0.149781 0.252946 0.149678 0.257392 0.1491799 0.252723 0.149781 0.252946 0.150272 0.258038 0.149678 0.257392 0.149781 0.252946 0.1491799 0.252723 0.1489109 0.247526 0.1496 0.247442 0.149781 0.252946 0.1489109 0.247526 0.149559 0.222298 0.1496 0.247442 0.1489109 0.247526 0.149559 0.222298 0.1489109 0.247526 0.1496 0.196603 0.148909 0.196519 0.1496 0.196603 0.1489109 0.247526 0.154375 0.176138 0.154375 0.267908 0.153174 0.267435 0.1914809 0.260664 0.191478 0.260918 0.154375 0.267908 0.185954 0.237509 0.1914809 0.260664 0.154375 0.267908 0.160588 0.2002519 0.154375 0.267908 0.154375 0.176138 0.167758 0.238556 0.168357 0.237299 0.154375 0.267908 0.170462 0.238758 0.154375 0.267908 0.168357 0.237299 0.167105 0.239028 0.167758 0.238556 0.154375 0.267908 0.160588 0.239553 0.167105 0.239028 0.154375 0.267908 0.160588 0.2002519 0.160588 0.239553 0.154375 0.267908 0.170462 0.238758 0.17214 0.238623 0.154375 0.267908 0.1734679 0.238516 0.154375 0.267908 0.17214 0.238623 0.1734679 0.238516 0.175015 0.238391 0.154375 0.267908 0.1789219 0.238076 0.154375 0.267908 0.175015 0.238391 0.1789219 0.238076 0.185954 0.237509 0.154375 0.267908 0.153169 0.176614 0.153174 0.267435 0.152034 0.265546 0.153169 0.176614 0.154375 0.176138 0.153174 0.267435 0.152028 0.178513 0.152034 0.265546 0.151042 0.262342 0.152028 0.178513 0.153169 0.176614 0.152034 0.265546 0.151037 0.181727 0.151042 0.262342 0.150272 0.258038 0.151037 0.181727 0.152028 0.178513 0.151042 0.262342 0.150268 0.186035 0.150272 0.258038 0.149781 0.252946 0.150268 0.186035 0.151037 0.181727 0.150272 0.258038 0.149779 0.191118 0.149781 0.252946 0.1496 0.247442 0.149779 0.191118 0.150268 0.186035 0.149781 0.252946 0.149559 0.222298 0.1496 0.196603 0.1496 0.247442 0.149779 0.191118 0.1496 0.247442 0.1496 0.196603 0.192348 0.259873 0.191478 0.260918 0.1914809 0.260664 0.191482 0.183382 0.192348 0.259873 0.1914809 0.260664 0.186177 0.209478 0.191482 0.183382 0.1914809 0.260664 0.185954 0.237509 0.186177 0.209478 0.1914809 0.260664 0.149179 0.191319 0.149779 0.191118 0.1496 0.196603 0.149179 0.191319 0.1496 0.196603 0.148909 0.196519 0.192348 0.184172 0.193147 0.257909 0.192348 0.259873 0.192356 0.260371 0.192348 0.259873 0.193147 0.257909 0.191482 0.183382 0.192348 0.184172 0.192348 0.259873 0.193147 0.186137 0.193828 0.254921 0.193147 0.257909 0.193192 0.258396 0.193147 0.257909 0.193828 0.254921 0.192348 0.184172 0.193147 0.186137 0.193147 0.257909 0.192785 0.259527 0.192356 0.260371 0.193147 0.257909 0.193192 0.258396 0.192785 0.259527 0.193147 0.257909 0.194348 0.192936 0.194348 0.25111 0.193828 0.254921 0.19391 0.25532 0.193828 0.254921 0.194348 0.25111 0.193828 0.189126 0.194348 0.192936 0.193828 0.254921 0.193147 0.186137 0.193828 0.189126 0.193828 0.254921 0.19357 0.256989 0.193192 0.258396 0.193828 0.254921 0.19391 0.25532 0.19357 0.256989 0.193828 0.254921 0.1946769 0.197324 0.1946769 0.2467229 0.194348 0.25111 0.1944479 0.251306 0.194348 0.25111 0.1946769 0.2467229 0.194348 0.192936 0.1946769 0.197324 0.194348 0.25111 0.194207 0.253403 0.19391 0.25532 0.194348 0.25111 0.1944479 0.251306 0.194207 0.253403 0.194348 0.25111 0.194793 0.202013 0.194793 0.242032 0.1946769 0.2467229 0.194747 0.2468309 0.1946769 0.2467229 0.194793 0.242032 0.1946769 0.197324 0.194793 0.202013 0.1946769 0.2467229 0.194747 0.2468309 0.1944479 0.251306 0.1946769 0.2467229 0.194793 0.202013 0.194799 0.222275 0.194793 0.242032 0.194886 0.202026 0.194793 0.242032 0.194799 0.222275 0.194885 0.24202 0.194793 0.242032 0.194886 0.202026 0.194747 0.2468309 0.194793 0.242032 0.194885 0.24202 0.194886 0.202026 0.194799 0.222275 0.194793 0.202013 0.194886 0.202026 0.194793 0.202013 0.1946769 0.197324 0.194624 0.1948969 0.1946769 0.197324 0.194348 0.192936 0.1948119 0.20204 0.194886 0.202026 0.1946769 0.197324 0.19481 0.199635 0.1948119 0.20204 0.1946769 0.197324 0.194748 0.197235 0.19481 0.199635 0.1946769 0.197324 0.194624 0.1948969 0.194748 0.197235 0.1946769 0.197324 0.1942059 0.19064 0.194348 0.192936 0.193828 0.189126 0.194442 0.192685 0.194624 0.1948969 0.194348 0.192936 0.1942059 0.19064 0.194442 0.192685 0.194348 0.192936 0.1935819 0.187108 0.193828 0.189126 0.193147 0.186137 0.193919 0.188773 0.1942059 0.19064 0.193828 0.189126 0.1935819 0.187108 0.193919 0.188773 0.193828 0.189126 0.192797 0.184547 0.193147 0.186137 0.192348 0.184172 0.1932049 0.185692 0.1935819 0.187108 0.193147 0.186137 0.192797 0.184547 0.1932049 0.185692 0.193147 0.186137 0.191916 0.183131 0.192348 0.184172 0.191482 0.183382 0.192364 0.1836889 0.192797 0.184547 0.192348 0.184172 0.191916 0.183131 0.192364 0.1836889 0.192348 0.184172 0.160588 0.2002519 0.154375 0.176138 0.191482 0.183382 0.154336 0.175411 0.191482 0.183382 0.154375 0.176138 0.160588 0.2002519 0.191482 0.183382 0.162319 0.200425 0.170462 0.201238 0.162319 0.200425 0.191482 0.183382 0.17214 0.201406 0.170462 0.201238 0.191482 0.183382 0.1734679 0.201539 0.17214 0.201406 0.191482 0.183382 0.178134 0.202006 0.1734679 0.201539 0.191482 0.183382 0.178842 0.202077 0.178134 0.202006 0.191482 0.183382 0.186177 0.202812 0.178842 0.202077 0.191482 0.183382 0.186177 0.209478 0.186177 0.202812 0.191482 0.183382 0.191478 0.183127 0.191482 0.183382 0.154336 0.175411 0.191916 0.183131 0.191482 0.183382 0.191478 0.183127 0.154336 0.175411 0.154375 0.176138 0.153169 0.176614 0.152181 0.1770859 0.153169 0.176614 0.152028 0.178513 0.153234 0.175725 0.154336 0.175411 0.153169 0.176614 0.152181 0.1770859 0.153234 0.175725 0.153169 0.176614 0.151216 0.179416 0.152028 0.178513 0.151037 0.181727 0.151216 0.179416 0.152181 0.1770859 0.152028 0.178513 0.15037 0.182639 0.151037 0.181727 0.150268 0.186035 0.15037 0.182639 0.151216 0.179416 0.151037 0.181727 0.149678 0.186651 0.150268 0.186035 0.149779 0.191118 0.149678 0.186651 0.15037 0.182639 0.150268 0.186035 0.149179 0.191319 0.149678 0.186651 0.149779 0.191118 0.170462 0.201238 0.162319 0.2145259 0.162319 0.200425 0.170462 0.201238 0.16926 0.220779 0.168869 0.21829 0.170462 0.238758 0.169506 0.229941 0.170462 0.201238 0.175015 0.238391 0.175015 0.208748 0.178134 0.208952 0.1734679 0.201539 0.17214 0.238623 0.17214 0.201406 0.170462 0.201238 0.169506 0.223672 0.16926 0.220779 0.178842 0.208998 0.1789219 0.231157 0.175015 0.238391 0.1789219 0.238076 0.175015 0.238391 0.1789219 0.231157 0.167105 0.222023 0.162319 0.231918 0.162319 0.222023 0.167105 0.222023 0.167105 0.231699 0.162319 0.231918 0.167306 0.222126 0.167306 0.231586 0.167105 0.231699 0.167105 0.222023 0.167306 0.222126 0.167105 0.231699 0.16749 0.222397 0.16749 0.231308 0.167306 0.231586 0.167306 0.222126 0.16749 0.222397 0.167306 0.231586 0.167661 0.222843 0.167661 0.230854 0.16749 0.231308 0.16749 0.222397 0.167661 0.222843 0.16749 0.231308 0.16781 0.223435 0.16781 0.230255 0.167661 0.230854 0.167661 0.222843 0.16781 0.223435 0.167661 0.230854 0.167932 0.224158 0.167932 0.229526 0.16781 0.230255 0.16781 0.223435 0.167932 0.224158 0.16781 0.230255 0.168024 0.224982 0.168024 0.228698 0.167932 0.229526 0.167932 0.224158 0.168024 0.224982 0.167932 0.229526 0.168079 0.225872 0.168079 0.227806 0.168024 0.228698 0.168024 0.224982 0.168079 0.225872 0.168024 0.228698 0.168079 0.225872 0.1680999 0.2268379 0.168079 0.227806 0.147864 0.209508 0.147745 0.196448 0.148909 0.196519 0.14798 0.193482 0.148909 0.196519 0.147745 0.196448 0.147918 0.221107 0.147864 0.209508 0.148909 0.196519 0.147864 0.232931 0.147918 0.221107 0.148909 0.196519 0.149179 0.191319 0.148909 0.196519 0.14798 0.193482 0.143453 0.191215 0.147745 0.196448 0.147864 0.209508 0.149179 0.191319 0.14798 0.193482 0.148292 0.19055 0.149179 0.191319 0.148292 0.19055 0.148683 0.187731 0.149678 0.186651 0.148683 0.187731 0.149139 0.185108 0.149179 0.191319 0.148683 0.187731 0.149678 0.186651 0.149678 0.186651 0.149139 0.185108 0.149649 0.1827329 0.15037 0.182639 0.149649 0.1827329 0.150209 0.1806 0.149678 0.186651 0.149649 0.1827329 0.15037 0.182639 0.15037 0.182639 0.150209 0.1806 0.1508229 0.178724 0.151216 0.179416 0.1508229 0.178724 0.151472 0.177179 0.15037 0.182639 0.1508229 0.178724 0.151216 0.179416 0.152181 0.1770859 0.151472 0.177179 0.152142 0.175992 0.151216 0.179416 0.151472 0.177179 0.152181 0.1770859 0.152181 0.1770859 0.152142 0.175992 0.152829 0.175172 0.153234 0.175725 0.152829 0.175172 0.153527 0.174736 0.152181 0.1770859 0.152829 0.175172 0.153234 0.175725 0.153234 0.175725 0.153527 0.174736 0.154223 0.1746889 0.153234 0.175725 0.154223 0.1746889 0.154336 0.175411 0.154336 0.175411 0.154223 0.1746889 0.164863 0.177017 0.174537 0.179141 0.183369 0.181087 0.154336 0.175411 0.164863 0.177017 0.174537 0.179141 0.154336 0.175411 0.183369 0.181087 0.191461 0.182874 0.154336 0.175411 0.191478 0.183127 0.154336 0.175411 0.191461 0.182874 0.191916 0.183131 0.191478 0.183127 0.191461 0.182874 0.194885 0.24202 0.194886 0.202026 0.1948119 0.20204 0.193909 0.196922 0.1948119 0.20204 0.19481 0.199635 0.194824 0.212444 0.194885 0.24202 0.1948119 0.20204 0.19482 0.234089 0.1948119 0.242005 0.194885 0.24202 0.194747 0.2468309 0.194885 0.24202 0.1948119 0.242005 0.194826 0.227398 0.19482 0.234089 0.194885 0.24202 0.194828 0.2214339 0.194826 0.227398 0.194885 0.24202 0.194824 0.212444 0.194828 0.2214339 0.194885 0.24202 0.193909 0.247123 0.1948119 0.242005 0.19482 0.234089 0.357008 0.17431 0.353618 0.16745 0.349413 0.1683 0.357008 0.17431 0.359847 0.173426 0.353618 0.16745 0.351347 0.175544 0.349413 0.1683 0.345257 0.168721 0.354168 0.175018 0.357008 0.17431 0.349413 0.1683 0.351347 0.175544 0.354168 0.175018 0.349413 0.1683 0.348568 0.17588 0.345257 0.168721 0.341215 0.1687059 0.348568 0.17588 0.351347 0.175544 0.345257 0.168721 0.345852 0.176026 0.348568 0.17588 0.341215 0.1687059 0.343219 0.17598 0.345852 0.176026 0.341215 0.1687059 0.367789 0.186245 0.359847 0.173426 0.357008 0.17431 0.36348 0.187799 0.357008 0.17431 0.354168 0.175018 0.36348 0.187799 0.367789 0.186245 0.357008 0.17431 0.36348 0.187799 0.354168 0.175018 0.351347 0.175544 0.359217 0.189001 0.351347 0.175544 0.348568 0.17588 0.359217 0.189001 0.36348 0.187799 0.351347 0.175544 0.355072 0.1898249 0.348568 0.17588 0.345852 0.176026 0.355072 0.1898249 0.359217 0.189001 0.348568 0.17588 0.351114 0.1902599 0.345852 0.176026 0.343219 0.17598 0.351114 0.1902599 0.355072 0.1898249 0.345852 0.176026 0.376398 0.200392 0.367789 0.186245 0.36348 0.187799 0.370617 0.2027159 0.36348 0.187799 0.359217 0.189001 0.370617 0.2027159 0.376398 0.200392 0.36348 0.187799 0.365005 0.204531 0.359217 0.189001 0.355072 0.1898249 0.365005 0.204531 0.370617 0.2027159 0.359217 0.189001 0.359746 0.2057729 0.355072 0.1898249 0.351114 0.1902599 0.359746 0.2057729 0.365005 0.204531 0.355072 0.1898249 0.331727 0.207085 0.335613 0.206634 0.331521 0.206466 0.286184 0.2066929 0.331521 0.206466 0.331134 0.205865 0.331727 0.207085 0.331521 0.206466 0.286184 0.2066929 0.286184 0.2066929 0.331134 0.205865 0.330822 0.2052569 0.286184 0.2066929 0.330822 0.2052569 0.330576 0.204648 0.286184 0.2066929 0.330576 0.204648 0.330392 0.204044 0.286184 0.2066929 0.330392 0.204044 0.330272 0.203451 0.275357 0.204348 0.286184 0.2066929 0.281166 0.1908479 0.331727 0.207085 0.286184 0.2066929 0.286345 0.207302 0.275357 0.204348 0.286345 0.207302 0.286184 0.2066929 0.267037 0.1750079 0.281166 0.1908479 0.276528 0.176354 0.271082 0.1889809 0.275357 0.204348 0.281166 0.1908479 0.271082 0.1889809 0.281166 0.1908479 0.267037 0.1750079 0.263465 0.162627 0.276528 0.176354 0.272612 0.163482 0.267037 0.1750079 0.276528 0.176354 0.263465 0.162627 0.260573 0.151974 0.272612 0.163482 0.269741 0.1526679 0.263465 0.162627 0.272612 0.163482 0.260573 0.151974 0.2585 0.143094 0.269741 0.1526679 0.268093 0.143941 0.260573 0.151974 0.269741 0.1526679 0.2585 0.143094 0.257303 0.135936 0.268093 0.143941 0.267723 0.140268 0.2585 0.143094 0.268093 0.143941 0.257303 0.135936 0.257303 0.135936 0.267723 0.140268 0.267639 0.1370429 0.331727 0.207085 0.286345 0.207302 0.286492 0.207915 0.275357 0.204348 0.286492 0.207915 0.286345 0.207302 0.331979 0.207714 0.331727 0.207085 0.286492 0.207915 0.286603 0.209957 0.331979 0.207714 0.286492 0.207915 0.275627 0.205724 0.286492 0.207915 0.275357 0.204348 0.286603 0.209957 0.286492 0.207915 0.275627 0.205724 0.332073 0.207892 0.331979 0.207714 0.286603 0.209957 0.336248 0.208065 0.331979 0.207714 0.332073 0.207892 0.336248 0.208065 0.336047 0.207723 0.331979 0.207714 0.253295 0.1922259 0.252859 0.190309 0.249559 0.183516 0.248866 0.174365 0.249559 0.183516 0.252859 0.190309 0.249832 0.184578 0.253295 0.1922259 0.249559 0.183516 0.246868 0.1770009 0.249832 0.184578 0.249559 0.183516 0.246868 0.1770009 0.249559 0.183516 0.248318 0.178793 0.248866 0.174365 0.248318 0.178793 0.249559 0.183516 0.258763 0.197826 0.258405 0.19611 0.252859 0.190309 0.254046 0.178382 0.252859 0.190309 0.258405 0.19611 0.253295 0.1922259 0.258763 0.197826 0.252859 0.190309 0.254046 0.178382 0.248866 0.174365 0.252859 0.190309 0.266292 0.202347 0.265987 0.200811 0.258405 0.19611 0.261818 0.18442 0.258405 0.19611 0.265987 0.200811 0.258763 0.197826 0.266292 0.202347 0.258405 0.19611 0.261818 0.18442 0.254046 0.178382 0.258405 0.19611 0.275627 0.205724 0.275357 0.204348 0.265987 0.200811 0.271082 0.1889809 0.265987 0.200811 0.275357 0.204348 0.266292 0.202347 0.275627 0.205724 0.265987 0.200811 0.271082 0.1889809 0.261818 0.18442 0.265987 0.200811 0.275928 0.208559 0.275627 0.205724 0.266292 0.202347 0.275928 0.208559 0.286603 0.209957 0.275627 0.205724 0.266867 0.206137 0.266292 0.202347 0.258763 0.197826 0.275928 0.208559 0.266292 0.202347 0.266867 0.206137 0.254641 0.198306 0.258763 0.197826 0.253295 0.1922259 0.259688 0.202706 0.258763 0.197826 0.254641 0.198306 0.266867 0.206137 0.258763 0.197826 0.259688 0.202706 0.249832 0.184578 0.250108 0.18565 0.253295 0.1922259 0.251927 0.192923 0.253295 0.1922259 0.250108 0.18565 0.254641 0.198306 0.253295 0.1922259 0.251927 0.192923 0.246868 0.1770009 0.250108 0.18565 0.249832 0.184578 0.251927 0.192923 0.250108 0.18565 0.246868 0.1770009 0.236835 0.147432 0.226303 0.119837 0.220103 0.115765 0.239975 0.1496739 0.235647 0.135783 0.226303 0.119837 0.240157 0.1502709 0.239975 0.1496739 0.226303 0.119837 0.236835 0.147432 0.240157 0.1502709 0.226303 0.119837 0.232841 0.144376 0.220103 0.115765 0.212686 0.111371 0.232841 0.144376 0.236835 0.147432 0.220103 0.115765 0.22803 0.141113 0.212686 0.111371 0.20376 0.106599 0.22803 0.141113 0.232841 0.144376 0.212686 0.111371 0.192339 0.100443 0.193028 0.101383 0.20376 0.106599 0.222226 0.137606 0.20376 0.106599 0.193028 0.101383 0.189788 0.09699898 0.192339 0.100443 0.20376 0.106599 0.187146 0.09348297 0.189788 0.09699898 0.20376 0.106599 0.184413 0.08990198 0.187146 0.09348297 0.20376 0.106599 0.181585 0.08625197 0.184413 0.08990198 0.20376 0.106599 0.178655 0.08252996 0.181585 0.08625197 0.20376 0.106599 0.1756229 0.07874298 0.178655 0.08252996 0.20376 0.106599 0.172489 0.07489299 0.1756229 0.07874298 0.20376 0.106599 0.222226 0.137606 0.22803 0.141113 0.20376 0.106599 0.193639 0.102845 0.193028 0.101383 0.192339 0.100443 0.196043 0.105535 0.222226 0.137606 0.193028 0.101383 0.193639 0.102845 0.196043 0.105535 0.193028 0.101383 0.190343 0.09839898 0.192339 0.100443 0.189788 0.09699898 0.193639 0.102845 0.192339 0.100443 0.190343 0.09839898 0.187014 0.09398996 0.189788 0.09699898 0.187146 0.09348297 0.190343 0.09839898 0.189788 0.09699898 0.187014 0.09398996 0.1836529 0.08961898 0.187146 0.09348297 0.184413 0.08990198 0.187014 0.09398996 0.187146 0.09348297 0.1836529 0.08961898 0.180258 0.08528697 0.184413 0.08990198 0.181585 0.08625197 0.1836529 0.08961898 0.184413 0.08990198 0.180258 0.08528697 0.180258 0.08528697 0.181585 0.08625197 0.178655 0.08252996 0.176831 0.08099299 0.178655 0.08252996 0.1756229 0.07874298 0.180258 0.08528697 0.178655 0.08252996 0.176831 0.08099299 0.173372 0.07673698 0.1756229 0.07874298 0.172489 0.07489299 0.176831 0.08099299 0.1756229 0.07874298 0.173372 0.07673698 0.173372 0.07673698 0.172489 0.07489299 0.169881 0.07252097 0.241155 0.146728 0.235647 0.135783 0.239975 0.1496739 0.241155 0.146728 0.2377949 0.135298 0.235647 0.135783 0.241155 0.146728 0.239975 0.1496739 0.240157 0.1502709 0.244679 0.165598 0.240157 0.1502709 0.236835 0.147432 0.244902 0.159786 0.240157 0.1502709 0.244679 0.165598 0.244902 0.159786 0.241155 0.146728 0.240157 0.1502709 0.246868 0.1770009 0.236835 0.147432 0.232841 0.144376 0.248318 0.178793 0.244679 0.165598 0.236835 0.147432 0.246868 0.1770009 0.248318 0.178793 0.236835 0.147432 0.244966 0.174973 0.232841 0.144376 0.22803 0.141113 0.244966 0.174973 0.246868 0.1770009 0.232841 0.144376 0.242566 0.172845 0.22803 0.141113 0.222226 0.137606 0.242566 0.172845 0.244966 0.174973 0.22803 0.141113 0.212678 0.129817 0.215313 0.1338919 0.222226 0.137606 0.239575 0.170597 0.222226 0.137606 0.215313 0.1338919 0.209919 0.12562 0.212678 0.129817 0.222226 0.137606 0.207301 0.121703 0.209919 0.12562 0.222226 0.137606 0.204564 0.117673 0.207301 0.121703 0.222226 0.137606 0.20171 0.11354 0.204564 0.117673 0.222226 0.137606 0.1989369 0.10959 0.20171 0.11354 0.222226 0.137606 0.196043 0.105535 0.1989369 0.10959 0.222226 0.137606 0.239575 0.170597 0.242566 0.172845 0.222226 0.137606 0.212698 0.130278 0.215313 0.1338919 0.212678 0.129817 0.217153 0.136776 0.239575 0.170597 0.215313 0.1338919 0.215753 0.134972 0.217153 0.136776 0.215313 0.1338919 0.215753 0.134972 0.215313 0.1338919 0.212698 0.130278 0.209608 0.125618 0.212678 0.129817 0.209919 0.12562 0.212698 0.130278 0.212678 0.129817 0.209608 0.125618 0.209608 0.125618 0.209919 0.12562 0.207301 0.121703 0.206483 0.120992 0.207301 0.121703 0.204564 0.117673 0.209608 0.125618 0.207301 0.121703 0.206483 0.120992 0.203323 0.116401 0.204564 0.117673 0.20171 0.11354 0.206483 0.120992 0.204564 0.117673 0.203323 0.116401 0.200129 0.111846 0.20171 0.11354 0.1989369 0.10959 0.203323 0.116401 0.20171 0.11354 0.200129 0.111846 0.196901 0.107327 0.1989369 0.10959 0.196043 0.105535 0.200129 0.111846 0.1989369 0.10959 0.196901 0.107327 0.196901 0.107327 0.196043 0.105535 0.193639 0.102845 0.248866 0.174365 0.244679 0.165598 0.248318 0.178793 0.248866 0.174365 0.244902 0.159786 0.244679 0.165598 0.255946 0.207845 0.246868 0.1770009 0.244966 0.174973 0.25277 0.196421 0.251927 0.192923 0.246868 0.1770009 0.253773 0.200716 0.25277 0.196421 0.246868 0.1770009 0.255611 0.209046 0.253773 0.200716 0.246868 0.1770009 0.255946 0.207845 0.255611 0.209046 0.246868 0.1770009 0.255971 0.206664 0.244966 0.174973 0.242566 0.172845 0.255971 0.206664 0.255946 0.207845 0.244966 0.174973 0.255614 0.2054809 0.242566 0.172845 0.239575 0.170597 0.255614 0.2054809 0.255971 0.206664 0.242566 0.172845 0.2345409 0.165774 0.235932 0.168242 0.239575 0.170597 0.254599 0.203849 0.239575 0.170597 0.235932 0.168242 0.231989 0.16131 0.2345409 0.165774 0.239575 0.170597 0.229324 0.156728 0.231989 0.16131 0.239575 0.170597 0.227472 0.153589 0.229324 0.156728 0.239575 0.170597 0.2255589 0.150387 0.227472 0.153589 0.239575 0.170597 0.223573 0.147105 0.2255589 0.150387 0.239575 0.170597 0.2215149 0.143748 0.223573 0.147105 0.239575 0.170597 0.2193779 0.140309 0.2215149 0.143748 0.239575 0.170597 0.217153 0.136776 0.2193779 0.140309 0.239575 0.170597 0.254599 0.203849 0.255614 0.2054809 0.239575 0.170597 0.236119 0.16872 0.235932 0.168242 0.2345409 0.165774 0.254395 0.203427 0.254599 0.203849 0.235932 0.168242 0.254183 0.2029899 0.254395 0.203427 0.235932 0.168242 0.253969 0.202552 0.254183 0.2029899 0.235932 0.168242 0.252683 0.199944 0.253969 0.202552 0.235932 0.168242 0.251209 0.196991 0.252683 0.199944 0.235932 0.168242 0.249539 0.193686 0.251209 0.196991 0.235932 0.168242 0.2477149 0.190126 0.249539 0.193686 0.235932 0.168242 0.237659 0.171335 0.2477149 0.190126 0.235932 0.168242 0.236119 0.16872 0.237659 0.171335 0.235932 0.168242 0.233322 0.163809 0.2345409 0.165774 0.231989 0.16131 0.236119 0.16872 0.2345409 0.165774 0.233322 0.163809 0.230486 0.158927 0.231989 0.16131 0.229324 0.156728 0.233322 0.163809 0.231989 0.16131 0.230486 0.158927 0.227613 0.154074 0.229324 0.156728 0.227472 0.153589 0.230486 0.158927 0.229324 0.156728 0.227613 0.154074 0.227613 0.154074 0.227472 0.153589 0.2255589 0.150387 0.224703 0.149251 0.2255589 0.150387 0.223573 0.147105 0.227613 0.154074 0.2255589 0.150387 0.224703 0.149251 0.221756 0.144459 0.223573 0.147105 0.2215149 0.143748 0.224703 0.149251 0.223573 0.147105 0.221756 0.144459 0.221756 0.144459 0.2215149 0.143748 0.2193779 0.140309 0.218773 0.139699 0.2193779 0.140309 0.217153 0.136776 0.221756 0.144459 0.2193779 0.140309 0.218773 0.139699 0.218773 0.139699 0.217153 0.136776 0.215753 0.134972 0.254641 0.198306 0.251927 0.192923 0.25277 0.196421 0.254641 0.198306 0.25277 0.196421 0.253773 0.200716 0.256006 0.204764 0.253773 0.200716 0.255611 0.209046 0.254641 0.198306 0.253773 0.200716 0.256006 0.204764 0.256318 0.212462 0.255611 0.209046 0.255946 0.207845 0.256006 0.204764 0.255611 0.209046 0.257351 0.211529 0.257876 0.214314 0.257351 0.211529 0.255611 0.209046 0.257876 0.214314 0.255611 0.209046 0.256318 0.212462 0.257733 0.215407 0.255946 0.207845 0.255971 0.206664 0.111195 0.03646188 0.09822797 0.389906 0.111204 0.407595 0.257008 0.2160159 0.256318 0.212462 0.255946 0.207845 0.257733 0.215407 0.257008 0.2160159 0.255946 0.207845 0.25816 0.214798 0.255971 0.206664 0.255614 0.2054809 0.25816 0.214798 0.257733 0.215407 0.255971 0.206664 0.254599 0.203849 0.254793 0.204252 0.255614 0.2054809 0.258226 0.214177 0.255614 0.2054809 0.254793 0.204252 0.258226 0.214177 0.25816 0.214798 0.255614 0.2054809 0.254788 0.204243 0.254793 0.204252 0.254599 0.203849 0.258226 0.214177 0.254793 0.204252 0.25501 0.204712 0.254281 0.203195 0.253969 0.202552 0.252683 0.199944 0.25197 0.1985239 0.252683 0.199944 0.251209 0.196991 0.25197 0.1985239 0.254281 0.203195 0.252683 0.199944 0.25197 0.1985239 0.251209 0.196991 0.249539 0.193686 0.249483 0.193604 0.249539 0.193686 0.2477149 0.190126 0.25197 0.1985239 0.249539 0.193686 0.249483 0.193604 0.239336 0.174377 0.2457489 0.186343 0.2477149 0.190126 0.2469069 0.188609 0.2477149 0.190126 0.2457489 0.186343 0.237659 0.171335 0.239336 0.174377 0.2477149 0.190126 0.249483 0.193604 0.2477149 0.190126 0.2469069 0.188609 0.241584 0.1785089 0.243713 0.182485 0.2457489 0.186343 0.244278 0.183615 0.2457489 0.186343 0.243713 0.182485 0.239336 0.174377 0.241584 0.1785089 0.2457489 0.186343 0.2469069 0.188609 0.2457489 0.186343 0.244278 0.183615 0.241598 0.178625 0.243713 0.182485 0.241584 0.1785089 0.244278 0.183615 0.243713 0.182485 0.241598 0.178625 0.241598 0.178625 0.241584 0.1785089 0.239336 0.174377 0.238878 0.173659 0.239336 0.174377 0.237659 0.171335 0.241598 0.178625 0.239336 0.174377 0.238878 0.173659 0.238878 0.173659 0.237659 0.171335 0.236119 0.16872 0.245899 0.148493 0.2377949 0.135298 0.241155 0.146728 0.245899 0.148493 0.242647 0.1367239 0.2377949 0.135298 0.2497799 0.162427 0.241155 0.146728 0.244902 0.159786 0.2497799 0.162427 0.245899 0.148493 0.241155 0.146728 0.254046 0.178382 0.244902 0.159786 0.248866 0.174365 0.254046 0.178382 0.2497799 0.162427 0.244902 0.159786 0.251148 0.145305 0.242647 0.1367239 0.245899 0.148493 0.251148 0.145305 0.248914 0.136081 0.242647 0.1367239 0.254158 0.156482 0.245899 0.148493 0.2497799 0.162427 0.254158 0.156482 0.251148 0.145305 0.245899 0.148493 0.257788 0.169569 0.2497799 0.162427 0.254046 0.178382 0.257788 0.169569 0.254158 0.156482 0.2497799 0.162427 0.261818 0.18442 0.257788 0.169569 0.254046 0.178382 0.2585 0.143094 0.248914 0.136081 0.251148 0.145305 0.2585 0.143094 0.257303 0.135936 0.248914 0.136081 0.260573 0.151974 0.251148 0.145305 0.254158 0.156482 0.260573 0.151974 0.2585 0.143094 0.251148 0.145305 0.263465 0.162627 0.254158 0.156482 0.257788 0.169569 0.263465 0.162627 0.260573 0.151974 0.254158 0.156482 0.267037 0.1750079 0.257788 0.169569 0.261818 0.18442 0.267037 0.1750079 0.263465 0.162627 0.257788 0.169569 0.271082 0.1889809 0.267037 0.1750079 0.261818 0.18442 0.276426 0.2115769 0.277088 0.214731 0.287644 0.214398 0.288022 0.215489 0.287644 0.214398 0.277088 0.214731 0.286996 0.212124 0.276426 0.2115769 0.287644 0.214398 0.334048 0.213281 0.286996 0.212124 0.287644 0.214398 0.288022 0.215489 0.334048 0.213281 0.287644 0.214398 0.276426 0.2115769 0.268335 0.214374 0.277088 0.214731 0.277405 0.216055 0.277088 0.214731 0.268335 0.214374 0.277405 0.216055 0.288022 0.215489 0.277088 0.214731 0.267558 0.210166 0.261668 0.213309 0.268335 0.214374 0.268672 0.216116 0.268335 0.214374 0.261668 0.213309 0.276426 0.2115769 0.267558 0.210166 0.268335 0.214374 0.277405 0.216055 0.268335 0.214374 0.268672 0.216116 0.260667 0.207889 0.257351 0.211529 0.261668 0.213309 0.262073 0.21554 0.261668 0.213309 0.257351 0.211529 0.267558 0.210166 0.260667 0.207889 0.261668 0.213309 0.268672 0.216116 0.261668 0.213309 0.262073 0.21554 0.260667 0.207889 0.256006 0.204764 0.257351 0.211529 0.262073 0.21554 0.257351 0.211529 0.257876 0.214314 0.259688 0.202706 0.256006 0.204764 0.260667 0.207889 0.259688 0.202706 0.254641 0.198306 0.256006 0.204764 0.266867 0.206137 0.260667 0.207889 0.267558 0.210166 0.266867 0.206137 0.259688 0.202706 0.260667 0.207889 0.275928 0.208559 0.267558 0.210166 0.276426 0.2115769 0.275928 0.208559 0.266867 0.206137 0.267558 0.210166 0.275928 0.208559 0.276426 0.2115769 0.286996 0.212124 0.275928 0.208559 0.286996 0.212124 0.286603 0.209957 0.332162 0.208079 0.286603 0.209957 0.286996 0.212124 0.334048 0.213281 0.332162 0.208079 0.286996 0.212124 0.332162 0.208079 0.332073 0.207892 0.286603 0.209957 0.336248 0.208065 0.332073 0.207892 0.332162 0.208079 0.336248 0.208065 0.332162 0.208079 0.334048 0.213281 0.288384 0.216458 0.334991 0.2190459 0.334048 0.213281 0.288022 0.215489 0.288384 0.216458 0.334048 0.213281 0.09815096 0.05426889 0.08652597 0.365936 0.09822797 0.389906 0.289253 0.224368 0.334995 0.2249619 0.334991 0.2190459 0.289314 0.223917 0.289253 0.224368 0.334991 0.2190459 0.289371 0.220603 0.289314 0.223917 0.334991 0.2190459 0.289316 0.220146 0.289371 0.220603 0.334991 0.2190459 0.288384 0.216458 0.289316 0.220146 0.334991 0.2190459 0.287644 0.2296479 0.334049 0.230758 0.334995 0.2249619 0.287983 0.228667 0.287644 0.2296479 0.334995 0.2249619 0.08641898 0.07837396 0.07669895 0.336237 0.08652597 0.365936 0.288384 0.2275879 0.287983 0.228667 0.334995 0.2249619 0.289253 0.224368 0.288384 0.2275879 0.334995 0.2249619 0.286604 0.2340829 0.332162 0.235967 0.334049 0.230758 0.286997 0.231919 0.286604 0.2340829 0.334049 0.230758 0.287644 0.2296479 0.286997 0.231919 0.334049 0.230758 0.286492 0.2361299 0.332073 0.236153 0.332162 0.235967 0.336047 0.2363229 0.332162 0.235967 0.332073 0.236153 0.286604 0.2340829 0.286492 0.2361299 0.332162 0.235967 0.336047 0.2363229 0.336248 0.235981 0.332162 0.235967 0.286492 0.2361299 0.331979 0.2363319 0.332073 0.236153 0.336047 0.2363229 0.332073 0.236153 0.331979 0.2363319 0.286345 0.236744 0.331979 0.2363319 0.286492 0.2361299 0.331728 0.236961 0.336047 0.2363229 0.331979 0.2363319 0.331728 0.236961 0.331979 0.2363319 0.286345 0.236744 0.275929 0.2354789 0.286492 0.2361299 0.286604 0.2340829 0.275929 0.2354789 0.275628 0.2383199 0.286492 0.2361299 0.286345 0.236744 0.286492 0.2361299 0.275628 0.2383199 0.276427 0.232465 0.286604 0.2340829 0.286997 0.231919 0.276427 0.232465 0.275929 0.2354789 0.286604 0.2340829 0.277088 0.2293159 0.286997 0.231919 0.287644 0.2296479 0.276427 0.232465 0.286997 0.231919 0.277088 0.2293159 0.277419 0.227939 0.287644 0.2296479 0.287983 0.228667 0.277419 0.227939 0.277088 0.2293159 0.287644 0.2296479 0.06909996 0.1430799 0.06915998 0.30132 0.07660299 0.108164 0.277794 0.226585 0.287983 0.228667 0.288384 0.2275879 0.277419 0.227939 0.287983 0.228667 0.277794 0.226585 0.278403 0.223542 0.288384 0.2275879 0.289253 0.224368 0.278403 0.223542 0.277794 0.226585 0.288384 0.2275879 0.278403 0.223542 0.289253 0.224368 0.289314 0.223917 0.2784 0.220473 0.289314 0.223917 0.289371 0.220603 0.2784 0.220473 0.278403 0.223542 0.289314 0.223917 0.2784 0.220473 0.289371 0.220603 0.289316 0.220146 0.277794 0.217461 0.289316 0.220146 0.288384 0.216458 0.2784 0.220473 0.289316 0.220146 0.277794 0.217461 0.277794 0.217461 0.288384 0.216458 0.288022 0.215489 0.07660299 0.108164 0.07669895 0.336237 0.08641898 0.07837396 0.277405 0.216055 0.277794 0.217461 0.288022 0.215489 0.331728 0.236961 0.340129 0.236353 0.336047 0.2363229 0.331728 0.236961 0.339868 0.236832 0.340129 0.236353 0.348012 0.237776 0.355014 0.237646 0.355522 0.236652 0.359746 0.238272 0.355522 0.236652 0.355014 0.237646 0.340871 0.2379119 0.348012 0.237776 0.355522 0.236652 0.340514 0.237801 0.340871 0.2379119 0.355522 0.236652 0.340249 0.237705 0.340514 0.237801 0.355522 0.236652 0.340062 0.237623 0.340249 0.237705 0.355522 0.236652 0.339938 0.237556 0.340062 0.237623 0.355522 0.236652 0.339806 0.237457 0.339938 0.237556 0.355522 0.236652 0.339738 0.237303 0.339806 0.237457 0.355522 0.236652 0.339868 0.236832 0.339738 0.237303 0.355522 0.236652 0.341868 0.240244 0.355014 0.237646 0.348012 0.237776 0.353639 0.248726 0.359746 0.238272 0.355014 0.237646 0.350405 0.247406 0.353639 0.248726 0.355014 0.237646 0.343167 0.246854 0.350405 0.247406 0.355014 0.237646 0.342632 0.243192 0.343167 0.246854 0.355014 0.237646 0.341868 0.240244 0.342632 0.243192 0.355014 0.237646 0.341868 0.240244 0.348012 0.237776 0.340871 0.2379119 0.335526 0.239504 0.340871 0.2379119 0.340514 0.237801 0.335862 0.243419 0.341868 0.240244 0.340871 0.2379119 0.335526 0.239504 0.335862 0.243419 0.340871 0.2379119 0.330282 0.240548 0.340514 0.237801 0.340249 0.237705 0.330214 0.241178 0.335526 0.239504 0.340514 0.237801 0.330282 0.240548 0.330214 0.241178 0.340514 0.237801 0.330411 0.239929 0.340249 0.237705 0.340062 0.237623 0.330282 0.240548 0.340249 0.237705 0.330411 0.239929 0.330603 0.23932 0.340062 0.237623 0.339938 0.237556 0.330411 0.239929 0.340062 0.237623 0.330603 0.23932 0.330853 0.238723 0.339938 0.237556 0.339806 0.237457 0.330603 0.23932 0.339938 0.237556 0.330853 0.238723 0.330853 0.238723 0.339806 0.237457 0.339738 0.237303 0.335613 0.237412 0.339738 0.237303 0.339868 0.236832 0.335613 0.237412 0.330853 0.238723 0.339738 0.237303 0.331728 0.236961 0.331521 0.23758 0.339868 0.236832 0.335613 0.237412 0.339868 0.236832 0.331521 0.23758 0.359746 0.238272 0.366225 0.237448 0.36081 0.236318 0.36648 0.23233 0.36081 0.236318 0.366225 0.237448 0.361822 0.231777 0.36081 0.236318 0.36648 0.23233 0.370617 0.24133 0.372024 0.239107 0.366225 0.237448 0.371489 0.233159 0.366225 0.237448 0.372024 0.239107 0.365005 0.239515 0.370617 0.24133 0.366225 0.237448 0.359746 0.238272 0.365005 0.239515 0.366225 0.237448 0.36648 0.23233 0.366225 0.237448 0.371489 0.233159 0.376398 0.243654 0.378011 0.2412379 0.372024 0.239107 0.376732 0.2342399 0.372024 0.239107 0.378011 0.2412379 0.370617 0.24133 0.376398 0.243654 0.372024 0.239107 0.371489 0.233159 0.372024 0.239107 0.376732 0.2342399 0.376732 0.2342399 0.378011 0.2412379 0.382089 0.23555 0.36643 0.25165 0.376398 0.243654 0.370617 0.24133 0.36643 0.25165 0.370912 0.253366 0.376398 0.243654 0.362003 0.250287 0.370617 0.24133 0.365005 0.239515 0.362003 0.250287 0.36643 0.25165 0.370617 0.24133 0.357713 0.249306 0.365005 0.239515 0.359746 0.238272 0.357713 0.249306 0.362003 0.250287 0.365005 0.239515 0.353639 0.248726 0.357713 0.249306 0.359746 0.238272 0.382089 0.23555 0.384004 0.228925 0.378415 0.228248 0.376732 0.2342399 0.378415 0.228248 0.372958 0.227692 0.376732 0.2342399 0.382089 0.23555 0.378415 0.228248 0.371489 0.233159 0.372958 0.227692 0.367761 0.22727 0.371489 0.233159 0.376732 0.2342399 0.372958 0.227692 0.36648 0.23233 0.367761 0.22727 0.362947 0.226994 0.36648 0.23233 0.371489 0.233159 0.367761 0.22727 0.361822 0.231777 0.36648 0.23233 0.362947 0.226994 0.364722 0.262125 0.370912 0.253366 0.36643 0.25165 0.360586 0.260737 0.36643 0.25165 0.362003 0.250287 0.360586 0.260737 0.364722 0.262125 0.36643 0.25165 0.356488 0.259695 0.362003 0.250287 0.357713 0.249306 0.356488 0.259695 0.360586 0.260737 0.362003 0.250287 0.352491 0.259018 0.357713 0.249306 0.353639 0.248726 0.352491 0.259018 0.356488 0.259695 0.357713 0.249306 0.350405 0.247406 0.349888 0.248507 0.353639 0.248726 0.348658 0.258718 0.353639 0.248726 0.349888 0.248507 0.348658 0.258718 0.352491 0.259018 0.353639 0.248726 0.343406 0.25081 0.349888 0.248507 0.350405 0.247406 0.348658 0.258718 0.349888 0.248507 0.345558 0.257713 0.3433 0.254531 0.345558 0.257713 0.349888 0.248507 0.343406 0.25081 0.3433 0.254531 0.349888 0.248507 0.343167 0.246854 0.343406 0.25081 0.350405 0.247406 0.345078 0.258753 0.348658 0.258718 0.345558 0.257713 0.34284 0.258543 0.345078 0.258753 0.345558 0.257713 0.3433 0.254531 0.34284 0.258543 0.345558 0.257713 0.357007 0.269736 0.364722 0.262125 0.360586 0.260737 0.357007 0.269736 0.359847 0.27062 0.364722 0.262125 0.354167 0.269028 0.360586 0.260737 0.356488 0.259695 0.354167 0.269028 0.357007 0.269736 0.360586 0.260737 0.351347 0.268502 0.356488 0.259695 0.352491 0.259018 0.351347 0.268502 0.354167 0.269028 0.356488 0.259695 0.345852 0.26802 0.352491 0.259018 0.348658 0.258718 0.348568 0.268166 0.351347 0.268502 0.352491 0.259018 0.345852 0.26802 0.348568 0.268166 0.352491 0.259018 0.343218 0.268066 0.348658 0.258718 0.345078 0.258753 0.343218 0.268066 0.345852 0.26802 0.348658 0.258718 0.343218 0.268066 0.345078 0.258753 0.340687 0.268305 0.341596 0.264856 0.340687 0.268305 0.345078 0.258753 0.34231 0.261596 0.341596 0.264856 0.345078 0.258753 0.34284 0.258543 0.34231 0.261596 0.345078 0.258753 0.341214 0.27534 0.343218 0.268066 0.340687 0.268305 0.326242 0.269299 0.340687 0.268305 0.341596 0.264856 0.3392 0.27155 0.340687 0.268305 0.326242 0.269299 0.341214 0.27534 0.340687 0.268305 0.3392 0.27155 0.353618 0.276597 0.359847 0.27062 0.357007 0.269736 0.353618 0.276597 0.357007 0.269736 0.354167 0.269028 0.349413 0.275747 0.354167 0.269028 0.351347 0.268502 0.349413 0.275747 0.353618 0.276597 0.354167 0.269028 0.345257 0.275325 0.351347 0.268502 0.348568 0.268166 0.345257 0.275325 0.349413 0.275747 0.351347 0.268502 0.345257 0.275325 0.348568 0.268166 0.345852 0.26802 0.341214 0.27534 0.345852 0.26802 0.343218 0.268066 0.341214 0.27534 0.345257 0.275325 0.345852 0.26802 0.328492 0.265112 0.341596 0.264856 0.34231 0.261596 0.328492 0.265112 0.326242 0.269299 0.341596 0.264856 0.330581 0.260832 0.34231 0.261596 0.34284 0.258543 0.330581 0.260832 0.328492 0.265112 0.34231 0.261596 0.332467 0.256477 0.34284 0.258543 0.3433 0.254531 0.332467 0.256477 0.330581 0.260832 0.34284 0.258543 0.334077 0.252076 0.3433 0.254531 0.343406 0.25081 0.334077 0.252076 0.332467 0.256477 0.3433 0.254531 0.334077 0.252076 0.343406 0.25081 0.343167 0.246854 0.335273 0.247689 0.343167 0.246854 0.342632 0.243192 0.335273 0.247689 0.334077 0.252076 0.343167 0.246854 0.335862 0.243419 0.342632 0.243192 0.341868 0.240244 0.335862 0.243419 0.335273 0.247689 0.342632 0.243192 0.319128 0.302308 0.299489 0.303857 0.296732 0.306403 0.278192 0.308804 0.296732 0.306403 0.299489 0.303857 0.316415 0.304629 0.319128 0.302308 0.296732 0.306403 0.321727 0.299857 0.302281 0.301125 0.299489 0.303857 0.280606 0.306411 0.299489 0.303857 0.302281 0.301125 0.319128 0.302308 0.321727 0.299857 0.299489 0.303857 0.280606 0.306411 0.278192 0.308804 0.299489 0.303857 0.324217 0.29728 0.305087 0.298213 0.302281 0.301125 0.283024 0.303963 0.302281 0.301125 0.305087 0.298213 0.321727 0.299857 0.324217 0.29728 0.302281 0.301125 0.283024 0.303963 0.280606 0.306411 0.302281 0.301125 0.326588 0.294585 0.307891 0.295128 0.305087 0.298213 0.287815 0.298984 0.305087 0.298213 0.307891 0.295128 0.324217 0.29728 0.326588 0.294585 0.305087 0.298213 0.285445 0.301479 0.283024 0.303963 0.305087 0.298213 0.287815 0.298984 0.285445 0.301479 0.305087 0.298213 0.328818 0.291783 0.310677 0.291875 0.307891 0.295128 0.290143 0.296496 0.307891 0.295128 0.310677 0.291875 0.326588 0.294585 0.328818 0.291783 0.307891 0.295128 0.290143 0.296496 0.287815 0.298984 0.307891 0.295128 0.330899 0.288882 0.313431 0.288464 0.310677 0.291875 0.292435 0.293998 0.310677 0.291875 0.313431 0.288464 0.328818 0.291783 0.330899 0.288882 0.310677 0.291875 0.292435 0.293998 0.290143 0.296496 0.310677 0.291875 0.332836 0.285888 0.316139 0.2849 0.313431 0.288464 0.296915 0.28899 0.313431 0.288464 0.316139 0.2849 0.330899 0.288882 0.332836 0.285888 0.313431 0.288464 0.294699 0.291489 0.292435 0.293998 0.313431 0.288464 0.296915 0.28899 0.294699 0.291489 0.313431 0.288464 0.299076 0.286513 0.316139 0.2849 0.318789 0.281193 0.299076 0.286513 0.296915 0.28899 0.316139 0.2849 0.335927 0.279297 0.321366 0.277351 0.318789 0.281193 0.303195 0.281681 0.318789 0.281193 0.321366 0.277351 0.301177 0.284069 0.299076 0.286513 0.318789 0.281193 0.303195 0.281681 0.301177 0.284069 0.318789 0.281193 0.337514 0.275406 0.323857 0.273383 0.321366 0.277351 0.307007 0.27708 0.321366 0.277351 0.323857 0.273383 0.337355 0.275781 0.337514 0.275406 0.321366 0.277351 0.335927 0.279297 0.337355 0.275781 0.321366 0.277351 0.305139 0.279354 0.303195 0.281681 0.321366 0.277351 0.307007 0.27708 0.305139 0.279354 0.321366 0.277351 0.3392 0.27155 0.326242 0.269299 0.323857 0.273383 0.308803 0.274869 0.323857 0.273383 0.326242 0.269299 0.337514 0.275406 0.3392 0.27155 0.323857 0.273383 0.308803 0.274869 0.307007 0.27708 0.323857 0.273383 0.313767 0.268577 0.326242 0.269299 0.328492 0.265112 0.310528 0.272713 0.308803 0.274869 0.326242 0.269299 0.313767 0.268577 0.310528 0.272713 0.326242 0.269299 0.316874 0.26448 0.328492 0.265112 0.330581 0.260832 0.316874 0.26448 0.313767 0.268577 0.328492 0.265112 0.319763 0.260533 0.330581 0.260832 0.332467 0.256477 0.319763 0.260533 0.316874 0.26448 0.330581 0.260832 0.322349 0.256847 0.332467 0.256477 0.334077 0.252076 0.322349 0.256847 0.319763 0.260533 0.332467 0.256477 0.326912 0.249653 0.334077 0.252076 0.335273 0.247689 0.324737 0.253242 0.322349 0.256847 0.334077 0.252076 0.326912 0.249653 0.324737 0.253242 0.334077 0.252076 0.328661 0.246302 0.335273 0.247689 0.335862 0.243419 0.328661 0.246302 0.326912 0.249653 0.335273 0.247689 0.329777 0.243463 0.335862 0.243419 0.335526 0.239504 0.329777 0.243463 0.328661 0.246302 0.335862 0.243419 0.330214 0.241178 0.329777 0.243463 0.335526 0.239504 0.341214 0.27534 0.3392 0.27155 0.337514 0.275406 0.341214 0.27534 0.337514 0.275406 0.337355 0.275781 0.267841 0.309791 0.278192 0.308804 0.280606 0.306411 0.267638 0.306984 0.280606 0.306411 0.283024 0.303963 0.267638 0.306984 0.267841 0.309791 0.280606 0.306411 0.267725 0.303748 0.283024 0.303963 0.285445 0.301479 0.267725 0.303748 0.267638 0.306984 0.283024 0.303963 0.267725 0.303748 0.285445 0.301479 0.287815 0.298984 0.268098 0.300064 0.287815 0.298984 0.290143 0.296496 0.268098 0.300064 0.267725 0.303748 0.287815 0.298984 0.268098 0.300064 0.290143 0.296496 0.292435 0.293998 0.268098 0.300064 0.292435 0.293998 0.294699 0.291489 0.269755 0.291316 0.294699 0.291489 0.296915 0.28899 0.269755 0.291316 0.268098 0.300064 0.294699 0.291489 0.269755 0.291316 0.296915 0.28899 0.299076 0.286513 0.269755 0.291316 0.299076 0.286513 0.301177 0.284069 0.269755 0.291316 0.301177 0.284069 0.303195 0.281681 0.272632 0.280493 0.303195 0.281681 0.305139 0.279354 0.272632 0.280493 0.269755 0.291316 0.303195 0.281681 0.272632 0.280493 0.305139 0.279354 0.307007 0.27708 0.272632 0.280493 0.307007 0.27708 0.308803 0.274869 0.272632 0.280493 0.308803 0.274869 0.310528 0.272713 0.272632 0.280493 0.310528 0.272713 0.313767 0.268577 0.276546 0.267631 0.313767 0.268577 0.316874 0.26448 0.276546 0.267631 0.272632 0.280493 0.313767 0.268577 0.276546 0.267631 0.316874 0.26448 0.319763 0.260533 0.276546 0.267631 0.319763 0.260533 0.322349 0.256847 0.276546 0.267631 0.322349 0.256847 0.324737 0.253242 0.281175 0.253168 0.324737 0.253242 0.326912 0.249653 0.281175 0.253168 0.276546 0.267631 0.324737 0.253242 0.281175 0.253168 0.326912 0.249653 0.328661 0.246302 0.281175 0.253168 0.328661 0.246302 0.329777 0.243463 0.281175 0.253168 0.329777 0.243463 0.330214 0.241178 0.330282 0.240548 0.281175 0.253168 0.330214 0.241178 0.257303 0.308111 0.267725 0.303748 0.268098 0.300064 0.258499 0.300955 0.268098 0.300064 0.269755 0.291316 0.258499 0.300955 0.257303 0.308111 0.268098 0.300064 0.260571 0.292079 0.269755 0.291316 0.272632 0.280493 0.260571 0.292079 0.258499 0.300955 0.269755 0.291316 0.263461 0.281431 0.272632 0.280493 0.276546 0.267631 0.263461 0.281431 0.260571 0.292079 0.272632 0.280493 0.267031 0.269055 0.276546 0.267631 0.281175 0.253168 0.267031 0.269055 0.263461 0.281431 0.276546 0.267631 0.331521 0.23758 0.286184 0.237353 0.281175 0.253168 0.271074 0.255091 0.281175 0.253168 0.286184 0.237353 0.330853 0.238723 0.331521 0.23758 0.281175 0.253168 0.330603 0.23932 0.330853 0.238723 0.281175 0.253168 0.330411 0.239929 0.330603 0.23932 0.281175 0.253168 0.330282 0.240548 0.330411 0.239929 0.281175 0.253168 0.271074 0.255091 0.267031 0.269055 0.281175 0.253168 0.331728 0.236961 0.286184 0.237353 0.331521 0.23758 0.275357 0.239697 0.271074 0.255091 0.286184 0.237353 0.275628 0.2383199 0.275357 0.239697 0.286184 0.237353 0.286345 0.236744 0.275628 0.2383199 0.286184 0.237353 0.331728 0.236961 0.286345 0.236744 0.286184 0.237353 0.335613 0.237412 0.331521 0.23758 0.330853 0.238723 0.248913 0.307968 0.257303 0.308111 0.258499 0.300955 0.251147 0.298747 0.258499 0.300955 0.260571 0.292079 0.251147 0.298747 0.248913 0.307968 0.258499 0.300955 0.254154 0.287576 0.260571 0.292079 0.263461 0.281431 0.254154 0.287576 0.251147 0.298747 0.260571 0.292079 0.257783 0.274494 0.263461 0.281431 0.267031 0.269055 0.257783 0.274494 0.254154 0.287576 0.263461 0.281431 0.261811 0.259654 0.267031 0.269055 0.271074 0.255091 0.261811 0.259654 0.257783 0.274494 0.267031 0.269055 0.261811 0.259654 0.271074 0.255091 0.275357 0.239697 0.265986 0.243235 0.261811 0.259654 0.275357 0.239697 0.275628 0.2383199 0.265986 0.243235 0.275357 0.239697 0.242646 0.307325 0.248913 0.307968 0.251147 0.298747 0.245895 0.295563 0.251147 0.298747 0.254154 0.287576 0.245895 0.295563 0.242646 0.307325 0.251147 0.298747 0.249776 0.281634 0.254154 0.287576 0.257783 0.274494 0.249776 0.281634 0.245895 0.295563 0.254154 0.287576 0.254039 0.265692 0.257783 0.274494 0.261811 0.259654 0.254039 0.265692 0.249776 0.281634 0.257783 0.274494 0.254039 0.265692 0.261811 0.259654 0.265986 0.243235 0.258405 0.2479349 0.254039 0.265692 0.265986 0.243235 0.266293 0.241697 0.258405 0.2479349 0.265986 0.243235 0.266293 0.241697 0.265986 0.243235 0.275628 0.2383199 0.237793 0.308753 0.242646 0.307325 0.245895 0.295563 0.241152 0.297328 0.245895 0.295563 0.249776 0.281634 0.241152 0.297328 0.237793 0.308753 0.245895 0.295563 0.244897 0.284277 0.249776 0.281634 0.254039 0.265692 0.244897 0.284277 0.241152 0.297328 0.249776 0.281634 0.248858 0.26971 0.254039 0.265692 0.258405 0.2479349 0.248858 0.26971 0.244897 0.284277 0.254039 0.265692 0.252858 0.253736 0.248858 0.26971 0.258405 0.2479349 0.258762 0.2462199 0.252858 0.253736 0.258405 0.2479349 0.258762 0.2462199 0.258405 0.2479349 0.266293 0.241697 0.235621 0.308344 0.237793 0.308753 0.241152 0.297328 0.239935 0.294503 0.241152 0.297328 0.244897 0.284277 0.239935 0.294503 0.235621 0.308344 0.241152 0.297328 0.2446449 0.278564 0.244897 0.284277 0.248858 0.26971 0.2401379 0.293835 0.239935 0.294503 0.244897 0.284277 0.2446449 0.278564 0.2401379 0.293835 0.244897 0.284277 0.2483 0.265321 0.248858 0.26971 0.252858 0.253736 0.2483 0.265321 0.2446449 0.278564 0.248858 0.26971 0.2495599 0.26053 0.2483 0.265321 0.252858 0.253736 0.249832 0.259468 0.2495599 0.26053 0.252858 0.253736 0.249832 0.259468 0.252858 0.253736 0.250107 0.258396 0.253293 0.25182 0.250107 0.258396 0.252858 0.253736 0.253293 0.25182 0.252858 0.253736 0.258762 0.2462199 0.226215 0.324308 0.239935 0.294503 0.2401379 0.293835 0.236814 0.296671 0.2401379 0.293835 0.2446449 0.278564 0.236814 0.296671 0.226215 0.324308 0.2401379 0.293835 0.236814 0.296671 0.2446449 0.278564 0.2483 0.265321 0.246849 0.267105 0.2483 0.265321 0.2495599 0.26053 0.246849 0.267105 0.236814 0.296671 0.2483 0.265321 0.249832 0.259468 0.246849 0.267105 0.2495599 0.26053 0.236814 0.296671 0.220017 0.328373 0.226215 0.324308 0.2328169 0.299729 0.212607 0.332758 0.220017 0.328373 0.236814 0.296671 0.2328169 0.299729 0.220017 0.328373 0.228 0.302994 0.203694 0.33752 0.212607 0.332758 0.2328169 0.299729 0.228 0.302994 0.212607 0.332758 0.228 0.302994 0.222189 0.306503 0.203694 0.33752 0.242538 0.271266 0.222189 0.306503 0.228 0.302994 0.242538 0.271266 0.2395409 0.273517 0.222189 0.306503 0.244943 0.269136 0.228 0.302994 0.2328169 0.299729 0.244943 0.269136 0.242538 0.271266 0.228 0.302994 0.246849 0.267105 0.2328169 0.299729 0.236814 0.296671 0.246849 0.267105 0.244943 0.269136 0.2328169 0.299729 0.255615 0.238557 0.2395409 0.273517 0.242538 0.271266 0.254375 0.240661 0.254167 0.241088 0.2395409 0.273517 0.254586 0.240225 0.254375 0.240661 0.2395409 0.273517 0.254793 0.239794 0.254586 0.240225 0.2395409 0.273517 0.255615 0.238557 0.254793 0.239794 0.2395409 0.273517 0.255973 0.23737 0.242538 0.271266 0.244943 0.269136 0.255973 0.23737 0.255615 0.238557 0.242538 0.271266 0.255947 0.236191 0.244943 0.269136 0.246849 0.267105 0.255947 0.236191 0.255973 0.23737 0.244943 0.269136 0.255611 0.235 0.255947 0.236191 0.246849 0.267105 0.253557 0.244268 0.255611 0.235 0.246849 0.267105 0.252554 0.248529 0.253557 0.244268 0.246849 0.267105 0.251949 0.251031 0.252554 0.248529 0.246849 0.267105 0.250107 0.258396 0.251949 0.251031 0.246849 0.267105 0.249832 0.259468 0.250107 0.258396 0.246849 0.267105 0.258226 0.229869 0.254793 0.239794 0.255615 0.238557 0.255212 0.238892 0.25479 0.239799 0.254793 0.239794 0.258226 0.229869 0.255212 0.238892 0.254793 0.239794 0.258161 0.229249 0.255615 0.238557 0.255973 0.23737 0.258161 0.229249 0.258226 0.229869 0.255615 0.238557 0.257734 0.22864 0.255973 0.23737 0.255947 0.236191 0.257734 0.22864 0.258161 0.229249 0.255973 0.23737 0.256267 0.231835 0.255947 0.236191 0.255611 0.235 0.256324 0.231552 0.257008 0.22803 0.255947 0.236191 0.257734 0.22864 0.255947 0.236191 0.257008 0.22803 0.256324 0.231552 0.255947 0.236191 0.256267 0.231835 0.256007 0.239273 0.255611 0.235 0.253557 0.244268 0.256267 0.231835 0.255611 0.235 0.257351 0.232517 0.256007 0.239273 0.257351 0.232517 0.255611 0.235 0.254644 0.245724 0.253557 0.244268 0.252554 0.248529 0.256007 0.239273 0.253557 0.244268 0.254644 0.245724 0.254644 0.245724 0.252554 0.248529 0.251949 0.251031 0.253293 0.25182 0.251949 0.251031 0.250107 0.258396 0.254644 0.245724 0.251949 0.251031 0.253293 0.25182 0.256343 0.236052 0.255839 0.237399 0.255951 0.237115 0.257866 0.230526 0.255951 0.237115 0.255785 0.237536 0.256343 0.236052 0.255951 0.237115 0.257866 0.230526 0.257866 0.230526 0.255785 0.237536 0.255606 0.237976 0.258226 0.229869 0.255606 0.237976 0.255212 0.238892 0.258226 0.229869 0.257866 0.230526 0.255606 0.237976 0.258708 0.222023 0.257857 0.230565 0.257866 0.230526 0.257353 0.232755 0.257866 0.230526 0.257626 0.231642 0.257047 0.233868 0.257866 0.230526 0.257353 0.232755 0.256709 0.23497 0.257866 0.230526 0.257047 0.233868 0.256343 0.236052 0.257866 0.230526 0.256709 0.23497 0.258226 0.229869 0.258708 0.222023 0.257866 0.230526 0.257629 0.212417 0.257857 0.213481 0.257866 0.21352 0.258991 0.222023 0.257866 0.21352 0.258708 0.222023 0.258226 0.214177 0.257629 0.212417 0.257866 0.21352 0.258991 0.222023 0.258226 0.214177 0.257866 0.21352 0.258991 0.222023 0.258708 0.222023 0.258226 0.229869 0.255792 0.206525 0.255839 0.206646 0.255951 0.20693 0.258226 0.214177 0.255951 0.20693 0.256347 0.2080039 0.258226 0.214177 0.255792 0.206525 0.255951 0.20693 0.258226 0.214177 0.256347 0.2080039 0.256714 0.209093 0.258226 0.214177 0.256714 0.209093 0.257053 0.210198 0.258226 0.214177 0.257053 0.210198 0.257358 0.21131 0.258226 0.214177 0.257358 0.21131 0.257629 0.212417 0.258226 0.214177 0.25501 0.204712 0.255225 0.205184 0.258226 0.214177 0.255225 0.205184 0.255428 0.205647 0.258226 0.214177 0.255428 0.205647 0.255617 0.2060959 0.258226 0.214177 0.255617 0.2060959 0.255792 0.206525 0.172043 0.073547 0.173372 0.07673698 0.169881 0.07252097 0.168875 0.06966996 0.172043 0.073547 0.169881 0.07252097 0.175128 0.07738399 0.176831 0.08099299 0.173372 0.07673698 0.172043 0.073547 0.175128 0.07738399 0.173372 0.07673698 0.1781319 0.08117997 0.180258 0.08528697 0.176831 0.08099299 0.175128 0.07738399 0.1781319 0.08117997 0.176831 0.08099299 0.181055 0.08493298 0.1836529 0.08961898 0.180258 0.08528697 0.1781319 0.08117997 0.181055 0.08493298 0.180258 0.08528697 0.184598 0.08955895 0.187014 0.09398996 0.1836529 0.08961898 0.181055 0.08493298 0.184598 0.08955895 0.1836529 0.08961898 0.188023 0.094114 0.190343 0.09839898 0.187014 0.09398996 0.184598 0.08955895 0.188023 0.094114 0.187014 0.09398996 0.191335 0.09860098 0.193639 0.102845 0.190343 0.09839898 0.188023 0.094114 0.191335 0.09860098 0.190343 0.09839898 0.194535 0.103014 0.196901 0.107327 0.193639 0.102845 0.191335 0.09860098 0.194535 0.103014 0.193639 0.102845 0.197627 0.107352 0.200129 0.111846 0.196901 0.107327 0.194535 0.103014 0.197627 0.107352 0.196901 0.107327 0.200617 0.111617 0.203323 0.116401 0.200129 0.111846 0.197627 0.107352 0.200617 0.111617 0.200129 0.111846 0.206297 0.119925 0.206483 0.120992 0.203323 0.116401 0.2035059 0.11581 0.206297 0.119925 0.203323 0.116401 0.200617 0.111617 0.2035059 0.11581 0.203323 0.116401 0.208992 0.12396 0.209608 0.125618 0.206483 0.120992 0.206297 0.119925 0.208992 0.12396 0.206483 0.120992 0.211591 0.1279129 0.212698 0.130278 0.209608 0.125618 0.208992 0.12396 0.211591 0.1279129 0.209608 0.125618 0.2140949 0.13178 0.215753 0.134972 0.212698 0.130278 0.211591 0.1279129 0.2140949 0.13178 0.212698 0.130278 0.216511 0.135565 0.218773 0.139699 0.215753 0.134972 0.2140949 0.13178 0.216511 0.135565 0.215753 0.134972 0.219601 0.140487 0.221756 0.144459 0.218773 0.139699 0.216511 0.135565 0.219601 0.140487 0.218773 0.139699 0.222541 0.145258 0.224703 0.149251 0.221756 0.144459 0.219601 0.140487 0.222541 0.145258 0.221756 0.144459 0.225349 0.149896 0.227613 0.154074 0.224703 0.149251 0.222541 0.145258 0.225349 0.149896 0.224703 0.149251 0.228034 0.154409 0.230486 0.158927 0.227613 0.154074 0.225349 0.149896 0.228034 0.154409 0.227613 0.154074 0.233036 0.163027 0.233322 0.163809 0.230486 0.158927 0.230596 0.158788 0.233036 0.163027 0.230486 0.158927 0.228034 0.154409 0.230596 0.158788 0.230486 0.158927 0.235357 0.167123 0.236119 0.16872 0.233322 0.163809 0.233036 0.163027 0.235357 0.167123 0.233322 0.163809 0.2375659 0.171081 0.238878 0.173659 0.236119 0.16872 0.235357 0.167123 0.2375659 0.171081 0.236119 0.16872 0.241654 0.178567 0.241598 0.178625 0.238878 0.173659 0.239661 0.174892 0.241654 0.178567 0.238878 0.173659 0.2375659 0.171081 0.239661 0.174892 0.238878 0.173659 0.243562 0.182137 0.244278 0.183615 0.241598 0.178625 0.241654 0.178567 0.243562 0.182137 0.241598 0.178625 0.245387 0.185593 0.2469069 0.188609 0.244278 0.183615 0.243562 0.182137 0.245387 0.185593 0.244278 0.183615 0.247974 0.190578 0.249483 0.193604 0.2469069 0.188609 0.245387 0.185593 0.247974 0.190578 0.2469069 0.188609 0.25039 0.195321 0.25197 0.1985239 0.249483 0.193604 0.247974 0.190578 0.25039 0.195321 0.249483 0.193604 0.25039 0.195321 0.252599 0.199742 0.25197 0.1985239 0.2044849 0.108388 0.2035059 0.11581 0.200617 0.111617 0.2044849 0.108388 0.200617 0.111617 0.197627 0.107352 0.2044849 0.108388 0.197627 0.107352 0.194535 0.103014 0.2044849 0.108388 0.194535 0.103014 0.191335 0.09860098 0.2044849 0.108388 0.191335 0.09860098 0.188023 0.094114 0.2044849 0.108388 0.188023 0.094114 0.184598 0.08955895 0.186426 0.08204197 0.184598 0.08955895 0.181055 0.08493298 0.186426 0.08204197 0.2044849 0.108388 0.184598 0.08955895 0.186426 0.08204197 0.181055 0.08493298 0.1781319 0.08117997 0.186426 0.08204197 0.1781319 0.08117997 0.175128 0.07738399 0.186426 0.08204197 0.175128 0.07738399 0.172043 0.073547 0.186426 0.08204197 0.172043 0.073547 0.168875 0.06966996 0.08641898 0.07837396 0.08652597 0.365936 0.09815096 0.05426889 0.258419 0.217242 0.256318 0.212462 0.257008 0.2160159 0.257876 0.214314 0.256318 0.212462 0.258419 0.217242 0.257514 0.220027 0.257008 0.2160159 0.257733 0.215407 0.257514 0.220027 0.258419 0.217242 0.257008 0.2160159 0.258569 0.222023 0.257733 0.215407 0.25816 0.214798 0.257514 0.220027 0.257733 0.215407 0.257576 0.222016 0.258569 0.222023 0.257576 0.222016 0.257733 0.215407 0.06441098 0.181628 0.06442999 0.262652 0.06909996 0.1430799 0.258991 0.222023 0.25816 0.214798 0.258226 0.214177 0.258991 0.222023 0.258569 0.222023 0.25816 0.214798 0.277405 0.216055 0.269066 0.217949 0.277794 0.217461 0.2784 0.220473 0.277794 0.217461 0.269066 0.217949 0.262073 0.21554 0.262514 0.217884 0.269066 0.217949 0.269466 0.220646 0.269066 0.217949 0.262514 0.217884 0.268672 0.216116 0.262073 0.21554 0.269066 0.217949 0.277405 0.216055 0.268672 0.216116 0.269066 0.217949 0.2784 0.220473 0.269066 0.217949 0.269466 0.220646 0.257876 0.214314 0.258419 0.217242 0.262514 0.217884 0.258756 0.220398 0.262514 0.217884 0.258419 0.217242 0.262073 0.21554 0.257876 0.214314 0.262514 0.217884 0.262823 0.220624 0.262514 0.217884 0.258756 0.220398 0.269466 0.220646 0.262514 0.217884 0.262823 0.220624 0.258756 0.220398 0.258419 0.217242 0.257514 0.220027 0.278403 0.223542 0.269066 0.226097 0.277794 0.226585 0.277419 0.227939 0.277794 0.226585 0.269066 0.226097 0.262824 0.223394 0.262514 0.226162 0.269066 0.226097 0.268685 0.227862 0.269066 0.226097 0.262514 0.226162 0.269468 0.223372 0.262824 0.223394 0.269066 0.226097 0.278403 0.223542 0.269468 0.223372 0.269066 0.226097 0.277419 0.227939 0.269066 0.226097 0.268685 0.227862 0.258757 0.223616 0.258418 0.226803 0.262514 0.226162 0.257896 0.229624 0.262514 0.226162 0.258418 0.226803 0.262824 0.223394 0.258757 0.223616 0.262514 0.226162 0.262089 0.228419 0.262514 0.226162 0.257896 0.229624 0.268685 0.227862 0.262514 0.226162 0.262089 0.228419 0.257512 0.224038 0.257008 0.22803 0.258418 0.226803 0.257896 0.229624 0.258418 0.226803 0.257008 0.22803 0.258757 0.223616 0.257512 0.224038 0.258418 0.226803 0.06441098 0.181628 0.06281995 0.222023 0.06442999 0.262652 0.257734 0.22864 0.257008 0.22803 0.257512 0.224038 0.257896 0.229624 0.257008 0.22803 0.256324 0.231552 0.06909996 0.1430799 0.06442999 0.262652 0.06915998 0.30132 0.258756 0.220398 0.258757 0.223616 0.262824 0.223394 0.257576 0.222016 0.257512 0.224038 0.258757 0.223616 0.257514 0.220027 0.257576 0.222016 0.258757 0.223616 0.07660299 0.108164 0.06915998 0.30132 0.07669895 0.336237 0.258756 0.220398 0.257514 0.220027 0.258757 0.223616 0.262823 0.220624 0.262824 0.223394 0.269468 0.223372 0.262823 0.220624 0.258756 0.220398 0.262824 0.223394 0.269466 0.220646 0.269468 0.223372 0.278403 0.223542 0.269466 0.220646 0.262823 0.220624 0.269468 0.223372 0.2784 0.220473 0.269466 0.220646 0.278403 0.223542 0.258569 0.222023 0.257512 0.224038 0.257576 0.222016 0.258569 0.222023 0.257734 0.22864 0.257512 0.224038 0.277419 0.227939 0.268335 0.229672 0.277088 0.2293159 0.276427 0.232465 0.277088 0.2293159 0.268335 0.229672 0.268685 0.227862 0.261668 0.230738 0.268335 0.229672 0.267559 0.233875 0.268335 0.229672 0.261668 0.230738 0.277419 0.227939 0.268685 0.227862 0.268335 0.229672 0.276427 0.232465 0.268335 0.229672 0.267559 0.233875 0.257896 0.229624 0.257351 0.232517 0.261668 0.230738 0.260668 0.23615 0.261668 0.230738 0.257351 0.232517 0.262089 0.228419 0.257896 0.229624 0.261668 0.230738 0.268685 0.227862 0.262089 0.228419 0.261668 0.230738 0.267559 0.233875 0.261668 0.230738 0.260668 0.23615 0.256324 0.231552 0.256267 0.231835 0.257351 0.232517 0.257896 0.229624 0.256324 0.231552 0.257351 0.232517 0.260668 0.23615 0.257351 0.232517 0.256007 0.239273 0.275929 0.2354789 0.266293 0.241697 0.275628 0.2383199 0.25969 0.241327 0.258762 0.2462199 0.266293 0.241697 0.266868 0.237899 0.25969 0.241327 0.266293 0.241697 0.275929 0.2354789 0.266868 0.237899 0.266293 0.241697 0.254644 0.245724 0.253293 0.25182 0.258762 0.2462199 0.25969 0.241327 0.254644 0.245724 0.258762 0.2462199 0.256007 0.239273 0.254644 0.245724 0.25969 0.241327 0.260668 0.23615 0.25969 0.241327 0.266868 0.237899 0.260668 0.23615 0.256007 0.239273 0.25969 0.241327 0.267559 0.233875 0.266868 0.237899 0.275929 0.2354789 0.267559 0.233875 0.260668 0.23615 0.266868 0.237899 0.276427 0.232465 0.267559 0.233875 0.275929 0.2354789 0.258991 0.222023 0.258226 0.229869 0.258161 0.229249 0.258569 0.222023 0.258161 0.229249 0.257734 0.22864 0.258991 0.222023 0.258161 0.229249 0.258569 0.222023 0.36576 0.222023 0.392787 0.222023 0.392609 0.209709 0.366 0.236288 0.392787 0.222023 0.36576 0.222023 0.392611 0.234269 0.392787 0.222023 0.366 0.236288 0.366701 0.194167 0.392609 0.209709 0.392076 0.197699 0.365997 0.207836 0.392609 0.209709 0.366701 0.194167 0.36576 0.222023 0.392609 0.209709 0.365997 0.207836 0.367839 0.181545 0.392076 0.197699 0.391201 0.18632 0.366701 0.194167 0.392076 0.197699 0.367839 0.181545 0.369353 0.170467 0.391201 0.18632 0.390011 0.175916 0.367839 0.181545 0.391201 0.18632 0.369353 0.170467 0.371199 0.161169 0.390011 0.175916 0.388517 0.1666499 0.369353 0.170467 0.390011 0.175916 0.371199 0.161169 0.3733 0.153969 0.388517 0.1666499 0.386752 0.158818 0.371199 0.161169 0.388517 0.1666499 0.3733 0.153969 0.3733 0.153969 0.386752 0.158818 0.38476 0.152691 0.37557 0.149075 0.38476 0.152691 0.382587 0.148488 0.3733 0.153969 0.38476 0.152691 0.37557 0.149075 0.377925 0.146558 0.382587 0.148488 0.380288 0.146394 0.37557 0.149075 0.382587 0.148488 0.377925 0.146558 0.392083 0.246232 0.366 0.236288 0.36671 0.250008 0.392611 0.234269 0.366 0.236288 0.392083 0.246232 0.391213 0.257594 0.36671 0.250008 0.367856 0.262644 0.392083 0.246232 0.36671 0.250008 0.391213 0.257594 0.390027 0.268011 0.367856 0.262644 0.369373 0.273702 0.391213 0.257594 0.367856 0.262644 0.390027 0.268011 0.388532 0.277317 0.369373 0.273702 0.371217 0.282953 0.390027 0.268011 0.369373 0.273702 0.388532 0.277317 0.386761 0.285197 0.371217 0.282953 0.373309 0.290103 0.388532 0.277317 0.371217 0.282953 0.386761 0.285197 0.386761 0.285197 0.373309 0.290103 0.375568 0.294968 0.384758 0.291358 0.375568 0.294968 0.377915 0.297482 0.386761 0.285197 0.375568 0.294968 0.384758 0.291358 0.382577 0.295572 0.377915 0.297482 0.380275 0.297657 0.384758 0.291358 0.377915 0.297482 0.382577 0.295572 0.170462 0.201238 0.167105 0.2146919 0.162319 0.2145259 0.170462 0.201238 0.168358 0.216365 0.167758 0.215135 0.170462 0.238758 0.168868 0.235351 0.169259 0.232845 0.170462 0.238758 0.168357 0.237299 0.168868 0.235351 0.170462 0.201238 0.169506 0.229941 0.169591 0.226804 0.1734679 0.238516 0.17214 0.238623 0.1734679 0.201539 0.178842 0.202077 0.178134 0.208952 0.178134 0.202006 0.170462 0.201238 0.169591 0.226804 0.169506 0.223672 0.170462 0.201238 0.168869 0.21829 0.168358 0.216365 0.178842 0.208998 0.175015 0.238391 0.178134 0.208952 0.178842 0.202077 0.178842 0.208998 0.178134 0.208952 0.170462 0.238758 0.169259 0.232845 0.169506 0.229941 0.185954 0.230834 0.180945 0.209136 0.186177 0.209478 0.178842 0.208998 0.183957 0.230926 0.1789219 0.231157 0.185954 0.237509 0.185954 0.230834 0.186177 0.209478 0.170462 0.201238 0.167758 0.215135 0.167105 0.2146919 0.1681939 0.220779 0.168869 0.21829 0.16926 0.220779 0.1681939 0.220779 0.167801 0.21829 0.168869 0.21829 0.171088 0.2014099 0.17214 0.201406 0.17214 0.238623 0.171088 0.2014099 0.169402 0.201243 0.17214 0.201406 0.171088 0.23862 0.17214 0.238623 0.170462 0.238758 0.1684409 0.229938 0.168527 0.226803 0.169506 0.229941 0.1681939 0.232842 0.1684409 0.229938 0.169506 0.229941 0.1779029 0.231155 0.1789219 0.231157 0.183957 0.230926 0.1779029 0.238073 0.1789219 0.238076 0.1789219 0.231157 0.1779029 0.231155 0.1779029 0.238073 0.1789219 0.231157 0.182964 0.230924 0.183957 0.230926 0.178842 0.208998 0.182964 0.230924 0.1779029 0.231155 0.183957 0.230926 0.177823 0.209001 0.178842 0.208998 0.178842 0.202077 0.182964 0.230924 0.178842 0.208998 0.177823 0.209001 0.177823 0.202081 0.178842 0.202077 0.186177 0.202812 0.177823 0.209001 0.178842 0.202077 0.177823 0.202081 0.185194 0.202816 0.186177 0.202812 0.186177 0.209478 0.177823 0.202081 0.186177 0.202812 0.185194 0.202816 0.1684409 0.223671 0.16926 0.220779 0.169506 0.223672 0.1684409 0.223671 0.1681939 0.220779 0.16926 0.220779 0.166029 0.214694 0.167105 0.2146919 0.167758 0.215135 0.16122 0.214528 0.167105 0.2146919 0.166029 0.214694 0.16122 0.20043 0.162319 0.200425 0.162319 0.2145259 0.15948 0.200257 0.160588 0.2002519 0.162319 0.200425 0.16122 0.20043 0.15948 0.200257 0.162319 0.200425 0.1681939 0.232842 0.169506 0.229941 0.169259 0.232845 0.167288 0.237295 0.168868 0.235351 0.168357 0.237299 0.167288 0.237295 0.167801 0.235348 0.168868 0.235351 0.166685 0.238552 0.168357 0.237299 0.167758 0.238556 0.166685 0.238552 0.167288 0.237295 0.168357 0.237299 0.166685 0.238552 0.167758 0.238556 0.167105 0.239028 0.166029 0.2390249 0.167105 0.239028 0.160588 0.239553 0.166685 0.238552 0.167105 0.239028 0.166029 0.2390249 0.15948 0.239548 0.160588 0.239553 0.160588 0.2002519 0.166029 0.2390249 0.160588 0.239553 0.15948 0.239548 0.15948 0.239548 0.160588 0.2002519 0.15948 0.200257 0.169402 0.201243 0.170462 0.201238 0.17214 0.201406 0.169402 0.238755 0.170462 0.238758 0.170462 0.201238 0.169402 0.201243 0.169402 0.238755 0.170462 0.201238 0.185194 0.209481 0.186177 0.209478 0.180945 0.209136 0.15948 0.239548 0.15948 0.200257 0.16122 0.20043 0.16122 0.214528 0.15948 0.239548 0.16122 0.20043 0.166029 0.231697 0.166029 0.2390249 0.15948 0.239548 0.16122 0.222023 0.15948 0.239548 0.16122 0.214528 0.16122 0.222023 0.16122 0.231916 0.15948 0.239548 0.166029 0.231697 0.15948 0.239548 0.16122 0.231916 0.1665869 0.230852 0.166685 0.238552 0.166029 0.2390249 0.166416 0.231306 0.1665869 0.230852 0.166029 0.2390249 0.166231 0.231584 0.166416 0.231306 0.166029 0.2390249 0.166029 0.231697 0.166231 0.231584 0.166029 0.2390249 0.166029 0.222023 0.166029 0.214694 0.166685 0.215136 0.16122 0.222023 0.16122 0.214528 0.166029 0.214694 0.166029 0.222023 0.16122 0.222023 0.166029 0.214694 0.166737 0.223435 0.166685 0.215136 0.167287 0.2163659 0.166231 0.222126 0.166029 0.222023 0.166685 0.215136 0.166416 0.222396 0.166231 0.222126 0.166685 0.215136 0.1665869 0.222842 0.166416 0.222396 0.166685 0.215136 0.166737 0.223435 0.1665869 0.222842 0.166685 0.215136 0.167288 0.237295 0.167287 0.2163659 0.167801 0.21829 0.167008 0.227805 0.167287 0.2163659 0.167288 0.237295 0.16686 0.224157 0.166737 0.223435 0.167287 0.2163659 0.166952 0.224982 0.16686 0.224157 0.167287 0.2163659 0.167008 0.225871 0.166952 0.224982 0.167287 0.2163659 0.167029 0.226837 0.167008 0.225871 0.167287 0.2163659 0.167008 0.227805 0.167029 0.226837 0.167287 0.2163659 0.167801 0.235348 0.167801 0.21829 0.1681939 0.220779 0.167288 0.237295 0.167801 0.21829 0.167801 0.235348 0.1681939 0.232842 0.1681939 0.220779 0.1684409 0.223671 0.167801 0.235348 0.1681939 0.220779 0.1681939 0.232842 0.1684409 0.229938 0.1684409 0.223671 0.168527 0.226803 0.1681939 0.232842 0.1684409 0.223671 0.1684409 0.229938 0.167008 0.227805 0.167288 0.237295 0.166685 0.238552 0.166952 0.228696 0.167008 0.227805 0.166685 0.238552 0.16686 0.229525 0.166952 0.228696 0.166685 0.238552 0.166737 0.230253 0.16686 0.229525 0.166685 0.238552 0.1665869 0.230852 0.166737 0.230253 0.166685 0.238552 0.162319 0.231918 0.16122 0.231916 0.16122 0.222023 0.167105 0.231699 0.166029 0.231697 0.16122 0.231916 0.167105 0.231699 0.16122 0.231916 0.162319 0.231918 0.162319 0.222023 0.16122 0.222023 0.166029 0.222023 0.162319 0.222023 0.162319 0.231918 0.16122 0.222023 0.167105 0.222023 0.166029 0.222023 0.166231 0.222126 0.167105 0.222023 0.162319 0.222023 0.166029 0.222023 0.167306 0.222126 0.166231 0.222126 0.166416 0.222396 0.167105 0.222023 0.166231 0.222126 0.167306 0.222126 0.16749 0.222397 0.166416 0.222396 0.1665869 0.222842 0.167306 0.222126 0.166416 0.222396 0.16749 0.222397 0.167661 0.222843 0.1665869 0.222842 0.166737 0.223435 0.16749 0.222397 0.1665869 0.222842 0.167661 0.222843 0.16781 0.223435 0.166737 0.223435 0.16686 0.224157 0.167661 0.222843 0.166737 0.223435 0.16781 0.223435 0.167932 0.224158 0.16686 0.224157 0.166952 0.224982 0.16781 0.223435 0.16686 0.224157 0.167932 0.224158 0.168024 0.224982 0.166952 0.224982 0.167008 0.225871 0.167932 0.224158 0.166952 0.224982 0.168024 0.224982 0.168079 0.225872 0.167008 0.225871 0.167029 0.226837 0.168024 0.224982 0.167008 0.225871 0.168079 0.225872 0.1680999 0.2268379 0.167029 0.226837 0.167008 0.227805 0.168079 0.225872 0.167029 0.226837 0.1680999 0.2268379 0.168079 0.227806 0.167008 0.227805 0.166952 0.228696 0.1680999 0.2268379 0.167008 0.227805 0.168079 0.227806 0.168024 0.228698 0.166952 0.228696 0.16686 0.229525 0.168079 0.227806 0.166952 0.228696 0.168024 0.228698 0.167932 0.229526 0.16686 0.229525 0.166737 0.230253 0.168024 0.228698 0.16686 0.229525 0.167932 0.229526 0.16781 0.230255 0.166737 0.230253 0.1665869 0.230852 0.167932 0.229526 0.166737 0.230253 0.16781 0.230255 0.167661 0.230854 0.1665869 0.230852 0.166416 0.231306 0.16781 0.230255 0.1665869 0.230852 0.167661 0.230854 0.16749 0.231308 0.166416 0.231306 0.166231 0.231584 0.167661 0.230854 0.166416 0.231306 0.16749 0.231308 0.167306 0.231586 0.166231 0.231584 0.166029 0.231697 0.16749 0.231308 0.166231 0.231584 0.167306 0.231586 0.167306 0.231586 0.166029 0.231697 0.167105 0.231699 0.185194 0.202816 0.186177 0.209478 0.185194 0.209481 0.179936 0.209138 0.180945 0.209136 0.185954 0.230834 0.185194 0.209481 0.180945 0.209136 0.179936 0.209138 0.18497 0.2308329 0.185954 0.230834 0.185954 0.237509 0.179936 0.209138 0.185954 0.230834 0.18497 0.2308329 0.18497 0.237506 0.185954 0.237509 0.1789219 0.238076 0.18497 0.2308329 0.185954 0.237509 0.18497 0.237506 0.18497 0.237506 0.1789219 0.238076 0.1779029 0.238073 0.167801 0.235348 0.169259 0.232845 0.168868 0.235351 0.167801 0.235348 0.1681939 0.232842 0.169259 0.232845 0.171088 0.23862 0.169402 0.238755 0.169402 0.201243 0.171088 0.2014099 0.171088 0.23862 0.169402 0.201243 0.173978 0.238388 0.172423 0.2385129 0.172423 0.201543 0.173978 0.208751 0.173978 0.238388 0.172423 0.201543 0.177112 0.208954 0.173978 0.208751 0.172423 0.201543 0.177112 0.20201 0.177112 0.208954 0.172423 0.201543 0.182964 0.230924 0.1779029 0.238073 0.1779029 0.231155 0.18497 0.2308329 0.18497 0.237506 0.1779029 0.238073 0.182964 0.230924 0.18497 0.2308329 0.1779029 0.238073 0.182964 0.230924 0.179936 0.209138 0.18497 0.2308329 0.185194 0.202816 0.185194 0.209481 0.179936 0.209138 0.177823 0.209001 0.185194 0.202816 0.179936 0.209138 0.182964 0.230924 0.177823 0.209001 0.179936 0.209138 0.177823 0.209001 0.177823 0.202081 0.185194 0.202816 0.167287 0.2163659 0.167758 0.215135 0.168358 0.216365 0.166685 0.215136 0.166029 0.214694 0.167758 0.215135 0.167287 0.2163659 0.166685 0.215136 0.167758 0.215135 0.173978 0.208751 0.175015 0.238391 0.173978 0.238388 0.173978 0.238388 0.1734679 0.238516 0.172423 0.2385129 0.167801 0.21829 0.168358 0.216365 0.168869 0.21829 0.167801 0.21829 0.167287 0.2163659 0.168358 0.216365 0.177112 0.20201 0.178134 0.202006 0.178134 0.208952 0.177112 0.20201 0.172423 0.201543 0.178134 0.202006 0.171088 0.2014099 0.17214 0.238623 0.171088 0.23862 0.171088 0.23862 0.170462 0.238758 0.169402 0.238755 0.172423 0.201543 0.1734679 0.201539 0.178134 0.202006 0.172423 0.2385129 0.1734679 0.238516 0.1734679 0.201539 0.172423 0.201543 0.172423 0.2385129 0.1734679 0.201539 0.1684409 0.223671 0.169506 0.223672 0.169591 0.226804 0.177112 0.20201 0.178134 0.208952 0.177112 0.208954 0.173978 0.208751 0.175015 0.208748 0.175015 0.238391 0.177112 0.208954 0.175015 0.208748 0.173978 0.208751 0.173978 0.238388 0.175015 0.238391 0.1734679 0.238516 0.177112 0.208954 0.178134 0.208952 0.175015 0.208748 0.168527 0.226803 0.169591 0.226804 0.169506 0.229941 0.168527 0.226803 0.1684409 0.223671 0.169591 0.226804 0.16122 0.214528 0.162319 0.2145259 0.167105 0.2146919 0.16122 0.214528 0.16122 0.20043 0.162319 0.2145259 0.112214 0.03107196 0.115394 0.0528469 0.114721 0.05769091 0.134313 0.05737495 0.114721 0.05769091 0.115394 0.0528469 0.09991699 0.06646496 0.112214 0.03107196 0.114721 0.05769091 0.111041 0.091802 0.09991699 0.06646496 0.114721 0.05769091 0.140795 0.1091639 0.111041 0.091802 0.114721 0.05769091 0.140795 0.1091639 0.114721 0.05769091 0.134313 0.05737495 0.112214 0.03107196 0.11585 0.048415 0.115394 0.0528469 0.132905 0.04834693 0.115394 0.0528469 0.11585 0.048415 0.132905 0.04834693 0.134313 0.05737495 0.115394 0.0528469 0.112214 0.03107196 0.116047 0.04084599 0.11585 0.048415 0.131143 0.04082298 0.11585 0.048415 0.116047 0.04084599 0.131143 0.04082298 0.132905 0.04834693 0.11585 0.048415 0.112214 0.03107196 0.1152009 0.03529793 0.116047 0.04084599 0.130153 0.03775393 0.116047 0.04084599 0.1152009 0.03529793 0.130153 0.03775393 0.131143 0.04082298 0.116047 0.04084599 0.112214 0.03107196 0.1132709 0.03198695 0.1152009 0.03529793 0.129102 0.03519892 0.1152009 0.03529793 0.1132709 0.03198695 0.129102 0.03519892 0.130153 0.03775393 0.1152009 0.03529793 0.126879 0.03181093 0.1132709 0.03198695 0.112214 0.03107196 0.126879 0.03181093 0.129102 0.03519892 0.1132709 0.03198695 0.07719498 0.01694995 0.112214 0.03107196 0.09991699 0.06646496 0.09858596 0.01919299 0.112214 0.03107196 0.07719498 0.01694995 0.126879 0.03181093 0.112214 0.03107196 0.09858596 0.01919299 0.111041 0.091802 0.09109801 0.102917 0.09991699 0.06646496 0.06164389 0.06539398 0.09991699 0.06646496 0.09109801 0.102917 0.07441598 0.02429896 0.07719498 0.01694995 0.09991699 0.06646496 0.07259297 0.02935296 0.07441598 0.02429896 0.09991699 0.06646496 0.06739795 0.04511892 0.07259297 0.02935296 0.09991699 0.06646496 0.06164389 0.06539398 0.06739795 0.04511892 0.09991699 0.06646496 0.110477 0.125273 0.08579295 0.140075 0.09109801 0.102917 0.05370193 0.102303 0.09109801 0.102917 0.08579295 0.140075 0.111041 0.091802 0.110477 0.125273 0.09109801 0.102917 0.06139898 0.066347 0.06164389 0.06539398 0.09109801 0.102917 0.056373 0.08808296 0.06139898 0.066347 0.09109801 0.102917 0.05370193 0.102303 0.056373 0.08808296 0.09109801 0.102917 0.113788 0.173361 0.08402198 0.177588 0.08579295 0.140075 0.04897391 0.139806 0.08579295 0.140075 0.08402198 0.177588 0.113669 0.169189 0.113788 0.173361 0.08579295 0.140075 0.113342 0.163245 0.113669 0.169189 0.08579295 0.140075 0.112826 0.157728 0.113342 0.163245 0.08579295 0.140075 0.110477 0.125273 0.112826 0.157728 0.08579295 0.140075 0.05244499 0.11013 0.05370193 0.102303 0.08579295 0.140075 0.04964697 0.132475 0.05244499 0.11013 0.08579295 0.140075 0.04897391 0.139806 0.04964697 0.132475 0.08579295 0.140075 0.112826 0.197448 0.08579295 0.215101 0.08402198 0.177588 0.04739296 0.177588 0.08402198 0.177588 0.08579295 0.215101 0.113342 0.191931 0.112826 0.197448 0.08402198 0.177588 0.113669 0.1859869 0.113342 0.191931 0.08402198 0.177588 0.113788 0.181816 0.113669 0.1859869 0.08402198 0.177588 0.113828 0.1775889 0.113788 0.181816 0.08402198 0.177588 0.113788 0.173361 0.113828 0.1775889 0.08402198 0.177588 0.04795897 0.154999 0.04897391 0.139806 0.08402198 0.177588 0.04739296 0.177588 0.04795897 0.154999 0.08402198 0.177588 0.110477 0.229897 0.09109801 0.252259 0.08579295 0.215101 0.04957598 0.22198 0.08579295 0.215101 0.09109801 0.252259 0.112826 0.197448 0.110477 0.229897 0.08579295 0.215101 0.047957 0.200173 0.04739296 0.177588 0.08579295 0.215101 0.04957598 0.22198 0.047957 0.200173 0.08579295 0.215101 0.111041 0.26337 0.09991699 0.288711 0.09109801 0.252259 0.05611795 0.265904 0.09109801 0.252259 0.09991699 0.288711 0.110477 0.229897 0.111041 0.26337 0.09109801 0.252259 0.049649 0.222714 0.04957598 0.22198 0.09109801 0.252259 0.05245095 0.24502 0.049649 0.222714 0.09109801 0.252259 0.05611795 0.265904 0.05245095 0.24502 0.09109801 0.252259 0.1132709 0.323189 0.112214 0.324104 0.09991699 0.288711 0.066998 0.30889 0.09991699 0.288711 0.112214 0.324104 0.115202 0.319876 0.1132709 0.323189 0.09991699 0.288711 0.116047 0.314324 0.115202 0.319876 0.09991699 0.288711 0.11585 0.306756 0.116047 0.314324 0.09991699 0.288711 0.115393 0.302325 0.11585 0.306756 0.09991699 0.288711 0.114721 0.297485 0.115393 0.302325 0.09991699 0.288711 0.111041 0.26337 0.114721 0.297485 0.09991699 0.288711 0.05636495 0.267129 0.05611795 0.265904 0.09991699 0.288711 0.06133192 0.288781 0.05636495 0.267129 0.09991699 0.288711 0.066998 0.30889 0.06133192 0.288781 0.09991699 0.288711 0.09799897 0.350855 0.112214 0.324104 0.1132709 0.323189 0.06737697 0.310116 0.066998 0.30889 0.112214 0.324104 0.07438397 0.330787 0.06737697 0.310116 0.112214 0.324104 0.09858596 0.335983 0.07438397 0.330787 0.112214 0.324104 0.09799897 0.350855 0.09858596 0.335983 0.112214 0.324104 0.126879 0.323365 0.1132709 0.323189 0.115202 0.319876 0.09799897 0.350855 0.1132709 0.323189 0.126879 0.323365 0.129102 0.319977 0.115202 0.319876 0.116047 0.314324 0.126879 0.323365 0.115202 0.319876 0.129102 0.319977 0.131143 0.314353 0.116047 0.314324 0.11585 0.306756 0.130153 0.317422 0.116047 0.314324 0.131143 0.314353 0.129102 0.319977 0.116047 0.314324 0.130153 0.317422 0.132905 0.30683 0.11585 0.306756 0.115393 0.302325 0.131143 0.314353 0.11585 0.306756 0.132905 0.30683 0.132905 0.30683 0.115393 0.302325 0.114721 0.297485 0.134313 0.297797 0.114721 0.297485 0.111041 0.26337 0.132905 0.30683 0.114721 0.297485 0.134313 0.297797 0.140795 0.246011 0.111041 0.26337 0.110477 0.229897 0.134313 0.297797 0.111041 0.26337 0.140795 0.246011 0.14688 0.197248 0.110477 0.229897 0.112826 0.197448 0.140795 0.246011 0.110477 0.229897 0.14688 0.197248 0.14688 0.197248 0.112826 0.197448 0.113342 0.191931 0.14771 0.187835 0.113342 0.191931 0.113669 0.1859869 0.14688 0.197248 0.113342 0.191931 0.14771 0.187835 0.14771 0.187835 0.113669 0.1859869 0.113788 0.181816 0.14771 0.187835 0.113788 0.181816 0.113828 0.1775889 0.147994 0.177588 0.113828 0.1775889 0.113788 0.173361 0.14771 0.187835 0.113828 0.1775889 0.147994 0.177588 0.147994 0.177588 0.113788 0.173361 0.113669 0.169189 0.14771 0.16734 0.113669 0.169189 0.113342 0.163245 0.147994 0.177588 0.113669 0.169189 0.14771 0.16734 0.14771 0.16734 0.113342 0.163245 0.112826 0.157728 0.146881 0.157932 0.112826 0.157728 0.110477 0.125273 0.14771 0.16734 0.112826 0.157728 0.146881 0.157932 0.140795 0.1091639 0.110477 0.125273 0.111041 0.091802 0.140795 0.1091639 0.146881 0.157932 0.110477 0.125273 0.09858596 0.01919299 0.07719498 0.01694995 0.08217698 0.004699945 0.06573396 0.02092289 0.08217698 0.004699945 0.07719498 0.01694995 0.126879 0.03181093 0.09858596 0.01919299 0.08217698 0.004699945 0.09799998 0.004321992 0.126879 0.03181093 0.08217698 0.004699945 0.09798097 0.004303932 0.09799998 0.004321992 0.08217698 0.004699945 0.08215999 0.004683971 0.09798097 0.004303932 0.08217698 0.004699945 0.06573396 0.02092289 0.08215999 0.004683971 0.08217698 0.004699945 0.06573396 0.02092289 0.07719498 0.01694995 0.07441598 0.02429896 0.05978399 0.04278898 0.07441598 0.02429896 0.07259297 0.02935296 0.05978399 0.04278898 0.06573396 0.02092289 0.07441598 0.02429896 0.05978399 0.04278898 0.07259297 0.02935296 0.06739795 0.04511892 0.06139898 0.066347 0.06739795 0.04511892 0.06164389 0.06539398 0.05501097 0.06498998 0.06739795 0.04511892 0.06139898 0.066347 0.05978399 0.04278898 0.06739795 0.04511892 0.05501097 0.06498998 0.05501097 0.06498998 0.06139898 0.066347 0.056373 0.08808296 0.05128699 0.08742499 0.056373 0.08808296 0.05370193 0.102303 0.05501097 0.06498998 0.056373 0.08808296 0.05128699 0.08742499 0.04865998 0.109996 0.05370193 0.102303 0.05244499 0.11013 0.05128699 0.08742499 0.05370193 0.102303 0.04865998 0.109996 0.04711788 0.1326 0.05244499 0.11013 0.04964697 0.132475 0.04865998 0.109996 0.05244499 0.11013 0.04711788 0.1326 0.04668599 0.155158 0.04964697 0.132475 0.04897391 0.139806 0.04711788 0.1326 0.04964697 0.132475 0.04668599 0.155158 0.04668599 0.155158 0.04897391 0.139806 0.04795897 0.154999 0.04668599 0.155158 0.04795897 0.154999 0.04739296 0.177588 0.04668498 0.199971 0.04739296 0.177588 0.047957 0.200173 0.04539489 0.155928 0.04668599 0.155158 0.04739296 0.177588 0.0440849 0.157171 0.04539489 0.155928 0.04739296 0.177588 0.04278689 0.159045 0.0440849 0.157171 0.04739296 0.177588 0.04162293 0.161677 0.04278689 0.159045 0.04739296 0.177588 0.04070997 0.165009 0.04162293 0.161677 0.04739296 0.177588 0.04002189 0.16894 0.04070997 0.165009 0.04739296 0.177588 0.0395559 0.173215 0.04002189 0.16894 0.04739296 0.177588 0.03939098 0.177586 0.0395559 0.173215 0.04739296 0.177588 0.03956192 0.181963 0.03939098 0.177586 0.04739296 0.177588 0.04002588 0.186241 0.03956192 0.181963 0.04739296 0.177588 0.04071193 0.190171 0.04002588 0.186241 0.04739296 0.177588 0.04162198 0.193516 0.04071193 0.190171 0.04739296 0.177588 0.04278391 0.1961629 0.04162198 0.193516 0.04739296 0.177588 0.04408395 0.198014 0.04278391 0.1961629 0.04739296 0.177588 0.04539597 0.199205 0.04408395 0.198014 0.04739296 0.177588 0.04668498 0.199971 0.04539597 0.199205 0.04739296 0.177588 0.04711788 0.222482 0.047957 0.200173 0.04957598 0.22198 0.04711788 0.222482 0.04668498 0.199971 0.047957 0.200173 0.04711788 0.222482 0.04957598 0.22198 0.049649 0.222714 0.04866397 0.2450399 0.049649 0.222714 0.05245095 0.24502 0.04866397 0.2450399 0.04711788 0.222482 0.049649 0.222714 0.05127096 0.267561 0.05245095 0.24502 0.05611795 0.265904 0.05127096 0.267561 0.04866397 0.2450399 0.05245095 0.24502 0.05127096 0.267561 0.05611795 0.265904 0.05636495 0.267129 0.05494689 0.289948 0.05636495 0.267129 0.06133192 0.288781 0.05494689 0.289948 0.05127096 0.267561 0.05636495 0.267129 0.05973798 0.312105 0.06133192 0.288781 0.066998 0.30889 0.05973798 0.312105 0.05494689 0.289948 0.06133192 0.288781 0.05973798 0.312105 0.066998 0.30889 0.06737697 0.310116 0.06570595 0.333921 0.06737697 0.310116 0.07438397 0.330787 0.05973798 0.312105 0.06737697 0.310116 0.06570595 0.333921 0.09858596 0.335983 0.082179 0.350475 0.07438397 0.330787 0.08215999 0.350492 0.07438397 0.330787 0.082179 0.350475 0.07835298 0.353089 0.07438397 0.330787 0.08215999 0.350492 0.07421398 0.354475 0.07438397 0.330787 0.07835298 0.353089 0.06570595 0.333921 0.07438397 0.330787 0.07421398 0.354475 0.09799897 0.350855 0.082179 0.350475 0.09858596 0.335983 0.08215999 0.350492 0.082179 0.350475 0.09799897 0.350855 0.140795 0.246011 0.140795 0.1091639 0.134313 0.05737495 0.134313 0.297797 0.134313 0.05737495 0.132905 0.04834693 0.134313 0.297797 0.140795 0.246011 0.134313 0.05737495 0.14688 0.197248 0.146881 0.157932 0.140795 0.1091639 0.14771 0.187835 0.14771 0.16734 0.146881 0.157932 0.14688 0.197248 0.14771 0.187835 0.146881 0.157932 0.140795 0.246011 0.14688 0.197248 0.140795 0.1091639 0.132905 0.30683 0.132905 0.04834693 0.131143 0.04082298 0.132905 0.30683 0.134313 0.297797 0.132905 0.04834693 0.131143 0.314353 0.131143 0.04082298 0.130153 0.03775393 0.131143 0.314353 0.132905 0.30683 0.131143 0.04082298 0.130153 0.317422 0.130153 0.03775393 0.129102 0.03519892 0.130153 0.317422 0.131143 0.314353 0.130153 0.03775393 0.129102 0.319977 0.129102 0.03519892 0.126879 0.03181093 0.129102 0.319977 0.130153 0.317422 0.129102 0.03519892 0.126879 0.323365 0.126879 0.03181093 0.09799998 0.004321992 0.126879 0.323365 0.129102 0.319977 0.126879 0.03181093 0.09799897 0.350855 0.126879 0.323365 0.09799998 0.004321992 0.09798097 0.004303932 0.09799897 0.350855 0.09799998 0.004321992 0.14771 0.187835 0.147994 0.177588 0.14771 0.16734 0.09798097 0.004303932 0.09798097 0.350872 0.09799897 0.350855 0.08215999 0.350492 0.09799897 0.350855 0.09798097 0.350872 0.094473 0.001636922 0.094473 0.35354 0.09798097 0.350872 0.08215999 0.350492 0.09798097 0.350872 0.094473 0.35354 0.09798097 0.004303932 0.094473 0.001636922 0.09798097 0.350872 0.09101897 2.4e-4 0.091035 0.354934 0.094473 0.35354 0.07421398 0.354475 0.094473 0.35354 0.091035 0.354934 0.094473 0.001636922 0.09101897 2.4e-4 0.094473 0.35354 0.07835298 0.353089 0.08215999 0.350492 0.094473 0.35354 0.07421398 0.354475 0.07835298 0.353089 0.094473 0.35354 0.09101897 2.4e-4 0.08798098 0.355181 0.091035 0.354934 0.07027399 0.354716 0.091035 0.354934 0.08798098 0.355181 0.07027399 0.354716 0.07421398 0.354475 0.091035 0.354934 0.08794295 0 0.08535999 0.354655 0.08798098 0.355181 0.066711 0.35419 0.08798098 0.355181 0.08535999 0.354655 0.09101897 2.4e-4 0.08794295 0 0.08798098 0.355181 0.066711 0.35419 0.07027399 0.354716 0.08798098 0.355181 0.08530396 5.42e-4 0.08074897 0.352052 0.08535999 0.354655 0.059991 0.351574 0.08535999 0.354655 0.08074897 0.352052 0.08794295 0 0.08530396 5.42e-4 0.08535999 0.354655 0.059991 0.351574 0.066711 0.35419 0.08535999 0.354655 0.07795095 0.005787968 0.07509398 0.345777 0.08074897 0.352052 0.05113697 0.345257 0.08074897 0.352052 0.07509398 0.345777 0.08065199 0.003203988 0.07795095 0.005787968 0.08074897 0.352052 0.08530396 5.42e-4 0.08065199 0.003203988 0.08074897 0.352052 0.05113697 0.345257 0.059991 0.351574 0.08074897 0.352052 0.074907 0.009667992 0.06976795 0.336416 0.07509398 0.345777 0.0423119 0.335802 0.07509398 0.345777 0.06976795 0.336416 0.07795095 0.005787968 0.074907 0.009667992 0.07509398 0.345777 0.0423119 0.335802 0.05113697 0.345257 0.07509398 0.345777 0.06958699 0.01914393 0.065961 0.327292 0.06976795 0.336416 0.03571891 0.326523 0.06976795 0.336416 0.065961 0.327292 0.074907 0.009667992 0.06958699 0.01914393 0.06976795 0.336416 0.03571891 0.326523 0.0423119 0.335802 0.06976795 0.336416 0.06580895 0.02829498 0.06260198 0.31719 0.065961 0.327292 0.03571891 0.326523 0.065961 0.327292 0.06260198 0.31719 0.06958699 0.01914393 0.06580895 0.02829498 0.065961 0.327292 0.0624929 0.03834992 0.06068789 0.310393 0.06260198 0.31719 0.029778 0.316235 0.06260198 0.31719 0.06068789 0.310393 0.06580895 0.02829498 0.0624929 0.03834992 0.06260198 0.31719 0.029778 0.316235 0.03571891 0.326523 0.06260198 0.31719 0.06059789 0.04512488 0.05857998 0.301846 0.06068789 0.310393 0.02643996 0.309456 0.06068789 0.310393 0.05857998 0.301846 0.0624929 0.03834992 0.06059789 0.04512488 0.06068789 0.310393 0.02643996 0.309456 0.029778 0.316235 0.06068789 0.310393 0.05851 0.05363392 0.05633199 0.291236 0.05857998 0.301846 0.02276688 0.300941 0.05857998 0.301846 0.05633199 0.291236 0.06059789 0.04512488 0.05851 0.05363392 0.05857998 0.301846 0.02276688 0.300941 0.02643996 0.309456 0.05857998 0.301846 0.05627495 0.064233 0.05430489 0.27996 0.05633199 0.291236 0.01886695 0.290322 0.05633199 0.291236 0.05430489 0.27996 0.05851 0.05363392 0.05627495 0.064233 0.05633199 0.291236 0.01886695 0.290322 0.02276688 0.300941 0.05633199 0.291236 0.0542699 0.07543098 0.05271697 0.269566 0.05430489 0.27996 0.01537793 0.279116 0.05430489 0.27996 0.05271697 0.269566 0.05627495 0.064233 0.0542699 0.07543098 0.05430489 0.27996 0.01537793 0.279116 0.01886695 0.290322 0.05430489 0.27996 0.05270296 0.08570599 0.05148392 0.260209 0.05271697 0.269566 0.01031392 0.259592 0.05271697 0.269566 0.05148392 0.260209 0.0542699 0.07543098 0.05270296 0.08570599 0.05271697 0.269566 0.01258796 0.268884 0.01537793 0.279116 0.05271697 0.269566 0.01031392 0.259592 0.01258796 0.268884 0.05271697 0.269566 0.04951989 0.11359 0.04949295 0.241289 0.05148392 0.260209 0.01031392 0.259592 0.05148392 0.260209 0.04949295 0.241289 0.05147397 0.09504997 0.04951989 0.11359 0.05148392 0.260209 0.05270296 0.08570599 0.05147397 0.09504997 0.05148392 0.260209 0.04791796 0.135668 0.04786497 0.218566 0.04949295 0.241289 0.006296992 0.240389 0.04949295 0.241289 0.04786497 0.218566 0.04951989 0.11359 0.04791796 0.135668 0.04949295 0.241289 0.006296992 0.240389 0.01031392 0.259592 0.04949295 0.241289 0.0469399 0.161035 0.04691398 0.192902 0.04786497 0.218566 0.002734959 0.217759 0.04786497 0.218566 0.04691398 0.192902 0.04791796 0.135668 0.0469399 0.161035 0.04786497 0.218566 0.002734959 0.217759 0.006296992 0.240389 0.04786497 0.218566 4.49e-4 0.1922219 0.04691398 0.192902 0.0469399 0.161035 4.49e-4 0.1922219 0.002734959 0.217759 0.04691398 0.192902 5.32e-4 0.160679 0.0469399 0.161035 0.04791796 0.135668 5.32e-4 0.160679 4.49e-4 0.1922219 0.0469399 0.161035 0.002908945 0.135704 0.04791796 0.135668 0.04951989 0.11359 0.002908945 0.135704 5.32e-4 0.160679 0.04791796 0.135668 0.006468892 0.113751 0.04951989 0.11359 0.05147397 0.09504997 0.006468892 0.113751 0.002908945 0.135704 0.04951989 0.11359 0.01038491 0.09531295 0.05147397 0.09504997 0.05270296 0.08570599 0.01038491 0.09531295 0.006468892 0.113751 0.05147397 0.09504997 0.01265299 0.08605796 0.05270296 0.08570599 0.0542699 0.07543098 0.01265299 0.08605796 0.01038491 0.09531295 0.05270296 0.08570599 0.01545792 0.07577699 0.0542699 0.07543098 0.05627495 0.064233 0.01545792 0.07577699 0.01265299 0.08605796 0.0542699 0.07543098 0.01896589 0.06455999 0.05627495 0.064233 0.05851 0.05363392 0.01896589 0.06455999 0.01545792 0.07577699 0.05627495 0.064233 0.02288097 0.05396991 0.05851 0.05363392 0.06059789 0.04512488 0.02288097 0.05396991 0.01896589 0.06455999 0.05851 0.05363392 0.026573 0.04548192 0.06059789 0.04512488 0.0624929 0.03834992 0.026573 0.04548192 0.02288097 0.05396991 0.06059789 0.04512488 0.02992188 0.0387389 0.0624929 0.03834992 0.06580895 0.02829498 0.02992188 0.0387389 0.026573 0.04548192 0.0624929 0.03834992 0.03573298 0.02872192 0.06580895 0.02829498 0.06958699 0.01914393 0.03573298 0.02872192 0.02992188 0.0387389 0.06580895 0.02829498 0.04227197 0.01949495 0.06958699 0.01914393 0.074907 0.009667992 0.04227197 0.01949495 0.03573298 0.02872192 0.06958699 0.01914393 0.05111998 0.009937942 0.074907 0.009667992 0.07795095 0.005787968 0.05111998 0.009937942 0.04227197 0.01949495 0.074907 0.009667992 0.05111998 0.009937942 0.07795095 0.005787968 0.08065199 0.003203988 0.05985796 0.003628969 0.08065199 0.003203988 0.08530396 5.42e-4 0.05985796 0.003628969 0.05111998 0.009937942 0.08065199 0.003203988 0.06652599 0.001003921 0.08530396 5.42e-4 0.08794295 0 0.06652599 0.001003921 0.05985796 0.003628969 0.08530396 5.42e-4 0.070158 4.65e-4 0.08794295 0 0.09101897 2.4e-4 0.070158 4.65e-4 0.06652599 0.001003921 0.08794295 0 0.07420796 7.2e-4 0.09101897 2.4e-4 0.094473 0.001636922 0.07420796 7.2e-4 0.070158 4.65e-4 0.09101897 2.4e-4 0.078422 0.002136886 0.094473 0.001636922 0.09798097 0.004303932 0.078422 0.002136886 0.07420796 7.2e-4 0.094473 0.001636922 0.078422 0.002136886 0.09798097 0.004303932 0.08215999 0.004683971 0.06573396 0.02092289 0.078422 0.002136886 0.08215999 0.004683971 0.06570595 0.333921 0.07421398 0.354475 0.07027399 0.354716 0.06570595 0.333921 0.07027399 0.354716 0.066711 0.35419 0.05607998 0.33376 0.066711 0.35419 0.059991 0.351574 0.05607998 0.33376 0.06570595 0.333921 0.066711 0.35419 0.05607998 0.33376 0.059991 0.351574 0.05113697 0.345257 0.04587197 0.329455 0.05113697 0.345257 0.0423119 0.335802 0.04587197 0.329455 0.05607998 0.33376 0.05113697 0.345257 0.0350089 0.3194 0.0423119 0.335802 0.03571891 0.326523 0.0350089 0.3194 0.04587197 0.329455 0.0423119 0.335802 0.0350089 0.3194 0.03571891 0.326523 0.029778 0.316235 0.0350089 0.3194 0.029778 0.316235 0.02643996 0.309456 0.02437895 0.302276 0.02643996 0.309456 0.02276688 0.300941 0.02437895 0.302276 0.0350089 0.3194 0.02643996 0.309456 0.02437895 0.302276 0.02276688 0.300941 0.01886695 0.290322 0.01532596 0.278147 0.01886695 0.290322 0.01537793 0.279116 0.01532596 0.278147 0.02437895 0.302276 0.01886695 0.290322 0.01532596 0.278147 0.01537793 0.279116 0.01258796 0.268884 0.01532596 0.278147 0.01258796 0.268884 0.01031392 0.259592 0.007790923 0.247877 0.01031392 0.259592 0.006296992 0.240389 0.007790923 0.247877 0.01532596 0.278147 0.01031392 0.259592 0.007790923 0.247877 0.006296992 0.240389 0.002734959 0.217759 0.00217998 0.213529 0.002734959 0.217759 4.49e-4 0.1922219 0.00217998 0.213529 0.007790923 0.247877 0.002734959 0.217759 0 0.177599 4.49e-4 0.1922219 5.32e-4 0.160679 0 0.177599 0.00217998 0.213529 4.49e-4 0.1922219 0.002121925 0.141707 5.32e-4 0.160679 0.002908945 0.135704 0.002121925 0.141707 0 0.177599 5.32e-4 0.160679 0.002121925 0.141707 0.002908945 0.135704 0.006468892 0.113751 0.007763922 0.107379 0.006468892 0.113751 0.01038491 0.09531295 0.007763922 0.107379 0.002121925 0.141707 0.006468892 0.113751 0.007763922 0.107379 0.01038491 0.09531295 0.01265299 0.08605796 0.007763922 0.107379 0.01265299 0.08605796 0.01545792 0.07577699 0.01529788 0.07710999 0.01545792 0.07577699 0.01896589 0.06455999 0.01529788 0.07710999 0.007763922 0.107379 0.01545792 0.07577699 0.01529788 0.07710999 0.01896589 0.06455999 0.02288097 0.05396991 0.02433788 0.0530759 0.02288097 0.05396991 0.026573 0.04548192 0.02433788 0.0530759 0.01529788 0.07710999 0.02288097 0.05396991 0.02433788 0.0530759 0.026573 0.04548192 0.02992188 0.0387389 0.02433788 0.0530759 0.02992188 0.0387389 0.03573298 0.02872192 0.034976 0.03605097 0.03573298 0.02872192 0.04227197 0.01949495 0.034976 0.03605097 0.02433788 0.0530759 0.03573298 0.02872192 0.04585492 0.02580398 0.04227197 0.01949495 0.05111998 0.009937942 0.04585492 0.02580398 0.034976 0.03605097 0.04227197 0.01949495 0.04585492 0.02580398 0.05111998 0.009937942 0.05985796 0.003628969 0.05609095 0.02110296 0.05985796 0.003628969 0.06652599 0.001003921 0.05609095 0.02110296 0.04585492 0.02580398 0.05985796 0.003628969 0.05609095 0.02110296 0.06652599 0.001003921 0.070158 4.65e-4 0.06573396 0.02092289 0.070158 4.65e-4 0.07420796 7.2e-4 0.06573396 0.02092289 0.05609095 0.02110296 0.070158 4.65e-4 0.06573396 0.02092289 0.07420796 7.2e-4 0.078422 0.002136886 0.05973798 0.312105 0.06570595 0.333921 0.05607998 0.33376 0.05132395 0.311174 0.05607998 0.33376 0.04587197 0.329455 0.05973798 0.312105 0.05607998 0.33376 0.05132395 0.311174 0.04241997 0.306754 0.04587197 0.329455 0.0350089 0.3194 0.05132395 0.311174 0.04587197 0.329455 0.04241997 0.306754 0.03274995 0.297641 0.0350089 0.3194 0.02437895 0.302276 0.04241997 0.306754 0.0350089 0.3194 0.03274995 0.297641 0.0231319 0.282734 0.02437895 0.302276 0.01532596 0.278147 0.03274995 0.297641 0.02437895 0.302276 0.0231319 0.282734 0.0150299 0.262091 0.01532596 0.278147 0.007790923 0.247877 0.0231319 0.282734 0.01532596 0.278147 0.0150299 0.262091 0.008408963 0.236466 0.007790923 0.247877 0.00217998 0.213529 0.0150299 0.262091 0.007790923 0.247877 0.008408963 0.236466 0.003519952 0.207607 0.00217998 0.213529 0 0.177599 0.008408963 0.236466 0.00217998 0.213529 0.003519952 0.207607 0.001631975 0.177543 0 0.177599 0.002121925 0.141707 0.003519952 0.207607 0 0.177599 0.001631975 0.177543 0.003479957 0.147512 0.002121925 0.141707 0.007763922 0.107379 0.001631975 0.177543 0.002121925 0.141707 0.003479957 0.147512 0.008402943 0.118678 0.007763922 0.107379 0.01529788 0.07710999 0.003479957 0.147512 0.007763922 0.107379 0.008402943 0.118678 0.01503098 0.09306895 0.01529788 0.07710999 0.02433788 0.0530759 0.008402943 0.118678 0.01529788 0.07710999 0.01503098 0.09306895 0.02312994 0.07252496 0.02433788 0.0530759 0.034976 0.03605097 0.01503098 0.09306895 0.02433788 0.0530759 0.02312994 0.07252496 0.03276091 0.05772292 0.034976 0.03605097 0.04585492 0.02580398 0.02312994 0.07252496 0.034976 0.03605097 0.03276091 0.05772292 0.04243993 0.04846888 0.04585492 0.02580398 0.05609095 0.02110296 0.03276091 0.05772292 0.04585492 0.02580398 0.04243993 0.04846888 0.05135893 0.04372495 0.05609095 0.02110296 0.06573396 0.02092289 0.04243993 0.04846888 0.05609095 0.02110296 0.05135893 0.04372495 0.05135893 0.04372495 0.06573396 0.02092289 0.05978399 0.04278898 0.04711788 0.1326 0.04668599 0.155158 0.04539489 0.155928 0.04451292 0.133943 0.04539489 0.155928 0.0440849 0.157171 0.04451292 0.133943 0.04711788 0.1326 0.04539489 0.155928 0.04175895 0.136268 0.0440849 0.157171 0.04278689 0.159045 0.04175895 0.136268 0.04451292 0.133943 0.0440849 0.157171 0.03891396 0.139903 0.04278689 0.159045 0.04162293 0.161677 0.03891396 0.139903 0.04175895 0.136268 0.04278689 0.159045 0.03630089 0.145135 0.04162293 0.161677 0.04070997 0.165009 0.03630089 0.145135 0.03891396 0.139903 0.04162293 0.161677 0.03422999 0.151858 0.04070997 0.165009 0.04002189 0.16894 0.03422999 0.151858 0.03630089 0.145135 0.04070997 0.165009 0.03261095 0.159856 0.04002189 0.16894 0.0395559 0.173215 0.03261095 0.159856 0.03422999 0.151858 0.04002189 0.16894 0.03144598 0.168608 0.0395559 0.173215 0.03939098 0.177586 0.03144598 0.168608 0.03261095 0.159856 0.0395559 0.173215 0.03101789 0.17759 0.03939098 0.177586 0.03956192 0.181963 0.03101789 0.17759 0.03144598 0.168608 0.03939098 0.177586 0.03146398 0.186583 0.03956192 0.181963 0.04002588 0.186241 0.03146398 0.186583 0.03101789 0.17759 0.03956192 0.181963 0.03262192 0.195341 0.04002588 0.186241 0.04071193 0.190171 0.03262192 0.195341 0.03146398 0.186583 0.04002588 0.186241 0.0342369 0.203338 0.04071193 0.190171 0.04162198 0.193516 0.0342369 0.203338 0.03262192 0.195341 0.04071193 0.190171 0.03630393 0.210086 0.04162198 0.193516 0.04278391 0.1961629 0.03630393 0.210086 0.0342369 0.203338 0.04162198 0.193516 0.03891396 0.215345 0.04278391 0.1961629 0.04408395 0.198014 0.03891396 0.215345 0.03630393 0.210086 0.04278391 0.1961629 0.04176098 0.218931 0.04408395 0.198014 0.04539597 0.199205 0.04176098 0.218931 0.03891396 0.215345 0.04408395 0.198014 0.04451698 0.22115 0.04539597 0.199205 0.04668498 0.199971 0.04451698 0.22115 0.04176098 0.218931 0.04539597 0.199205 0.04711788 0.222482 0.04451698 0.22115 0.04668498 0.199971 0.04865998 0.109996 0.04711788 0.1326 0.04451292 0.133943 0.04469794 0.1116639 0.04451292 0.133943 0.04175895 0.136268 0.04469794 0.1116639 0.04865998 0.109996 0.04451292 0.133943 0.040434 0.114928 0.04175895 0.136268 0.03891396 0.139903 0.040434 0.114928 0.04469794 0.1116639 0.04175895 0.136268 0.03587496 0.120204 0.03891396 0.139903 0.03630089 0.145135 0.03587496 0.120204 0.040434 0.114928 0.03891396 0.139903 0.03156691 0.127969 0.03630089 0.145135 0.03422999 0.151858 0.03156691 0.127969 0.03587496 0.120204 0.03630089 0.145135 0.02809095 0.138125 0.03422999 0.151858 0.03261095 0.159856 0.02809095 0.138125 0.03156691 0.127969 0.03422999 0.151858 0.0253179 0.1503289 0.03261095 0.159856 0.03144598 0.168608 0.0253179 0.1503289 0.02809095 0.138125 0.03261095 0.159856 0.02328199 0.163766 0.03144598 0.168608 0.03101789 0.17759 0.02328199 0.163766 0.0253179 0.1503289 0.03144598 0.168608 0.02252596 0.177601 0.03101789 0.17759 0.03146398 0.186583 0.02252596 0.177601 0.02328199 0.163766 0.03101789 0.17759 0.02331393 0.191452 0.03146398 0.186583 0.03262192 0.195341 0.02331393 0.191452 0.02252596 0.177601 0.03146398 0.186583 0.02533888 0.2048979 0.03262192 0.195341 0.0342369 0.203338 0.02533888 0.2048979 0.02331393 0.191452 0.03262192 0.195341 0.02810692 0.217099 0.0342369 0.203338 0.03630393 0.210086 0.02810692 0.217099 0.02533888 0.2048979 0.0342369 0.203338 0.03158193 0.227289 0.03630393 0.210086 0.03891396 0.215345 0.03158193 0.227289 0.02810692 0.217099 0.03630393 0.210086 0.03588396 0.23509 0.03891396 0.215345 0.04176098 0.218931 0.03588396 0.23509 0.03158193 0.227289 0.03891396 0.215345 0.04044389 0.240289 0.04176098 0.218931 0.04451698 0.22115 0.04044389 0.240289 0.03588396 0.23509 0.04176098 0.218931 0.04470795 0.2433879 0.04451698 0.22115 0.04711788 0.222482 0.04470795 0.2433879 0.04044389 0.240289 0.04451698 0.22115 0.04866397 0.2450399 0.04470795 0.2433879 0.04711788 0.222482 0.04586493 0.08913296 0.04865998 0.109996 0.04469794 0.1116639 0.04586493 0.08913296 0.05128699 0.08742499 0.04865998 0.109996 0.040057 0.09314596 0.04469794 0.1116639 0.040434 0.114928 0.040057 0.09314596 0.04586493 0.08913296 0.04469794 0.1116639 0.03372293 0.09991699 0.040434 0.114928 0.03587496 0.120204 0.03372293 0.09991699 0.040057 0.09314596 0.040434 0.114928 0.027565 0.110117 0.03587496 0.120204 0.03156691 0.127969 0.027565 0.110117 0.03372293 0.09991699 0.03587496 0.120204 0.02251189 0.123724 0.03156691 0.127969 0.02809095 0.138125 0.02251189 0.123724 0.027565 0.110117 0.03156691 0.127969 0.01844292 0.1402699 0.02809095 0.138125 0.0253179 0.1503289 0.01844292 0.1402699 0.02251189 0.123724 0.02809095 0.138125 0.01543796 0.158616 0.0253179 0.1503289 0.02328199 0.163766 0.01543796 0.158616 0.01844292 0.1402699 0.0253179 0.1503289 0.01431691 0.177575 0.02328199 0.163766 0.02252596 0.177601 0.01431691 0.177575 0.01543796 0.158616 0.02328199 0.163766 0.01547396 0.196554 0.02252596 0.177601 0.02331393 0.191452 0.01547396 0.196554 0.01431691 0.177575 0.02252596 0.177601 0.01845699 0.214915 0.02331393 0.191452 0.02533888 0.2048979 0.01845699 0.214915 0.01547396 0.196554 0.02331393 0.191452 0.02251899 0.2314659 0.02533888 0.2048979 0.02810692 0.217099 0.02251899 0.2314659 0.01845699 0.214915 0.02533888 0.2048979 0.02756989 0.24513 0.02810692 0.217099 0.03158193 0.227289 0.02756989 0.24513 0.02251899 0.2314659 0.02810692 0.217099 0.033719 0.255392 0.03158193 0.227289 0.03588396 0.23509 0.033719 0.255392 0.02756989 0.24513 0.03158193 0.227289 0.04005193 0.262067 0.03588396 0.23509 0.04044389 0.240289 0.04005193 0.262067 0.033719 0.255392 0.03588396 0.23509 0.0458579 0.265864 0.04044389 0.240289 0.04470795 0.2433879 0.0458579 0.265864 0.04005193 0.262067 0.04044389 0.240289 0.05127096 0.267561 0.04470795 0.2433879 0.04866397 0.2450399 0.05127096 0.267561 0.0458579 0.265864 0.04470795 0.2433879 0.0480619 0.06644099 0.05128699 0.08742499 0.04586493 0.08913296 0.0480619 0.06644099 0.05501097 0.06498998 0.05128699 0.08742499 0.040681 0.070948 0.04586493 0.08913296 0.040057 0.09314596 0.040681 0.070948 0.0480619 0.06644099 0.04586493 0.08913296 0.03259491 0.07903897 0.040057 0.09314596 0.03372293 0.09991699 0.03259491 0.07903897 0.040681 0.070948 0.040057 0.09314596 0.02457499 0.09156996 0.03372293 0.09991699 0.027565 0.110117 0.02457499 0.09156996 0.03259491 0.07903897 0.03372293 0.09991699 0.01790696 0.108632 0.027565 0.110117 0.02251189 0.123724 0.01790696 0.108632 0.02457499 0.09156996 0.027565 0.110117 0.01250797 0.129649 0.02251189 0.123724 0.01844292 0.1402699 0.01250797 0.129649 0.01790696 0.108632 0.02251189 0.123724 0.008507966 0.153133 0.01844292 0.1402699 0.01543796 0.158616 0.008507966 0.153133 0.01250797 0.129649 0.01844292 0.1402699 0.007004976 0.177498 0.01543796 0.158616 0.01431691 0.177575 0.007004976 0.177498 0.008507966 0.153133 0.01543796 0.158616 0.008531987 0.201892 0.01431691 0.177575 0.01547396 0.196554 0.008531987 0.201892 0.007004976 0.177498 0.01431691 0.177575 0.0124939 0.225405 0.01547396 0.196554 0.01845699 0.214915 0.0124939 0.225405 0.008531987 0.201892 0.01547396 0.196554 0.01788097 0.246447 0.01845699 0.214915 0.02251899 0.2314659 0.01788097 0.246447 0.0124939 0.225405 0.01845699 0.214915 0.02454096 0.263608 0.02251899 0.2314659 0.02756989 0.24513 0.02454096 0.263608 0.01788097 0.246447 0.02251899 0.2314659 0.03254497 0.276246 0.02756989 0.24513 0.033719 0.255392 0.03254497 0.276246 0.02454096 0.263608 0.02756989 0.24513 0.04062891 0.284238 0.033719 0.255392 0.04005193 0.262067 0.04062891 0.284238 0.03254497 0.276246 0.033719 0.255392 0.04800593 0.288492 0.04005193 0.262067 0.0458579 0.265864 0.04800593 0.288492 0.04062891 0.284238 0.04005193 0.262067 0.05494689 0.289948 0.0458579 0.265864 0.05127096 0.267561 0.05494689 0.289948 0.04800593 0.288492 0.0458579 0.265864 0.05978399 0.04278898 0.05501097 0.06498998 0.0480619 0.06644099 0.05135893 0.04372495 0.0480619 0.06644099 0.040681 0.070948 0.05135893 0.04372495 0.05978399 0.04278898 0.0480619 0.06644099 0.04243993 0.04846888 0.040681 0.070948 0.03259491 0.07903897 0.04243993 0.04846888 0.05135893 0.04372495 0.040681 0.070948 0.03276091 0.05772292 0.03259491 0.07903897 0.02457499 0.09156996 0.03276091 0.05772292 0.04243993 0.04846888 0.03259491 0.07903897 0.02312994 0.07252496 0.02457499 0.09156996 0.01790696 0.108632 0.02312994 0.07252496 0.03276091 0.05772292 0.02457499 0.09156996 0.01503098 0.09306895 0.01790696 0.108632 0.01250797 0.129649 0.01503098 0.09306895 0.02312994 0.07252496 0.01790696 0.108632 0.008402943 0.118678 0.01250797 0.129649 0.008507966 0.153133 0.008402943 0.118678 0.01503098 0.09306895 0.01250797 0.129649 0.003479957 0.147512 0.008507966 0.153133 0.007004976 0.177498 0.003479957 0.147512 0.008402943 0.118678 0.008507966 0.153133 0.001631975 0.177543 0.007004976 0.177498 0.008531987 0.201892 0.001631975 0.177543 0.003479957 0.147512 0.007004976 0.177498 0.003519952 0.207607 0.008531987 0.201892 0.0124939 0.225405 0.003519952 0.207607 0.001631975 0.177543 0.008531987 0.201892 0.008408963 0.236466 0.0124939 0.225405 0.01788097 0.246447 0.008408963 0.236466 0.003519952 0.207607 0.0124939 0.225405 0.0150299 0.262091 0.01788097 0.246447 0.02454096 0.263608 0.0150299 0.262091 0.008408963 0.236466 0.01788097 0.246447 0.0231319 0.282734 0.02454096 0.263608 0.03254497 0.276246 0.0231319 0.282734 0.0150299 0.262091 0.02454096 0.263608 0.03274995 0.297641 0.03254497 0.276246 0.04062891 0.284238 0.03274995 0.297641 0.0231319 0.282734 0.03254497 0.276246 0.04241997 0.306754 0.04062891 0.284238 0.04800593 0.288492 0.04241997 0.306754 0.03274995 0.297641 0.04062891 0.284238 0.05132395 0.311174 0.04800593 0.288492 0.05494689 0.289948 0.05132395 0.311174 0.04241997 0.306754 0.04800593 0.288492 0.05973798 0.312105 0.05132395 0.311174 0.05494689 0.289948 0.06450098 0.1436859 0.041426 0.137299 0.03551989 0.1313199 0.04228198 0.1316159 0.03551989 0.1313199 0.041426 0.137299 0.03362298 0.128967 0.06450098 0.1436859 0.03551989 0.1313199 0.02934288 0.111016 0.03362298 0.128967 0.03551989 0.1313199 0.02934288 0.111016 0.03551989 0.1313199 0.04228198 0.1316159 0.06450098 0.1436859 0.04771298 0.141435 0.041426 0.137299 0.05232989 0.141616 0.041426 0.137299 0.04771298 0.141435 0.04690599 0.137452 0.04228198 0.1316159 0.041426 0.137299 0.05232989 0.141616 0.04690599 0.137452 0.041426 0.137299 0.06450098 0.1436859 0.05099093 0.14284 0.04771298 0.141435 0.05525398 0.143009 0.04771298 0.141435 0.05099093 0.14284 0.05525398 0.143009 0.05232989 0.141616 0.04771298 0.141435 0.06450098 0.1436859 0.054223 0.1437489 0.05099093 0.14284 0.05826497 0.143922 0.05099093 0.14284 0.054223 0.1437489 0.05826497 0.143922 0.05525398 0.143009 0.05099093 0.14284 0.06450098 0.1436859 0.0603609 0.144102 0.054223 0.1437489 0.06132495 0.14435 0.054223 0.1437489 0.0603609 0.144102 0.06132495 0.14435 0.05826497 0.143922 0.054223 0.1437489 0.06440496 0.144291 0.0603609 0.144102 0.06450098 0.1436859 0.06440496 0.144291 0.06132495 0.14435 0.0603609 0.144102 0.03362298 0.128967 0.06014597 0.123579 0.06450098 0.1436859 0.07831096 0.142305 0.06450098 0.1436859 0.06014597 0.123579 0.06440496 0.144291 0.06450098 0.1436859 0.07831096 0.142305 0.03063398 0.110198 0.05723893 0.103147 0.06014597 0.123579 0.08638197 0.121711 0.06014597 0.123579 0.05723893 0.103147 0.03362298 0.128967 0.03063398 0.110198 0.06014597 0.123579 0.09056395 0.14109 0.07831096 0.142305 0.06014597 0.123579 0.08638197 0.121711 0.09056395 0.14109 0.06014597 0.123579 0.02884596 0.09123295 0.055785 0.08252 0.05723893 0.103147 0.08359098 0.102021 0.05723893 0.103147 0.055785 0.08252 0.03063398 0.110198 0.02884596 0.09123295 0.05723893 0.103147 0.08359098 0.102021 0.08638197 0.121711 0.05723893 0.103147 0.02824896 0.07217496 0.055785 0.06182897 0.055785 0.08252 0.08219397 0.08214396 0.055785 0.08252 0.055785 0.06182897 0.02884596 0.09123295 0.02824896 0.07217496 0.055785 0.08252 0.08219397 0.08214396 0.08359098 0.102021 0.055785 0.08252 0.02884596 0.05311596 0.05723893 0.04120296 0.055785 0.06182897 0.08359098 0.04232895 0.055785 0.06182897 0.05723893 0.04120296 0.02824896 0.07217496 0.02884596 0.05311596 0.055785 0.06182897 0.08219397 0.06220489 0.08219397 0.08214396 0.055785 0.06182897 0.08359098 0.04232895 0.08219397 0.06220489 0.055785 0.06182897 0.03063398 0.03415089 0.06014597 0.0207709 0.05723893 0.04120296 0.08638197 0.02263796 0.05723893 0.04120296 0.06014597 0.0207709 0.02884596 0.05311596 0.03063398 0.03415089 0.05723893 0.04120296 0.08638197 0.02263796 0.08359098 0.04232895 0.05723893 0.04120296 0.05422097 6.01e-4 0.06450098 6.64e-4 0.06014597 0.0207709 0.07831096 0.002044916 0.06014597 0.0207709 0.06450098 6.64e-4 0.05098789 0.001510918 0.05422097 6.01e-4 0.06014597 0.0207709 0.04770892 0.002916932 0.05098789 0.001510918 0.06014597 0.0207709 0.04142391 0.007051885 0.04770892 0.002916932 0.06014597 0.0207709 0.03551989 0.01302999 0.04142391 0.007051885 0.06014597 0.0207709 0.03362697 0.01537793 0.03551989 0.01302999 0.06014597 0.0207709 0.03063398 0.03415089 0.03362697 0.01537793 0.06014597 0.0207709 0.09056395 0.003259897 0.08638197 0.02263796 0.06014597 0.0207709 0.07831096 0.002044916 0.09056395 0.003259897 0.06014597 0.0207709 0.05422097 6.01e-4 0.0603609 2.48e-4 0.06450098 6.64e-4 0.100233 0.003607988 0.06450098 6.64e-4 0.0603609 2.48e-4 0.100233 0.003607988 0.07831096 0.002044916 0.06450098 6.64e-4 0.06440496 5.8e-5 0.0603609 2.48e-4 0.05422097 6.01e-4 0.100233 0.003607988 0.0603609 2.48e-4 0.06440496 5.8e-5 0.05826497 4.28e-4 0.05422097 6.01e-4 0.05098789 0.001510918 0.06132495 0 0.05422097 6.01e-4 0.05826497 4.28e-4 0.06440496 5.8e-5 0.05422097 6.01e-4 0.06132495 0 0.05525398 0.001339972 0.05098789 0.001510918 0.04770892 0.002916932 0.05826497 4.28e-4 0.05098789 0.001510918 0.05525398 0.001339972 0.05232989 0.002733886 0.04770892 0.002916932 0.04142391 0.007051885 0.05525398 0.001339972 0.04770892 0.002916932 0.05232989 0.002733886 0.04690599 0.006897926 0.04142391 0.007051885 0.03551989 0.01302999 0.05232989 0.002733886 0.04142391 0.007051885 0.04690599 0.006897926 0.04228198 0.01273298 0.03551989 0.01302999 0.03362697 0.01537793 0.04690599 0.006897926 0.03551989 0.01302999 0.04228198 0.01273298 0.01981699 0.03337198 0.03362697 0.01537793 0.03063398 0.03415089 0.04228198 0.01273298 0.03362697 0.01537793 0.01981699 0.03337198 0.01981699 0.03337198 0.03063398 0.03415089 0.02884596 0.05311596 0.005089998 0.05449098 0.02884596 0.05311596 0.02824896 0.07217496 0.005089998 0.05449098 0.01981699 0.03337198 0.02884596 0.05311596 0 0.07217496 0.02824896 0.07217496 0.02884596 0.09123295 0.002332985 0.05979496 0.005089998 0.05449098 0.02824896 0.07217496 5.94e-4 0.06580799 0.002332985 0.05979496 0.02824896 0.07217496 0 0.07217496 5.94e-4 0.06580799 0.02824896 0.07217496 0.005088925 0.089859 0.02884596 0.09123295 0.03063398 0.110198 5.94e-4 0.07854199 0 0.07217496 0.02884596 0.09123295 0.002332985 0.08455395 5.94e-4 0.07854199 0.02884596 0.09123295 0.005088925 0.089859 0.002332985 0.08455395 0.02884596 0.09123295 0.01981699 0.110977 0.03063398 0.110198 0.03362298 0.128967 0.01981699 0.110977 0.005088925 0.089859 0.03063398 0.110198 0.02934288 0.111016 0.01981699 0.110977 0.03362298 0.128967 0.06440496 0.144291 0.07831096 0.142305 0.09056395 0.14109 0.09584599 0.140569 0.09056395 0.14109 0.08638197 0.121711 0.06440496 0.144291 0.09056395 0.14109 0.09584599 0.140569 0.110897 0.114822 0.08638197 0.121711 0.08359098 0.102021 0.100005 0.139869 0.09584599 0.140569 0.08638197 0.121711 0.103983 0.138599 0.100005 0.139869 0.08638197 0.121711 0.107767 0.136764 0.103983 0.138599 0.08638197 0.121711 0.111337 0.134362 0.107767 0.136764 0.08638197 0.121711 0.114241 0.1318269 0.111337 0.134362 0.08638197 0.121711 0.110897 0.114822 0.114241 0.1318269 0.08638197 0.121711 0.108766 0.09784799 0.08359098 0.102021 0.08219397 0.08214396 0.108766 0.09784799 0.110897 0.114822 0.08359098 0.102021 0.1077 0.080747 0.08219397 0.08214396 0.08219397 0.06220489 0.1077 0.080747 0.108766 0.09784799 0.08219397 0.08214396 0.108766 0.04650396 0.08219397 0.06220489 0.08359098 0.04232895 0.1077 0.06360399 0.1077 0.080747 0.08219397 0.06220489 0.108766 0.04650396 0.1077 0.06360399 0.08219397 0.06220489 0.110897 0.02952992 0.08359098 0.04232895 0.08638197 0.02263796 0.110897 0.02952992 0.108766 0.04650396 0.08359098 0.04232895 0.114242 0.01252388 0.08638197 0.02263796 0.09056395 0.003259897 0.114242 0.01252388 0.110897 0.02952992 0.08638197 0.02263796 0.100233 0.003607988 0.09056395 0.003259897 0.07831096 0.002044916 0.111398 0.01003599 0.114242 0.01252388 0.09056395 0.003259897 0.10781 0.007610976 0.111398 0.01003599 0.09056395 0.003259897 0.104008 0.005760908 0.10781 0.007610976 0.09056395 0.003259897 0.100015 0.004482984 0.104008 0.005760908 0.09056395 0.003259897 0.09584599 0.003780961 0.100015 0.004482984 0.09056395 0.003259897 0.100233 0.003607988 0.09584599 0.003780961 0.09056395 0.003259897 0.100233 0.140741 0.09584599 0.140569 0.100005 0.139869 0.100233 0.140741 0.06440496 0.144291 0.09584599 0.140569 0.108523 0.138791 0.100005 0.139869 0.103983 0.138599 0.10442 0.1400409 0.100005 0.139869 0.108523 0.138791 0.100233 0.140741 0.100005 0.139869 0.10442 0.1400409 0.1125349 0.137004 0.103983 0.138599 0.107767 0.136764 0.108523 0.138791 0.103983 0.138599 0.1125349 0.137004 0.116406 0.134698 0.107767 0.136764 0.111337 0.134362 0.1125349 0.137004 0.107767 0.136764 0.116406 0.134698 0.116406 0.134698 0.111337 0.134362 0.114241 0.1318269 0.117574 0.128107 0.114241 0.1318269 0.110897 0.114822 0.123594 0.128661 0.114241 0.1318269 0.117574 0.128107 0.116406 0.134698 0.114241 0.1318269 0.123594 0.128661 0.126727 0.110337 0.110897 0.114822 0.108766 0.09784799 0.120276 0.124283 0.117574 0.128107 0.110897 0.114822 0.122706 0.120017 0.120276 0.124283 0.110897 0.114822 0.124855 0.115357 0.122706 0.120017 0.110897 0.114822 0.126727 0.110337 0.124855 0.115357 0.110897 0.114822 0.1306689 0.09371095 0.108766 0.09784799 0.1077 0.080747 0.128322 0.104997 0.126727 0.110337 0.108766 0.09784799 0.1296319 0.09943997 0.128322 0.104997 0.108766 0.09784799 0.1306689 0.09371095 0.1296319 0.09943997 0.108766 0.09784799 0.132073 0.08003699 0.1077 0.080747 0.1077 0.06360399 0.131444 0.08783596 0.1306689 0.09371095 0.1077 0.080747 0.132073 0.08003699 0.131444 0.08783596 0.1077 0.080747 0.131444 0.05651295 0.1077 0.06360399 0.108766 0.04650396 0.132282 0.07217496 0.132073 0.08003699 0.1077 0.06360399 0.132073 0.06431299 0.132282 0.07217496 0.1077 0.06360399 0.131444 0.05651295 0.132073 0.06431299 0.1077 0.06360399 0.129663 0.04506099 0.108766 0.04650396 0.110897 0.02952992 0.130684 0.05072891 0.131444 0.05651295 0.108766 0.04650396 0.129663 0.04506099 0.130684 0.05072891 0.108766 0.04650396 0.124933 0.02918189 0.110897 0.02952992 0.114242 0.01252388 0.128371 0.03953891 0.129663 0.04506099 0.110897 0.02952992 0.126792 0.03420895 0.128371 0.03953891 0.110897 0.02952992 0.124933 0.02918189 0.126792 0.03420895 0.110897 0.02952992 0.123645 0.015742 0.114242 0.01252388 0.111398 0.01003599 0.122791 0.02450096 0.124933 0.02918189 0.114242 0.01252388 0.1203629 0.02020597 0.122791 0.02450096 0.114242 0.01252388 0.117657 0.016348 0.1203629 0.02020597 0.114242 0.01252388 0.123645 0.015742 0.117657 0.016348 0.114242 0.01252388 0.116447 0.009679973 0.111398 0.01003599 0.10781 0.007610976 0.123645 0.015742 0.111398 0.01003599 0.116447 0.009679973 0.112565 0.007361948 0.10781 0.007610976 0.104008 0.005760908 0.116447 0.009679973 0.10781 0.007610976 0.112565 0.007361948 0.108542 0.005565941 0.104008 0.005760908 0.100015 0.004482984 0.112565 0.007361948 0.104008 0.005760908 0.108542 0.005565941 0.104429 0.004310965 0.100015 0.004482984 0.09584599 0.003780961 0.108542 0.005565941 0.100015 0.004482984 0.104429 0.004310965 0.104429 0.004310965 0.09584599 0.003780961 0.100233 0.003607988 0.123594 0.128661 0.117574 0.128107 0.120276 0.124283 0.129908 0.120885 0.120276 0.124283 0.122706 0.120017 0.123594 0.128661 0.120276 0.124283 0.129908 0.120885 0.129908 0.120885 0.122706 0.120017 0.124855 0.115357 0.135173 0.111634 0.124855 0.115357 0.126727 0.110337 0.129908 0.120885 0.124855 0.115357 0.135173 0.111634 0.135173 0.111634 0.126727 0.110337 0.128322 0.104997 0.139239 0.10122 0.128322 0.104997 0.1296319 0.09943997 0.135173 0.111634 0.128322 0.104997 0.139239 0.10122 0.14079 0.09567695 0.1296319 0.09943997 0.1306689 0.09371095 0.139239 0.10122 0.1296319 0.09943997 0.14079 0.09567695 0.1420069 0.08995896 0.1306689 0.09371095 0.131444 0.08783596 0.14079 0.09567695 0.1306689 0.09371095 0.1420069 0.08995896 0.142882 0.084113 0.131444 0.08783596 0.132073 0.08003699 0.1420069 0.08995896 0.131444 0.08783596 0.142882 0.084113 0.14341 0.078188 0.132073 0.08003699 0.132282 0.07217496 0.142882 0.084113 0.132073 0.08003699 0.14341 0.078188 0.143414 0.066235 0.132282 0.07217496 0.132073 0.06431299 0.143588 0.07221096 0.132282 0.07217496 0.143414 0.066235 0.14341 0.078188 0.132282 0.07217496 0.143588 0.07221096 0.142891 0.0603109 0.132073 0.06431299 0.131444 0.05651295 0.143414 0.066235 0.132073 0.06431299 0.142891 0.0603109 0.142021 0.05446696 0.131444 0.05651295 0.130684 0.05072891 0.142891 0.0603109 0.131444 0.05651295 0.142021 0.05446696 0.140808 0.04874789 0.130684 0.05072891 0.129663 0.04506099 0.142021 0.05446696 0.130684 0.05072891 0.140808 0.04874789 0.139262 0.04320293 0.129663 0.04506099 0.128371 0.03953891 0.140808 0.04874789 0.129663 0.04506099 0.139262 0.04320293 0.139262 0.04320293 0.128371 0.03953891 0.126792 0.03420895 0.135205 0.03278297 0.126792 0.03420895 0.124933 0.02918189 0.139262 0.04320293 0.126792 0.03420895 0.135205 0.03278297 0.135205 0.03278297 0.124933 0.02918189 0.122791 0.02450096 0.129953 0.02353 0.122791 0.02450096 0.1203629 0.02020597 0.135205 0.03278297 0.122791 0.02450096 0.129953 0.02353 0.129953 0.02353 0.1203629 0.02020597 0.117657 0.016348 0.129953 0.02353 0.117657 0.016348 0.123645 0.015742 0.02934288 0.03333389 0.01981699 0.03337198 0.005089998 0.05449098 0.04228198 0.01273298 0.01981699 0.03337198 0.02934288 0.03333389 0.01605695 0.05446493 0.005089998 0.05449098 0.002332985 0.05979496 0.02934288 0.03333389 0.005089998 0.05449098 0.01605695 0.05446493 0.01304197 0.06092488 0.002332985 0.05979496 5.94e-4 0.06580799 0.01605695 0.05446493 0.002332985 0.05979496 0.01304197 0.06092488 0.01146394 0.06831496 5.94e-4 0.06580799 0 0.07217496 0.01304197 0.06092488 5.94e-4 0.06580799 0.01146394 0.06831496 0.01146394 0.07603496 0 0.07217496 5.94e-4 0.07854199 0.01146394 0.06831496 0 0.07217496 0.01146394 0.07603496 0.01304197 0.08342498 5.94e-4 0.07854199 0.002332985 0.08455395 0.01146394 0.07603496 5.94e-4 0.07854199 0.01304197 0.08342498 0.01304197 0.08342498 0.002332985 0.08455395 0.005088925 0.089859 0.01605695 0.08988398 0.005088925 0.089859 0.01981699 0.110977 0.01304197 0.08342498 0.005088925 0.089859 0.01605695 0.08988398 0.02934288 0.111016 0.01605695 0.08988398 0.01981699 0.110977 0.04228198 0.01273298 0.04228198 0.1316159 0.04690599 0.137452 0.02934288 0.03333389 0.02934288 0.111016 0.04228198 0.1316159 0.04228198 0.01273298 0.02934288 0.03333389 0.04228198 0.1316159 0.04690599 0.006897926 0.04690599 0.137452 0.05232989 0.141616 0.04690599 0.006897926 0.04228198 0.01273298 0.04690599 0.137452 0.05232989 0.002733886 0.05232989 0.141616 0.05525398 0.143009 0.05232989 0.002733886 0.04690599 0.006897926 0.05232989 0.141616 0.05525398 0.001339972 0.05525398 0.143009 0.05826497 0.143922 0.05525398 0.001339972 0.05232989 0.002733886 0.05525398 0.143009 0.05826497 4.28e-4 0.05826497 0.143922 0.06132495 0.14435 0.05826497 4.28e-4 0.05525398 0.001339972 0.05826497 0.143922 0.06132495 0 0.06132495 0.14435 0.06440496 0.144291 0.06132495 0 0.05826497 4.28e-4 0.06132495 0.14435 0.06440496 5.8e-5 0.06132495 0 0.06440496 0.144291 0.100233 0.140741 0.06440496 5.8e-5 0.06440496 0.144291 0.01605695 0.05446493 0.01605695 0.08988398 0.02934288 0.111016 0.01304197 0.06092488 0.01304197 0.08342498 0.01605695 0.08988398 0.01605695 0.05446493 0.01304197 0.06092488 0.01605695 0.08988398 0.02934288 0.03333389 0.01605695 0.05446493 0.02934288 0.111016 0.01146394 0.06831496 0.01146394 0.07603496 0.01304197 0.08342498 0.01304197 0.06092488 0.01146394 0.06831496 0.01304197 0.08342498 0.100233 0.140741 0.100233 0.003607988 0.06440496 5.8e-5 0.10442 0.1400409 0.104429 0.004310965 0.100233 0.003607988 0.100233 0.140741 0.10442 0.1400409 0.100233 0.003607988 0.108523 0.138791 0.108542 0.005565941 0.104429 0.004310965 0.10442 0.1400409 0.108523 0.138791 0.104429 0.004310965 0.1125349 0.137004 0.112565 0.007361948 0.108542 0.005565941 0.108523 0.138791 0.1125349 0.137004 0.108542 0.005565941 0.116406 0.134698 0.116447 0.009679973 0.112565 0.007361948 0.1125349 0.137004 0.116406 0.134698 0.112565 0.007361948 0.123594 0.128661 0.123645 0.015742 0.116447 0.009679973 0.116406 0.134698 0.123594 0.128661 0.116447 0.009679973 0.129908 0.120885 0.129953 0.02353 0.123645 0.015742 0.123594 0.128661 0.129908 0.120885 0.123645 0.015742 0.135173 0.111634 0.135205 0.03278297 0.129953 0.02353 0.129908 0.120885 0.135173 0.111634 0.129953 0.02353 0.139239 0.10122 0.139262 0.04320293 0.135205 0.03278297 0.135173 0.111634 0.139239 0.10122 0.135205 0.03278297 0.14079 0.09567695 0.140808 0.04874789 0.139262 0.04320293 0.139239 0.10122 0.14079 0.09567695 0.139262 0.04320293 0.1420069 0.08995896 0.142021 0.05446696 0.140808 0.04874789 0.14079 0.09567695 0.1420069 0.08995896 0.140808 0.04874789 0.142882 0.084113 0.142891 0.0603109 0.142021 0.05446696 0.1420069 0.08995896 0.142882 0.084113 0.142021 0.05446696 0.14341 0.078188 0.143414 0.066235 0.142891 0.0603109 0.142882 0.084113 0.14341 0.078188 0.142891 0.0603109 0.14341 0.078188 0.143588 0.07221096 0.143414 0.066235 - - - - - - - - - - - - - - -

0 0 0 1 1 1 2 2 2 3 3 3 4 3 4 5 3 5 6 4 6 7 5 7 8 6 8 9 7 9 10 7 10 4 7 11 3 8 12 9 8 13 4 8 14 0 0 15 11 9 16 1 1 17 3 10 18 5 10 19 12 10 20 0 0 21 13 11 22 11 9 23 14 12 24 15 13 25 16 14 26 14 12 27 17 15 28 15 13 29 3 16 30 12 16 31 18 16 32 0 0 33 19 17 34 13 11 35 20 18 36 16 14 37 21 19 38 14 12 39 16 14 40 20 18 41 22 20 42 23 21 43 19 17 44 20 18 45 21 19 46 24 22 47 25 23 48 22 20 49 19 17 50 0 0 51 25 23 52 19 17 53 26 24 54 27 25 55 28 26 56 29 27 57 27 25 58 26 24 59 30 28 60 31 29 61 32 30 62 30 28 63 33 31 64 31 29 65 26 24 66 28 26 67 34 32 68 35 33 69 36 34 70 7 5 71 37 35 72 36 34 73 35 33 74 38 36 75 39 37 76 40 38 77 41 39 78 39 37 79 38 36 80 35 33 81 7 5 82 6 4 83 42 40 84 43 41 85 44 42 86 45 43 87 46 43 88 47 43 89 48 44 90 42 40 91 44 42 92 49 45 93 50 46 94 51 47 95 52 48 96 51 47 97 53 49 98 45 50 99 54 50 100 46 50 101 52 48 102 49 45 103 51 47 104 42 40 105 55 51 106 43 41 107 56 52 108 47 52 109 57 52 110 56 53 111 45 53 112 47 53 113 35 33 114 6 4 115 55 51 116 56 54 117 57 54 118 10 54 119 42 40 120 35 33 121 55 51 122 9 55 123 56 55 124 10 55 125 37 35 126 35 33 127 42 40 128 58 56 129 42 40 130 48 44 131 59 57 132 37 35 133 42 40 134 58 56 135 59 57 136 42 40 137 58 56 138 48 44 139 60 58 140 61 59 141 62 60 142 50 46 143 63 61 144 61 59 145 50 46 146 64 62 147 63 61 148 50 46 149 49 45 150 64 62 151 50 46 152 65 63 153 66 64 154 38 36 155 67 65 156 38 36 157 66 64 158 68 66 159 69 67 160 70 68 161 71 69 162 67 65 163 66 64 164 68 66 165 72 70 166 69 67 167 41 39 168 38 36 169 67 65 170 52 48 171 53 49 172 73 71 173 45 72 174 74 72 175 54 72 176 75 73 177 76 74 178 77 75 179 45 76 180 78 76 181 74 76 182 68 66 183 70 68 184 79 77 185 80 78 186 81 79 187 82 80 188 83 81 189 81 79 190 80 78 191 84 82 192 85 83 193 86 84 194 87 85 195 82 80 196 88 86 197 80 78 198 82 80 199 87 85 200 89 87 201 88 86 202 76 74 203 87 85 204 88 86 205 89 87 206 89 87 207 76 74 208 75 73 209 90 88 210 91 89 211 92 90 212 93 91 213 94 91 214 95 91 215 96 92 216 90 88 217 92 90 218 97 93 219 98 94 220 99 95 221 93 96 222 100 96 223 94 96 224 90 88 225 101 97 226 91 89 227 93 98 228 95 98 229 102 98 230 103 99 231 104 100 232 101 97 233 105 101 234 102 101 235 106 101 236 90 88 237 103 99 238 101 97 239 105 102 240 93 102 241 102 102 242 103 99 243 107 103 244 104 100 245 108 104 246 106 104 247 109 104 248 108 105 249 105 105 250 106 105 251 110 106 252 111 107 253 107 103 254 112 108 255 109 108 256 113 108 257 103 99 258 110 106 259 107 103 260 112 109 261 108 109 262 109 109 263 110 106 264 114 110 265 111 107 266 115 111 267 113 111 268 116 111 269 115 112 270 112 112 271 113 112 272 117 113 273 118 114 274 114 110 275 119 115 276 116 115 277 120 115 278 110 106 279 117 113 280 114 110 281 121 116 282 115 116 283 116 116 284 119 117 285 121 117 286 116 117 287 89 87 288 75 73 289 118 114 290 122 118 291 120 118 292 78 118 293 117 113 294 89 87 295 118 114 296 123 119 297 119 119 298 120 119 299 124 120 300 123 120 301 120 120 302 122 121 303 124 121 304 120 121 305 125 122 306 78 122 307 45 122 308 125 123 309 122 123 310 78 123 311 87 85 312 89 87 313 117 113 314 126 124 315 117 113 316 110 106 317 126 124 318 87 85 319 117 113 320 127 125 321 110 106 322 103 99 323 127 125 324 126 124 325 110 106 326 128 126 327 103 99 328 90 88 329 128 126 330 127 125 331 103 99 332 129 127 333 90 88 334 96 92 335 129 127 336 128 126 337 90 88 338 129 127 339 96 92 340 130 128 341 131 129 342 132 130 343 98 94 344 131 129 345 98 94 346 97 93 347 133 131 348 129 127 349 130 128 350 133 131 351 130 128 352 134 132 353 135 133 354 136 134 355 132 130 356 135 133 357 132 130 358 131 129 359 80 78 360 87 85 361 126 124 362 137 135 363 126 124 364 127 125 365 137 135 366 80 78 367 126 124 368 138 136 369 127 125 370 128 126 371 138 136 372 137 135 373 127 125 374 139 137 375 128 126 376 129 127 377 139 137 378 138 136 379 128 126 380 133 131 381 139 137 382 129 127 383 140 138 384 133 131 385 134 132 386 140 138 387 134 132 388 141 139 389 142 140 390 143 141 391 136 134 392 142 140 393 136 134 394 135 133 395 144 142 396 80 78 397 137 135 398 144 142 399 83 81 400 80 78 401 145 143 402 137 135 403 138 136 404 146 144 405 144 142 406 137 135 407 145 143 408 146 144 409 137 135 410 147 145 411 138 136 412 139 137 413 148 146 414 145 143 415 138 136 416 147 145 417 148 146 418 138 136 419 149 147 420 139 137 421 133 131 422 150 148 423 147 145 424 139 137 425 151 149 426 150 148 427 139 137 428 149 147 429 151 149 430 139 137 431 152 150 432 149 147 433 133 131 434 153 151 435 152 150 436 133 131 437 140 138 438 153 151 439 133 131 440 154 152 441 155 153 442 156 154 443 157 155 444 143 141 445 142 140 446 158 156 447 159 157 448 160 158 449 154 152 450 156 154 451 161 159 452 84 82 453 86 84 454 162 160 455 163 161 456 162 160 457 164 162 458 84 82 459 162 160 460 165 163 461 163 161 462 165 163 463 162 160 464 163 161 465 164 162 466 166 164 467 167 165 468 166 164 469 168 166 470 163 161 471 166 164 472 167 165 473 167 165 474 168 166 475 169 167 476 167 165 477 169 167 478 170 168 479 171 169 480 170 168 481 172 170 482 167 165 483 170 168 484 171 169 485 171 169 486 172 170 487 173 171 488 171 169 489 173 171 490 174 172 491 171 169 492 174 172 493 175 173 494 154 152 495 175 173 496 155 153 497 171 169 498 175 173 499 154 152 500 176 174 501 177 175 502 178 176 503 179 177 504 180 177 505 181 177 506 182 178 507 176 174 508 178 176 509 183 179 510 184 180 511 185 181 512 186 182 513 187 182 514 180 182 515 179 183 516 186 183 517 180 183 518 176 174 519 188 184 520 177 175 521 179 185 522 181 185 523 189 185 524 190 186 525 191 187 526 188 184 527 192 188 528 189 188 529 193 188 530 176 174 531 190 186 532 188 184 533 192 189 534 179 189 535 189 189 536 194 190 537 195 191 538 191 187 539 192 192 540 193 192 541 196 192 542 190 186 543 194 190 544 191 187 545 194 190 546 197 193 547 195 191 548 198 194 549 196 194 550 199 194 551 198 195 552 192 195 553 196 195 554 200 196 555 201 197 556 197 193 557 198 198 558 199 198 559 202 198 560 194 190 561 200 196 562 197 193 563 131 129 564 97 93 565 201 197 566 93 199 567 202 199 568 100 199 569 200 196 570 131 129 571 201 197 572 93 200 573 198 200 574 202 200 575 135 133 576 131 129 577 200 196 578 203 201 579 200 196 580 194 190 581 203 201 582 135 133 583 200 196 584 204 202 585 194 190 586 190 186 587 204 202 588 203 201 589 194 190 590 205 203 591 190 186 592 176 174 593 205 203 594 204 202 595 190 186 596 206 204 597 176 174 598 182 178 599 206 204 600 205 203 601 176 174 602 206 204 603 182 178 604 207 205 605 208 206 606 209 207 607 184 180 608 208 206 609 184 180 610 183 179 611 210 208 612 206 204 613 207 205 614 208 206 615 211 209 616 209 207 617 142 140 618 135 133 619 203 201 620 212 210 621 203 201 622 204 202 623 212 210 624 142 140 625 203 201 626 213 211 627 204 202 628 205 203 629 213 211 630 212 210 631 204 202 632 214 212 633 205 203 634 206 204 635 214 212 636 213 211 637 205 203 638 215 213 639 206 204 640 210 208 641 215 213 642 214 212 643 206 204 644 215 213 645 210 208 646 216 214 647 217 215 648 218 216 649 211 209 650 217 215 651 211 209 652 208 206 653 219 217 654 215 213 655 216 214 656 220 218 657 221 219 658 218 216 659 220 218 660 218 216 661 217 215 662 222 220 663 142 140 664 212 210 665 223 221 666 157 155 667 142 140 668 222 220 669 223 221 670 142 140 671 224 222 672 212 210 673 213 211 674 224 222 675 222 220 676 212 210 677 225 223 678 213 211 679 214 212 680 225 223 681 224 222 682 213 211 683 226 224 684 214 212 685 215 213 686 227 225 687 225 223 688 214 212 689 226 224 690 227 225 691 214 212 692 228 226 693 215 213 694 219 217 695 228 226 696 226 224 697 215 213 698 228 226 699 219 217 700 229 227 701 220 218 702 230 228 703 221 219 704 231 229 705 232 230 706 233 231 707 234 232 708 235 233 709 236 234 710 237 235 711 231 229 712 233 231 713 234 232 714 238 236 715 235 233 716 239 237 717 160 158 718 240 238 719 158 156 720 160 158 721 239 237 722 239 237 723 240 238 724 241 239 725 239 237 726 241 239 727 242 240 728 243 241 729 242 240 730 244 242 731 243 241 732 239 237 733 242 240 734 245 243 735 244 242 736 246 244 737 245 243 738 243 241 739 244 242 740 245 243 741 246 244 742 247 245 743 231 229 744 247 245 745 232 230 746 231 229 747 245 243 748 247 245 749 248 246 750 183 179 751 249 247 752 186 248 753 250 248 754 187 248 755 251 249 756 252 250 757 253 251 758 251 249 759 253 251 760 254 252 761 186 253 762 255 253 763 250 253 764 248 246 765 208 206 766 183 179 767 256 254 768 217 215 769 208 206 770 248 246 771 256 254 772 208 206 773 257 255 774 220 218 775 217 215 776 256 254 777 257 255 778 217 215 779 258 256 780 236 234 781 259 257 782 258 256 783 234 232 784 236 234 785 260 258 786 261 259 787 262 260 788 263 261 789 264 262 790 265 263 791 263 261 792 266 264 793 264 262 794 267 265 795 262 260 796 252 250 797 268 266 798 260 258 799 262 260 800 269 267 801 268 266 802 262 260 803 267 265 804 269 267 805 262 260 806 251 249 807 267 265 808 252 250 809 251 249 810 254 252 811 270 268 812 186 269 813 271 269 814 255 269 815 272 270 816 273 271 817 274 272 818 275 273 819 276 273 820 271 273 821 186 274 822 275 274 823 271 274 824 277 275 825 265 263 826 278 276 827 263 261 828 265 263 829 277 275 830 277 275 831 278 276 832 279 277 833 280 278 834 281 279 835 282 280 836 283 281 837 281 279 838 280 278 839 284 282 840 285 283 841 286 284 842 287 285 843 285 283 844 284 282 845 288 286 846 282 280 847 273 271 848 288 286 849 280 278 850 282 280 851 272 270 852 288 286 853 273 271 854 289 287 855 290 288 856 291 289 857 292 290 858 291 289 859 290 288 860 293 291 861 294 292 862 295 293 863 296 294 864 291 289 865 292 290 866 297 295 867 298 295 868 299 295 869 300 296 870 301 297 871 302 298 872 300 296 873 302 298 874 303 299 875 304 300 876 305 301 877 306 302 878 307 302 879 304 300 880 306 302 881 308 303 882 309 304 883 290 288 884 292 290 885 290 288 886 309 304 887 310 305 888 308 303 889 290 288 890 289 287 891 310 305 892 290 288 893 311 306 894 312 307 895 309 304 896 313 308 897 309 304 898 312 307 899 314 309 900 311 306 901 309 304 902 315 310 903 314 309 904 309 304 905 316 311 906 315 310 907 309 304 908 308 303 909 316 311 910 309 304 911 313 308 912 292 290 913 309 304 914 317 312 915 280 278 916 312 307 917 318 313 918 312 307 919 280 278 920 319 314 921 317 312 922 312 307 923 320 315 924 319 314 925 312 307 926 311 306 927 320 315 928 312 307 929 318 313 930 313 308 931 312 307 932 321 316 933 283 281 934 280 278 935 317 312 936 321 316 937 280 278 938 288 286 939 318 313 940 280 278 941 284 282 942 286 284 943 322 317 944 323 318 945 322 317 946 324 319 947 284 282 948 322 317 949 323 318 950 323 318 951 324 319 952 325 320 953 326 321 954 325 320 955 327 322 956 323 318 957 325 320 958 326 321 959 326 321 960 327 322 961 328 323 962 329 324 963 328 323 964 330 325 965 326 321 966 328 323 967 329 324 968 329 324 969 330 325 970 331 326 971 329 324 972 331 326 973 332 327 974 333 328 975 332 327 976 334 329 977 329 324 978 332 327 979 333 328 980 333 328 981 334 329 982 335 330 983 336 331 984 335 330 985 294 292 986 337 332 987 333 328 988 335 330 989 336 331 990 337 332 991 335 330 992 293 291 993 336 331 994 294 292 995 338 333 996 292 290 997 313 308 998 338 333 999 296 294 1000 292 290 1001 339 334 1002 313 308 1003 318 313 1004 339 334 1005 338 333 1006 313 308 1007 340 335 1008 318 313 1009 288 286 1010 341 336 1011 339 334 1012 318 313 1013 340 335 1014 341 336 1015 318 313 1016 272 270 1017 340 335 1018 288 286 1019 275 337 1020 299 337 1021 342 337 1022 343 338 1023 297 338 1024 299 338 1025 275 339 1026 343 339 1027 299 339 1028 275 340 1029 342 340 1030 344 340 1031 275 341 1032 344 341 1033 345 341 1034 275 342 1035 345 342 1036 346 342 1037 275 343 1038 346 343 1039 276 343 1040 347 344 1041 348 345 1042 333 328 1043 329 324 1044 333 328 1045 348 345 1046 337 332 1047 347 344 1048 333 328 1049 349 346 1050 350 347 1051 348 345 1052 351 348 1053 348 345 1054 350 347 1055 347 344 1056 349 346 1057 348 345 1058 351 348 1059 329 324 1060 348 345 1061 352 349 1062 353 350 1063 350 347 1064 354 351 1065 350 347 1066 353 350 1067 349 346 1068 352 349 1069 350 347 1070 354 351 1071 351 348 1072 350 347 1073 355 352 1074 356 353 1075 353 350 1076 357 354 1077 353 350 1078 356 353 1079 352 349 1080 355 352 1081 353 350 1082 357 354 1083 354 351 1084 353 350 1085 358 355 1086 359 356 1087 356 353 1088 360 357 1089 356 353 1090 359 356 1091 355 352 1092 358 355 1093 356 353 1094 360 357 1095 357 354 1096 356 353 1097 361 358 1098 362 359 1099 359 356 1100 363 360 1101 359 356 1102 362 359 1103 364 361 1104 361 358 1105 359 356 1106 358 355 1107 364 361 1108 359 356 1109 363 360 1110 360 357 1111 359 356 1112 365 362 1113 366 363 1114 362 359 1115 367 364 1116 362 359 1117 366 363 1118 368 365 1119 365 362 1120 362 359 1121 361 358 1122 368 365 1123 362 359 1124 367 364 1125 363 360 1126 362 359 1127 369 366 1128 370 367 1129 366 363 1130 371 368 1131 366 363 1132 370 367 1133 365 362 1134 369 366 1135 366 363 1136 371 368 1137 367 364 1138 366 363 1139 372 369 1140 373 370 1141 370 367 1142 374 371 1143 370 367 1144 373 370 1145 375 372 1146 372 369 1147 370 367 1148 369 366 1149 375 372 1150 370 367 1151 374 371 1152 371 368 1153 370 367 1154 376 373 1155 377 374 1156 373 370 1157 374 371 1158 373 370 1159 377 374 1160 378 375 1161 376 373 1162 373 370 1163 372 369 1164 378 375 1165 373 370 1166 379 376 1167 380 377 1168 381 378 1169 382 379 1170 374 371 1171 377 374 1172 379 376 1173 383 380 1174 380 377 1175 384 381 1176 385 382 1177 386 383 1178 384 381 1179 387 384 1180 385 382 1181 379 376 1182 381 378 1183 388 385 1184 389 386 1185 386 383 1186 390 387 1187 389 386 1188 384 381 1189 386 383 1190 389 386 1191 390 387 1192 391 388 1193 389 386 1194 391 388 1195 392 389 1196 393 390 1197 392 389 1198 394 391 1199 393 390 1200 389 386 1201 392 389 1202 393 390 1203 394 391 1204 395 392 1205 396 393 1206 395 392 1207 397 394 1208 396 393 1209 393 390 1210 395 392 1211 396 393 1212 397 394 1213 398 395 1214 399 396 1215 398 395 1216 400 397 1217 399 396 1218 396 393 1219 398 395 1220 399 396 1221 400 397 1222 401 398 1223 402 399 1224 401 398 1225 403 400 1226 402 399 1227 399 396 1228 401 398 1229 404 401 1230 403 400 1231 405 402 1232 404 401 1233 402 399 1234 403 400 1235 404 401 1236 405 402 1237 406 403 1238 407 404 1239 406 403 1240 408 405 1241 407 404 1242 404 401 1243 406 403 1244 300 296 1245 408 405 1246 409 406 1247 300 296 1248 407 404 1249 408 405 1250 300 296 1251 409 406 1252 301 297 1253 326 321 1254 329 324 1255 351 348 1256 410 407 1257 351 348 1258 354 351 1259 410 407 1260 326 321 1261 351 348 1262 411 408 1263 354 351 1264 357 354 1265 411 408 1266 410 407 1267 354 351 1268 412 409 1269 357 354 1270 360 357 1271 412 409 1272 411 408 1273 357 354 1274 413 410 1275 360 357 1276 363 360 1277 413 410 1278 412 409 1279 360 357 1280 414 411 1281 363 360 1282 367 364 1283 414 411 1284 413 410 1285 363 360 1286 415 412 1287 367 364 1288 371 368 1289 415 412 1290 414 411 1291 367 364 1292 416 413 1293 371 368 1294 374 371 1295 416 413 1296 415 412 1297 371 368 1298 417 414 1299 374 371 1300 382 379 1301 417 414 1302 416 413 1303 374 371 1304 418 415 1305 417 414 1306 382 379 1307 419 416 1308 420 417 1309 383 380 1310 419 416 1311 383 380 1312 379 376 1313 323 318 1314 326 321 1315 410 407 1316 421 418 1317 410 407 1318 411 408 1319 421 418 1320 323 318 1321 410 407 1322 422 419 1323 411 408 1324 412 409 1325 422 419 1326 421 418 1327 411 408 1328 423 420 1329 412 409 1330 413 410 1331 423 420 1332 422 419 1333 412 409 1334 424 421 1335 413 410 1336 414 411 1337 424 421 1338 423 420 1339 413 410 1340 425 422 1341 414 411 1342 415 412 1343 425 422 1344 424 421 1345 414 411 1346 426 423 1347 415 412 1348 416 413 1349 426 423 1350 425 422 1351 415 412 1352 427 424 1353 416 413 1354 417 414 1355 427 424 1356 426 423 1357 416 413 1358 427 424 1359 417 414 1360 418 415 1361 428 425 1362 427 424 1363 418 415 1364 429 426 1365 430 427 1366 420 417 1367 429 426 1368 420 417 1369 419 416 1370 284 282 1371 323 318 1372 421 418 1373 431 428 1374 421 418 1375 422 419 1376 431 428 1377 284 282 1378 421 418 1379 432 429 1380 422 419 1381 423 420 1382 432 429 1383 431 428 1384 422 419 1385 433 430 1386 423 420 1387 424 421 1388 433 430 1389 432 429 1390 423 420 1391 434 431 1392 424 421 1393 425 422 1394 434 431 1395 433 430 1396 424 421 1397 435 432 1398 425 422 1399 426 423 1400 435 432 1401 434 431 1402 425 422 1403 436 433 1404 426 423 1405 427 424 1406 436 433 1407 435 432 1408 426 423 1409 436 433 1410 427 424 1411 428 425 1412 437 434 1413 436 433 1414 428 425 1415 438 435 1416 439 436 1417 430 427 1418 438 435 1419 430 427 1420 429 426 1421 287 285 1422 284 282 1423 431 428 1424 440 437 1425 431 428 1426 432 429 1427 440 437 1428 287 285 1429 431 428 1430 441 438 1431 432 429 1432 433 430 1433 441 438 1434 440 437 1435 432 429 1436 442 439 1437 433 430 1438 434 431 1439 443 440 1440 441 438 1441 433 430 1442 442 439 1443 443 440 1444 433 430 1445 444 441 1446 434 431 1447 435 432 1448 445 442 1449 442 439 1450 434 431 1451 444 441 1452 445 442 1453 434 431 1454 446 443 1455 435 432 1456 436 433 1457 447 444 1458 444 441 1459 435 432 1460 448 445 1461 447 444 1462 435 432 1463 446 443 1464 448 445 1465 435 432 1466 449 446 1467 436 433 1468 437 434 1469 450 447 1470 446 443 1471 436 433 1472 449 446 1473 450 447 1474 436 433 1475 451 448 1476 449 446 1477 437 434 1478 452 449 1479 453 450 1480 439 436 1481 454 451 1482 439 436 1483 438 435 1484 455 452 1485 439 436 1486 454 451 1487 452 449 1488 439 436 1489 455 452 1490 263 261 1491 277 275 1492 456 453 1493 263 261 1494 456 453 1495 457 454 1496 263 261 1497 457 454 1498 458 455 1499 459 456 1500 458 455 1501 460 457 1502 263 261 1503 458 455 1504 459 456 1505 459 456 1506 460 457 1507 461 458 1508 459 456 1509 461 458 1510 462 459 1511 463 460 1512 462 459 1513 464 461 1514 465 462 1515 462 459 1516 463 460 1517 466 463 1518 462 459 1519 465 462 1520 467 464 1521 462 459 1522 466 463 1523 468 465 1524 462 459 1525 467 464 1526 469 466 1527 462 459 1528 468 465 1529 470 467 1530 462 459 1531 469 466 1532 459 456 1533 462 459 1534 470 467 1535 471 468 1536 464 461 1537 472 469 1538 463 460 1539 464 461 1540 471 468 1541 473 470 1542 472 469 1543 474 471 1544 475 472 1545 472 469 1546 473 470 1547 471 468 1548 472 469 1549 475 472 1550 476 473 1551 474 471 1552 477 474 1553 478 475 1554 474 471 1555 476 473 1556 479 476 1557 474 471 1558 478 475 1559 473 470 1560 474 471 1561 479 476 1562 480 477 1563 477 474 1564 481 478 1565 482 479 1566 477 474 1567 480 477 1568 483 480 1569 477 474 1570 482 479 1571 476 473 1572 477 474 1573 483 480 1574 484 481 1575 481 478 1576 485 482 1577 486 483 1578 481 478 1579 484 481 1580 487 484 1581 481 478 1582 486 483 1583 488 485 1584 481 478 1585 487 484 1586 480 477 1587 481 478 1588 488 485 1589 489 486 1590 490 487 1591 491 488 1592 489 489 1593 492 489 1594 490 489 1595 493 490 1596 485 482 1597 494 491 1598 484 481 1599 485 482 1600 493 490 1601 495 492 1602 496 492 1603 497 492 1604 304 300 1605 498 493 1606 305 301 1607 384 381 1608 499 494 1609 387 384 1610 379 376 1611 388 385 1612 500 495 1613 384 381 1614 501 496 1615 499 494 1616 502 497 1617 503 498 1618 504 499 1619 502 497 1620 505 500 1621 503 498 1622 506 501 1623 507 502 1624 501 496 1625 502 497 1626 504 499 1627 508 503 1628 384 381 1629 506 501 1630 501 496 1631 506 501 1632 509 504 1633 507 502 1634 510 505 1635 508 503 1636 511 506 1637 510 505 1638 502 497 1639 508 503 1640 506 501 1641 512 507 1642 509 504 1643 510 505 1644 511 506 1645 513 508 1646 506 501 1647 514 509 1648 512 507 1649 515 510 1650 513 508 1651 516 511 1652 510 505 1653 513 508 1654 515 510 1655 517 512 1656 518 513 1657 519 513 1658 520 514 1659 518 513 1660 517 512 1661 521 515 1662 522 516 1663 523 517 1664 524 518 1665 522 516 1666 521 515 1667 525 492 1668 526 492 1669 527 492 1670 528 519 1671 529 519 1672 526 519 1673 525 492 1674 528 492 1675 526 492 1676 530 520 1677 527 520 1678 531 520 1679 530 521 1680 525 521 1681 527 521 1682 532 492 1683 531 492 1684 533 492 1685 532 492 1686 530 492 1687 531 492 1688 534 492 1689 533 492 1690 535 492 1691 534 492 1692 532 492 1693 533 492 1694 536 492 1695 535 492 1696 537 492 1697 536 492 1698 534 492 1699 535 492 1700 538 492 1701 537 492 1702 539 492 1703 538 492 1704 536 492 1705 537 492 1706 540 492 1707 539 492 1708 541 492 1709 542 492 1710 538 492 1711 539 492 1712 540 522 1713 542 522 1714 539 522 1715 543 492 1716 541 492 1717 544 492 1718 543 523 1719 540 523 1720 541 523 1721 545 492 1722 544 492 1723 496 492 1724 545 492 1725 543 492 1726 544 492 1727 495 492 1728 546 492 1729 496 492 1730 545 524 1731 496 524 1732 546 524 1733 528 525 1734 547 525 1735 529 525 1736 520 514 1737 517 512 1738 548 526 1739 528 492 1740 549 492 1741 547 492 1742 550 527 1743 548 526 1744 551 528 1745 552 529 1746 520 514 1747 548 526 1748 550 530 1749 552 530 1750 548 530 1751 528 531 1752 553 531 1753 549 531 1754 554 532 1755 551 528 1756 555 533 1757 556 534 1758 550 527 1759 551 528 1760 557 535 1761 558 535 1762 559 535 1763 554 532 1764 556 534 1765 551 528 1766 560 492 1767 561 492 1768 553 492 1769 562 536 1770 555 533 1771 563 537 1772 528 538 1773 560 538 1774 553 538 1775 564 539 1776 554 532 1777 555 533 1778 565 540 1779 564 539 1780 555 533 1781 562 536 1782 565 540 1783 555 533 1784 560 492 1785 566 492 1786 561 492 1787 567 541 1788 563 537 1789 568 542 1790 567 541 1791 562 536 1792 563 537 1793 569 492 1794 570 492 1795 566 492 1796 571 543 1797 568 542 1798 572 544 1799 560 492 1800 569 492 1801 566 492 1802 571 543 1803 567 541 1804 568 542 1805 569 545 1806 573 545 1807 570 545 1808 574 546 1809 572 544 1810 575 547 1811 574 546 1812 571 543 1813 572 544 1814 576 492 1815 577 492 1816 573 492 1817 578 548 1818 575 547 1819 579 549 1820 569 492 1821 576 492 1822 573 492 1823 580 550 1824 574 546 1825 575 547 1826 578 548 1827 580 550 1828 575 547 1829 581 492 1830 582 492 1831 577 492 1832 583 551 1833 579 549 1834 584 552 1835 576 492 1836 581 492 1837 577 492 1838 583 551 1839 578 548 1840 579 549 1841 581 492 1842 585 492 1843 582 492 1844 586 553 1845 584 552 1846 587 554 1847 586 553 1848 583 551 1849 584 552 1850 588 492 1851 589 492 1852 585 492 1853 590 555 1854 587 554 1855 591 556 1856 581 492 1857 588 492 1858 585 492 1859 590 555 1860 586 553 1861 587 554 1862 588 492 1863 592 492 1864 589 492 1865 593 557 1866 591 556 1867 594 558 1868 593 557 1869 590 555 1870 591 556 1871 595 492 1872 596 492 1873 592 492 1874 593 557 1875 594 558 1876 597 559 1877 588 492 1878 595 492 1879 592 492 1880 595 492 1881 598 492 1882 596 492 1883 599 560 1884 597 559 1885 600 561 1886 599 560 1887 593 557 1888 597 559 1889 601 492 1890 602 492 1891 598 492 1892 603 562 1893 600 561 1894 604 563 1895 595 564 1896 601 564 1897 598 564 1898 603 562 1899 599 560 1900 600 561 1901 605 492 1902 606 492 1903 602 492 1904 607 565 1905 604 563 1906 608 566 1907 601 492 1908 605 492 1909 602 492 1910 607 565 1911 603 562 1912 604 563 1913 609 492 1914 610 492 1915 606 492 1916 611 567 1917 608 566 1918 612 568 1919 613 492 1920 609 492 1921 606 492 1922 605 492 1923 613 492 1924 606 492 1925 611 567 1926 607 565 1927 608 566 1928 614 492 1929 615 492 1930 610 492 1931 611 567 1932 612 568 1933 616 569 1934 609 492 1935 614 492 1936 610 492 1937 617 492 1938 618 492 1939 615 492 1940 619 570 1941 616 569 1942 620 571 1943 614 492 1944 617 492 1945 615 492 1946 619 570 1947 611 567 1948 616 569 1949 617 492 1950 621 492 1951 618 492 1952 622 572 1953 620 571 1954 623 573 1955 622 572 1956 619 570 1957 620 571 1958 624 574 1959 623 573 1960 625 575 1961 624 574 1962 622 572 1963 623 573 1964 626 576 1965 625 575 1966 627 577 1967 626 576 1968 624 574 1969 625 575 1970 628 578 1971 627 577 1972 629 579 1973 628 578 1974 626 576 1975 627 577 1976 613 492 1977 630 492 1978 609 492 1979 628 578 1980 629 579 1981 631 580 1982 632 492 1983 633 492 1984 630 492 1985 634 581 1986 631 580 1987 635 582 1988 613 492 1989 632 492 1990 630 492 1991 634 581 1992 628 578 1993 631 580 1994 636 583 1995 637 583 1996 633 583 1997 634 581 1998 635 582 1999 638 584 2000 632 492 2001 636 492 2002 633 492 2003 639 585 2004 640 585 2005 637 585 2006 641 586 2007 638 584 2008 642 587 2009 636 588 2010 639 588 2011 637 588 2012 641 586 2013 634 581 2014 638 584 2015 639 492 2016 643 492 2017 640 492 2018 641 586 2019 642 587 2020 644 589 2021 645 492 2022 646 492 2023 643 492 2024 647 590 2025 644 589 2026 648 591 2027 639 492 2028 645 492 2029 643 492 2030 647 590 2031 641 586 2032 644 589 2033 645 492 2034 649 492 2035 646 492 2036 647 590 2037 648 591 2038 650 592 2039 651 593 2040 652 593 2041 649 593 2042 653 594 2043 650 592 2044 654 595 2045 645 492 2046 651 492 2047 649 492 2048 653 594 2049 647 590 2050 650 592 2051 651 596 2052 655 596 2053 652 596 2054 653 594 2055 654 595 2056 656 597 2057 657 492 2058 658 492 2059 655 492 2060 659 598 2061 656 597 2062 660 599 2063 651 600 2064 657 600 2065 655 600 2066 659 598 2067 653 594 2068 656 597 2069 657 492 2070 661 492 2071 658 492 2072 659 598 2073 660 599 2074 662 601 2075 663 492 2076 664 492 2077 661 492 2078 665 602 2079 662 601 2080 666 603 2081 657 492 2082 663 492 2083 661 492 2084 665 602 2085 659 598 2086 662 601 2087 663 492 2088 667 492 2089 664 492 2090 668 604 2091 666 603 2092 669 605 2093 668 604 2094 665 602 2095 666 603 2096 670 492 2097 671 492 2098 667 492 2099 668 604 2100 669 605 2101 672 606 2102 663 607 2103 670 607 2104 667 607 2105 670 492 2106 673 492 2107 671 492 2108 674 608 2109 672 606 2110 675 609 2111 674 608 2112 668 604 2113 672 606 2114 676 492 2115 677 492 2116 673 492 2117 678 610 2118 675 609 2119 679 611 2120 670 612 2121 676 612 2122 673 612 2123 678 610 2124 674 608 2125 675 609 2126 680 613 2127 681 613 2128 677 613 2129 678 610 2130 679 611 2131 682 614 2132 680 492 2133 677 492 2134 676 492 2135 680 615 2136 683 615 2137 681 615 2138 678 610 2139 682 614 2140 684 616 2141 680 492 2142 685 492 2143 683 492 2144 686 617 2145 684 616 2146 687 618 2147 686 617 2148 678 610 2149 684 616 2150 688 492 2151 689 492 2152 685 492 2153 690 619 2154 687 618 2155 691 620 2156 680 492 2157 688 492 2158 685 492 2159 692 621 2160 686 617 2161 687 618 2162 690 619 2163 692 621 2164 687 618 2165 693 492 2166 694 492 2167 689 492 2168 695 622 2169 691 620 2170 696 623 2171 688 624 2172 693 624 2173 689 624 2174 697 625 2175 690 619 2176 691 620 2177 695 622 2178 697 625 2179 691 620 2180 698 492 2181 699 492 2182 694 492 2183 700 626 2184 696 623 2185 701 627 2186 693 492 2187 698 492 2188 694 492 2189 702 628 2190 695 622 2191 696 623 2192 700 626 2193 702 628 2194 696 623 2195 703 492 2196 704 492 2197 699 492 2198 705 629 2199 701 627 2200 706 630 2201 698 492 2202 703 492 2203 699 492 2204 707 631 2205 700 626 2206 701 627 2207 705 629 2208 707 631 2209 701 627 2210 708 492 2211 709 492 2212 704 492 2213 710 632 2214 706 630 2215 711 633 2216 703 492 2217 708 492 2218 704 492 2219 712 634 2220 705 629 2221 706 630 2222 710 632 2223 712 634 2224 706 630 2225 713 492 2226 714 492 2227 709 492 2228 715 635 2229 711 633 2230 716 636 2231 708 637 2232 713 637 2233 709 637 2234 717 638 2235 710 632 2236 711 633 2237 715 635 2238 717 638 2239 711 633 2240 718 492 2241 546 492 2242 714 492 2243 719 639 2244 716 636 2245 720 640 2246 721 492 2247 718 492 2248 714 492 2249 713 641 2250 721 641 2251 714 641 2252 722 642 2253 715 635 2254 716 636 2255 719 639 2256 722 642 2257 716 636 2258 723 643 2259 720 640 2260 498 493 2261 718 492 2262 545 492 2263 546 492 2264 723 643 2265 719 639 2266 720 640 2267 304 300 2268 723 643 2269 498 493 2270 724 644 2271 725 645 2272 726 646 2273 727 647 2274 728 648 2275 729 649 2276 727 647 2277 729 649 2278 730 650 2279 731 651 2280 726 646 2281 732 652 2282 731 651 2283 724 644 2284 726 646 2285 733 653 2286 732 652 2287 734 654 2288 733 653 2289 731 651 2290 732 652 2291 735 655 2292 734 654 2293 736 656 2294 735 655 2295 733 653 2296 734 654 2297 737 657 2298 736 656 2299 738 658 2300 737 657 2301 735 655 2302 736 656 2303 739 659 2304 738 658 2305 740 660 2306 739 659 2307 737 657 2308 738 658 2309 741 661 2310 740 660 2311 742 662 2312 741 661 2313 739 659 2314 740 660 2315 743 663 2316 742 662 2317 744 664 2318 745 665 2319 741 661 2320 742 662 2321 743 663 2322 745 665 2323 742 662 2324 746 666 2325 744 664 2326 747 667 2327 746 666 2328 743 663 2329 744 664 2330 748 668 2331 747 667 2332 749 669 2333 748 668 2334 746 666 2335 747 667 2336 750 670 2337 749 669 2338 751 671 2339 750 670 2340 748 668 2341 749 669 2342 752 672 2343 751 671 2344 753 673 2345 752 672 2346 750 670 2347 751 671 2348 752 672 2349 753 673 2350 754 674 2351 755 675 2352 754 674 2353 756 676 2354 755 675 2355 752 672 2356 754 674 2357 757 677 2358 756 676 2359 758 678 2360 757 677 2361 755 675 2362 756 676 2363 759 679 2364 758 678 2365 760 680 2366 759 679 2367 757 677 2368 758 678 2369 761 681 2370 760 680 2371 762 682 2372 761 681 2373 759 679 2374 760 680 2375 763 683 2376 762 682 2377 764 684 2378 763 683 2379 761 681 2380 762 682 2381 765 685 2382 764 684 2383 766 686 2384 765 685 2385 763 683 2386 764 684 2387 767 687 2388 768 688 2389 769 689 2390 770 690 2391 765 685 2392 766 686 2393 771 691 2394 769 689 2395 772 692 2396 771 691 2397 767 687 2398 769 689 2399 773 693 2400 772 692 2401 774 694 2402 773 693 2403 771 691 2404 772 692 2405 775 695 2406 774 694 2407 776 696 2408 775 695 2409 773 693 2410 774 694 2411 777 697 2412 776 696 2413 778 698 2414 777 697 2415 775 695 2416 776 696 2417 779 699 2418 778 698 2419 780 700 2420 779 699 2421 777 697 2422 778 698 2423 781 701 2424 780 700 2425 782 702 2426 781 701 2427 779 699 2428 780 700 2429 783 703 2430 782 702 2431 784 704 2432 785 705 2433 781 701 2434 782 702 2435 783 703 2436 785 705 2437 782 702 2438 786 706 2439 784 704 2440 787 707 2441 786 706 2442 783 703 2443 784 704 2444 788 708 2445 787 707 2446 789 709 2447 788 708 2448 786 706 2449 787 707 2450 790 710 2451 789 709 2452 791 711 2453 790 710 2454 788 708 2455 789 709 2456 792 712 2457 791 711 2458 793 713 2459 792 712 2460 790 710 2461 791 711 2462 792 712 2463 793 713 2464 794 714 2465 795 715 2466 794 714 2467 796 716 2468 795 715 2469 792 712 2470 794 714 2471 797 717 2472 796 716 2473 798 718 2474 797 717 2475 795 715 2476 796 716 2477 799 719 2478 798 718 2479 800 720 2480 799 719 2481 797 717 2482 798 718 2483 801 721 2484 800 720 2485 802 722 2486 801 721 2487 799 719 2488 800 720 2489 803 723 2490 802 722 2491 728 648 2492 803 723 2493 801 721 2494 802 722 2495 727 647 2496 803 723 2497 728 648 2498 521 515 2499 523 517 2500 804 724 2501 805 725 2502 804 724 2503 806 726 2504 805 725 2505 521 515 2506 804 724 2507 805 725 2508 806 726 2509 807 727 2510 808 728 2511 809 728 2512 557 728 2513 810 729 2514 805 725 2515 807 727 2516 810 729 2517 807 727 2518 811 730 2519 812 731 2520 813 732 2521 814 733 2522 812 731 2523 815 734 2524 813 732 2525 812 731 2526 814 733 2527 816 735 2528 817 736 2529 818 737 2530 819 738 2531 820 739 2532 819 738 2533 821 740 2534 820 739 2535 817 736 2536 819 738 2537 820 739 2538 821 740 2539 822 741 2540 823 742 2541 822 741 2542 824 743 2543 823 742 2544 820 739 2545 822 741 2546 825 744 2547 824 743 2548 826 745 2549 825 744 2550 823 742 2551 824 743 2552 825 744 2553 826 745 2554 827 746 2555 828 747 2556 827 746 2557 829 748 2558 828 747 2559 825 744 2560 827 746 2561 828 747 2562 829 748 2563 830 749 2564 831 750 2565 830 749 2566 832 751 2567 831 750 2568 828 747 2569 830 749 2570 833 752 2571 832 751 2572 834 753 2573 833 752 2574 831 750 2575 832 751 2576 835 754 2577 834 753 2578 836 755 2579 835 754 2580 833 752 2581 834 753 2582 837 756 2583 836 755 2584 838 757 2585 837 756 2586 835 754 2587 836 755 2588 839 758 2589 838 757 2590 840 759 2591 839 758 2592 837 756 2593 838 757 2594 841 760 2595 840 759 2596 842 761 2597 841 760 2598 839 758 2599 840 759 2600 843 762 2601 842 761 2602 844 763 2603 841 760 2604 842 761 2605 843 762 2606 845 764 2607 844 763 2608 846 765 2609 847 492 2610 848 492 2611 808 492 2612 845 764 2613 849 766 2614 844 763 2615 850 767 2616 844 763 2617 849 766 2618 851 768 2619 844 763 2620 850 767 2621 852 769 2622 844 763 2623 851 768 2624 853 770 2625 844 763 2626 852 769 2627 854 771 2628 844 763 2629 853 770 2630 855 772 2631 844 763 2632 854 771 2633 856 773 2634 844 763 2635 855 772 2636 857 774 2637 844 763 2638 856 773 2639 858 775 2640 844 763 2641 857 774 2642 843 762 2643 844 763 2644 858 775 2645 859 776 2646 860 776 2647 861 776 2648 862 777 2649 860 777 2650 859 777 2651 863 778 2652 864 778 2653 847 778 2654 865 779 2655 866 780 2656 867 781 2657 868 782 2658 866 780 2659 865 779 2660 869 783 2661 866 780 2662 868 782 2663 870 784 2664 871 785 2665 872 786 2666 873 787 2667 874 788 2668 875 789 2669 876 790 2670 872 786 2671 877 791 2672 878 792 2673 872 786 2674 876 790 2675 870 784 2676 872 786 2677 878 792 2678 879 793 2679 877 791 2680 880 794 2681 876 790 2682 877 791 2683 879 793 2684 881 795 2685 880 794 2686 882 796 2687 879 793 2688 880 794 2689 881 795 2690 883 797 2691 882 796 2692 884 798 2693 881 795 2694 882 796 2695 883 797 2696 885 799 2697 884 798 2698 886 800 2699 883 797 2700 884 798 2701 885 799 2702 887 801 2703 886 800 2704 888 802 2705 885 799 2706 886 800 2707 887 801 2708 889 803 2709 888 802 2710 890 804 2711 887 801 2712 888 802 2713 889 803 2714 891 805 2715 890 804 2716 892 806 2717 889 803 2718 890 804 2719 891 805 2720 893 807 2721 892 806 2722 894 808 2723 891 805 2724 892 806 2725 893 807 2726 893 807 2727 894 808 2728 895 809 2729 896 810 2730 895 809 2731 897 811 2732 893 807 2733 895 809 2734 896 810 2735 896 810 2736 897 811 2737 898 812 2738 899 813 2739 898 812 2740 900 814 2741 896 810 2742 898 812 2743 899 813 2744 901 815 2745 900 814 2746 902 816 2747 899 813 2748 900 814 2749 901 815 2750 901 815 2751 902 816 2752 903 817 2753 904 818 2754 903 817 2755 905 819 2756 901 815 2757 903 817 2758 904 818 2759 904 818 2760 905 819 2761 906 820 2762 907 821 2763 906 820 2764 908 822 2765 904 818 2766 906 820 2767 907 821 2768 907 821 2769 908 822 2770 909 823 2771 910 824 2772 909 823 2773 911 825 2774 907 821 2775 909 823 2776 910 824 2777 910 824 2778 911 825 2779 912 826 2780 913 827 2781 912 826 2782 914 828 2783 910 824 2784 912 826 2785 913 827 2786 913 827 2787 914 828 2788 915 829 2789 916 830 2790 915 829 2791 917 831 2792 913 827 2793 915 829 2794 916 830 2795 916 830 2796 917 831 2797 918 832 2798 919 833 2799 918 832 2800 920 834 2801 916 830 2802 918 832 2803 919 833 2804 921 835 2805 920 834 2806 922 836 2807 919 833 2808 920 834 2809 921 835 2810 923 837 2811 922 836 2812 924 838 2813 921 835 2814 922 836 2815 923 837 2816 925 839 2817 926 840 2818 927 841 2819 928 842 2820 926 840 2821 925 839 2822 923 837 2823 924 838 2824 929 843 2825 930 844 2826 931 845 2827 521 515 2828 932 846 2829 521 515 2830 931 845 2831 805 725 2832 930 844 2833 521 515 2834 932 846 2835 524 518 2836 521 515 2837 933 847 2838 934 848 2839 931 845 2840 932 846 2841 931 845 2842 934 848 2843 930 844 2844 933 847 2845 931 845 2846 935 849 2847 936 850 2848 934 848 2849 937 851 2850 934 848 2851 936 850 2852 933 847 2853 935 849 2854 934 848 2855 937 851 2856 932 846 2857 934 848 2858 938 852 2859 939 853 2860 936 850 2861 940 854 2862 936 850 2863 939 853 2864 935 849 2865 938 852 2866 936 850 2867 940 854 2868 937 851 2869 936 850 2870 941 855 2871 942 856 2872 939 853 2873 943 857 2874 939 853 2875 942 856 2876 944 858 2877 941 855 2878 939 853 2879 938 852 2880 944 858 2881 939 853 2882 943 857 2883 940 854 2884 939 853 2885 945 859 2886 946 860 2887 947 861 2888 948 862 2889 943 857 2890 942 856 2891 945 859 2892 949 863 2893 946 860 2894 950 864 2895 947 861 2896 951 865 2897 950 864 2898 945 859 2899 947 861 2900 952 866 2901 944 858 2902 938 852 2903 953 867 2904 951 865 2905 954 868 2906 955 869 2907 950 864 2908 951 865 2909 953 867 2910 955 869 2911 951 865 2912 956 870 2913 938 852 2914 935 849 2915 957 871 2916 952 866 2917 938 852 2918 956 870 2919 957 871 2920 938 852 2921 958 872 2922 935 849 2923 933 847 2924 958 872 2925 956 870 2926 935 849 2927 958 872 2928 933 847 2929 930 844 2930 959 873 2931 930 844 2932 805 725 2933 959 873 2934 958 872 2935 930 844 2936 810 729 2937 959 873 2938 805 725 2939 960 874 2940 961 875 2941 962 876 2942 963 877 2943 964 877 2944 965 877 2945 966 878 2946 965 879 2947 964 880 2948 967 881 2949 954 868 2950 968 882 2951 969 883 2952 953 867 2953 954 868 2954 970 884 2955 969 883 2956 954 868 2957 967 881 2958 970 884 2959 954 868 2960 966 878 2961 964 880 2962 971 885 2963 972 886 2964 962 876 2965 973 887 2966 960 874 2967 962 876 2968 974 888 2969 972 886 2970 974 888 2971 962 876 2972 975 889 2973 973 887 2974 976 890 2975 975 889 2976 972 886 2977 973 887 2978 977 891 2979 976 890 2980 978 892 2981 975 889 2982 976 890 2983 977 891 2984 979 893 2985 978 892 2986 815 734 2987 977 891 2988 978 892 2989 979 893 2990 979 893 2991 815 734 2992 812 731 2993 510 505 2994 515 510 2995 980 894 2996 981 895 2997 980 894 2998 982 896 2999 510 505 3000 980 894 3001 981 895 3002 983 897 3003 982 896 3004 984 898 3005 985 899 3006 982 896 3007 983 897 3008 981 895 3009 982 896 3010 985 899 3011 986 900 3012 984 898 3013 987 901 3014 983 897 3015 984 898 3016 986 900 3017 986 900 3018 987 901 3019 988 902 3020 986 900 3021 988 902 3022 989 903 3023 990 904 3024 991 905 3025 949 863 3026 992 906 3027 990 904 3028 949 863 3029 945 859 3030 992 906 3031 949 863 3032 502 497 3033 993 907 3034 505 500 3035 994 908 3036 995 909 3037 993 907 3038 996 910 3039 994 908 3040 993 907 3041 502 497 3042 996 910 3043 993 907 3044 997 911 3045 998 912 3046 995 909 3047 994 908 3048 997 911 3049 995 909 3050 999 913 3051 1000 914 3052 998 912 3053 997 911 3054 999 913 3055 998 912 3056 1001 915 3057 1002 916 3058 1000 914 3059 999 913 3060 1001 915 3061 1000 914 3062 1003 917 3063 1004 918 3064 1005 919 3065 1006 920 3066 491 488 3067 1007 921 3068 1008 922 3069 1009 922 3070 1007 922 3071 1010 923 3072 1007 921 3073 1009 924 3074 1003 917 3075 1011 925 3076 1004 918 3077 1012 926 3078 1006 920 3079 1007 921 3080 1010 923 3081 1012 926 3082 1007 921 3083 1013 927 3084 1001 915 3085 999 913 3086 1014 928 3087 1005 919 3088 1015 929 3089 1016 930 3090 1003 917 3091 1005 919 3092 1017 931 3093 1016 930 3094 1005 919 3095 1018 932 3096 1017 931 3097 1005 919 3098 1014 928 3099 1018 932 3100 1005 919 3101 986 900 3102 999 913 3103 997 911 3104 989 903 3105 1013 927 3106 999 913 3107 986 900 3108 989 903 3109 999 913 3110 983 897 3111 997 911 3112 994 908 3113 983 897 3114 986 900 3115 997 911 3116 985 899 3117 994 908 3118 996 910 3119 985 899 3120 983 897 3121 994 908 3122 981 895 3123 996 910 3124 502 497 3125 981 895 3126 985 899 3127 996 910 3128 510 505 3129 981 895 3130 502 497 3131 1019 933 3132 1015 929 3133 991 905 3134 1019 933 3135 1014 928 3136 1015 929 3137 990 904 3138 1019 933 3139 991 905 3140 847 934 3141 864 934 3142 848 934 3143 1020 935 3144 489 486 3145 491 488 3146 863 936 3147 1021 936 3148 864 936 3149 1022 937 3150 1020 935 3151 491 488 3152 1006 920 3153 1022 937 3154 491 488 3155 1003 917 3156 1023 938 3157 1011 925 3158 1024 939 3159 1025 940 3160 1026 941 3161 1027 942 3162 1028 943 3163 1029 944 3164 1024 939 3165 1026 941 3166 1030 945 3167 1031 946 3168 1032 947 3169 1033 948 3170 1034 949 3171 1032 947 3172 1031 946 3173 1035 950 3174 1036 951 3175 1037 952 3176 1038 953 3177 1036 951 3178 1035 950 3179 1039 492 3180 1021 492 3181 863 492 3182 1031 946 3183 1033 948 3184 1040 954 3185 1041 955 3186 1033 948 3187 1042 956 3188 1040 954 3189 1033 948 3190 1041 955 3191 1043 957 3192 1044 957 3193 1045 957 3194 1041 955 3195 1042 956 3196 1046 958 3197 1047 959 3198 1048 960 3199 1049 961 3200 1050 962 3201 1046 958 3202 1042 956 3203 1051 963 3204 1049 961 3205 1052 964 3206 1047 959 3207 1049 961 3208 1053 965 3209 1054 966 3210 1053 965 3211 1049 961 3212 1051 963 3213 1054 966 3214 1049 961 3215 1055 967 3216 1052 964 3217 1056 968 3218 1055 967 3219 1051 963 3220 1052 964 3221 1024 939 3222 1056 968 3223 1025 940 3224 1057 969 3225 1055 967 3226 1056 968 3227 1024 939 3228 1057 969 3229 1056 968 3230 967 881 3231 968 882 3232 1058 970 3233 1059 971 3234 1060 972 3235 1061 973 3236 1062 974 3237 1063 975 3238 1064 976 3239 1059 971 3240 1061 973 3241 1065 977 3242 1066 978 3243 1029 944 3244 1067 979 3245 1068 980 3246 1027 942 3247 1029 944 3248 1069 981 3249 1068 980 3250 1029 944 3251 1066 978 3252 1069 981 3253 1029 944 3254 1070 982 3255 1067 979 3256 1071 983 3257 1070 982 3258 1066 978 3259 1067 979 3260 1072 984 3261 1071 983 3262 1073 985 3263 1072 984 3264 1070 982 3265 1071 983 3266 1074 986 3267 1073 985 3268 1075 987 3269 1074 986 3270 1072 984 3271 1073 985 3272 1074 986 3273 1075 987 3274 1076 988 3275 1077 989 3276 1078 990 3277 1079 991 3278 1074 986 3279 1076 988 3280 1080 992 3281 1081 993 3282 1079 991 3283 1082 994 3284 1081 993 3285 1077 989 3286 1079 991 3287 1083 995 3288 1082 994 3289 1084 996 3290 1083 995 3291 1081 993 3292 1082 994 3293 1083 995 3294 1084 996 3295 1085 997 3296 1086 998 3297 1087 999 3298 1088 1000 3299 1083 995 3300 1085 997 3301 1089 1001 3302 1090 1002 3303 1088 1000 3304 1091 1003 3305 1092 1004 3306 1086 998 3307 1088 1000 3308 1090 1002 3309 1092 1004 3310 1088 1000 3311 1093 1005 3312 1091 1003 3313 1094 1006 3314 1093 1005 3315 1090 1002 3316 1091 1003 3317 1095 1007 3318 1094 1006 3319 1096 1008 3320 1095 1007 3321 1093 1005 3322 1094 1006 3323 1097 1009 3324 1096 1008 3325 1060 972 3326 1097 1009 3327 1095 1007 3328 1096 1008 3329 1059 971 3330 1097 1009 3331 1060 972 3332 1098 1010 3333 1099 1011 3334 1100 1012 3335 1101 1013 3336 1102 1014 3337 1103 1015 3338 1104 1016 3339 1105 1017 3340 1106 1018 3341 1101 1013 3342 1107 1019 3343 1102 1014 3344 1108 1020 3345 1109 1021 3346 1110 1022 3347 1104 1016 3348 1106 1018 3349 1111 1023 3350 1112 1024 3351 971 885 3352 1099 1011 3353 1113 1025 3354 1112 1024 3355 1099 1011 3356 1045 1026 3357 1044 1026 3358 1039 1026 3359 1098 1010 3360 1113 1025 3361 1099 1011 3362 1114 492 3363 1115 492 3364 1043 492 3365 1116 1027 3366 1117 1028 3367 1118 1029 3368 1119 1030 3369 1116 1027 3370 1118 1029 3371 1120 1031 3372 966 878 3373 971 885 3374 1112 1024 3375 1120 1031 3376 971 885 3377 1121 1032 3378 1064 976 3379 1122 1033 3380 1123 1034 3381 1062 974 3382 1064 976 3383 1124 1035 3384 1123 1034 3385 1064 976 3386 1121 1032 3387 1124 1035 3388 1064 976 3389 1121 1032 3390 1122 1033 3391 1125 1036 3392 1126 1037 3393 1125 1036 3394 1127 1038 3395 1126 1037 3396 1121 1032 3397 1125 1036 3398 1039 1039 3399 1044 1039 3400 1021 1039 3401 1126 1037 3402 1127 1038 3403 1128 1040 3404 1129 1041 3405 1130 1042 3406 1105 1017 3407 1131 1043 3408 1130 1042 3409 1129 1041 3410 1132 1044 3411 1130 1042 3412 1131 1043 3413 1133 1045 3414 1130 1042 3415 1132 1044 3416 1043 1046 3417 1115 1046 3418 1044 1046 3419 1129 1041 3420 1105 1017 3421 1104 1016 3422 1101 1013 3423 1134 1047 3424 1107 1019 3425 1135 1048 3426 1110 1022 3427 1136 1049 3428 1108 1020 3429 1110 1022 3430 1135 1048 3431 1101 1013 3432 1137 1050 3433 1134 1047 3434 1135 1048 3435 1136 1049 3436 1138 1051 3437 1101 1013 3438 1139 1052 3439 1137 1050 3440 1140 1053 3441 1138 1051 3442 1141 1054 3443 1135 1048 3444 1138 1051 3445 1140 1053 3446 1142 1055 3447 1143 1056 3448 1139 1052 3449 1144 1057 3450 1141 1054 3451 1145 1058 3452 1101 1013 3453 1142 1055 3454 1139 1052 3455 1140 1053 3456 1141 1054 3457 1144 1057 3458 1142 1055 3459 1146 1059 3460 1143 1056 3461 1147 1060 3462 1145 1058 3463 1148 1061 3464 1144 1057 3465 1145 1058 3466 1147 1060 3467 1142 1055 3468 1149 1062 3469 1146 1059 3470 1150 1063 3471 1148 1061 3472 1151 1064 3473 1147 1060 3474 1148 1061 3475 1150 1063 3476 1152 1065 3477 1153 1066 3478 1149 1062 3479 1150 1063 3480 1151 1064 3481 1154 1067 3482 1142 1055 3483 1152 1065 3484 1149 1062 3485 1152 1065 3486 1155 1068 3487 1153 1066 3488 1156 1069 3489 1154 1067 3490 1157 1070 3491 1150 1063 3492 1154 1067 3493 1156 1069 3494 1158 1071 3495 1159 1072 3496 1155 1068 3497 1160 1073 3498 1157 1070 3499 1161 1074 3500 1152 1065 3501 1158 1071 3502 1155 1068 3503 1156 1069 3504 1157 1070 3505 1160 1073 3506 1158 1071 3507 1162 1075 3508 1159 1072 3509 1163 1076 3510 1161 1074 3511 1164 1077 3512 1160 1073 3513 1161 1074 3514 1163 1076 3515 1165 1078 3516 1166 1079 3517 1162 1075 3518 1167 1080 3519 1164 1077 3520 1168 1081 3521 1158 1071 3522 1165 1078 3523 1162 1075 3524 1163 1076 3525 1164 1077 3526 1167 1080 3527 1165 1078 3528 1169 1082 3529 1166 1079 3530 1167 1080 3531 1168 1081 3532 1170 1083 3533 1165 1078 3534 1171 1084 3535 1169 1082 3536 1172 1085 3537 1170 1083 3538 1173 1086 3539 1167 1080 3540 1170 1083 3541 1172 1085 3542 1174 1087 3543 1175 1088 3544 1171 1084 3545 1176 1089 3546 1173 1086 3547 1177 1090 3548 1165 1078 3549 1174 1087 3550 1171 1084 3551 1172 1085 3552 1173 1086 3553 1176 1089 3554 1174 1087 3555 1178 1091 3556 1175 1088 3557 1179 1092 3558 1177 1090 3559 1180 1093 3560 1176 1089 3561 1177 1090 3562 1179 1092 3563 1174 1087 3564 1181 1094 3565 1178 1091 3566 1182 1095 3567 1180 1093 3568 1183 1096 3569 1179 1092 3570 1180 1093 3571 1182 1095 3572 1174 1087 3573 1184 1097 3574 1181 1094 3575 1182 1095 3576 1183 1096 3577 1185 1098 3578 1174 1087 3579 1186 1099 3580 1184 1097 3581 1187 1100 3582 1185 1098 3583 1188 1101 3584 1182 1095 3585 1185 1098 3586 1187 1100 3587 1174 1087 3588 1189 1102 3589 1186 1099 3590 1190 1103 3591 1188 1101 3592 1191 1104 3593 1187 1100 3594 1188 1101 3595 1190 1103 3596 1192 1105 3597 1193 1106 3598 1189 1102 3599 1194 1107 3600 1191 1104 3601 1195 1108 3602 1174 1087 3603 1192 1105 3604 1189 1102 3605 1190 1103 3606 1191 1104 3607 1194 1107 3608 1192 1105 3609 1196 1109 3610 1193 1106 3611 1197 1110 3612 1195 1108 3613 1198 1111 3614 1194 1107 3615 1195 1108 3616 1197 1110 3617 1192 1105 3618 1199 1112 3619 1196 1109 3620 1200 1113 3621 1198 1111 3622 1201 1114 3623 1197 1110 3624 1198 1111 3625 1200 1113 3626 1192 1105 3627 1202 1115 3628 1199 1112 3629 1203 1116 3630 1201 1114 3631 1204 1117 3632 1200 1113 3633 1201 1114 3634 1203 1116 3635 1192 1105 3636 1205 1118 3637 1202 1115 3638 1203 1116 3639 1204 1117 3640 1206 1119 3641 1207 1120 3642 1208 1121 3643 1205 1118 3644 1209 1122 3645 1206 1119 3646 1210 1123 3647 1192 1105 3648 1207 1120 3649 1205 1118 3650 1203 1116 3651 1206 1119 3652 1209 1122 3653 1207 1120 3654 1211 1124 3655 1208 1121 3656 1212 1125 3657 1210 1123 3658 1213 1126 3659 1209 1122 3660 1210 1123 3661 1212 1125 3662 1207 1120 3663 1214 1127 3664 1211 1124 3665 1215 1128 3666 1213 1126 3667 1216 1129 3668 1212 1125 3669 1213 1126 3670 1215 1128 3671 1207 1120 3672 1217 1130 3673 1214 1127 3674 1218 1131 3675 1216 1129 3676 1219 1132 3677 1215 1128 3678 1216 1129 3679 1218 1131 3680 1207 1120 3681 1220 1133 3682 1217 1130 3683 1218 1131 3684 1219 1132 3685 1221 1134 3686 1222 1135 3687 1223 1136 3688 1224 1137 3689 1218 1131 3690 1221 1134 3691 1225 1138 3692 1226 1139 3693 1227 1140 3694 1228 1141 3695 1229 1142 3696 1226 1139 3697 1228 1141 3698 1230 1143 3699 1231 1144 3700 1223 1136 3701 1222 1135 3702 1230 1143 3703 1223 1136 3704 1232 1145 3705 1207 1120 3706 1192 1105 3707 1233 1146 3708 1207 1120 3709 1232 1145 3710 1222 1135 3711 1224 1137 3712 1234 1147 3713 1232 1145 3714 1235 1148 3715 1233 1146 3716 1236 1149 3717 1192 1105 3718 1174 1087 3719 1236 1149 3720 1232 1145 3721 1192 1105 3722 1237 1150 3723 1174 1087 3724 1165 1078 3725 1238 1151 3726 1236 1149 3727 1174 1087 3728 1239 1152 3729 1238 1151 3730 1174 1087 3731 1240 1153 3732 1239 1152 3733 1174 1087 3734 1237 1150 3735 1240 1153 3736 1174 1087 3737 1241 1154 3738 1242 1155 3739 1243 1156 3740 1241 1154 3741 1244 1157 3742 1242 1155 3743 1245 1158 3744 1243 1156 3745 1246 1159 3746 1245 1158 3747 1241 1154 3748 1243 1156 3749 1245 1158 3750 1246 1159 3751 1247 1160 3752 1116 1027 3753 1247 1160 3754 1117 1028 3755 1116 1027 3756 1245 1158 3757 1247 1160 3758 1222 1135 3759 1234 1147 3760 1248 1161 3761 1249 1162 3762 1250 1163 3763 1251 1164 3764 1252 1165 3765 1253 1166 3766 1254 1167 3767 1249 1162 3768 1255 1168 3769 1250 1163 3770 1256 1169 3771 1251 1164 3772 1257 1170 3773 1256 1169 3774 1249 1162 3775 1251 1164 3776 1258 1171 3777 1257 1170 3778 1259 1172 3779 1258 1171 3780 1256 1169 3781 1257 1170 3782 1258 1171 3783 1259 1172 3784 1260 1173 3785 1261 1174 3786 1260 1173 3787 1262 1175 3788 1261 1174 3789 1258 1171 3790 1260 1173 3791 1261 1174 3792 1262 1175 3793 1244 1157 3794 1241 1154 3795 1261 1174 3796 1244 1157 3797 1218 1131 3798 1225 1138 3799 1263 1176 3800 1226 1139 3801 1264 1177 3802 1227 1140 3803 1265 1178 3804 1218 1131 3805 1263 1176 3806 1266 1179 3807 1267 1180 3808 1268 1181 3809 1269 1182 3810 1264 1177 3811 1226 1139 3812 1270 1183 3813 1271 1184 3814 1272 1185 3815 1273 1186 3816 1271 1184 3817 1270 1183 3818 1274 1187 3819 1215 1128 3820 1218 1131 3821 1265 1178 3822 1274 1187 3823 1218 1131 3824 1275 1188 3825 1212 1125 3826 1215 1128 3827 1274 1187 3828 1275 1188 3829 1215 1128 3830 1276 1189 3831 1209 1122 3832 1212 1125 3833 1275 1188 3834 1276 1189 3835 1212 1125 3836 1277 1190 3837 1203 1116 3838 1209 1122 3839 1276 1189 3840 1277 1190 3841 1209 1122 3842 1278 1191 3843 1200 1113 3844 1203 1116 3845 1277 1190 3846 1278 1191 3847 1203 1116 3848 1279 1192 3849 1197 1110 3850 1200 1113 3851 1280 1193 3852 1279 1192 3853 1200 1113 3854 1281 1194 3855 1280 1193 3856 1200 1113 3857 1278 1191 3858 1281 1194 3859 1200 1113 3860 1282 1195 3861 1194 1107 3862 1197 1110 3863 1279 1192 3864 1282 1195 3865 1197 1110 3866 1283 1196 3867 1190 1103 3868 1194 1107 3869 1282 1195 3870 1283 1196 3871 1194 1107 3872 1284 1197 3873 1187 1100 3874 1190 1103 3875 1285 1198 3876 1284 1197 3877 1190 1103 3878 1283 1196 3879 1285 1198 3880 1190 1103 3881 1286 1199 3882 1182 1095 3883 1187 1100 3884 1284 1197 3885 1286 1199 3886 1187 1100 3887 1287 1200 3888 1179 1092 3889 1182 1095 3890 1286 1199 3891 1287 1200 3892 1182 1095 3893 1288 1201 3894 1176 1089 3895 1179 1092 3896 1289 1202 3897 1288 1201 3898 1179 1092 3899 1287 1200 3900 1289 1202 3901 1179 1092 3902 1290 1203 3903 1172 1085 3904 1176 1089 3905 1288 1201 3906 1290 1203 3907 1176 1089 3908 1291 1204 3909 1167 1080 3910 1172 1085 3911 1290 1203 3912 1291 1204 3913 1172 1085 3914 1292 1205 3915 1163 1076 3916 1167 1080 3917 1291 1204 3918 1292 1205 3919 1167 1080 3920 1293 1206 3921 1160 1073 3922 1163 1076 3923 1294 1207 3924 1293 1206 3925 1163 1076 3926 1292 1205 3927 1294 1207 3928 1163 1076 3929 1295 1208 3930 1156 1069 3931 1160 1073 3932 1293 1206 3933 1295 1208 3934 1160 1073 3935 1296 1209 3936 1150 1063 3937 1156 1069 3938 1297 1210 3939 1296 1209 3940 1156 1069 3941 1295 1208 3942 1297 1210 3943 1156 1069 3944 1298 1211 3945 1147 1060 3946 1150 1063 3947 1299 1212 3948 1298 1211 3949 1150 1063 3950 1296 1209 3951 1299 1212 3952 1150 1063 3953 1300 1213 3954 1144 1057 3955 1147 1060 3956 1298 1211 3957 1300 1213 3958 1147 1060 3959 1301 1214 3960 1140 1053 3961 1144 1057 3962 1302 1215 3963 1301 1214 3964 1144 1057 3965 1300 1213 3966 1302 1215 3967 1144 1057 3968 1303 1216 3969 1135 1048 3970 1140 1053 3971 1304 1217 3972 1303 1216 3973 1140 1053 3974 1301 1214 3975 1304 1217 3976 1140 1053 3977 1305 1218 3978 1108 1020 3979 1135 1048 3980 1303 1216 3981 1305 1218 3982 1135 1048 3983 1104 1016 3984 1111 1023 3985 1306 1219 3986 1307 1220 3987 1308 1221 3988 1309 1222 3989 1310 1223 3990 1308 1221 3991 1307 1220 3992 1307 1220 3993 1309 1222 3994 1311 1224 3995 1312 1225 3996 1311 1224 3997 1313 1226 3998 1307 1220 3999 1311 1224 4000 1312 1225 4001 1314 1227 4002 1313 1226 4003 1315 1228 4004 1316 1229 4005 1313 1226 4006 1314 1227 4007 1312 1225 4008 1313 1226 4009 1316 1229 4010 1317 1230 4011 1315 1228 4012 1318 1231 4013 1314 1227 4014 1315 1228 4015 1317 1230 4016 1319 1232 4017 1312 1225 4018 1320 1233 4019 1321 1234 4020 1312 1225 4021 1319 1232 4022 1322 1235 4023 1312 1225 4024 1321 1234 4025 1323 1236 4026 1312 1225 4027 1322 1235 4028 1324 1237 4029 1312 1225 4030 1323 1236 4031 1325 1238 4032 1312 1225 4033 1324 1237 4034 1326 1239 4035 1312 1225 4036 1325 1238 4037 1307 1220 4038 1312 1225 4039 1326 1239 4040 1327 1240 4041 1326 1239 4042 1328 1241 4043 1329 1242 4044 1326 1239 4045 1327 1240 4046 1330 1243 4047 1326 1239 4048 1329 1242 4049 1331 1244 4050 1326 1239 4051 1330 1243 4052 1332 1245 4053 1326 1239 4054 1331 1244 4055 1307 1220 4056 1326 1239 4057 1332 1245 4058 1332 1245 4059 1331 1244 4060 1333 1246 4061 1332 1245 4062 1333 1246 4063 1334 1247 4064 1332 1245 4065 1334 1247 4066 1335 1248 4067 1266 1179 4068 1335 1248 4069 1336 1249 4070 1337 1250 4071 1335 1248 4072 1266 1179 4073 1332 1245 4074 1335 1248 4075 1337 1250 4076 1266 1179 4077 1336 1249 4078 1338 1251 4079 1266 1179 4080 1338 1251 4081 1339 1252 4082 1266 1179 4083 1339 1252 4084 1340 1253 4085 1266 1179 4086 1340 1253 4087 1341 1254 4088 1266 1179 4089 1341 1254 4090 1342 1255 4091 1266 1179 4092 1342 1255 4093 1267 1180 4094 1343 1256 4095 1344 1257 4096 1345 1258 4097 1346 1259 4098 1347 1259 4099 1348 1259 4100 1349 1260 4101 1350 1261 4102 1351 1262 4103 1346 1263 4104 1352 1263 4105 1347 1263 4106 1353 1264 4107 1354 1265 4108 1344 1257 4109 1355 1266 4110 1344 1257 4111 1354 1265 4112 1343 1256 4113 1353 1264 4114 1344 1257 4115 1356 1267 4116 1348 1267 4117 1357 1267 4118 1356 1268 4119 1346 1268 4120 1348 1268 4121 1358 1269 4122 1226 1139 4123 1354 1265 4124 1359 1270 4125 1354 1265 4126 1226 1139 4127 1353 1264 4128 1358 1269 4129 1354 1265 4130 1359 1270 4131 1355 1266 4132 1354 1265 4133 1360 1271 4134 1269 1182 4135 1226 1139 4136 1358 1269 4137 1360 1271 4138 1226 1139 4139 1229 1142 4140 1359 1270 4141 1226 1139 4142 1361 1272 4143 1272 1185 4144 1362 1273 4145 1270 1183 4146 1272 1185 4147 1361 1272 4148 1361 1272 4149 1362 1273 4150 1363 1274 4151 1364 1275 4152 1363 1274 4153 1365 1276 4154 1361 1272 4155 1363 1274 4156 1364 1275 4157 1364 1275 4158 1365 1276 4159 1350 1261 4160 1364 1275 4161 1350 1261 4162 1349 1260 4163 1366 1277 4164 1367 1278 4165 1368 1279 4166 1369 1280 4167 1356 1280 4168 1357 1280 4169 1230 1143 4170 1368 1279 4171 1231 1144 4172 1366 1277 4173 1368 1279 4174 1370 1281 4175 1371 1282 4176 1370 1281 4177 1368 1279 4178 1114 1283 4179 1372 1283 4180 1115 1283 4181 1230 1143 4182 1371 1282 4183 1368 1279 4184 1373 1284 4185 1374 1284 4186 1372 1284 4187 1375 1285 4188 1376 1286 4189 1377 1287 4190 1378 1288 4191 1379 1288 4192 1380 1288 4193 1381 1289 4194 1375 1285 4195 1377 1287 4196 1382 1290 4197 1383 1291 4198 1384 1292 4199 1378 1293 4200 1385 1293 4201 1379 1293 4202 1375 1285 4203 1386 1294 4204 1376 1286 4205 1387 1295 4206 1380 1295 4207 1388 1295 4208 1387 1296 4209 1378 1296 4210 1380 1296 4211 1389 1297 4212 1390 1298 4213 1386 1294 4214 1387 1299 4215 1388 1299 4216 1391 1299 4217 1375 1285 4218 1389 1297 4219 1386 1294 4220 1392 1300 4221 1393 1301 4222 1390 1298 4223 1394 1302 4224 1391 1302 4225 1395 1302 4226 1389 1297 4227 1392 1300 4228 1390 1298 4229 1394 1303 4230 1387 1303 4231 1391 1303 4232 1396 1304 4233 1397 1305 4234 1393 1301 4235 1394 1306 4236 1395 1306 4237 1398 1306 4238 1392 1300 4239 1396 1304 4240 1393 1301 4241 1396 1304 4242 1399 1307 4243 1397 1305 4244 1400 1308 4245 1398 1308 4246 1401 1308 4247 1400 1309 4248 1394 1309 4249 1398 1309 4250 1364 1275 4251 1349 1260 4252 1399 1307 4253 1400 1310 4254 1401 1310 4255 1352 1310 4256 1396 1304 4257 1364 1275 4258 1399 1307 4259 1346 1311 4260 1400 1311 4261 1352 1311 4262 1361 1272 4263 1364 1275 4264 1396 1304 4265 1402 1312 4266 1396 1304 4267 1392 1300 4268 1402 1312 4269 1361 1272 4270 1396 1304 4271 1403 1313 4272 1392 1300 4273 1389 1297 4274 1403 1313 4275 1402 1312 4276 1392 1300 4277 1404 1314 4278 1389 1297 4279 1375 1285 4280 1404 1314 4281 1403 1313 4282 1389 1297 4283 1405 1315 4284 1375 1285 4285 1381 1289 4286 1405 1315 4287 1404 1314 4288 1375 1285 4289 1405 1315 4290 1381 1289 4291 1406 1316 4292 1407 1317 4293 1408 1318 4294 1383 1291 4295 1407 1317 4296 1383 1291 4297 1382 1290 4298 1409 1319 4299 1405 1315 4300 1406 1316 4301 1409 1319 4302 1406 1316 4303 1410 1320 4304 1411 1321 4305 1412 1322 4306 1408 1318 4307 1411 1321 4308 1408 1318 4309 1407 1317 4310 1270 1183 4311 1361 1272 4312 1402 1312 4313 1413 1323 4314 1402 1312 4315 1403 1313 4316 1413 1323 4317 1270 1183 4318 1402 1312 4319 1414 1324 4320 1403 1313 4321 1404 1314 4322 1414 1324 4323 1413 1323 4324 1403 1313 4325 1415 1325 4326 1404 1314 4327 1405 1315 4328 1415 1325 4329 1414 1324 4330 1404 1314 4331 1409 1319 4332 1415 1325 4333 1405 1315 4334 1416 1326 4335 1409 1319 4336 1410 1320 4337 1417 1327 4338 1410 1320 4339 1418 1328 4340 1419 1329 4341 1420 1330 4342 1412 1322 4343 1417 1327 4344 1416 1326 4345 1410 1320 4346 1419 1329 4347 1412 1322 4348 1411 1321 4349 1421 1331 4350 1270 1183 4351 1413 1323 4352 1421 1331 4353 1273 1186 4354 1270 1183 4355 1422 1332 4356 1413 1323 4357 1414 1324 4358 1422 1332 4359 1421 1331 4360 1413 1323 4361 1423 1333 4362 1414 1324 4363 1415 1325 4364 1424 1334 4365 1422 1332 4366 1414 1324 4367 1423 1333 4368 1424 1334 4369 1414 1324 4370 1425 1335 4371 1415 1325 4372 1409 1319 4373 1425 1335 4374 1423 1333 4375 1415 1325 4376 1416 1326 4377 1425 1335 4378 1409 1319 4379 1426 1336 4380 1427 1337 4381 1428 1338 4382 1429 1339 4383 1420 1330 4384 1419 1329 4385 1430 1340 4386 1431 1341 4387 1432 1342 4388 1433 1343 4389 1431 1341 4390 1430 1340 4391 1337 1250 4392 1266 1179 4393 1434 1344 4394 1337 1250 4395 1434 1344 4396 1435 1345 4397 1436 1346 4398 1435 1345 4399 1437 1347 4400 1337 1250 4401 1435 1345 4402 1436 1346 4403 1438 1348 4404 1437 1347 4405 1439 1349 4406 1436 1346 4407 1437 1347 4408 1438 1348 4409 1438 1348 4410 1439 1349 4411 1440 1350 4412 1441 1351 4413 1440 1350 4414 1442 1352 4415 1438 1348 4416 1440 1350 4417 1441 1351 4418 1441 1351 4419 1442 1352 4420 1427 1337 4421 1443 1353 4422 1427 1337 4423 1426 1336 4424 1441 1351 4425 1427 1337 4426 1443 1353 4427 1444 1354 4428 1445 1355 4429 1446 1356 4430 1447 1357 4431 1448 1357 4432 1449 1357 4433 1450 1358 4434 1444 1354 4435 1446 1356 4436 1451 1359 4437 1452 1360 4438 1453 1361 4439 1451 1359 4440 1453 1361 4441 1454 1362 4442 1455 1363 4443 1456 1363 4444 1448 1363 4445 1447 1364 4446 1455 1364 4447 1448 1364 4448 1457 1365 4449 1458 1366 4450 1445 1355 4451 1459 1367 4452 1449 1367 4453 1460 1367 4454 1444 1354 4455 1457 1365 4456 1445 1355 4457 1459 1368 4458 1447 1368 4459 1449 1368 4460 1461 1369 4461 1462 1370 4462 1458 1366 4463 1463 1371 4464 1460 1371 4465 1464 1371 4466 1457 1365 4467 1461 1369 4468 1458 1366 4469 1465 1372 4470 1459 1372 4471 1460 1372 4472 1463 1373 4473 1465 1373 4474 1460 1373 4475 1466 1374 4476 1467 1375 4477 1462 1370 4478 1468 1376 4479 1464 1376 4480 1469 1376 4481 1461 1369 4482 1466 1374 4483 1462 1370 4484 1470 1377 4485 1463 1377 4486 1464 1377 4487 1471 1378 4488 1470 1378 4489 1464 1378 4490 1468 1379 4491 1471 1379 4492 1464 1379 4493 1466 1374 4494 1472 1380 4495 1467 1375 4496 1473 1381 4497 1469 1381 4498 1474 1381 4499 1475 1382 4500 1468 1382 4501 1469 1382 4502 1473 1383 4503 1475 1383 4504 1469 1383 4505 1476 1384 4506 1477 1385 4507 1472 1380 4508 1478 1386 4509 1474 1386 4510 1479 1386 4511 1466 1374 4512 1476 1384 4513 1472 1380 4514 1478 1387 4515 1473 1387 4516 1474 1387 4517 1407 1317 4518 1480 1388 4519 1477 1385 4520 1378 1389 4521 1479 1389 4522 1481 1389 4523 1476 1384 4524 1407 1317 4525 1477 1385 4526 1378 1390 4527 1478 1390 4528 1479 1390 4529 1407 1317 4530 1382 1290 4531 1480 1388 4532 1378 1391 4533 1481 1391 4534 1385 1391 4535 1411 1321 4536 1407 1317 4537 1476 1384 4538 1482 1392 4539 1476 1384 4540 1466 1374 4541 1482 1392 4542 1411 1321 4543 1476 1384 4544 1483 1393 4545 1466 1374 4546 1461 1369 4547 1483 1393 4548 1482 1392 4549 1466 1374 4550 1484 1394 4551 1461 1369 4552 1457 1365 4553 1484 1394 4554 1483 1393 4555 1461 1369 4556 1485 1395 4557 1457 1365 4558 1444 1354 4559 1485 1395 4560 1484 1394 4561 1457 1365 4562 1486 1396 4563 1444 1354 4564 1450 1358 4565 1486 1396 4566 1485 1395 4567 1444 1354 4568 1486 1396 4569 1450 1358 4570 1487 1397 4571 1451 1359 4572 1488 1398 4573 1452 1360 4574 1489 1399 4575 1486 1396 4576 1487 1397 4577 1489 1399 4578 1487 1397 4579 1490 1400 4580 1451 1359 4581 1491 1401 4582 1488 1398 4583 1419 1329 4584 1411 1321 4585 1482 1392 4586 1492 1402 4587 1482 1392 4588 1483 1393 4589 1492 1402 4590 1419 1329 4591 1482 1392 4592 1493 1403 4593 1483 1393 4594 1484 1394 4595 1493 1403 4596 1492 1402 4597 1483 1393 4598 1494 1404 4599 1484 1394 4600 1485 1395 4601 1494 1404 4602 1493 1403 4603 1484 1394 4604 1495 1405 4605 1485 1395 4606 1486 1396 4607 1495 1405 4608 1494 1404 4609 1485 1395 4610 1489 1399 4611 1495 1405 4612 1486 1396 4613 1496 1406 4614 1489 1399 4615 1490 1400 4616 1496 1406 4617 1490 1400 4618 1497 1407 4619 1498 1408 4620 1499 1409 4621 1491 1401 4622 1500 1410 4623 1498 1408 4624 1491 1401 4625 1451 1359 4626 1500 1410 4627 1491 1401 4628 1501 1411 4629 1419 1329 4630 1492 1402 4631 1501 1411 4632 1429 1339 4633 1419 1329 4634 1502 1412 4635 1492 1402 4636 1493 1403 4637 1503 1413 4638 1501 1411 4639 1492 1402 4640 1504 1414 4641 1503 1413 4642 1492 1402 4643 1502 1412 4644 1504 1414 4645 1492 1402 4646 1505 1415 4647 1493 1403 4648 1494 1404 4649 1506 1416 4650 1502 1412 4651 1493 1403 4652 1505 1415 4653 1506 1416 4654 1493 1403 4655 1507 1417 4656 1494 1404 4657 1495 1405 4658 1508 1418 4659 1505 1415 4660 1494 1404 4661 1507 1417 4662 1508 1418 4663 1494 1404 4664 1509 1419 4665 1495 1405 4666 1489 1399 4667 1510 1420 4668 1507 1417 4669 1495 1405 4670 1509 1419 4671 1510 1420 4672 1495 1405 4673 1496 1406 4674 1509 1419 4675 1489 1399 4676 1511 1421 4677 1512 1422 4678 1513 1423 4679 1514 1424 4680 1515 1425 4681 1516 1426 4682 1517 1427 4683 1515 1425 4684 1514 1424 4685 1430 1340 4686 1432 1342 4687 1518 1428 4688 1519 1429 4689 1518 1428 4690 1520 1430 4691 1430 1340 4692 1518 1428 4693 1519 1429 4694 1519 1429 4695 1520 1430 4696 1521 1431 4697 1519 1429 4698 1521 1431 4699 1522 1432 4700 1519 1429 4701 1522 1432 4702 1523 1433 4703 1524 1434 4704 1523 1433 4705 1525 1435 4706 1519 1429 4707 1523 1433 4708 1524 1434 4709 1524 1434 4710 1525 1435 4711 1526 1436 4712 1524 1434 4713 1526 1436 4714 1527 1437 4715 1528 1438 4716 1527 1437 4717 1529 1439 4718 1524 1434 4719 1527 1437 4720 1528 1438 4721 1528 1438 4722 1529 1439 4723 1530 1440 4724 1511 1421 4725 1530 1440 4726 1512 1422 4727 1531 1441 4728 1530 1440 4729 1511 1421 4730 1532 1442 4731 1530 1440 4732 1531 1441 4733 1528 1438 4734 1530 1440 4735 1532 1442 4736 1451 1359 4737 1454 1362 4738 1533 1443 4739 1455 1444 4740 1534 1444 4741 1456 1444 4742 1535 1445 4743 1536 1446 4744 1537 1447 4745 1455 1448 4746 1538 1448 4747 1534 1448 4748 1539 1449 4749 1540 1450 4750 1536 1446 4751 1541 1451 4752 1540 1450 4753 1539 1449 4754 1542 1452 4755 1543 1453 4756 1544 1454 4757 1545 1455 4758 1543 1453 4759 1542 1452 4760 1517 1427 4761 1514 1424 4762 1546 1456 4763 1539 1449 4764 1536 1446 4765 1535 1445 4766 1547 1457 4767 1548 1458 4768 1549 1459 4769 1550 1460 4770 1551 1460 4771 1552 1460 4772 1553 1461 4773 1547 1457 4774 1549 1459 4775 1554 1462 4776 1555 1463 4777 1556 1464 4778 1554 1462 4779 1556 1464 4780 1557 1465 4781 1558 1466 4782 1559 1466 4783 1551 1466 4784 1550 1467 4785 1558 1467 4786 1551 1467 4787 1560 1468 4788 1561 1469 4789 1548 1458 4790 1550 1470 4791 1552 1470 4792 1562 1470 4793 1547 1457 4794 1560 1468 4795 1548 1458 4796 1539 1449 4797 1535 1445 4798 1561 1469 4799 1455 1471 4800 1562 1471 4801 1538 1471 4802 1560 1468 4803 1539 1449 4804 1561 1469 4805 1455 1472 4806 1550 1472 4807 1562 1472 4808 1541 1451 4809 1539 1449 4810 1560 1468 4811 1563 1473 4812 1560 1468 4813 1547 1457 4814 1563 1473 4815 1541 1451 4816 1560 1468 4817 1564 1474 4818 1547 1457 4819 1553 1461 4820 1564 1474 4821 1563 1473 4822 1547 1457 4823 1564 1474 4824 1553 1461 4825 1565 1475 4826 1566 1476 4827 1567 1477 4828 1555 1463 4829 1568 1478 4830 1566 1476 4831 1555 1463 4832 1554 1462 4833 1568 1478 4834 1555 1463 4835 1569 1479 4836 1570 1480 4837 1571 1481 4838 1572 1482 4839 1571 1481 4840 1570 1480 4841 1573 1483 4842 1574 1484 4843 1575 1485 4844 1576 1486 4845 1574 1484 4846 1573 1483 4847 1542 1452 4848 1544 1454 4849 1571 1481 4850 1572 1482 4851 1542 1452 4852 1571 1481 4853 1554 1462 4854 1557 1465 4855 1577 1487 4856 1578 1488 4857 1579 1488 4858 1559 1488 4859 1580 1489 4860 1581 1490 4861 1582 1491 4862 1578 1492 4863 1583 1492 4864 1579 1492 4865 1558 1493 4866 1578 1493 4867 1559 1493 4868 1584 1494 4869 1585 1495 4870 1581 1490 4871 1586 1496 4872 1585 1495 4873 1584 1494 4874 1587 1497 4875 1588 1498 4876 1589 1499 4877 1590 1500 4878 1588 1498 4879 1587 1497 4880 1591 1501 4881 1588 1498 4882 1590 1500 4883 1576 1486 4884 1573 1483 4885 1592 1502 4886 1580 1489 4887 1584 1494 4888 1581 1490 4889 1593 1503 4890 1594 1504 4891 1595 1505 4892 1596 1506 4893 1595 1505 4894 1594 1504 4895 1597 1507 4896 1598 1508 4897 1599 1509 4898 1578 1510 4899 1600 1510 4900 1601 1510 4901 1602 1511 4902 1603 1512 4903 1604 1513 4904 1605 1514 4905 1602 1511 4906 1604 1513 4907 1606 1515 4908 1605 1514 4909 1604 1513 4910 1607 1516 4911 1606 1515 4912 1604 1513 4913 1608 1517 4914 1609 1518 4915 1594 1504 4916 1610 1519 4917 1594 1504 4918 1609 1518 4919 1593 1503 4920 1608 1517 4921 1594 1504 4922 1610 1519 4923 1596 1506 4924 1594 1504 4925 1611 1520 4926 1612 1521 4927 1609 1518 4928 1613 1522 4929 1609 1518 4930 1612 1521 4931 1614 1523 4932 1611 1520 4933 1609 1518 4934 1608 1517 4935 1614 1523 4936 1609 1518 4937 1613 1522 4938 1610 1519 4939 1609 1518 4940 1615 1524 4941 1584 1494 4942 1612 1521 4943 1616 1525 4944 1612 1521 4945 1584 1494 4946 1617 1526 4947 1615 1524 4948 1612 1521 4949 1611 1520 4950 1617 1526 4951 1612 1521 4952 1616 1525 4953 1613 1522 4954 1612 1521 4955 1615 1524 4956 1586 1496 4957 1584 1494 4958 1580 1489 4959 1616 1525 4960 1584 1494 4961 1587 1497 4962 1589 1499 4963 1618 1527 4964 1619 1528 4965 1618 1527 4966 1620 1529 4967 1587 1497 4968 1618 1527 4969 1619 1528 4970 1621 1530 4971 1620 1529 4972 1622 1531 4973 1619 1528 4974 1620 1529 4975 1621 1530 4976 1621 1530 4977 1622 1531 4978 1623 1532 4979 1624 1533 4980 1623 1532 4981 1625 1534 4982 1626 1535 4983 1621 1530 4984 1623 1532 4985 1624 1533 4986 1626 1535 4987 1623 1532 4988 1627 1536 4989 1625 1534 4990 1598 1508 4991 1627 1536 4992 1624 1533 4993 1625 1534 4994 1597 1507 4995 1627 1536 4996 1598 1508 4997 1578 1537 4998 1601 1537 4999 1628 1537 5000 1578 1538 5001 1628 1538 5002 1629 1538 5003 1578 1539 5004 1629 1539 5005 1630 1539 5006 1578 1540 5007 1630 1540 5008 1583 1540 5009 1631 1541 5010 1619 1528 5011 1621 1530 5012 1626 1535 5013 1631 1541 5014 1621 1530 5015 1632 1542 5016 1633 1543 5017 1619 1528 5018 1587 1497 5019 1619 1528 5020 1633 1543 5021 1631 1541 5022 1632 1542 5023 1619 1528 5024 1634 1544 5025 1635 1545 5026 1633 1543 5027 1590 1500 5028 1633 1543 5029 1635 1545 5030 1632 1542 5031 1634 1544 5032 1633 1543 5033 1590 1500 5034 1587 1497 5035 1633 1543 5036 1636 1546 5037 1637 1547 5038 1635 1545 5039 1638 1548 5040 1635 1545 5041 1637 1547 5042 1634 1544 5043 1636 1546 5044 1635 1545 5045 1638 1548 5046 1590 1500 5047 1635 1545 5048 1639 1549 5049 1640 1550 5050 1637 1547 5051 1641 1551 5052 1637 1547 5053 1640 1550 5054 1636 1546 5055 1639 1549 5056 1637 1547 5057 1641 1551 5058 1638 1548 5059 1637 1547 5060 1642 1552 5061 1643 1553 5062 1640 1550 5063 1644 1554 5064 1640 1550 5065 1643 1553 5066 1645 1555 5067 1642 1552 5068 1640 1550 5069 1639 1549 5070 1645 1555 5071 1640 1550 5072 1644 1554 5073 1641 1551 5074 1640 1550 5075 1646 1556 5076 1647 1557 5077 1643 1553 5078 1648 1558 5079 1643 1553 5080 1647 1557 5081 1649 1559 5082 1646 1556 5083 1643 1553 5084 1642 1552 5085 1649 1559 5086 1643 1553 5087 1648 1558 5088 1644 1554 5089 1643 1553 5090 1650 1560 5091 1651 1561 5092 1647 1557 5093 1652 1562 5094 1647 1557 5095 1651 1561 5096 1653 1563 5097 1650 1560 5098 1647 1557 5099 1654 1564 5100 1653 1563 5101 1647 1557 5102 1646 1556 5103 1654 1564 5104 1647 1557 5105 1652 1562 5106 1648 1558 5107 1647 1557 5108 1655 1565 5109 1656 1566 5110 1657 1567 5111 1658 1568 5112 1652 1562 5113 1651 1561 5114 1659 1569 5115 1660 1570 5116 1656 1566 5117 1659 1569 5118 1656 1566 5119 1655 1565 5120 1655 1565 5121 1657 1567 5122 1661 1571 5123 1662 1572 5124 1663 1573 5125 1664 1574 5126 1662 1572 5127 1665 1575 5128 1663 1573 5129 1655 1565 5130 1661 1571 5131 1666 1576 5132 1667 1577 5133 1664 1574 5134 1668 1578 5135 1667 1577 5136 1662 1572 5137 1664 1574 5138 1667 1577 5139 1668 1578 5140 1669 1579 5141 1667 1577 5142 1669 1579 5143 1670 1580 5144 1667 1577 5145 1670 1580 5146 1671 1581 5147 1672 1582 5148 1671 1581 5149 1673 1583 5150 1672 1582 5151 1667 1577 5152 1671 1581 5153 1672 1582 5154 1673 1583 5155 1674 1584 5156 1675 1585 5157 1674 1584 5158 1676 1586 5159 1675 1585 5160 1672 1582 5161 1674 1584 5162 1675 1585 5163 1676 1586 5164 1677 1587 5165 1675 1585 5166 1677 1587 5167 1678 1588 5168 1679 1589 5169 1678 1588 5170 1680 1590 5171 1679 1589 5172 1675 1585 5173 1678 1588 5174 1679 1589 5175 1680 1590 5176 1681 1591 5177 1602 1511 5178 1681 1591 5179 1682 1592 5180 1679 1589 5181 1681 1591 5182 1602 1511 5183 1602 1511 5184 1682 1592 5185 1603 1512 5186 1591 1501 5187 1590 1500 5188 1638 1548 5189 1683 1593 5190 1638 1548 5191 1641 1551 5192 1683 1593 5193 1591 1501 5194 1638 1548 5195 1684 1594 5196 1641 1551 5197 1644 1554 5198 1684 1594 5199 1683 1593 5200 1641 1551 5201 1685 1595 5202 1644 1554 5203 1648 1558 5204 1686 1596 5205 1684 1594 5206 1644 1554 5207 1685 1595 5208 1686 1596 5209 1644 1554 5210 1687 1597 5211 1648 1558 5212 1652 1562 5213 1688 1598 5214 1685 1595 5215 1648 1558 5216 1687 1597 5217 1688 1598 5218 1648 1558 5219 1658 1568 5220 1689 1599 5221 1652 1562 5222 1690 1600 5223 1652 1562 5224 1689 1599 5225 1690 1600 5226 1687 1597 5227 1652 1562 5228 1691 1601 5229 1692 1602 5230 1660 1570 5231 1693 1603 5232 1690 1600 5233 1689 1599 5234 1694 1604 5235 1695 1605 5236 1692 1602 5237 1694 1604 5238 1692 1602 5239 1691 1601 5240 1691 1601 5241 1660 1570 5242 1659 1569 5243 1696 1606 5244 1592 1502 5245 1697 1607 5246 1576 1486 5247 1592 1502 5248 1696 1606 5249 1698 1608 5250 1697 1607 5251 1699 1609 5252 1696 1606 5253 1697 1607 5254 1698 1608 5255 1700 1610 5256 1699 1609 5257 1701 1611 5258 1698 1608 5259 1699 1609 5260 1700 1610 5261 1702 1612 5262 1701 1611 5263 1703 1613 5264 1700 1610 5265 1701 1611 5266 1702 1612 5267 1702 1612 5268 1703 1613 5269 1704 1614 5270 1705 1615 5271 1704 1614 5272 1706 1616 5273 1702 1612 5274 1704 1614 5275 1705 1615 5276 1707 1617 5277 1706 1616 5278 1708 1618 5279 1705 1615 5280 1706 1616 5281 1707 1617 5282 1693 1603 5283 1709 1619 5284 1690 1600 5285 1710 1620 5286 1708 1618 5287 1711 1621 5288 1707 1617 5289 1708 1618 5290 1710 1620 5291 1712 1622 5292 1713 1623 5293 1695 1605 5294 1714 1624 5295 1715 1625 5296 1716 1626 5297 1717 1627 5298 1716 1626 5299 1715 1625 5300 1718 1628 5301 1714 1624 5302 1716 1626 5303 1712 1622 5304 1695 1605 5305 1719 1629 5306 1694 1604 5307 1719 1629 5308 1695 1605 5309 1720 1630 5310 1721 1630 5311 1722 1630 5312 1723 1631 5313 1721 1631 5314 1720 1631 5315 1606 1515 5316 1724 1632 5317 1605 1514 5318 1725 1633 5319 1726 1634 5320 1724 1632 5321 1723 492 5322 1720 492 5323 1727 492 5324 1606 1515 5325 1725 1633 5326 1724 1632 5327 1728 1635 5328 1729 1636 5329 1726 1634 5330 1723 1637 5331 1727 1637 5332 1730 1637 5333 1725 1633 5334 1728 1635 5335 1726 1634 5336 1728 1635 5337 1731 1638 5338 1729 1636 5339 1732 492 5340 1730 492 5341 1733 492 5342 1732 492 5343 1723 492 5344 1730 492 5345 1734 1639 5346 1735 1640 5347 1731 1638 5348 1736 492 5349 1733 492 5350 1737 492 5351 1728 1635 5352 1734 1639 5353 1731 1638 5354 1738 492 5355 1732 492 5356 1733 492 5357 1736 1641 5358 1738 1641 5359 1733 1641 5360 1739 1642 5361 1740 1643 5362 1735 1640 5363 1736 1644 5364 1737 1644 5365 1741 1644 5366 1734 1639 5367 1739 1642 5368 1735 1640 5369 1739 1642 5370 1742 1645 5371 1740 1643 5372 1743 492 5373 1741 492 5374 1744 492 5375 1743 1646 5376 1736 1646 5377 1741 1646 5378 1745 1647 5379 1746 1648 5380 1742 1645 5381 1747 492 5382 1744 492 5383 1748 492 5384 1739 1642 5385 1745 1647 5386 1742 1645 5387 1747 1649 5388 1743 1649 5389 1744 1649 5390 1745 1647 5391 1749 1650 5392 1746 1648 5393 1747 1651 5394 1748 1651 5395 1750 1651 5396 1751 1652 5397 1752 1653 5398 1749 1650 5399 1753 1654 5400 1750 1654 5401 1754 1654 5402 1745 1647 5403 1751 1652 5404 1749 1650 5405 1753 492 5406 1747 492 5407 1750 492 5408 1751 1652 5409 1755 1655 5410 1752 1653 5411 1753 492 5412 1754 492 5413 1756 492 5414 1757 1656 5415 1758 1657 5416 1755 1655 5417 1759 1658 5418 1756 1658 5419 1760 1658 5420 1751 1652 5421 1757 1656 5422 1755 1655 5423 1759 492 5424 1753 492 5425 1756 492 5426 1761 1659 5427 1762 1660 5428 1758 1657 5429 1759 1661 5430 1760 1661 5431 1763 1661 5432 1757 1656 5433 1761 1659 5434 1758 1657 5435 1761 1659 5436 1764 1662 5437 1762 1660 5438 1765 492 5439 1763 492 5440 1766 492 5441 1765 1663 5442 1759 1663 5443 1763 1663 5444 1767 1664 5445 1768 1665 5446 1764 1662 5447 1765 492 5448 1766 492 5449 1769 492 5450 1761 1659 5451 1767 1664 5452 1764 1662 5453 1767 1664 5454 1770 1666 5455 1768 1665 5456 1771 492 5457 1769 492 5458 1772 492 5459 1771 492 5460 1765 492 5461 1769 492 5462 1773 1667 5463 1774 1668 5464 1770 1666 5465 1771 492 5466 1772 492 5467 1775 492 5468 1767 1664 5469 1773 1667 5470 1770 1666 5471 1776 1669 5472 1777 1670 5473 1774 1668 5474 1778 492 5475 1775 492 5476 1779 492 5477 1773 1667 5478 1776 1669 5479 1774 1668 5480 1771 492 5481 1775 492 5482 1778 492 5483 1780 1671 5484 1781 1672 5485 1777 1670 5486 1782 1673 5487 1779 1673 5488 1783 1673 5489 1776 1669 5490 1780 1671 5491 1777 1670 5492 1784 1674 5493 1778 1674 5494 1779 1674 5495 1782 1675 5496 1784 1675 5497 1779 1675 5498 1785 1676 5499 1786 1677 5500 1781 1672 5501 1787 492 5502 1783 492 5503 1788 492 5504 1780 1671 5505 1785 1676 5506 1781 1672 5507 1787 1678 5508 1782 1678 5509 1783 1678 5510 1789 1679 5511 1790 1680 5512 1786 1677 5513 1791 1681 5514 1788 1681 5515 1792 1681 5516 1785 1676 5517 1789 1679 5518 1786 1677 5519 1791 1682 5520 1787 1682 5521 1788 1682 5522 1793 1683 5523 1794 1684 5524 1790 1680 5525 1795 1685 5526 1792 1685 5527 1796 1685 5528 1789 1679 5529 1793 1683 5530 1790 1680 5531 1795 492 5532 1791 492 5533 1792 492 5534 1797 1686 5535 1798 1687 5536 1794 1684 5537 1799 492 5538 1796 492 5539 1800 492 5540 1793 1683 5541 1797 1686 5542 1794 1684 5543 1799 1688 5544 1795 1688 5545 1796 1688 5546 1801 1689 5547 1802 1690 5548 1798 1687 5549 1803 1691 5550 1800 1691 5551 1804 1691 5552 1797 1686 5553 1801 1689 5554 1798 1687 5555 1803 492 5556 1799 492 5557 1800 492 5558 1805 1692 5559 1806 1693 5560 1802 1690 5561 1807 492 5562 1804 492 5563 1808 492 5564 1801 1689 5565 1805 1692 5566 1802 1690 5567 1809 1694 5568 1803 1694 5569 1804 1694 5570 1807 1695 5571 1809 1695 5572 1804 1695 5573 1810 1696 5574 1811 1696 5575 1806 1693 5576 1812 492 5577 1808 492 5578 1813 492 5579 1814 1697 5580 1810 1696 5581 1806 1693 5582 1815 1698 5583 1814 1697 5584 1806 1693 5585 1816 1699 5586 1815 1698 5587 1806 1693 5588 1805 1692 5589 1816 1699 5590 1806 1693 5591 1812 1700 5592 1817 1700 5593 1808 1700 5594 1807 492 5595 1808 492 5596 1817 492 5597 1818 1701 5598 1819 1702 5599 1820 1703 5600 1821 1704 5601 1822 1705 5602 1819 1702 5603 1823 1706 5604 1821 1704 5605 1819 1702 5606 1818 1701 5607 1823 1706 5608 1819 1702 5609 1824 1707 5610 1825 1707 5611 1826 1707 5612 1827 1708 5613 1828 1709 5614 1829 1710 5615 1830 1711 5616 1831 1712 5617 1832 1713 5618 1830 1711 5619 1832 1713 5620 1833 1714 5621 1834 1715 5622 1835 1716 5623 1836 1717 5624 1837 1718 5625 1826 1718 5626 1838 1718 5627 3 1719 5628 1838 1719 5629 1826 1719 5630 1839 1720 5631 1826 1720 5632 1837 1720 5633 1840 1721 5634 1826 1721 5635 1839 1721 5636 1841 1722 5637 1826 1722 5638 1840 1722 5639 1842 1723 5640 1826 1723 5641 1841 1723 5642 1824 1724 5643 1826 1724 5644 1842 1724 5645 1843 1725 5646 1844 1726 5647 1845 1727 5648 1846 1728 5649 1836 1717 5650 1847 1729 5651 1846 1728 5652 1834 1715 5653 1836 1717 5654 1848 1730 5655 1847 1729 5656 1849 1731 5657 1846 1728 5658 1847 1729 5659 1848 1730 5660 1850 1732 5661 1849 1731 5662 1851 1733 5663 1848 1730 5664 1849 1731 5665 1850 1732 5666 1850 1732 5667 1851 1733 5668 1852 1734 5669 1853 1735 5670 1852 1734 5671 1854 1736 5672 1850 1732 5673 1852 1734 5674 1853 1735 5675 1855 1737 5676 1854 1736 5677 1856 1738 5678 1853 1735 5679 1854 1736 5680 1855 1737 5681 1857 1739 5682 1856 1738 5683 1858 1740 5684 1855 1737 5685 1856 1738 5686 1857 1739 5687 1859 1741 5688 1858 1740 5689 1860 1742 5690 1857 1739 5691 1858 1740 5692 1859 1741 5693 1861 1743 5694 1860 1742 5695 1862 1744 5696 1859 1741 5697 1860 1742 5698 1861 1743 5699 1863 1745 5700 1862 1744 5701 1864 1746 5702 1861 1743 5703 1862 1744 5704 1863 1745 5705 1865 1747 5706 1864 1746 5707 1866 1748 5708 1863 1745 5709 1864 1746 5710 1865 1747 5711 1867 1749 5712 1866 1748 5713 1868 1750 5714 1865 1747 5715 1866 1748 5716 1867 1749 5717 1869 1751 5718 1868 1750 5719 1870 1752 5720 1867 1749 5721 1868 1750 5722 1869 1751 5723 1871 1753 5724 1870 1752 5725 1872 1754 5726 1869 1751 5727 1870 1752 5728 1871 1753 5729 1873 1755 5730 1872 1754 5731 1874 1756 5732 1871 1753 5733 1872 1754 5734 1873 1755 5735 1875 1757 5736 1874 1756 5737 1876 1758 5738 1873 1755 5739 1874 1756 5740 1875 1757 5741 1875 1757 5742 1876 1758 5743 1877 1759 5744 1878 1760 5745 1877 1759 5746 1879 1761 5747 1875 1757 5748 1877 1759 5749 1878 1760 5750 1880 1762 5751 1879 1761 5752 1881 1763 5753 1878 1760 5754 1879 1761 5755 1880 1762 5756 1882 1764 5757 1881 1763 5758 1883 1765 5759 1880 1762 5760 1881 1763 5761 1882 1764 5762 1882 1764 5763 1883 1765 5764 1884 1766 5765 1885 1767 5766 1886 1768 5767 1887 1769 5768 1888 1770 5769 1886 1768 5770 1885 1767 5771 1882 1764 5772 1884 1766 5773 1889 1771 5774 1662 1572 5775 1890 1772 5776 1665 1575 5777 1891 1773 5778 1666 1576 5779 1892 1774 5780 1655 1565 5781 1666 1576 5782 1891 1773 5783 1662 1572 5784 1893 1775 5785 1890 1772 5786 1891 1773 5787 1892 1774 5788 1894 1776 5789 1895 1777 5790 1896 1778 5791 1893 1775 5792 1897 1779 5793 1898 1780 5794 1899 1781 5795 1662 1572 5796 1895 1777 5797 1893 1775 5798 1900 1782 5799 1898 1780 5800 1897 1779 5801 1901 1783 5802 1902 1784 5803 1896 1778 5804 1903 1785 5805 1899 1781 5806 1904 1786 5807 1895 1777 5808 1901 1783 5809 1896 1778 5810 1897 1779 5811 1899 1781 5812 1903 1785 5813 1901 1783 5814 1905 1787 5815 1902 1784 5816 1903 1785 5817 1904 1786 5818 1906 1788 5819 1901 1783 5820 1907 1789 5821 1905 1787 5822 1908 1790 5823 1906 1788 5824 1909 1791 5825 1903 1785 5826 1906 1788 5827 1908 1790 5828 1901 1783 5829 1910 1792 5830 1907 1789 5831 1908 1790 5832 1909 1791 5833 1911 1793 5834 1912 1794 5835 1913 1795 5836 1910 1792 5837 1914 1796 5838 1915 1797 5839 1916 1798 5840 1901 1783 5841 1912 1794 5842 1910 1792 5843 1917 1799 5844 1915 1797 5845 1914 1796 5846 1912 1794 5847 1918 1800 5848 1913 1795 5849 1914 1796 5850 1916 1798 5851 1919 1801 5852 1912 1794 5853 1920 1802 5854 1918 1800 5855 1921 1803 5856 1922 1804 5857 1923 1805 5858 1921 1803 5859 1924 1806 5860 1922 1804 5861 1925 1807 5862 1926 1808 5863 1920 1802 5864 1927 1809 5865 1923 1805 5866 1928 1810 5867 1912 1794 5868 1925 1807 5869 1920 1802 5870 1921 1803 5871 1923 1805 5872 1927 1809 5873 1925 1807 5874 1929 1811 5875 1926 1808 5876 1927 1809 5877 1928 1810 5878 1930 1812 5879 1925 1807 5880 1931 1813 5881 1929 1811 5882 1932 1814 5883 1930 1812 5884 1933 1815 5885 1927 1809 5886 1930 1812 5887 1932 1814 5888 1925 1807 5889 1934 1816 5890 1931 1813 5891 1932 1814 5892 1933 1815 5893 1935 1817 5894 1936 1818 5895 1937 1819 5896 1938 1820 5897 1939 1821 5898 1937 1819 5899 1936 1818 5900 1940 1822 5901 1941 1823 5902 1942 1824 5903 1943 1825 5904 1941 1823 5905 1940 1822 5906 1944 492 5907 1945 492 5908 1946 492 5909 1947 492 5910 1948 492 5911 1945 492 5912 1944 492 5913 1947 492 5914 1945 492 5915 1949 1826 5916 1946 1826 5917 1950 1826 5918 1951 1827 5919 1944 1827 5920 1946 1827 5921 1949 1828 5922 1951 1828 5923 1946 1828 5924 1952 492 5925 1950 492 5926 1953 492 5927 1952 1829 5928 1949 1829 5929 1950 1829 5930 1954 1830 5931 1953 1830 5932 1955 1830 5933 1954 1831 5934 1952 1831 5935 1953 1831 5936 1956 1832 5937 1955 1832 5938 1957 1832 5939 1956 492 5940 1954 492 5941 1955 492 5942 1958 492 5943 1957 492 5944 1959 492 5945 1958 1833 5946 1956 1833 5947 1957 1833 5948 1960 1834 5949 1959 1834 5950 1961 1834 5951 1960 492 5952 1958 492 5953 1959 492 5954 1732 492 5955 1961 492 5956 1723 492 5957 1962 1835 5958 1960 1835 5959 1961 1835 5960 1732 1836 5961 1962 1836 5962 1961 1836 5963 1963 492 5964 1964 492 5965 1948 492 5966 1965 1837 5967 1936 1818 5968 1966 1838 5969 1947 492 5970 1963 492 5971 1948 492 5972 1967 1839 5973 1939 1821 5974 1936 1818 5975 1968 1840 5976 1967 1839 5977 1936 1818 5978 1969 1841 5979 1968 1840 5980 1936 1818 5981 1965 1837 5982 1969 1841 5983 1936 1818 5984 1970 492 5985 1971 492 5986 1964 492 5987 1972 1842 5988 1966 1838 5989 1973 1843 5990 1963 1844 5991 1970 1844 5992 1964 1844 5993 1974 1845 5994 1965 1837 5995 1966 1838 5996 1975 1846 5997 1974 1845 5998 1966 1838 5999 1976 1847 6000 1975 1846 6001 1966 1838 6002 1972 1842 6003 1976 1847 6004 1966 1838 6005 1977 492 6006 1978 492 6007 1971 492 6008 1979 1848 6009 1973 1843 6010 1980 1849 6011 1970 492 6012 1977 492 6013 1971 492 6014 1979 1848 6015 1972 1842 6016 1973 1843 6017 1981 492 6018 1982 492 6019 1978 492 6020 1983 1850 6021 1980 1849 6022 1984 1851 6023 1977 492 6024 1981 492 6025 1978 492 6026 1985 1852 6027 1979 1848 6028 1980 1849 6029 1986 1853 6030 1985 1852 6031 1980 1849 6032 1983 1850 6033 1986 1853 6034 1980 1849 6035 1987 1854 6036 1988 1854 6037 1982 1854 6038 1989 1855 6039 1984 1851 6040 1990 1856 6041 1981 1857 6042 1987 1857 6043 1982 1857 6044 1991 1858 6045 1983 1850 6046 1984 1851 6047 1989 1855 6048 1991 1858 6049 1984 1851 6050 1992 492 6051 1817 492 6052 1988 492 6053 1993 1859 6054 1990 1856 6055 1994 1860 6056 1995 1861 6057 1992 1861 6058 1988 1861 6059 1987 1862 6060 1995 1862 6061 1988 1862 6062 1996 1863 6063 1989 1855 6064 1990 1856 6065 1997 1864 6066 1996 1863 6067 1990 1856 6068 1998 1865 6069 1997 1864 6070 1990 1856 6071 1993 1859 6072 1998 1865 6073 1990 1856 6074 1999 1866 6075 1994 1860 6076 1822 1705 6077 1992 1867 6078 1807 1867 6079 1817 1867 6080 2000 1868 6081 1993 1859 6082 1994 1860 6083 2001 1869 6084 2000 1868 6085 1994 1860 6086 2002 1870 6087 2001 1869 6088 1994 1860 6089 1999 1866 6090 2002 1870 6091 1994 1860 6092 2003 1871 6093 1999 1866 6094 1822 1705 6095 1821 1704 6096 2003 1871 6097 1822 1705 6098 2004 1872 6099 2005 1873 6100 2006 1874 6101 2007 1875 6102 2008 1876 6103 2009 1877 6104 2007 1875 6105 2009 1877 6106 2010 1878 6107 2011 1879 6108 2006 1874 6109 2012 1880 6110 2011 1879 6111 2004 1872 6112 2006 1874 6113 2013 1881 6114 2012 1880 6115 2014 1882 6116 2013 1881 6117 2011 1879 6118 2012 1880 6119 2015 1883 6120 2014 1882 6121 2016 1884 6122 2015 1883 6123 2013 1881 6124 2014 1882 6125 2017 1885 6126 2016 1884 6127 2018 1886 6128 2017 1885 6129 2015 1883 6130 2016 1884 6131 2019 1887 6132 2018 1886 6133 2020 1888 6134 2019 1887 6135 2017 1885 6136 2018 1886 6137 2021 1889 6138 2020 1888 6139 2022 1890 6140 2021 1889 6141 2019 1887 6142 2020 1888 6143 2023 1891 6144 2022 1890 6145 2024 1892 6146 2025 1893 6147 2021 1889 6148 2022 1890 6149 2023 1891 6150 2025 1893 6151 2022 1890 6152 2026 1894 6153 2024 1892 6154 2027 1895 6155 2026 1894 6156 2023 1891 6157 2024 1892 6158 2028 1896 6159 2027 1895 6160 2029 1897 6161 2028 1896 6162 2026 1894 6163 2027 1895 6164 2030 1898 6165 2029 1897 6166 2031 1899 6167 2030 1898 6168 2028 1896 6169 2029 1897 6170 2030 1898 6171 2031 1899 6172 2032 1900 6173 2033 1901 6174 2032 1900 6175 2034 1902 6176 2033 1901 6177 2030 1898 6178 2032 1900 6179 2035 1903 6180 2034 1902 6181 2036 1904 6182 2035 1903 6183 2033 1901 6184 2034 1902 6185 2037 1905 6186 2036 1904 6187 2038 1906 6188 2037 1905 6189 2035 1903 6190 2036 1904 6191 2039 1907 6192 2038 1906 6193 2040 1908 6194 2039 1907 6195 2037 1905 6196 2038 1906 6197 2041 1909 6198 2040 1908 6199 2042 1910 6200 2041 1909 6201 2039 1907 6202 2040 1908 6203 2043 1911 6204 2042 1910 6205 2044 1912 6206 2043 1911 6207 2041 1909 6208 2042 1910 6209 2045 1913 6210 2046 1914 6211 2047 1915 6212 2048 1916 6213 2043 1911 6214 2044 1912 6215 2049 1917 6216 2047 1915 6217 2050 1918 6218 2049 1917 6219 2045 1913 6220 2047 1915 6221 2051 1919 6222 2050 1918 6223 2052 1920 6224 2051 1919 6225 2049 1917 6226 2050 1918 6227 2053 1921 6228 2052 1920 6229 2054 1922 6230 2053 1921 6231 2051 1919 6232 2052 1920 6233 2055 1923 6234 2054 1922 6235 2056 1924 6236 2055 1923 6237 2053 1921 6238 2054 1922 6239 2057 1925 6240 2056 1924 6241 2058 1926 6242 2057 1925 6243 2055 1923 6244 2056 1924 6245 2059 1927 6246 2058 1926 6247 2060 1928 6248 2059 1927 6249 2057 1925 6250 2058 1926 6251 2061 1929 6252 2060 1928 6253 2062 1930 6254 2063 1931 6255 2059 1927 6256 2060 1928 6257 2061 1929 6258 2063 1931 6259 2060 1928 6260 2064 1932 6261 2062 1930 6262 2065 1933 6263 2064 1932 6264 2061 1929 6265 2062 1930 6266 2066 1934 6267 2065 1933 6268 2067 1935 6269 2066 1934 6270 2064 1932 6271 2065 1933 6272 2068 1936 6273 2067 1935 6274 2069 1937 6275 2068 1936 6276 2066 1934 6277 2067 1935 6278 2068 1936 6279 2069 1937 6280 2070 1938 6281 2071 1939 6282 2070 1938 6283 2072 1940 6284 2071 1939 6285 2068 1936 6286 2070 1938 6287 2073 1941 6288 2072 1940 6289 2074 1942 6290 2073 1941 6291 2071 1939 6292 2072 1940 6293 2075 1943 6294 2074 1942 6295 2076 1944 6296 2075 1943 6297 2073 1941 6298 2074 1942 6299 2077 1945 6300 2076 1944 6301 2078 1946 6302 2077 1945 6303 2075 1943 6304 2076 1944 6305 2079 1947 6306 2078 1946 6307 2008 1876 6308 2079 1947 6309 2077 1945 6310 2078 1946 6311 2007 1875 6312 2079 1947 6313 2008 1876 6314 2080 1948 6315 1942 1824 6316 2081 1949 6317 1940 1822 6318 1942 1824 6319 2080 1948 6320 2080 1948 6321 2081 1949 6322 2082 1950 6323 2083 1951 6324 2082 1950 6325 2084 1952 6326 2080 1948 6327 2082 1950 6328 2083 1951 6329 2083 1951 6330 2084 1952 6331 2085 1953 6332 2086 1954 6333 2085 1953 6334 2087 1955 6335 2083 1951 6336 2085 1953 6337 2086 1954 6338 2088 1956 6339 2089 1957 6340 2090 1958 6341 2088 1956 6342 2091 1959 6343 2089 1957 6344 2088 1956 6345 2090 1958 6346 2092 1960 6347 2093 1961 6348 2094 1962 6349 2095 1963 6350 2096 1964 6351 2094 1962 6352 2093 1961 6353 2097 1965 6354 2095 1963 6355 2098 1966 6356 2093 1961 6357 2095 1963 6358 2097 1965 6359 2099 1967 6360 2100 1968 6361 2101 1969 6362 2102 1970 6363 2100 1968 6364 2099 1967 6365 2099 1967 6366 2101 1969 6367 2103 1971 6368 2104 1972 6369 2103 1971 6370 2105 1973 6371 2099 1967 6372 2103 1971 6373 2104 1972 6374 2106 1974 6375 2107 1975 6376 2108 1976 6377 2109 1977 6378 2108 1976 6379 2110 1978 6380 2111 1979 6381 2108 1976 6382 2109 1977 6383 2106 1974 6384 2108 1976 6385 2111 1979 6386 2112 1980 6387 2110 1978 6388 2113 1981 6389 2109 1977 6390 2110 1978 6391 2112 1980 6392 2112 1980 6393 2113 1981 6394 2114 1982 6395 2115 1983 6396 2114 1982 6397 2116 1984 6398 2112 1980 6399 2114 1982 6400 2115 1983 6401 2115 1983 6402 2116 1984 6403 2117 1985 6404 2118 1986 6405 2117 1985 6406 2119 1987 6407 2115 1983 6408 2117 1985 6409 2118 1986 6410 2118 1986 6411 2119 1987 6412 2120 1988 6413 2121 1989 6414 2120 1988 6415 2122 1990 6416 2118 1986 6417 2120 1988 6418 2121 1989 6419 2123 1991 6420 2122 1990 6421 2124 1992 6422 2121 1989 6423 2122 1990 6424 2123 1991 6425 2125 1993 6426 2124 1992 6427 2126 1994 6428 2123 1991 6429 2124 1992 6430 2125 1993 6431 2127 1995 6432 2126 1994 6433 2128 1996 6434 2125 1993 6435 2126 1994 6436 2127 1995 6437 2129 1997 6438 2128 1996 6439 2130 1998 6440 2127 1995 6441 2128 1996 6442 2129 1997 6443 2131 1999 6444 2130 1998 6445 1828 1709 6446 2131 1999 6447 2129 1997 6448 2130 1998 6449 2132 2000 6450 2131 1999 6451 1828 1709 6452 2133 2001 6453 2132 2000 6454 1828 1709 6455 1827 1708 6456 2133 2001 6457 1828 1709 6458 2134 2002 6459 2135 2003 6460 2136 2004 6461 2137 2005 6462 2138 2006 6463 2139 2007 6464 2140 2008 6465 2134 2002 6466 2136 2004 6467 2141 2009 6468 2142 2010 6469 2143 2011 6470 2141 2009 6471 2143 2011 6472 2144 2012 6473 2145 2013 6474 2146 2014 6475 2147 2015 6476 2148 2016 6477 2149 2017 6478 2135 2003 6479 2150 2018 6480 2139 2007 6481 2151 2019 6482 2134 2002 6483 2148 2016 6484 2135 2003 6485 2137 2005 6486 2139 2007 6487 2152 2020 6488 2150 2018 6489 2152 2020 6490 2139 2007 6491 2153 2021 6492 2154 2022 6493 2149 2017 6494 2155 2023 6495 2151 2019 6496 2156 2024 6497 2148 2016 6498 2153 2021 6499 2149 2017 6500 2150 2018 6501 2151 2019 6502 2155 2023 6503 2157 2025 6504 2086 1954 6505 2154 2022 6506 2088 1956 6507 2156 2024 6508 2091 1959 6509 2153 2021 6510 2157 2025 6511 2154 2022 6512 2158 2026 6513 2156 2024 6514 2088 1956 6515 2155 2023 6516 2156 2024 6517 2158 2026 6518 2157 2025 6519 2083 1951 6520 2086 1954 6521 2080 1948 6522 2083 1951 6523 2157 2025 6524 2159 2027 6525 2157 2025 6526 2153 2021 6527 2159 2027 6528 2080 1948 6529 2157 2025 6530 2160 2028 6531 2153 2021 6532 2148 2016 6533 2160 2028 6534 2159 2027 6535 2153 2021 6536 2161 2029 6537 2148 2016 6538 2134 2002 6539 2161 2029 6540 2160 2028 6541 2148 2016 6542 2162 2030 6543 2134 2002 6544 2140 2008 6545 2162 2030 6546 2161 2029 6547 2134 2002 6548 2162 2030 6549 2140 2008 6550 2163 2031 6551 2141 2009 6552 2164 2032 6553 2142 2010 6554 2165 2033 6555 2162 2030 6556 2163 2031 6557 2141 2009 6558 2166 2034 6559 2164 2032 6560 1940 1822 6561 2080 1948 6562 2159 2027 6563 2167 2035 6564 2159 2027 6565 2160 2028 6566 2167 2035 6567 1940 1822 6568 2159 2027 6569 2168 2036 6570 2160 2028 6571 2161 2029 6572 2168 2036 6573 2167 2035 6574 2160 2028 6575 2169 2037 6576 2161 2029 6577 2162 2030 6578 2169 2037 6579 2168 2036 6580 2161 2029 6581 2170 2038 6582 2162 2030 6583 2165 2033 6584 2170 2038 6585 2169 2037 6586 2162 2030 6587 2170 2038 6588 2165 2033 6589 2171 2039 6590 2172 2040 6591 2173 2041 6592 2166 2034 6593 2141 2009 6594 2172 2040 6595 2166 2034 6596 2174 2042 6597 2170 2038 6598 2171 2039 6599 2172 2040 6600 2175 2043 6601 2173 2041 6602 1943 1825 6603 1940 1822 6604 2167 2035 6605 2176 2044 6606 2167 2035 6607 2168 2036 6608 2176 2044 6609 1943 1825 6610 2167 2035 6611 2177 2045 6612 2168 2036 6613 2169 2037 6614 2177 2045 6615 2176 2044 6616 2168 2036 6617 2178 2046 6618 2169 2037 6619 2170 2038 6620 2178 2046 6621 2177 2045 6622 2169 2037 6623 2178 2046 6624 2170 2038 6625 2174 2042 6626 2178 2046 6627 2174 2042 6628 2179 2047 6629 2180 2048 6630 2181 2049 6631 2175 2043 6632 2172 2040 6633 2180 2048 6634 2175 2043 6635 2182 2050 6636 2183 2051 6637 2184 2052 6638 2185 2053 6639 2186 2054 6640 2181 2049 6641 2182 2050 6642 2184 2052 6643 2187 2055 6644 2180 2048 6645 2185 2053 6646 2181 2049 6647 2188 2056 6648 1932 1814 6649 2189 2057 6650 2188 2056 6651 1927 1809 6652 1932 1814 6653 2190 2058 6654 2189 2057 6655 2191 2059 6656 2190 2058 6657 2188 2056 6658 2189 2057 6659 2192 2060 6660 2191 2059 6661 2183 2051 6662 2192 2060 6663 2190 2058 6664 2191 2059 6665 2182 2050 6666 2192 2060 6667 2183 2051 6668 2141 2009 6669 2144 2012 6670 2193 2061 6671 2145 2013 6672 2194 2062 6673 2146 2014 6674 2195 2063 6675 2196 2064 6676 2197 2065 6677 2198 2066 6678 2194 2062 6679 2145 2013 6680 2199 2067 6681 2200 2068 6682 2201 2069 6683 2202 2070 6684 2200 2068 6685 2199 2067 6686 2203 2071 6687 2195 2063 6688 2197 2065 6689 2204 2072 6690 2200 2068 6691 2202 2070 6692 2205 2073 6693 2206 2074 6694 2186 2054 6695 2207 2075 6696 2187 2055 6697 2208 2076 6698 2185 2053 6699 2205 2073 6700 2186 2054 6701 2207 2075 6702 2182 2050 6703 2187 2055 6704 2209 2077 6705 2210 2078 6706 2206 2074 6707 2211 2079 6708 2208 2076 6709 2212 2080 6710 2213 2081 6711 2209 2077 6712 2206 2074 6713 2205 2073 6714 2213 2081 6715 2206 2074 6716 2207 2075 6717 2208 2076 6718 2211 2079 6719 2214 2082 6720 2215 2083 6721 2216 2084 6722 2217 2085 6723 2215 2083 6724 2214 2082 6725 2218 2086 6726 2215 2083 6727 2217 2085 6728 2218 2086 6729 2219 2087 6730 2215 2083 6731 2220 2088 6732 2221 2089 6733 2222 2090 6734 2220 2088 6735 2223 2091 6736 2221 2089 6737 2214 2082 6738 2216 2084 6739 2224 2092 6740 2225 2093 6741 2226 2094 6742 2227 2095 6743 2228 2096 6744 2229 2097 6745 2230 2098 6746 2231 2099 6747 2232 2100 6748 2229 2097 6749 2228 2096 6750 2231 2099 6751 2229 2097 6752 2233 2101 6753 2227 2095 6754 2234 2102 6755 2235 2103 6756 2227 2095 6757 2233 2101 6758 2225 2093 6759 2227 2095 6760 2235 2103 6761 2236 2104 6762 2234 2102 6763 2237 2105 6764 2233 2101 6765 2234 2102 6766 2236 2104 6767 2238 2106 6768 2237 2105 6769 2239 2107 6770 2236 2104 6771 2237 2105 6772 2238 2106 6773 2195 2063 6774 2239 2107 6775 2196 2064 6776 2238 2106 6777 2239 2107 6778 2195 2063 6779 2240 2108 6780 2241 2109 6781 2242 2110 6782 2243 2111 6783 2244 2112 6784 2245 2113 6785 2246 2114 6786 2247 2115 6787 2248 2116 6788 2243 2111 6789 2249 2117 6790 2244 2112 6791 2250 2118 6792 2251 2119 6793 2252 2120 6794 2246 2114 6795 2248 2116 6796 2253 2121 6797 2240 2108 6798 2254 2122 6799 2241 2109 6800 2243 2111 6801 2245 2113 6802 2255 2123 6803 2256 2124 6804 2145 2013 6805 2254 2122 6806 2257 2125 6807 2256 2124 6808 2254 2122 6809 2258 2126 6810 2257 2125 6811 2254 2122 6812 2259 2127 6813 2258 2126 6814 2254 2122 6815 2260 2128 6816 2259 2127 6817 2254 2122 6818 2261 2129 6819 2260 2128 6820 2254 2122 6821 2240 2108 6822 2261 2129 6823 2254 2122 6824 2262 2130 6825 2263 2131 6826 2264 2132 6827 2265 2133 6828 2198 2066 6829 2145 2013 6830 2266 2134 6831 2265 2133 6832 2145 2013 6833 2256 2124 6834 2266 2134 6835 2145 2013 6836 2267 2135 6837 2268 2136 6838 2269 2137 6839 2270 2138 6840 2269 2137 6841 2271 2139 6842 2272 2140 6843 2269 2137 6844 2270 2138 6845 2267 2135 6846 2269 2137 6847 2272 2140 6848 2273 2141 6849 2274 2142 6850 2275 2143 6851 2270 2138 6852 2271 2139 6853 2276 2144 6854 2277 2145 6855 2275 2143 6856 2278 2146 6857 2279 2147 6858 2273 2141 6859 2275 2143 6860 2280 2148 6861 2279 2147 6862 2275 2143 6863 2277 2145 6864 2280 2148 6865 2275 2143 6866 2277 2145 6867 2278 2146 6868 2281 2149 6869 2282 2150 6870 2281 2149 6871 2283 2151 6872 2282 2150 6873 2277 2145 6874 2281 2149 6875 2284 2152 6876 2283 2151 6877 2285 2153 6878 2284 2152 6879 2282 2150 6880 2283 2151 6881 2246 2114 6882 2285 2153 6883 2247 2115 6884 2246 2114 6885 2284 2152 6886 2285 2153 6887 2243 2111 6888 2286 2154 6889 2249 2117 6890 2287 2155 6891 2252 2120 6892 2288 2156 6893 2250 2118 6894 2252 2120 6895 2287 2155 6896 2243 2111 6897 2289 2157 6898 2286 2154 6899 2290 2158 6900 2288 2156 6901 2291 2159 6902 2287 2155 6903 2288 2156 6904 2290 2158 6905 2243 2111 6906 2292 2160 6907 2289 2157 6908 2293 2161 6909 2291 2159 6910 2294 2162 6911 2290 2158 6912 2291 2159 6913 2293 2161 6914 2295 2163 6915 2296 2164 6916 2292 2160 6917 2297 2165 6918 2294 2162 6919 2298 2166 6920 2243 2111 6921 2295 2163 6922 2292 2160 6923 2293 2161 6924 2294 2162 6925 2297 2165 6926 2299 2167 6927 2300 2168 6928 2296 2164 6929 2297 2165 6930 2298 2166 6931 2301 2169 6932 2295 2163 6933 2299 2167 6934 2296 2164 6935 2299 2167 6936 2302 2170 6937 2300 2168 6938 2303 2171 6939 2301 2169 6940 2304 2172 6941 2297 2165 6942 2301 2169 6943 2303 2171 6944 2299 2167 6945 2305 2173 6946 2302 2170 6947 2306 2174 6948 2304 2172 6949 2307 2175 6950 2303 2171 6951 2304 2172 6952 2306 2174 6953 2299 2167 6954 2308 2176 6955 2305 2173 6956 2309 2177 6957 2307 2175 6958 2310 2178 6959 2306 2174 6960 2307 2175 6961 2309 2177 6962 2311 2179 6963 2312 2180 6964 2313 2181 6965 2309 2177 6966 2310 2178 6967 2314 2182 6968 2315 2183 6969 2314 2182 6970 2310 2178 6971 2316 2184 6972 2317 2185 6973 2318 2186 6974 2311 2179 6975 2319 2187 6976 2312 2180 6977 2311 2179 6978 2313 2181 6979 2320 2188 6980 2262 2130 6981 2320 2188 6982 2263 2131 6983 2262 2130 6984 2311 2179 6985 2320 2188 6986 71 69 6987 2321 2189 6988 67 65 6989 2322 2190 6990 67 65 6991 2321 2189 6992 2322 2190 6993 41 39 6994 67 65 6995 2323 2191 6996 2324 2192 6997 2321 2189 6998 2325 2193 6999 2321 2189 7000 2324 2192 7001 71 69 7002 2323 2191 7003 2321 2189 7004 2325 2193 7005 2322 2190 7006 2321 2189 7007 2326 2194 7008 2327 2195 7009 2324 2192 7010 2328 2196 7011 2324 2192 7012 2327 2195 7013 2323 2191 7014 2326 2194 7015 2324 2192 7016 2328 2196 7017 2325 2193 7018 2324 2192 7019 2329 2197 7020 2330 2198 7021 2327 2195 7022 2331 2199 7023 2327 2195 7024 2330 2198 7025 2326 2194 7026 2329 2197 7027 2327 2195 7028 2331 2199 7029 2328 2196 7030 2327 2195 7031 2332 2200 7032 2333 2201 7033 2330 2198 7034 2334 2202 7035 2330 2198 7036 2333 2201 7037 2335 2203 7038 2332 2200 7039 2330 2198 7040 2329 2197 7041 2335 2203 7042 2330 2198 7043 2334 2202 7044 2331 2199 7045 2330 2198 7046 2336 2204 7047 2337 2205 7048 2333 2201 7049 2338 2206 7050 2333 2201 7051 2337 2205 7052 2332 2200 7053 2336 2204 7054 2333 2201 7055 2338 2206 7056 2334 2202 7057 2333 2201 7058 2339 2207 7059 2340 2208 7060 2337 2205 7061 2341 2209 7062 2337 2205 7063 2340 2208 7064 2342 2210 7065 2339 2207 7066 2337 2205 7067 2336 2204 7068 2342 2210 7069 2337 2205 7070 2341 2209 7071 2338 2206 7072 2337 2205 7073 2343 2211 7074 2344 2212 7075 2340 2208 7076 2345 2213 7077 2340 2208 7078 2344 2212 7079 2339 2207 7080 2343 2211 7081 2340 2208 7082 2345 2213 7083 2341 2209 7084 2340 2208 7085 2346 2214 7086 2347 2215 7087 2344 2212 7088 2348 2216 7089 2344 2212 7090 2347 2215 7091 2349 2217 7092 2346 2214 7093 2344 2212 7094 2343 2211 7095 2349 2217 7096 2344 2212 7097 2348 2216 7098 2345 2213 7099 2344 2212 7100 2350 2218 7101 2351 2219 7102 2347 2215 7103 2352 2220 7104 2347 2215 7105 2351 2219 7106 2346 2214 7107 2350 2218 7108 2347 2215 7109 2352 2220 7110 2348 2216 7111 2347 2215 7112 2353 2221 7113 2314 2182 7114 2351 2219 7115 2315 2183 7116 2351 2219 7117 2314 2182 7118 2354 2222 7119 2353 2221 7120 2351 2219 7121 2350 2218 7122 2354 2222 7123 2351 2219 7124 2355 2223 7125 2352 2220 7126 2351 2219 7127 2356 2224 7128 2355 2223 7129 2351 2219 7130 2315 2183 7131 2356 2224 7132 2351 2219 7133 2357 2225 7134 2309 2177 7135 2314 2182 7136 2353 2221 7137 2357 2225 7138 2314 2182 7139 2358 2226 7140 2306 2174 7141 2309 2177 7142 2357 2225 7143 2358 2226 7144 2309 2177 7145 2359 2227 7146 2303 2171 7147 2306 2174 7148 2358 2226 7149 2359 2227 7150 2306 2174 7151 2360 2228 7152 2297 2165 7153 2303 2171 7154 2361 2229 7155 2360 2228 7156 2303 2171 7157 2359 2227 7158 2361 2229 7159 2303 2171 7160 2362 2230 7161 2293 2161 7162 2297 2165 7163 2360 2228 7164 2362 2230 7165 2297 2165 7166 2363 2231 7167 2290 2158 7168 2293 2161 7169 2362 2230 7170 2363 2231 7171 2293 2161 7172 2364 2232 7173 2287 2155 7174 2290 2158 7175 2363 2231 7176 2364 2232 7177 2290 2158 7178 2365 2233 7179 2250 2118 7180 2287 2155 7181 2366 2234 7182 2365 2233 7183 2287 2155 7184 2364 2232 7185 2366 2234 7186 2287 2155 7187 2246 2114 7188 2253 2121 7189 2367 2235 7190 2368 2236 7191 2369 2237 7192 2370 2238 7193 2368 2236 7194 2371 2239 7195 2369 2237 7196 2368 2236 7197 2370 2238 7198 2372 2240 7199 2368 2236 7200 2372 2240 7201 2373 2241 7202 2374 2242 7203 2373 2241 7204 2375 2243 7205 2374 2242 7206 2368 2236 7207 2373 2241 7208 2374 2242 7209 2375 2243 7210 2376 2244 7211 2374 2242 7212 2376 2244 7213 2377 2245 7214 2374 2242 7215 2377 2245 7216 2378 2246 7217 2379 2247 7218 2378 2246 7219 2380 2248 7220 2379 2247 7221 2374 2242 7222 2378 2246 7223 2379 2247 7224 2380 2248 7225 2381 2249 7226 2379 2247 7227 2381 2249 7228 2382 2250 7229 2379 2247 7230 2382 2250 7231 2383 2251 7232 2379 2247 7233 2383 2251 7234 2384 2252 7235 2385 2253 7236 2384 2252 7237 2386 2254 7238 2385 2253 7239 2379 2247 7240 2384 2252 7241 2385 2253 7242 2386 2254 7243 2387 2255 7244 2385 2253 7245 2387 2255 7246 2388 2256 7247 2385 2253 7248 2388 2256 7249 2389 2257 7250 2390 2258 7251 2389 2257 7252 2391 2259 7253 2390 2258 7254 2385 2253 7255 2389 2257 7256 2390 2258 7257 2391 2259 7258 2392 2260 7259 2390 2258 7260 2392 2260 7261 2393 2261 7262 2394 2262 7263 2393 2261 7264 2395 2263 7265 2394 2262 7266 2390 2258 7267 2393 2261 7268 2394 2262 7269 2395 2263 7270 2396 2264 7271 2397 2265 7272 2396 2264 7273 2398 2266 7274 2397 2265 7275 2394 2262 7276 2396 2264 7277 2399 2267 7278 2398 2266 7279 2400 2268 7280 2399 2267 7281 2397 2265 7282 2398 2266 7283 2399 2267 7284 2400 2268 7285 72 70 7286 68 66 7287 2399 2267 7288 72 70 7289 29 27 7290 26 24 7291 2401 2269 7292 2402 2270 7293 2401 2269 7294 2403 2271 7295 2404 2272 7296 29 27 7297 2401 2269 7298 2402 2270 7299 2404 2272 7300 2401 2269 7301 2405 2273 7302 2403 2271 7303 2406 2274 7304 2407 2275 7305 2402 2270 7306 2403 2271 7307 2405 2273 7308 2407 2275 7309 2403 2271 7310 2408 2276 7311 2406 2274 7312 2409 2277 7313 2408 2276 7314 2405 2273 7315 2406 2274 7316 2410 2278 7317 2409 2277 7318 2411 2279 7319 2410 2278 7320 2408 2276 7321 2409 2277 7322 2412 2280 7323 2411 2279 7324 2413 2281 7325 2412 2280 7326 2410 2278 7327 2411 2279 7328 2414 2282 7329 2413 2281 7330 2415 2283 7331 2414 2282 7332 2412 2280 7333 2413 2281 7334 2414 2282 7335 2415 2283 7336 2416 2284 7337 2417 2285 7338 2418 2286 7339 2419 2287 7340 2420 2288 7341 2421 2289 7342 2422 2290 7343 2423 2291 7344 2420 2288 7345 2422 2290 7346 2417 2285 7347 2424 2292 7348 2418 2286 7349 2417 2285 7350 2419 2287 7351 2425 2293 7352 2417 2285 7353 2425 2293 7354 2426 2294 7355 2316 2184 7356 2426 2294 7357 2427 2295 7358 2316 2184 7359 2417 2285 7360 2426 2294 7361 2316 2184 7362 2427 2295 7363 2317 2185 7364 2428 2296 7365 32 30 7366 2429 2297 7367 2428 2296 7368 30 28 7369 32 30 7370 2428 2296 7371 2429 2297 7372 2430 2298 7373 2431 2299 7374 2430 2298 7375 2432 2300 7376 2431 2299 7377 2428 2296 7378 2430 2298 7379 2433 2301 7380 2432 2300 7381 2434 2302 7382 2433 2301 7383 2431 2299 7384 2432 2300 7385 2433 2301 7386 2434 2302 7387 2435 2303 7388 2436 2304 7389 2435 2303 7390 2437 2305 7391 2436 2304 7392 2433 2301 7393 2435 2303 7394 2438 2306 7395 2437 2305 7396 2439 2307 7397 2438 2306 7398 2436 2304 7399 2437 2305 7400 2420 2288 7401 2439 2307 7402 2421 2289 7403 2420 2288 7404 2438 2306 7405 2439 2307 7406 30 28 7407 2440 2308 7408 33 31 7409 14 12 7410 20 18 7411 2441 2309 7412 30 28 7413 2442 2310 7414 2440 2308 7415 2443 2311 7416 2441 2309 7417 2444 2312 7418 14 12 7419 2441 2309 7420 2443 2311 7421 2125 1993 7422 2442 2310 7423 30 28 7424 2127 1995 7425 2445 2313 7426 2442 2310 7427 2446 2314 7428 2444 2312 7429 2447 2315 7430 2125 1993 7431 2127 1995 7432 2442 2310 7433 2443 2311 7434 2444 2312 7435 2446 2314 7436 2123 1991 7437 30 28 7438 2428 2296 7439 2123 1991 7440 2125 1993 7441 30 28 7442 2121 1989 7443 2428 2296 7444 2431 2299 7445 2121 1989 7446 2123 1991 7447 2428 2296 7448 2118 1986 7449 2431 2299 7450 2433 2301 7451 2118 1986 7452 2121 1989 7453 2431 2299 7454 2115 1983 7455 2433 2301 7456 2436 2304 7457 2115 1983 7458 2118 1986 7459 2433 2301 7460 2112 1980 7461 2436 2304 7462 2438 2306 7463 2112 1980 7464 2115 1983 7465 2436 2304 7466 2109 1977 7467 2438 2306 7468 2420 2288 7469 2109 1977 7470 2112 1980 7471 2438 2306 7472 2423 2291 7473 2448 2316 7474 2420 2288 7475 2109 1977 7476 2420 2288 7477 2448 2316 7478 2417 2285 7479 2449 2317 7480 2424 2292 7481 2450 2318 7482 2109 1977 7483 2448 2316 7484 2451 2319 7485 2452 2320 7486 2449 2317 7487 2417 2285 7488 2451 2319 7489 2449 2317 7490 2127 1995 7491 2453 2321 7492 2445 2313 7493 2446 2314 7494 2447 2315 7495 2454 2322 7496 2127 1995 7497 2455 2323 7498 2453 2321 7499 2456 2324 7500 2454 2322 7501 2457 2325 7502 2446 2314 7503 2454 2322 7504 2456 2324 7505 2127 1995 7506 2129 1997 7507 2455 2323 7508 2458 2326 7509 2457 2325 7510 2459 2327 7511 2456 2324 7512 2457 2325 7513 2458 2326 7514 2460 2328 7515 2459 2327 7516 2461 2329 7517 2458 2326 7518 2459 2327 7519 2460 2328 7520 2450 2318 7521 2111 1979 7522 2109 1977 7523 2462 2330 7524 2463 2331 7525 2452 2320 7526 2099 1967 7527 2104 1972 7528 2463 2331 7529 2462 2330 7530 2099 1967 7531 2463 2331 7532 2451 2319 7533 2462 2330 7534 2452 2320 7535 2464 2332 7536 2461 2329 7537 2465 2333 7538 2460 2328 7539 2461 2329 7540 2464 2332 7541 2466 2334 7542 2465 2333 7543 2467 2335 7544 2464 2332 7545 2465 2333 7546 2466 2334 7547 1830 1711 7548 2467 2335 7549 1831 1712 7550 2466 2334 7551 2467 2335 7552 1830 1711 7553 2443 2311 7554 2468 2336 7555 17 15 7556 3 2337 7557 18 2337 7558 2469 2337 7559 14 12 7560 2443 2311 7561 17 15 7562 2443 2311 7563 2470 2338 7564 2468 2336 7565 3 2339 7566 2469 2339 7567 2471 2339 7568 2446 2314 7569 2472 2340 7570 2470 2338 7571 3 2341 7572 2471 2341 7573 1838 2341 7574 2443 2311 7575 2446 2314 7576 2470 2338 7577 2458 2326 7578 2473 2342 7579 2472 2340 7580 2456 2324 7581 2458 2326 7582 2472 2340 7583 2446 2314 7584 2456 2324 7585 2472 2340 7586 2460 2328 7587 2474 2343 7588 2473 2342 7589 2458 2326 7590 2460 2328 7591 2473 2342 7592 2460 2328 7593 2475 2344 7594 2474 2343 7595 2464 2332 7596 2476 2345 7597 2475 2344 7598 2460 2328 7599 2464 2332 7600 2475 2344 7601 2466 2334 7602 2477 2346 7603 2476 2345 7604 2464 2332 7605 2466 2334 7606 2476 2345 7607 1830 1711 7608 1833 1714 7609 2477 2346 7610 2466 2334 7611 1830 1711 7612 2477 2346 7613 2478 2347 7614 2479 2348 7615 2480 2349 7616 2481 2350 7617 2482 2351 7618 2483 2352 7619 2484 2353 7620 2479 2348 7621 2478 2347 7622 2485 2354 7623 2480 2349 7624 2486 2355 7625 2485 2354 7626 2478 2347 7627 2480 2349 7628 2485 2354 7629 2486 2355 7630 1844 1726 7631 2485 2354 7632 1844 1726 7633 1843 1725 7634 925 839 7635 927 841 7636 2487 2356 7637 2488 2357 7638 2489 2358 7639 2490 2359 7640 2491 2360 7641 2490 2359 7642 2492 2361 7643 2488 2357 7644 2490 2359 7645 2491 2360 7646 2493 2362 7647 2492 2361 7648 2494 2363 7649 2491 2360 7650 2492 2361 7651 2493 2362 7652 2495 2364 7653 2494 2363 7654 2496 2365 7655 2493 2362 7656 2494 2363 7657 2495 2364 7658 2497 2366 7659 2496 2365 7660 2498 2367 7661 2495 2364 7662 2496 2365 7663 2497 2366 7664 2497 2366 7665 2498 2367 7666 2499 2368 7667 2500 2369 7668 2501 2370 7669 2502 2371 7670 2497 2366 7671 2499 2368 7672 2503 2372 7673 2504 2373 7674 2502 2371 7675 2505 2374 7676 2504 2373 7677 2500 2369 7678 2502 2371 7679 2504 2373 7680 2505 2374 7681 2506 2375 7682 2507 2376 7683 2506 2375 7684 2508 2377 7685 2504 2373 7686 2506 2375 7687 2507 2376 7688 2509 2378 7689 2508 2377 7690 2510 2379 7691 2507 2376 7692 2508 2377 7693 2509 2378 7694 2509 2378 7695 2510 2379 7696 2511 2380 7697 2512 2381 7698 2511 2380 7699 2513 2382 7700 2509 2378 7701 2511 2380 7702 2512 2381 7703 2512 2381 7704 2513 2382 7705 2514 2383 7706 2515 2384 7707 2514 2383 7708 2482 2351 7709 2512 2381 7710 2514 2383 7711 2515 2384 7712 2515 2384 7713 2482 2351 7714 2481 2350 7715 2516 2385 7716 2517 2386 7717 2518 2387 7718 2519 2388 7719 2520 2389 7720 2521 2390 7721 2522 2391 7722 2523 2392 7723 2524 2393 7724 2525 2394 7725 2520 2389 7726 2519 2388 7727 2526 2395 7728 2527 2396 7729 2528 2397 7730 2529 2398 7731 2528 2397 7732 2527 2396 7733 2522 2391 7734 2524 2393 7735 2530 2399 7736 2531 2400 7737 2520 2389 7738 2525 2394 7739 2532 2401 7740 2533 2402 7741 2520 2389 7742 2529 2398 7743 2527 2396 7744 2534 2403 7745 2535 2404 7746 2532 2401 7747 2520 2389 7748 2531 2400 7749 2535 2404 7750 2520 2389 7751 2516 2385 7752 2536 2405 7753 2517 2386 7754 2537 2406 7755 2517 2386 7756 2536 2405 7757 2516 2385 7758 2538 2407 7759 2536 2405 7760 2539 2408 7761 2536 2405 7762 2538 2407 7763 2540 2409 7764 2536 2405 7765 2539 2408 7766 2541 2410 7767 2536 2405 7768 2540 2409 7769 2537 2406 7770 2536 2405 7771 2541 2410 7772 2542 2411 7773 2543 2412 7774 2538 2407 7775 2544 2413 7776 2538 2407 7777 2543 2412 7778 2516 2385 7779 2542 2411 7780 2538 2407 7781 2539 2408 7782 2538 2407 7783 2544 2413 7784 2484 2353 7785 2478 2347 7786 2543 2412 7787 2545 2414 7788 2543 2412 7789 2478 2347 7790 2542 2411 7791 2484 2353 7792 2543 2412 7793 2544 2413 7794 2543 2412 7795 2545 2414 7796 2545 2414 7797 2478 2347 7798 2485 2354 7799 2515 2384 7800 2481 2350 7801 2546 2415 7802 2547 2416 7803 2546 2415 7804 2523 2392 7805 2515 2384 7806 2546 2415 7807 2547 2416 7808 2547 2416 7809 2523 2392 7810 2522 2391 7811 2539 2408 7812 2548 2417 7813 2549 2418 7814 2550 2419 7815 2551 2420 7816 2552 2421 7817 2553 2422 7818 2539 2408 7819 2549 2418 7820 2554 2423 7821 2555 2424 7822 2556 2425 7823 2550 2419 7824 2557 2426 7825 2551 2420 7826 2544 2413 7827 2558 2427 7828 2548 2417 7829 2559 2428 7830 2552 2421 7831 2560 2429 7832 2539 2408 7833 2544 2413 7834 2548 2417 7835 2559 2428 7836 2550 2419 7837 2552 2421 7838 2545 2414 7839 1843 1725 7840 2558 2427 7841 1846 1728 7842 2560 2429 7843 1834 1715 7844 2544 2413 7845 2545 2414 7846 2558 2427 7847 1846 1728 7848 2559 2428 7849 2560 2429 7850 2545 2414 7851 2485 2354 7852 1843 1725 7853 2553 2422 7854 2540 2409 7855 2539 2408 7856 2561 2430 7857 2562 2431 7858 2555 2424 7859 2561 2430 7860 2563 2432 7861 2562 2431 7862 2564 2433 7863 2555 2424 7864 2554 2423 7865 2565 2434 7866 2555 2424 7867 2564 2433 7868 2566 2435 7869 2555 2424 7870 2565 2434 7871 2567 2436 7872 2555 2424 7873 2566 2435 7874 2568 2437 7875 2555 2424 7876 2567 2436 7877 2569 2438 7878 2555 2424 7879 2568 2437 7880 2569 2438 7881 2561 2430 7882 2555 2424 7883 2561 2430 7884 2519 2388 7885 2563 2432 7886 2570 2439 7887 2525 2394 7888 2519 2388 7889 2561 2430 7890 2570 2439 7891 2519 2388 7892 2571 2440 7893 2572 2441 7894 2573 2442 7895 2574 2443 7896 2575 2444 7897 2576 2445 7898 2577 2446 7899 2578 2447 7900 2579 2448 7901 2580 2449 7902 2581 2450 7903 2582 2451 7904 2583 2452 7905 2584 2453 7906 2572 2441 7907 2574 2443 7908 2576 2445 7909 2585 2454 7910 2571 2440 7911 2583 2452 7912 2572 2441 7913 2586 2455 7914 2587 2456 7915 2584 2453 7916 2588 2457 7917 2585 2454 7918 2589 2458 7919 2583 2452 7920 2586 2455 7921 2584 2453 7922 2588 2457 7923 2574 2443 7924 2585 2454 7925 2586 2455 7926 2590 2459 7927 2587 2456 7928 2588 2457 7929 2589 2458 7930 2591 2460 7931 2592 2461 7932 2593 2462 7933 2590 2459 7934 2594 2463 7935 2591 2460 7936 2595 2464 7937 2586 2455 7938 2592 2461 7939 2590 2459 7940 2588 2457 7941 2591 2460 7942 2594 2463 7943 2592 2461 7944 2596 2465 7945 2593 2462 7946 2597 2466 7947 2595 2464 7948 2598 2467 7949 2594 2463 7950 2595 2464 7951 2597 2466 7952 2528 2397 7953 2598 2467 7954 2599 2468 7955 2600 2469 7956 2601 2470 7957 2596 2465 7958 2602 2471 7959 2598 2467 7960 2528 2397 7961 2592 2461 7962 2600 2469 7963 2596 2465 7964 2597 2466 7965 2598 2467 7966 2602 2471 7967 2600 2469 7968 2603 2472 7969 2601 2470 7970 2522 2391 7971 2530 2399 7972 2603 2472 7973 2600 2469 7974 2522 2391 7975 2603 2472 7976 2602 2471 7977 2528 2397 7978 2529 2398 7979 2604 2473 7980 2522 2391 7981 2600 2469 7982 2604 2473 7983 2547 2416 7984 2522 2391 7985 2605 2474 7986 2600 2469 7987 2592 2461 7988 2605 2474 7989 2604 2473 7990 2600 2469 7991 2606 2475 7992 2592 2461 7993 2586 2455 7994 2606 2475 7995 2605 2474 7996 2592 2461 7997 2607 2476 7998 2586 2455 7999 2583 2452 8000 2607 2476 8001 2606 2475 8002 2586 2455 8003 2608 2477 8004 2583 2452 8005 2571 2440 8006 2607 2476 8007 2583 2452 8008 2608 2477 8009 2609 2478 8010 2610 2479 8011 2578 2447 8012 2611 2480 8013 2578 2447 8014 2577 2446 8015 2611 2480 8016 2609 2478 8017 2578 2447 8018 2500 2369 8019 2607 2476 8020 2608 2477 8021 2612 2481 8022 2503 2372 8023 2610 2479 8024 2612 2481 8025 2610 2479 8026 2609 2478 8027 2512 2381 8028 2547 2416 8029 2604 2473 8030 2512 2381 8031 2515 2384 8032 2547 2416 8033 2509 2378 8034 2604 2473 8035 2605 2474 8036 2509 2378 8037 2512 2381 8038 2604 2473 8039 2507 2376 8040 2605 2474 8041 2606 2475 8042 2507 2376 8043 2509 2378 8044 2605 2474 8045 2504 2373 8046 2606 2475 8047 2607 2476 8048 2504 2373 8049 2507 2376 8050 2606 2475 8051 2504 2373 8052 2607 2476 8053 2500 2369 8054 2497 2366 8055 2503 2372 8056 2612 2481 8057 2613 2482 8058 2581 2450 8059 2614 2483 8060 2580 2449 8061 2614 2483 8062 2581 2450 8063 2615 2484 8064 2616 2485 8065 2609 2478 8066 2612 2481 8067 2609 2478 8068 2616 2485 8069 2617 2486 8070 2615 2484 8071 2609 2478 8072 2611 2480 8073 2617 2486 8074 2609 2478 8075 2618 2487 8076 2619 2488 8077 2616 2485 8078 2620 2489 8079 2616 2485 8080 2619 2488 8081 2621 2490 8082 2618 2487 8083 2616 2485 8084 2615 2484 8085 2621 2490 8086 2616 2485 8087 2620 2489 8088 2612 2481 8089 2616 2485 8090 2622 2491 8091 2623 2492 8092 2619 2488 8093 2624 2493 8094 2619 2488 8095 2623 2492 8096 2625 2494 8097 2622 2491 8098 2619 2488 8099 2618 2487 8100 2625 2494 8101 2619 2488 8102 2624 2493 8103 2620 2489 8104 2619 2488 8105 2626 2495 8106 2627 2496 8107 2623 2492 8108 2628 2497 8109 2623 2492 8110 2627 2496 8111 2629 2498 8112 2626 2495 8113 2623 2492 8114 2630 2499 8115 2629 2498 8116 2623 2492 8117 2622 2491 8118 2630 2499 8119 2623 2492 8120 2628 2497 8121 2624 2493 8122 2623 2492 8123 2631 2500 8124 2632 2501 8125 2633 2502 8126 2634 2503 8127 2628 2497 8128 2627 2496 8129 2631 2500 8130 2635 2504 8131 2632 2501 8132 2636 2505 8133 2637 2506 8134 2638 2507 8135 2639 2508 8136 2637 2506 8137 2636 2505 8138 2640 2509 8139 2641 2510 8140 2642 2511 8141 2631 2500 8142 2633 2502 8143 2643 2512 8144 2644 2513 8145 2636 2505 8146 2645 2514 8147 2646 2515 8148 2636 2505 8149 2644 2513 8150 2647 2516 8151 2636 2505 8152 2646 2515 8153 2648 2517 8154 2639 2508 8155 2636 2505 8156 2649 2518 8157 2648 2517 8158 2636 2505 8159 2647 2516 8160 2649 2518 8161 2636 2505 8162 2650 2519 8163 2644 2513 8164 2651 2520 8165 2652 2521 8166 2644 2513 8167 2650 2519 8168 2646 2515 8169 2644 2513 8170 2653 2522 8171 2652 2521 8172 2653 2522 8173 2644 2513 8174 2614 2483 8175 2650 2519 8176 2654 2523 8177 2652 2521 8178 2650 2519 8179 2614 2483 8180 2655 2524 8181 2652 2521 8182 2614 2483 8183 2655 2524 8184 2614 2483 8185 2580 2449 8186 2497 2366 8187 2612 2481 8188 2620 2489 8189 2495 2364 8190 2620 2489 8191 2624 2493 8192 2495 2364 8193 2497 2366 8194 2620 2489 8195 2493 2362 8196 2624 2493 8197 2628 2497 8198 2493 2362 8199 2495 2364 8200 2624 2493 8201 2491 2360 8202 2628 2497 8203 2634 2503 8204 2491 2360 8205 2493 2362 8206 2628 2497 8207 2488 2357 8208 2491 2360 8209 2634 2503 8210 2656 2525 8211 925 839 8212 2635 2504 8213 2631 2500 8214 2656 2525 8215 2635 2504 8216 2656 2525 8217 928 842 8218 925 839 8219 2657 2526 8220 2658 2527 8221 2659 2528 8222 2660 2529 8223 2661 2529 8224 2662 2529 8225 2663 2530 8226 2657 2526 8227 2659 2528 8228 2664 2531 8229 2663 2530 8230 2659 2528 8231 2665 2532 8232 2666 2533 8233 2667 2534 8234 2665 2532 8235 2667 2534 8236 2668 2535 8237 2669 2536 8238 2670 2537 8239 2658 2527 8240 2660 2538 8241 2662 2538 8242 2671 2538 8243 2657 2526 8244 2669 2536 8245 2658 2527 8246 2669 2536 8247 2672 2539 8248 2670 2537 8249 2660 2540 8250 2671 2540 8251 2673 2540 8252 2674 2541 8253 2675 2542 8254 2672 2539 8255 2676 2543 8256 2677 2544 8257 2678 2545 8258 2669 2536 8259 2674 2541 8260 2672 2539 8261 2679 2546 8262 2660 2546 8263 2673 2546 8264 2680 2547 8265 2681 2548 8266 2675 2542 8267 2682 2549 8268 2678 2545 8269 2683 2550 8270 2674 2541 8271 2680 2547 8272 2675 2542 8273 2682 2549 8274 2676 2543 8275 2678 2545 8276 2680 2547 8277 2684 2551 8278 2681 2548 8279 2682 2549 8280 2683 2550 8281 2685 2552 8282 2686 2553 8283 2687 2554 8284 2684 2551 8285 2688 2555 8286 2684 2551 8287 2687 2554 8288 2680 2547 8289 2686 2553 8290 2684 2551 8291 2689 2556 8292 2685 2552 8293 2690 2557 8294 2689 2556 8295 2682 2549 8296 2685 2552 8297 2691 2558 8298 2692 2559 8299 2693 2560 8300 2694 2561 8301 2688 2555 8302 2687 2554 8303 2695 2562 8304 2694 2561 8305 2687 2554 8306 2696 2563 8307 2695 2562 8308 2687 2554 8309 2697 2564 8310 2696 2563 8311 2687 2554 8312 2698 2565 8313 2697 2564 8314 2687 2554 8315 2699 2566 8316 2698 2565 8317 2687 2554 8318 2700 2567 8319 2701 2568 8320 2692 2559 8321 2691 2558 8322 2700 2567 8323 2692 2559 8324 2691 2558 8325 2693 2560 8326 2702 2569 8327 2703 2570 8328 2680 2547 8329 2674 2541 8330 2704 2571 8331 2702 2569 8332 2705 2572 8333 2704 2571 8334 2691 2558 8335 2702 2569 8336 2706 2573 8337 2674 2541 8338 2669 2536 8339 2707 2574 8340 2703 2570 8341 2674 2541 8342 2706 2573 8343 2707 2574 8344 2674 2541 8345 2708 2575 8346 2669 2536 8347 2657 2526 8348 2709 2576 8349 2706 2573 8350 2669 2536 8351 2710 2577 8352 2709 2576 8353 2669 2536 8354 2711 2578 8355 2710 2577 8356 2669 2536 8357 2708 2575 8358 2711 2578 8359 2669 2536 8360 2712 2579 8361 2657 2526 8362 2663 2530 8363 2713 2580 8364 2708 2575 8365 2657 2526 8366 2714 2581 8367 2713 2580 8368 2657 2526 8369 2715 2582 8370 2714 2581 8371 2657 2526 8372 2712 2579 8373 2715 2582 8374 2657 2526 8375 2716 2583 8376 2717 2584 8377 2663 2530 8378 2718 2585 8379 2663 2530 8380 2717 2584 8381 2719 2586 8382 2716 2583 8383 2663 2530 8384 2720 2587 8385 2719 2586 8386 2663 2530 8387 2721 2588 8388 2720 2587 8389 2663 2530 8390 2664 2531 8391 2721 2588 8392 2663 2530 8393 2722 2589 8394 2712 2579 8395 2663 2530 8396 2723 2590 8397 2722 2589 8398 2663 2530 8399 2718 2585 8400 2723 2590 8401 2663 2530 8402 2724 2591 8403 2725 2592 8404 2717 2584 8405 2726 2593 8406 2717 2584 8407 2725 2592 8408 2716 2583 8409 2724 2591 8410 2717 2584 8411 2726 2593 8412 2718 2585 8413 2717 2584 8414 2727 2594 8415 2728 2595 8416 2725 2592 8417 2729 2596 8418 2725 2592 8419 2728 2595 8420 2730 2597 8421 2727 2594 8422 2725 2592 8423 2724 2591 8424 2730 2597 8425 2725 2592 8426 2731 2598 8427 2726 2593 8428 2725 2592 8429 2732 2599 8430 2731 2598 8431 2725 2592 8432 2729 2596 8433 2732 2599 8434 2725 2592 8435 2733 2600 8436 2653 2522 8437 2728 2595 8438 2734 2601 8439 2728 2595 8440 2653 2522 8441 2727 2594 8442 2733 2600 8443 2728 2595 8444 2735 2602 8445 2729 2596 8446 2728 2595 8447 2736 2603 8448 2735 2602 8449 2728 2595 8450 2737 2604 8451 2736 2603 8452 2728 2595 8453 2738 2605 8454 2737 2604 8455 2728 2595 8456 2739 2606 8457 2738 2605 8458 2728 2595 8459 2740 2607 8460 2739 2606 8461 2728 2595 8462 2734 2601 8463 2740 2607 8464 2728 2595 8465 2741 2608 8466 2646 2515 8467 2653 2522 8468 2742 2609 8469 2741 2608 8470 2653 2522 8471 2733 2600 8472 2742 2609 8473 2653 2522 8474 2652 2521 8475 2734 2601 8476 2653 2522 8477 2743 2610 8478 2744 2611 8479 2745 2612 8480 2743 2610 8481 2746 2613 8482 2744 2611 8483 2747 2614 8484 2745 2612 8485 2748 2615 8486 2747 2614 8487 2743 2610 8488 2745 2612 8489 2747 2614 8490 2748 2615 8491 2749 2616 8492 2750 2617 8493 2751 2617 8494 2752 2617 8495 2747 2614 8496 2749 2616 8497 2753 2618 8498 2750 2619 8499 2752 2619 8500 2754 2619 8501 2750 2620 8502 2754 2620 8503 2755 2620 8504 2756 2621 8505 2757 2622 8506 2758 2623 8507 2750 2624 8508 2755 2624 8509 2759 2624 8510 2760 2625 8511 2758 2623 8512 2761 2626 8513 2760 2625 8514 2756 2621 8515 2758 2623 8516 2762 2627 8517 2761 2626 8518 2763 2628 8519 2762 2627 8520 2760 2625 8521 2761 2626 8522 2764 2629 8523 2763 2628 8524 2765 2630 8525 2764 2629 8526 2762 2627 8527 2763 2628 8528 2665 2532 8529 2765 2630 8530 2666 2533 8531 2665 2532 8532 2764 2629 8533 2765 2630 8534 2766 2631 8535 2690 2557 8536 2767 2632 8537 2766 2631 8538 2689 2556 8539 2690 2557 8540 2766 2631 8541 2767 2632 8542 2768 2633 8543 2769 2634 8544 2770 2634 8545 2771 2634 8546 2766 2631 8547 2768 2633 8548 2772 2635 8549 2769 2636 8550 2771 2636 8551 2773 2636 8552 2774 2637 8553 2775 2638 8554 2776 2639 8555 2777 2640 8556 2778 2641 8557 2779 2642 8558 2769 2643 8559 2773 2643 8560 2780 2643 8561 2781 2644 8562 2776 2639 8563 2782 2645 8564 2774 2637 8565 2776 2639 8566 2783 2646 8567 2781 2644 8568 2783 2646 8569 2776 2639 8570 2784 2647 8571 2781 2644 8572 2782 2645 8573 2785 2648 8574 2786 2649 8575 2787 2650 8576 2788 2651 8577 2703 2570 8578 2707 2574 8579 2789 2652 8580 2705 2572 8581 2790 2653 8582 2789 2652 8583 2704 2571 8584 2705 2572 8585 2791 2654 8586 2707 2574 8587 2706 2573 8588 2792 2655 8589 2788 2651 8590 2707 2574 8591 2791 2654 8592 2792 2655 8593 2707 2574 8594 2793 2656 8595 2706 2573 8596 2709 2576 8597 2793 2656 8598 2791 2654 8599 2706 2573 8600 2794 2657 8601 2795 2658 8602 2796 2659 8603 2797 2660 8604 2798 2661 8605 2795 2658 8606 2794 2657 8607 2797 2660 8608 2795 2658 8609 2799 2662 8610 2800 2663 8611 2801 2664 8612 2794 2657 8613 2796 2659 8614 2802 2665 8615 2803 2666 8616 2801 2664 8617 2804 2667 8618 2803 2666 8619 2799 2662 8620 2801 2664 8621 2805 2668 8622 2804 2667 8623 2806 2669 8624 2805 2668 8625 2803 2666 8626 2804 2667 8627 2807 2670 8628 2806 2669 8629 2808 2671 8630 2807 2670 8631 2805 2668 8632 2806 2669 8633 2809 2672 8634 2808 2671 8635 2810 2673 8636 2809 2672 8637 2807 2670 8638 2808 2671 8639 2811 2674 8640 2810 2673 8641 2812 2675 8642 2811 2674 8643 2809 2672 8644 2810 2673 8645 2813 2676 8646 2812 2675 8647 2814 2677 8648 2813 2676 8649 2811 2674 8650 2812 2675 8651 2815 2678 8652 2816 2679 8653 2817 2680 8654 2818 2681 8655 2817 2680 8656 2819 2682 8657 2818 2681 8658 2815 2678 8659 2817 2680 8660 2820 2683 8661 2819 2682 8662 2821 2684 8663 2822 2685 8664 2818 2681 8665 2819 2682 8666 2820 2683 8667 2822 2685 8668 2819 2682 8669 2820 2683 8670 2821 2684 8671 2823 2686 8672 2824 2687 8673 2825 2688 8674 2826 2689 8675 2827 2690 8676 2820 2683 8677 2823 2686 8678 2828 2691 8679 2826 2689 8680 2829 2692 8681 2828 2691 8682 2824 2687 8683 2826 2689 8684 2830 2693 8685 2829 2692 8686 2831 2694 8687 2830 2693 8688 2828 2691 8689 2829 2692 8690 2832 2695 8691 2831 2694 8692 2833 2696 8693 2832 2695 8694 2830 2693 8695 2831 2694 8696 2834 2697 8697 2833 2696 8698 2835 2698 8699 2834 2697 8700 2832 2695 8701 2833 2696 8702 2836 2699 8703 2835 2698 8704 2837 2700 8705 2836 2699 8706 2834 2697 8707 2835 2698 8708 2836 2699 8709 2837 2700 8710 2838 2701 8711 2839 2702 8712 2840 2703 8713 2841 2704 8714 2842 2705 8715 2836 2699 8716 2838 2701 8717 2843 2706 8718 2740 2607 8719 2734 2601 8720 2844 2707 8721 2841 2704 8722 2845 2708 8723 2844 2707 8724 2839 2702 8725 2841 2704 8726 2655 2524 8727 2734 2601 8728 2652 2521 8729 2846 2709 8730 2734 2601 8731 2655 2524 8732 2843 2706 8733 2734 2601 8734 2846 2709 8735 2789 2652 8736 2790 2653 8737 2847 2710 8738 2848 2711 8739 2792 2655 8740 2791 2654 8741 2849 2712 8742 2847 2710 8743 2850 2713 8744 2849 2712 8745 2789 2652 8746 2847 2710 8747 2793 2656 8748 2851 2714 8749 2791 2654 8750 2852 2715 8751 2791 2654 8752 2851 2714 8753 2853 2716 8754 2848 2711 8755 2791 2654 8756 2854 2717 8757 2853 2716 8758 2791 2654 8759 2852 2715 8760 2854 2717 8761 2791 2654 8762 2855 2718 8763 2856 2719 8764 2798 2661 8765 2857 2720 8766 2852 2715 8767 2851 2714 8768 2858 2721 8769 2859 2722 8770 2856 2719 8771 2855 2718 8772 2858 2721 8773 2856 2719 8774 2797 2660 8775 2855 2718 8776 2798 2661 8777 2860 2723 8778 2850 2713 8779 2861 2724 8780 2849 2712 8781 2850 2713 8782 2860 2723 8783 2862 2725 8784 2863 2726 8785 2864 2727 8786 2865 2728 8787 2866 2729 8788 2867 2730 8789 2868 2731 8790 2864 2727 8791 2869 2732 8792 2870 2733 8793 2864 2727 8794 2868 2731 8795 2862 2725 8796 2864 2727 8797 2870 2733 8798 2871 2734 8799 2872 2735 8800 2852 2715 8801 2873 2736 8802 2869 2732 8803 2874 2737 8804 2875 2738 8805 2871 2734 8806 2852 2715 8807 2876 2739 8808 2875 2738 8809 2852 2715 8810 2857 2720 8811 2876 2739 8812 2852 2715 8813 2868 2731 8814 2869 2732 8815 2873 2736 8816 2877 2740 8817 2878 2741 8818 2872 2735 8819 2879 2742 8820 2874 2737 8821 2880 2743 8822 2881 2744 8823 2877 2740 8824 2872 2735 8825 2882 2745 8826 2881 2744 8827 2872 2735 8828 2883 2746 8829 2882 2745 8830 2872 2735 8831 2871 2734 8832 2883 2746 8833 2872 2735 8834 2873 2736 8835 2874 2737 8836 2879 2742 8837 2884 2747 8838 2885 2748 8839 2878 2741 8840 2886 2749 8841 2880 2743 8842 2887 2750 8843 2888 2751 8844 2884 2747 8845 2878 2741 8846 2889 2752 8847 2888 2751 8848 2878 2741 8849 2877 2740 8850 2889 2752 8851 2878 2741 8852 2879 2742 8853 2880 2743 8854 2886 2749 8855 2890 2753 8856 2891 2754 8857 2885 2748 8858 2886 2749 8859 2887 2750 8860 2892 2755 8861 2884 2747 8862 2890 2753 8863 2885 2748 8864 2890 2753 8865 2893 2756 8866 2891 2754 8867 2886 2749 8868 2892 2755 8869 2894 2757 8870 2895 2758 8871 2896 2759 8872 2893 2756 8873 2897 2760 8874 2894 2757 8875 2898 2761 8876 2890 2753 8877 2895 2758 8878 2893 2756 8879 2886 2749 8880 2894 2757 8881 2897 2760 8882 2899 2762 8883 2900 2763 8884 2896 2759 8885 2901 2764 8886 2898 2761 8887 2902 2765 8888 2903 2766 8889 2899 2762 8890 2896 2759 8891 2904 2767 8892 2903 2766 8893 2896 2759 8894 2905 2768 8895 2904 2767 8896 2896 2759 8897 2895 2758 8898 2905 2768 8899 2896 2759 8900 2897 2760 8901 2898 2761 8902 2901 2764 8903 2906 2769 8904 2907 2770 8905 2900 2763 8906 2588 2457 8907 2902 2765 8908 2908 2771 8909 2909 2772 8910 2906 2769 8911 2900 2763 8912 2910 2773 8913 2909 2772 8914 2900 2763 8915 2911 2774 8916 2910 2773 8917 2900 2763 8918 2912 2775 8919 2911 2774 8920 2900 2763 8921 2899 2762 8922 2912 2775 8923 2900 2763 8924 2901 2764 8925 2902 2765 8926 2588 2457 8927 2655 2524 8928 2580 2449 8929 2907 2770 8930 2588 2457 8931 2908 2771 8932 2574 2443 8933 2846 2709 8934 2655 2524 8935 2907 2770 8936 2906 2769 8937 2846 2709 8938 2907 2770 8939 2913 2776 8940 2914 2777 8941 2915 2778 8942 2913 2776 8943 2845 2708 8944 2914 2777 8945 2916 2779 8946 2917 2780 8947 2918 2781 8948 2919 2782 8949 2913 2776 8950 2915 2778 8951 2920 2783 8952 2918 2781 8953 2921 2784 8954 2920 2783 8955 2916 2779 8956 2918 2781 8957 2920 2783 8958 2921 2784 8959 2922 2785 8960 2923 2786 8961 2922 2785 8962 2924 2787 8963 2923 2786 8964 2920 2783 8965 2922 2785 8966 2925 2788 8967 2924 2787 8968 2926 2789 8969 2925 2788 8970 2923 2786 8971 2924 2787 8972 2927 2790 8973 2926 2789 8974 2928 2791 8975 2927 2790 8976 2925 2788 8977 2926 2789 8978 2929 2792 8979 2928 2791 8980 2930 2793 8981 2929 2792 8982 2927 2790 8983 2928 2791 8984 2931 2794 8985 2930 2793 8986 2932 2795 8987 2931 2794 8988 2929 2792 8989 2930 2793 8990 2933 2796 8991 2934 2797 8992 2935 2798 8993 2936 2799 8994 2935 2798 8995 2937 2800 8996 2936 2799 8997 2933 2796 8998 2935 2798 8999 2938 2801 9000 2937 2800 9001 2939 2802 9002 2938 2801 9003 2936 2799 9004 2937 2800 9005 2940 2803 9006 2939 2802 9007 2941 2804 9008 2940 2803 9009 2938 2801 9010 2939 2802 9011 2942 2805 9012 2941 2804 9013 2943 2806 9014 2942 2805 9015 2940 2803 9016 2941 2804 9017 2942 2805 9018 2943 2806 9019 2944 2807 9020 2945 2808 9021 2946 2809 9022 2947 2810 9023 2948 2811 9024 2942 2805 9025 2944 2807 9026 2949 2812 9027 2947 2810 9028 2950 2813 9029 2949 2812 9030 2945 2808 9031 2947 2810 9032 2951 2814 9033 2950 2813 9034 2952 2815 9035 2951 2814 9036 2949 2812 9037 2950 2813 9038 2953 2816 9039 2952 2815 9040 2954 2817 9041 2953 2816 9042 2951 2814 9043 2952 2815 9044 2955 2818 9045 2954 2817 9046 2956 2819 9047 2955 2818 9048 2953 2816 9049 2954 2817 9050 2957 2820 9051 2956 2819 9052 2958 2821 9053 2957 2820 9054 2955 2818 9055 2956 2819 9056 2957 2820 9057 2958 2821 9058 2959 2822 9059 2960 2823 9060 2957 2820 9061 2959 2822 9062 2961 2824 9063 2844 2707 9064 2845 2708 9065 2913 2776 9066 2961 2824 9067 2845 2708 9068 2648 2517 9069 2962 2825 9070 2639 2508 9071 2963 2826 9072 2642 2511 9073 2964 2827 9074 2965 2828 9075 2642 2511 9076 2963 2826 9077 2966 2829 9078 2642 2511 9079 2965 2828 9080 2967 2830 9081 2642 2511 9082 2966 2829 9083 2640 2509 9084 2642 2511 9085 2967 2830 9086 2648 2517 9087 2968 2831 9088 2962 2825 9089 2969 2832 9090 2970 2832 9091 2971 2832 9092 2972 2833 9093 2973 2834 9094 2974 2835 9095 2975 2836 9096 2973 2834 9097 2972 2833 9098 2969 2837 9099 2971 2837 9100 2976 2837 9101 2977 2838 9102 2978 2839 9103 2979 2840 9104 2969 2841 9105 2976 2841 9106 2980 2841 9107 2981 2842 9108 2979 2840 9109 2746 2613 9110 2981 2842 9111 2977 2838 9112 2979 2840 9113 2743 2610 9114 2981 2842 9115 2746 2613 9116 2982 2843 9117 2983 2843 9118 2984 2843 9119 2985 2844 9120 2983 2844 9121 2982 2844 9122 2986 2845 9123 2983 2845 9124 2985 2845 9125 2987 2846 9126 2982 2846 9127 2984 2846 9128 2988 2847 9129 2987 2847 9130 2984 2847 9131 2986 2848 9132 2985 2848 9133 2989 2848 9134 2986 2849 9135 2989 2849 9136 2990 2849 9137 2988 2850 9138 2991 2850 9139 2987 2850 9140 2992 2851 9141 2993 2851 9142 2994 2851 9143 2995 2852 9144 2996 2852 9145 2993 2852 9146 2992 2853 9147 2995 2853 9148 2993 2853 9149 2997 2854 9150 2994 2854 9151 2998 2854 9152 2997 2855 9153 2992 2855 9154 2994 2855 9155 2999 2856 9156 2998 2856 9157 2991 2856 9158 2997 2857 9159 2998 2857 9160 2999 2857 9161 2999 2858 9162 2991 2858 9163 2988 2858 9164 3000 2859 9165 2996 2859 9166 2995 2859 9167 3001 2860 9168 2996 2860 9169 3000 2860 9170 2777 2640 9171 3002 2861 9172 2778 2641 9173 3001 2862 9174 3000 2862 9175 3003 2862 9176 3004 2863 9177 3005 2864 9178 3002 2861 9179 3006 2865 9180 3004 2863 9181 3002 2861 9182 3007 2866 9183 3006 2865 9184 3002 2861 9185 2777 2640 9186 3007 2866 9187 3002 2861 9188 3008 2867 9189 3003 2867 9190 3009 2867 9191 3010 2868 9192 3011 2869 9193 3005 2864 9194 3001 2870 9195 3003 2870 9196 3008 2870 9197 3004 2863 9198 3010 2868 9199 3005 2864 9200 3012 2871 9201 3009 2871 9202 3013 2871 9203 3010 2868 9204 3014 2872 9205 3011 2869 9206 3015 2873 9207 3009 2873 9208 3012 2873 9209 3008 2874 9210 3009 2874 9211 3015 2874 9212 3016 2875 9213 3013 2875 9214 3017 2875 9215 3018 2876 9216 3019 2877 9217 3014 2872 9218 3012 2878 9219 3013 2878 9220 3016 2878 9221 3010 2868 9222 3018 2876 9223 3014 2872 9224 3020 2879 9225 3017 2879 9226 3021 2879 9227 3022 2880 9228 3023 2881 9229 3019 2877 9230 3016 2882 9231 3017 2882 9232 3020 2882 9233 3018 2876 9234 3022 2880 9235 3019 2877 9236 3024 2883 9237 3021 2883 9238 3025 2883 9239 3026 2884 9240 3027 2885 9241 3023 2881 9242 3020 2886 9243 3021 2886 9244 3024 2886 9245 3022 2880 9246 3026 2884 9247 3023 2881 9248 3028 2887 9249 3025 2887 9250 3029 2887 9251 3030 2888 9252 3031 2889 9253 3027 2885 9254 3024 2890 9255 3025 2890 9256 3028 2890 9257 3026 2884 9258 3030 2888 9259 3027 2885 9260 3032 2891 9261 3029 2891 9262 3033 2891 9263 3034 2892 9264 3035 2893 9265 3031 2889 9266 3028 2894 9267 3029 2894 9268 3032 2894 9269 3030 2888 9270 3034 2892 9271 3031 2889 9272 3036 2895 9273 3033 2895 9274 3037 2895 9275 3038 2896 9276 3039 2897 9277 3035 2893 9278 3032 2898 9279 3033 2898 9280 3036 2898 9281 3034 2892 9282 3038 2896 9283 3035 2893 9284 3040 2899 9285 3037 2899 9286 3041 2899 9287 3042 2900 9288 3043 2901 9289 3039 2897 9290 3036 2902 9291 3037 2902 9292 3040 2902 9293 3038 2896 9294 3042 2900 9295 3039 2897 9296 3044 2903 9297 3041 2903 9298 3045 2903 9299 3046 2904 9300 3047 2905 9301 3043 2901 9302 3040 2906 9303 3041 2906 9304 3044 2906 9305 3042 2900 9306 3046 2904 9307 3043 2901 9308 3048 2907 9309 3045 2907 9310 3049 2907 9311 3050 2908 9312 3051 2909 9313 3047 2905 9314 3044 2910 9315 3045 2910 9316 3048 2910 9317 3046 2904 9318 3050 2908 9319 3047 2905 9320 3052 2911 9321 3049 2911 9322 3053 2911 9323 3054 2912 9324 3055 2913 9325 3051 2909 9326 3048 2914 9327 3049 2914 9328 3052 2914 9329 3050 2908 9330 3054 2912 9331 3051 2909 9332 3052 2915 9333 3053 2915 9334 3056 2915 9335 3057 2916 9336 3058 2917 9337 3055 2913 9338 3054 2912 9339 3057 2916 9340 3055 2913 9341 3059 2918 9342 3056 2918 9343 3060 2918 9344 3061 2919 9345 3062 2920 9346 3058 2917 9347 3052 2921 9348 3056 2921 9349 3059 2921 9350 3057 2916 9351 3061 2919 9352 3058 2917 9353 3063 2922 9354 3060 2922 9355 3064 2922 9356 3065 2923 9357 3066 2924 9358 3062 2920 9359 3059 2925 9360 3060 2925 9361 3063 2925 9362 3061 2919 9363 3065 2923 9364 3062 2920 9365 3067 2926 9366 3064 2926 9367 3068 2926 9368 3069 2927 9369 3070 2928 9370 3066 2924 9371 3063 2929 9372 3064 2929 9373 3067 2929 9374 3065 2923 9375 3069 2927 9376 3066 2924 9377 3071 2930 9378 3068 2930 9379 3072 2930 9380 3073 2931 9381 3074 2932 9382 3070 2928 9383 3067 2933 9384 3068 2933 9385 3071 2933 9386 3069 2927 9387 3073 2931 9388 3070 2928 9389 3075 2934 9390 3072 2934 9391 3076 2934 9392 3077 2935 9393 3078 2936 9394 3074 2932 9395 3071 2937 9396 3072 2937 9397 3075 2937 9398 3073 2931 9399 3077 2935 9400 3074 2932 9401 3079 2938 9402 3080 2939 9403 3078 2936 9404 3081 2940 9405 3079 2938 9406 3078 2936 9407 3077 2935 9408 3081 2940 9409 3078 2936 9410 3082 2941 9411 3083 2942 9412 3080 2939 9413 3079 2938 9414 3082 2941 9415 3080 2939 9416 3084 2943 9417 3085 2944 9418 3083 2942 9419 3082 2941 9420 3084 2943 9421 3083 2942 9422 3086 2945 9423 3087 2946 9424 3085 2944 9425 3084 2943 9426 3086 2945 9427 3085 2944 9428 3088 2947 9429 3089 2948 9430 3087 2946 9431 3086 2945 9432 3088 2947 9433 3087 2946 9434 3090 2949 9435 3091 2950 9436 3089 2948 9437 3088 2947 9438 3090 2949 9439 3089 2948 9440 3092 2951 9441 3093 2952 9442 3091 2950 9443 3090 2949 9444 3092 2951 9445 3091 2950 9446 3094 2953 9447 3095 2954 9448 3093 2952 9449 3092 2951 9450 3094 2953 9451 3093 2952 9452 3096 2955 9453 3097 2956 9454 3095 2954 9455 3094 2953 9456 3096 2955 9457 3095 2954 9458 3098 2957 9459 3099 2958 9460 3097 2956 9461 3096 2955 9462 3098 2957 9463 3097 2956 9464 3100 2959 9465 3101 2960 9466 3099 2958 9467 3098 2957 9468 3100 2959 9469 3099 2958 9470 3102 2961 9471 3103 2962 9472 3101 2960 9473 3100 2959 9474 3102 2961 9475 3101 2960 9476 3104 2963 9477 3105 2964 9478 3103 2962 9479 3102 2961 9480 3104 2963 9481 3103 2962 9482 3106 2965 9483 3107 2966 9484 3105 2964 9485 3104 2963 9486 3106 2965 9487 3105 2964 9488 3108 2967 9489 3109 2968 9490 3107 2966 9491 3106 2965 9492 3108 2967 9493 3107 2966 9494 3110 2969 9495 3111 2970 9496 3109 2968 9497 3108 2967 9498 3110 2969 9499 3109 2968 9500 3112 2971 9501 3113 2972 9502 3111 2970 9503 3110 2969 9504 3112 2971 9505 3111 2970 9506 3114 2973 9507 3115 2974 9508 3113 2972 9509 3116 2975 9510 3114 2973 9511 3113 2972 9512 3112 2971 9513 3116 2975 9514 3113 2972 9515 3117 2976 9516 2972 2833 9517 3115 2974 9518 3118 2977 9519 3117 2976 9520 3115 2974 9521 3114 2973 9522 3118 2977 9523 3115 2974 9524 3117 2976 9525 2975 2836 9526 2972 2833 9527 3119 2978 9528 3120 2979 9529 3121 2980 9530 3122 2981 9531 3121 2980 9532 3123 2982 9533 3122 2981 9534 3119 2978 9535 3121 2980 9536 3122 2981 9537 3123 2982 9538 3124 2983 9539 3125 2984 9540 3124 2983 9541 3126 2985 9542 3125 2984 9543 3122 2981 9544 3124 2983 9545 3125 2984 9546 3126 2985 9547 3127 2986 9548 3128 2987 9549 3127 2986 9550 3129 2988 9551 3128 2987 9552 3125 2984 9553 3127 2986 9554 3130 2989 9555 3129 2988 9556 3131 2990 9557 3132 2991 9558 3128 2987 9559 3129 2988 9560 3133 2992 9561 3132 2991 9562 3129 2988 9563 3130 2989 9564 3133 2992 9565 3129 2988 9566 3134 2993 9567 3131 2990 9568 3135 2994 9569 3134 2993 9570 3130 2989 9571 3131 2990 9572 3136 2995 9573 3135 2994 9574 3137 2996 9575 3138 2997 9576 3134 2993 9577 3135 2994 9578 3139 2998 9579 3138 2997 9580 3135 2994 9581 3136 2995 9582 3139 2998 9583 3135 2994 9584 3140 2999 9585 3137 2996 9586 3141 3000 9587 3140 2999 9588 3136 2995 9589 3137 2996 9590 3142 3001 9591 3141 3000 9592 3143 3002 9593 3144 3003 9594 3140 2999 9595 3141 3000 9596 3142 3001 9597 3144 3003 9598 3141 3000 9599 3145 3004 9600 3143 3002 9601 3146 3005 9602 3145 3004 9603 3142 3001 9604 3143 3002 9605 3145 3004 9606 3146 3005 9607 3147 3006 9608 3148 3007 9609 3147 3006 9610 3149 3008 9611 3148 3007 9612 3145 3004 9613 3147 3006 9614 3150 3009 9615 3149 3008 9616 3151 3010 9617 3150 3009 9618 3148 3007 9619 3149 3008 9620 3150 3009 9621 3151 3010 9622 3152 3011 9623 3153 3012 9624 3152 3011 9625 3154 3013 9626 3153 3012 9627 3150 3009 9628 3152 3011 9629 3153 3012 9630 3154 3013 9631 3155 3014 9632 3156 3015 9633 3155 3014 9634 3157 3016 9635 3156 3015 9636 3153 3012 9637 3155 3014 9638 3158 3017 9639 3157 3016 9640 3159 3018 9641 3158 3017 9642 3156 3015 9643 3157 3016 9644 3158 3017 9645 3159 3018 9646 3160 3019 9647 3161 3020 9648 3160 3019 9649 3162 3021 9650 3161 3020 9651 3158 3017 9652 3160 3019 9653 3163 3022 9654 3162 3021 9655 3164 3023 9656 3163 3022 9657 3161 3020 9658 3162 3021 9659 3165 3024 9660 3164 3023 9661 3166 3025 9662 3165 3024 9663 3163 3022 9664 3164 3023 9665 3165 3024 9666 3166 3025 9667 3167 3026 9668 3168 3027 9669 3167 3026 9670 3169 3028 9671 3168 3027 9672 3165 3024 9673 3167 3026 9674 3170 3029 9675 3169 3028 9676 3171 3030 9677 3170 3029 9678 3168 3027 9679 3169 3028 9680 3172 3031 9681 3171 3030 9682 3173 3032 9683 3172 3031 9684 3170 3029 9685 3171 3030 9686 3174 3033 9687 3173 3032 9688 3175 3034 9689 3176 3035 9690 3172 3031 9691 3173 3032 9692 3177 3036 9693 3176 3035 9694 3173 3032 9695 3174 3033 9696 3177 3036 9697 3173 3032 9698 3178 3037 9699 3175 3034 9700 3179 3038 9701 3178 3037 9702 3174 3033 9703 3175 3034 9704 3180 3039 9705 3179 3038 9706 3181 3040 9707 3180 3039 9708 3178 3037 9709 3179 3038 9710 3182 3041 9711 3181 3040 9712 3183 3042 9713 3182 3041 9714 3180 3039 9715 3181 3040 9716 3184 3043 9717 3183 3042 9718 3185 3044 9719 3184 3043 9720 3182 3041 9721 3183 3042 9722 3186 3045 9723 3185 3044 9724 3187 3046 9725 3186 3045 9726 3184 3043 9727 3185 3044 9728 3188 3047 9729 3187 3046 9730 3189 3048 9731 3188 3047 9732 3186 3045 9733 3187 3046 9734 3190 3049 9735 3189 3048 9736 3191 3050 9737 3190 3049 9738 3188 3047 9739 3189 3048 9740 3192 3051 9741 3191 3050 9742 3193 3052 9743 3192 3051 9744 3190 3049 9745 3191 3050 9746 3194 3053 9747 3193 3052 9748 3195 3054 9749 3194 3053 9750 3192 3051 9751 3193 3052 9752 3196 3055 9753 3195 3054 9754 3197 3056 9755 3196 3055 9756 3194 3053 9757 3195 3054 9758 3196 3055 9759 3197 3056 9760 3198 3057 9761 3196 3055 9762 3198 3057 9763 3199 3058 9764 3196 3055 9765 3199 3058 9766 3200 3059 9767 2784 2647 9768 3201 3060 9769 2781 2644 9770 3196 3055 9771 3200 3059 9772 3202 3061 9773 2785 2648 9774 3203 3062 9775 2786 2649 9776 3204 3063 9777 3205 3064 9778 3206 3065 9779 3207 3066 9780 3204 3063 9781 3206 3065 9782 2785 2648 9783 3208 3067 9784 3203 3062 9785 3209 3068 9786 3210 3069 9787 3211 3070 9788 2631 2500 9789 2643 2512 9790 3212 3071 9791 3213 3072 9792 3211 3070 9793 3214 3073 9794 3213 3072 9795 3209 3068 9796 3211 3070 9797 3215 3074 9798 3214 3073 9799 3216 3075 9800 3215 3074 9801 3213 3072 9802 3214 3073 9803 3215 3074 9804 3216 3075 9805 3217 3076 9806 3215 3074 9807 3217 3076 9808 3218 3077 9809 3219 3078 9810 3218 3077 9811 3220 3079 9812 3219 3078 9813 3215 3074 9814 3218 3077 9815 3219 3078 9816 3220 3079 9817 3221 3080 9818 3219 3078 9819 3221 3080 9820 3222 3081 9821 3219 3078 9822 3222 3081 9823 3223 3082 9824 3224 3083 9825 3223 3082 9826 3225 3084 9827 3224 3083 9828 3219 3078 9829 3223 3082 9830 3224 3083 9831 3225 3084 9832 3226 3085 9833 3224 3083 9834 3226 3085 9835 3227 3086 9836 3228 3087 9837 3227 3086 9838 3229 3088 9839 3228 3087 9840 3224 3083 9841 3227 3086 9842 3230 3089 9843 3229 3088 9844 3231 3090 9845 3230 3089 9846 3228 3087 9847 3229 3088 9848 3232 3091 9849 3231 3090 9850 3233 3092 9851 3232 3091 9852 3230 3089 9853 3231 3090 9854 3234 3093 9855 3233 3092 9856 3235 3094 9857 3234 3093 9858 3232 3091 9859 3233 3092 9860 3236 3095 9861 3235 3094 9862 3237 3096 9863 3236 3095 9864 3234 3093 9865 3235 3094 9866 3238 3097 9867 3237 3096 9868 3239 3098 9869 3238 3097 9870 3236 3095 9871 3237 3096 9872 3240 3099 9873 3239 3098 9874 3241 3100 9875 3240 3099 9876 3238 3097 9877 3239 3098 9878 3240 3099 9879 3241 3100 9880 3242 3101 9881 3243 3102 9882 3242 3101 9883 3244 3103 9884 3243 3102 9885 3240 3099 9886 3242 3101 9887 3245 3104 9888 3244 3103 9889 3246 3105 9890 3245 3104 9891 3243 3102 9892 3244 3103 9893 3247 3106 9894 3246 3105 9895 3248 3107 9896 3247 3106 9897 3245 3104 9898 3246 3105 9899 3247 3106 9900 3248 3107 9901 3249 3108 9902 3247 3106 9903 3249 3108 9904 3250 3109 9905 3251 3110 9906 3250 3109 9907 3252 3111 9908 3251 3110 9909 3247 3106 9910 3250 3109 9911 3251 3110 9912 3252 3111 9913 3253 3112 9914 3254 3113 9915 3253 3112 9916 3255 3114 9917 3254 3113 9918 3251 3110 9919 3253 3112 9920 3254 3113 9921 3255 3114 9922 3256 3115 9923 3257 3116 9924 3256 3115 9925 3258 3117 9926 3257 3116 9927 3254 3113 9928 3256 3115 9929 3257 3116 9930 3258 3117 9931 3259 3118 9932 3260 3119 9933 3259 3118 9934 3261 3120 9935 3260 3119 9936 3257 3116 9937 3259 3118 9938 3260 3119 9939 3261 3120 9940 3262 3121 9941 3263 3122 9942 3262 3121 9943 3264 3123 9944 3263 3122 9945 3260 3119 9946 3262 3121 9947 3263 3122 9948 3264 3123 9949 3265 3124 9950 3266 3125 9951 3265 3124 9952 3267 3126 9953 3266 3125 9954 3263 3122 9955 3265 3124 9956 3266 3125 9957 3267 3126 9958 3205 3064 9959 3204 3063 9960 3266 3125 9961 3205 3064 9962 3268 3127 9963 929 843 9964 3269 3128 9965 923 837 9966 929 843 9967 3268 3127 9968 3213 3072 9969 3269 3128 9970 3209 3068 9971 3268 3127 9972 3269 3128 9973 3213 3072 9974 3268 3127 9975 3213 3072 9976 3215 3074 9977 3270 3129 9978 3215 3074 9979 3219 3078 9980 3270 3129 9981 3268 3127 9982 3215 3074 9983 3271 3130 9984 3219 3078 9985 3224 3083 9986 3271 3130 9987 3270 3129 9988 3219 3078 9989 3272 3131 9990 3224 3083 9991 3228 3087 9992 3272 3131 9993 3271 3130 9994 3224 3083 9995 3273 3132 9996 3228 3087 9997 3230 3089 9998 3273 3132 9999 3272 3131 10000 3228 3087 10001 3274 3133 10002 3230 3089 10003 3232 3091 10004 3274 3133 10005 3273 3132 10006 3230 3089 10007 3275 3134 10008 3232 3091 10009 3234 3093 10010 3275 3134 10011 3274 3133 10012 3232 3091 10013 3276 3135 10014 3234 3093 10015 3236 3095 10016 3276 3135 10017 3275 3134 10018 3234 3093 10019 3277 3136 10020 3236 3095 10021 3238 3097 10022 3277 3136 10023 3276 3135 10024 3236 3095 10025 3278 3137 10026 3238 3097 10027 3240 3099 10028 3278 3137 10029 3277 3136 10030 3238 3097 10031 3279 3138 10032 3240 3099 10033 3243 3102 10034 3279 3138 10035 3278 3137 10036 3240 3099 10037 3280 3139 10038 3243 3102 10039 3245 3104 10040 3280 3139 10041 3279 3138 10042 3243 3102 10043 3281 3140 10044 3245 3104 10045 3247 3106 10046 3281 3140 10047 3280 3139 10048 3245 3104 10049 3282 3141 10050 3247 3106 10051 3251 3110 10052 3282 3141 10053 3281 3140 10054 3247 3106 10055 3283 3142 10056 3251 3110 10057 3254 3113 10058 3283 3142 10059 3282 3141 10060 3251 3110 10061 3284 3143 10062 3254 3113 10063 3257 3116 10064 3284 3143 10065 3283 3142 10066 3254 3113 10067 3285 3144 10068 3257 3116 10069 3260 3119 10070 3285 3144 10071 3284 3143 10072 3257 3116 10073 3286 3145 10074 3260 3119 10075 3263 3122 10076 3286 3145 10077 3285 3144 10078 3260 3119 10079 3287 3146 10080 3263 3122 10081 3266 3125 10082 3287 3146 10083 3286 3145 10084 3263 3122 10085 3288 3147 10086 3266 3125 10087 3204 3063 10088 3288 3147 10089 3287 3146 10090 3266 3125 10091 3289 3148 10092 3204 3063 10093 3207 3066 10094 3289 3148 10095 3288 3147 10096 3204 3063 10097 3290 3149 10098 3289 3148 10099 3207 3066 10100 3291 3150 10101 3292 3151 10102 3208 3067 10103 2785 2648 10104 3291 3150 10105 3208 3067 10106 923 837 10107 3268 3127 10108 3270 3129 10109 921 835 10110 3270 3129 10111 3271 3130 10112 921 835 10113 923 837 10114 3270 3129 10115 919 833 10116 3271 3130 10117 3272 3131 10118 919 833 10119 921 835 10120 3271 3130 10121 916 830 10122 3272 3131 10123 3273 3132 10124 916 830 10125 919 833 10126 3272 3131 10127 913 827 10128 3273 3132 10129 3274 3133 10130 913 827 10131 916 830 10132 3273 3132 10133 910 824 10134 3274 3133 10135 3275 3134 10136 910 824 10137 913 827 10138 3274 3133 10139 907 821 10140 3275 3134 10141 3276 3135 10142 907 821 10143 910 824 10144 3275 3134 10145 904 818 10146 3276 3135 10147 3277 3136 10148 904 818 10149 907 821 10150 3276 3135 10151 901 815 10152 3277 3136 10153 3278 3137 10154 901 815 10155 904 818 10156 3277 3136 10157 899 813 10158 3278 3137 10159 3279 3138 10160 899 813 10161 901 815 10162 3278 3137 10163 896 810 10164 3279 3138 10165 3280 3139 10166 896 810 10167 899 813 10168 3279 3138 10169 893 807 10170 3280 3139 10171 3281 3140 10172 893 807 10173 896 810 10174 3280 3139 10175 891 805 10176 3281 3140 10177 3282 3141 10178 891 805 10179 893 807 10180 3281 3140 10181 889 803 10182 3282 3141 10183 3283 3142 10184 889 803 10185 891 805 10186 3282 3141 10187 887 801 10188 3283 3142 10189 3284 3143 10190 887 801 10191 889 803 10192 3283 3142 10193 885 799 10194 3284 3143 10195 3285 3144 10196 885 799 10197 887 801 10198 3284 3143 10199 883 797 10200 3285 3144 10201 3286 3145 10202 883 797 10203 885 799 10204 3285 3144 10205 881 795 10206 3286 3145 10207 3287 3146 10208 881 795 10209 883 797 10210 3286 3145 10211 879 793 10212 3287 3146 10213 3288 3147 10214 879 793 10215 881 795 10216 3287 3146 10217 876 790 10218 3288 3147 10219 3289 3148 10220 876 790 10221 879 793 10222 3288 3147 10223 878 792 10224 3289 3148 10225 3290 3149 10226 878 792 10227 876 790 10228 3289 3148 10229 870 784 10230 878 792 10231 3290 3149 10232 3293 3152 10233 875 789 10234 3292 3151 10235 3291 3150 10236 3293 3152 10237 3292 3151 10238 3294 3153 10239 873 787 10240 875 789 10241 3293 3152 10242 3294 3153 10243 875 789 10244 3295 3154 10245 859 3154 10246 3296 3154 10247 3295 3155 10248 862 3155 10249 859 3155 10250 3297 3156 10251 3298 3157 10252 3299 3158 10253 3300 3159 10254 3296 3159 10255 1356 3159 10256 3297 3156 10257 3301 3160 10258 3298 3157 10259 3302 3161 10260 3295 3161 10261 3296 3161 10262 3303 3162 10263 3302 3162 10264 3296 3162 10265 3304 3163 10266 3303 3163 10267 3296 3163 10268 3305 3164 10269 3304 3164 10270 3296 3164 10271 3306 3165 10272 3305 3165 10273 3296 3165 10274 3307 3166 10275 3306 3166 10276 3296 3166 10277 3308 3167 10278 3307 3167 10279 3296 3167 10280 3309 3168 10281 3308 3168 10282 3296 3168 10283 3310 3169 10284 3309 3169 10285 3296 3169 10286 3311 3170 10287 3310 3170 10288 3296 3170 10289 3312 3171 10290 3311 3171 10291 3296 3171 10292 3313 3172 10293 3312 3172 10294 3296 3172 10295 3314 3173 10296 3313 3173 10297 3296 3173 10298 3315 3174 10299 3314 3174 10300 3296 3174 10301 3316 3175 10302 3315 3175 10303 3296 3175 10304 3317 3176 10305 3316 3176 10306 3296 3176 10307 3318 3177 10308 3317 3177 10309 3296 3177 10310 3319 3178 10311 3318 3178 10312 3296 3178 10313 3320 3179 10314 3319 3179 10315 3296 3179 10316 3321 3180 10317 3320 3180 10318 3296 3180 10319 3300 3181 10320 3321 3181 10321 3296 3181 10322 3322 3182 10323 3299 3158 10324 3323 3183 10325 3297 3156 10326 3299 3158 10327 3322 3182 10328 2691 2558 10329 3323 3183 10330 2700 2567 10331 3322 3182 10332 3323 3183 10333 2691 2558 10334 3324 3184 10335 1887 1769 10336 3325 3185 10337 3324 3184 10338 1885 1767 10339 1887 1769 10340 3324 3184 10341 3325 3185 10342 3326 3186 10343 3327 3187 10344 3326 3186 10345 3328 3188 10346 3324 3184 10347 3326 3186 10348 3327 3187 10349 3329 3189 10350 3330 3190 10351 3331 3191 10352 3332 3192 10353 3331 3191 10354 3333 3193 10355 3332 3192 10356 3329 3189 10357 3331 3191 10358 3332 3192 10359 3333 3193 10360 3334 3194 10361 3335 3195 10362 3334 3194 10363 3336 3196 10364 3335 3195 10365 3332 3192 10366 3334 3194 10367 3335 3195 10368 3336 3196 10369 3337 3197 10370 3338 3198 10371 3337 3197 10372 3339 3199 10373 3338 3198 10374 3335 3195 10375 3337 3197 10376 3340 3200 10377 3339 3199 10378 3341 3201 10379 3340 3200 10380 3338 3198 10381 3339 3199 10382 3340 3200 10383 3341 3201 10384 3342 3202 10385 3343 3203 10386 3342 3202 10387 3344 3204 10388 3343 3203 10389 3340 3200 10390 3342 3202 10391 3343 3203 10392 3344 3204 10393 3345 3205 10394 3346 3206 10395 3347 3207 10396 3348 3208 10397 3349 3209 10398 3343 3203 10399 3345 3205 10400 3350 3210 10401 3348 3208 10402 3351 3211 10403 3350 3210 10404 3346 3206 10405 3348 3208 10406 3352 3212 10407 3351 3211 10408 3353 3213 10409 3350 3210 10410 3351 3211 10411 3352 3212 10412 3354 3214 10413 3353 3213 10414 3355 3215 10415 3352 3212 10416 3353 3213 10417 3354 3214 10418 3297 3156 10419 3355 3215 10420 3301 3160 10421 3354 3214 10422 3355 3215 10423 3297 3156 10424 3356 3216 10425 3300 3216 10426 1356 3216 10427 3357 3217 10428 3356 3217 10429 1356 3217 10430 3358 3218 10431 3357 3218 10432 1356 3218 10433 3359 3219 10434 3358 3219 10435 1356 3219 10436 3360 3220 10437 3359 3220 10438 1356 3220 10439 3361 3221 10440 3360 3221 10441 1356 3221 10442 3362 3222 10443 3361 3222 10444 1356 3222 10445 3363 3223 10446 3362 3223 10447 1356 3223 10448 3364 3224 10449 3363 3224 10450 1356 3224 10451 3365 3225 10452 3364 3225 10453 1356 3225 10454 3366 3226 10455 3365 3226 10456 1356 3226 10457 3367 3227 10458 3366 3227 10459 1356 3227 10460 3368 3228 10461 3367 3228 10462 1356 3228 10463 3369 3229 10464 3368 3229 10465 1356 3229 10466 1369 3230 10467 3369 3230 10468 1356 3230 10469 3370 3231 10470 867 781 10471 3371 3232 10472 808 3233 10473 848 3233 10474 809 3233 10475 3372 3234 10476 3371 3232 10477 3373 3235 10478 3372 3234 10479 3370 3231 10480 3371 3232 10481 3374 3236 10482 3373 3235 10483 3375 3237 10484 3374 3236 10485 3372 3234 10486 3373 3235 10487 3376 3238 10488 3375 3237 10489 3377 3239 10490 3376 3238 10491 3374 3236 10492 3375 3237 10493 3378 3240 10494 3377 3239 10495 3379 3241 10496 3378 3240 10497 3376 3238 10498 3377 3239 10499 3380 3242 10500 3379 3241 10501 3381 3243 10502 3380 3242 10503 3378 3240 10504 3379 3241 10505 3382 3244 10506 3381 3243 10507 3383 3245 10508 3382 3244 10509 3380 3242 10510 3381 3243 10511 3382 3244 10512 3383 3245 10513 3384 3246 10514 3385 3247 10515 3384 3246 10516 3386 3248 10517 3385 3247 10518 3382 3244 10519 3384 3246 10520 3387 3249 10521 3386 3248 10522 3388 3250 10523 3387 3249 10524 3385 3247 10525 3386 3248 10526 3389 3251 10527 3388 3250 10528 3390 3252 10529 3389 3251 10530 3387 3249 10531 3388 3250 10532 3391 3253 10533 3390 3252 10534 3392 3254 10535 3391 3253 10536 3389 3251 10537 3390 3252 10538 3393 3255 10539 3392 3254 10540 3394 3256 10541 3393 3255 10542 3391 3253 10543 3392 3254 10544 3395 3257 10545 3394 3256 10546 3396 3258 10547 3395 3257 10548 3393 3255 10549 3394 3256 10550 3397 3259 10551 3396 3258 10552 3398 3260 10553 3397 3259 10554 3395 3257 10555 3396 3258 10556 3399 3261 10557 3398 3260 10558 3400 3262 10559 3399 3261 10560 3397 3259 10561 3398 3260 10562 3401 3263 10563 3400 3262 10564 3402 3264 10565 3401 3263 10566 3399 3261 10567 3400 3262 10568 3403 3265 10569 3402 3264 10570 3404 3266 10571 3403 3265 10572 3401 3263 10573 3402 3264 10574 3405 3267 10575 3404 3266 10576 3406 3268 10577 3405 3267 10578 3403 3265 10579 3404 3266 10580 3407 3269 10581 3406 3268 10582 3408 3270 10583 3407 3269 10584 3405 3267 10585 3406 3268 10586 3409 3271 10587 3408 3270 10588 3410 3272 10589 3409 3271 10590 3407 3269 10591 3408 3270 10592 3411 3273 10593 3410 3272 10594 3412 3274 10595 3411 3273 10596 3409 3271 10597 3410 3272 10598 3413 3275 10599 3412 3274 10600 3414 3276 10601 3413 3275 10602 3411 3273 10603 3412 3274 10604 3415 3277 10605 3414 3276 10606 3416 3278 10607 3415 3277 10608 3413 3275 10609 3414 3276 10610 3417 3279 10611 3416 3278 10612 3418 3280 10613 3417 3279 10614 3415 3277 10615 3416 3278 10616 3419 3281 10617 3418 3280 10618 3420 3282 10619 3419 3281 10620 3417 3279 10621 3418 3280 10622 3421 3283 10623 3420 3282 10624 3422 3284 10625 3421 3283 10626 3419 3281 10627 3420 3282 10628 3423 3285 10629 3422 3284 10630 3424 3286 10631 3423 3285 10632 3421 3283 10633 3422 3284 10634 3425 3287 10635 3424 3286 10636 3426 3288 10637 3425 3287 10638 3423 3285 10639 3424 3286 10640 3427 3289 10641 3426 3288 10642 3428 3290 10643 3427 3289 10644 3425 3287 10645 3426 3288 10646 3429 3291 10647 3428 3290 10648 3430 3292 10649 3429 3291 10650 3427 3289 10651 3428 3290 10652 3431 3293 10653 3430 3292 10654 3432 3294 10655 3431 3293 10656 3429 3291 10657 3430 3292 10658 3433 3295 10659 3432 3294 10660 3434 3296 10661 3433 3295 10662 3431 3293 10663 3432 3294 10664 3435 3297 10665 3434 3296 10666 3436 3298 10667 3435 3297 10668 3433 3295 10669 3434 3296 10670 3437 3299 10671 3436 3298 10672 3438 3300 10673 3437 3299 10674 3435 3297 10675 3436 3298 10676 3437 3299 10677 3438 3300 10678 3439 3301 10679 3440 3302 10680 3437 3299 10681 3439 3301 10682 3441 3303 10683 3442 3304 10684 3443 3305 10685 3444 3306 10686 3445 3307 10687 3446 3308 10688 3447 3309 10689 3448 3310 10690 3449 3311 10691 3444 3306 10692 3450 3312 10693 3445 3307 10694 3441 3303 10695 3451 3313 10696 3442 3304 10697 3452 3314 10698 3446 3308 10699 3453 3315 10700 3452 3314 10701 3454 3316 10702 3446 3308 10703 3455 3317 10704 3446 3308 10705 3454 3316 10706 3455 3317 10707 3444 3306 10708 3446 3308 10709 3441 3303 10710 3456 3318 10711 3451 3313 10712 3457 3319 10713 3451 3313 10714 3456 3318 10715 3458 3320 10716 3453 3315 10717 3459 3321 10718 3458 3320 10719 3452 3314 10720 3453 3315 10721 3441 3303 10722 3460 3322 10723 3456 3318 10724 3461 3323 10725 3456 3318 10726 3460 3322 10727 3462 3324 10728 3456 3318 10729 3461 3323 10730 3463 3325 10731 3456 3318 10732 3462 3324 10733 3457 3319 10734 3456 3318 10735 3463 3325 10736 3464 3326 10737 3465 3327 10738 3460 3322 10739 3466 3328 10740 3460 3322 10741 3465 3327 10742 3441 3303 10743 3464 3326 10744 3460 3322 10745 3461 3323 10746 3460 3322 10747 3466 3328 10748 1888 1770 10749 1885 1767 10750 3465 3327 10751 3467 3329 10752 3465 3327 10753 1885 1767 10754 3464 3326 10755 1888 1770 10756 3465 3327 10757 3466 3328 10758 3465 3327 10759 3467 3329 10760 3467 3329 10761 1885 1767 10762 3324 3184 10763 3468 3330 10764 1889 1771 10765 3469 3331 10766 1882 1764 10767 1889 1771 10768 3468 3330 10769 3470 3332 10770 3469 3331 10771 3448 3310 10772 3468 3330 10773 3469 3331 10774 3470 3332 10775 3470 3332 10776 3448 3310 10777 3447 3309 10778 3461 3323 10779 3471 3333 10780 3472 3334 10781 3473 3335 10782 3474 3336 10783 3475 3337 10784 3462 3324 10785 3461 3323 10786 3472 3334 10787 3476 3338 10788 3477 3339 10789 3478 3340 10790 3479 3341 10791 3480 3342 10792 3481 3343 10793 3482 3344 10794 3479 3341 10795 3481 3343 10796 3473 3335 10797 3483 3345 10798 3474 3336 10799 3466 3328 10800 3484 3346 10801 3471 3333 10802 3485 3347 10803 3475 3337 10804 3486 3348 10805 3461 3323 10806 3466 3328 10807 3471 3333 10808 3473 3335 10809 3475 3337 10810 3485 3347 10811 3467 3329 10812 3327 3187 10813 3484 3346 10814 3332 3192 10815 3486 3348 10816 3329 3189 10817 3466 3328 10818 3467 3329 10819 3484 3346 10820 3485 3347 10821 3486 3348 10822 3332 3192 10823 3467 3329 10824 3324 3184 10825 3327 3187 10826 3476 3338 10827 3487 3349 10828 3477 3339 10829 3458 3320 10830 3459 3321 10831 3487 3349 10832 3476 3338 10833 3458 3320 10834 3487 3349 10835 2550 2419 10836 3488 3350 10837 2557 2426 10838 3489 3351 10839 3490 3352 10840 3488 3350 10841 2550 2419 10842 3489 3351 10843 3488 3350 10844 3489 3351 10845 3491 3353 10846 3490 3352 10847 3492 3354 10848 3493 3355 10849 3491 3353 10850 3489 3351 10851 3492 3354 10852 3491 3353 10853 3494 3356 10854 2567 2436 10855 3495 3357 10856 3492 3354 10857 3496 3358 10858 3493 3355 10859 3497 3359 10860 2567 2436 10861 3494 3356 10862 3498 3360 10863 2567 2436 10864 3497 3359 10865 3499 3361 10866 2568 2437 10867 2567 2436 10868 3500 3362 10869 3499 3361 10870 2567 2436 10871 3498 3360 10872 3500 3362 10873 2567 2436 10874 3492 3354 10875 3501 3363 10876 3496 3358 10877 3502 3364 10878 3503 3365 10879 3501 3363 10880 3497 3359 10881 3494 3356 10882 3504 3366 10883 3492 3354 10884 3502 3364 10885 3501 3363 10886 3502 3364 10887 3505 3367 10888 3503 3365 10889 3506 3368 10890 3504 3366 10891 3507 3369 10892 3506 3368 10893 3497 3359 10894 3504 3366 10895 3508 3370 10896 3509 3371 10897 3505 3367 10898 3506 3368 10899 3507 3369 10900 3510 3372 10901 3502 3364 10902 3508 3370 10903 3505 3367 10904 3508 3370 10905 3511 3373 10906 3509 3371 10907 3512 3374 10908 3510 3372 10909 3513 3375 10910 3512 3374 10911 3506 3368 10912 3510 3372 10913 3514 3376 10914 3515 3377 10915 3511 3373 10916 3516 3378 10917 3513 3375 10918 3517 3379 10919 3508 3370 10920 3514 3376 10921 3511 3373 10922 3516 3378 10923 3512 3374 10924 3513 3375 10925 3514 3376 10926 3518 3380 10927 3515 3377 10928 3516 3378 10929 3517 3379 10930 3519 3381 10931 3520 3382 10932 3521 3383 10933 3518 3380 10934 3522 3384 10935 3519 3381 10936 3523 3385 10937 3514 3376 10938 3520 3382 10939 3518 3380 10940 3522 3384 10941 3516 3378 10942 3519 3381 10943 3520 3382 10944 3524 3386 10945 3521 3383 10946 3522 3384 10947 3523 3385 10948 3525 3387 10949 3526 3388 10950 3527 3389 10951 3524 3386 10952 3528 3390 10953 3525 3387 10954 3529 3391 10955 3520 3382 10956 3526 3388 10957 3524 3386 10958 3528 3390 10959 3522 3384 10960 3525 3387 10961 3526 3388 10962 3530 3392 10963 3527 3389 10964 3528 3390 10965 3529 3391 10966 3531 3393 10967 3532 3394 10968 3533 3395 10969 3530 3392 10970 3534 3396 10971 3531 3393 10972 3535 3397 10973 3526 3388 10974 3532 3394 10975 3530 3392 10976 3534 3396 10977 3528 3390 10978 3531 3393 10979 3532 3394 10980 3536 3398 10981 3533 3395 10982 3534 3396 10983 3535 3397 10984 3537 3399 10985 3538 3400 10986 3539 3401 10987 3536 3398 10988 3540 3402 10989 3537 3399 10990 3541 3403 10991 3532 3394 10992 3538 3400 10993 3536 3398 10994 3540 3402 10995 3534 3396 10996 3537 3399 10997 3542 3404 10998 3543 3405 10999 3539 3401 11000 3544 3406 11001 3541 3403 11002 3545 3407 11003 3538 3400 11004 3542 3404 11005 3539 3401 11006 3544 3406 11007 3540 3402 11008 3541 3403 11009 3542 3404 11010 3546 3408 11011 3543 3405 11012 3544 3406 11013 3545 3407 11014 3547 3409 11015 3548 3410 11016 3549 3411 11017 3546 3408 11018 3550 3412 11019 3547 3409 11020 3551 3413 11021 3542 3404 11022 3548 3410 11023 3546 3408 11024 3550 3412 11025 3544 3406 11026 3547 3409 11027 3548 3410 11028 3552 3414 11029 3549 3411 11030 3550 3412 11031 3551 3413 11032 3553 3415 11033 3554 3416 11034 3555 3417 11035 3552 3414 11036 3556 3418 11037 3553 3415 11038 3557 3419 11039 3548 3410 11040 3554 3416 11041 3552 3414 11042 3556 3418 11043 3550 3412 11044 3553 3415 11045 3554 3416 11046 3558 3420 11047 3555 3417 11048 3556 3418 11049 3557 3419 11050 3559 3421 11051 3560 3422 11052 3561 3423 11053 3558 3420 11054 3562 3424 11055 3559 3421 11056 3563 3425 11057 3554 3416 11058 3560 3422 11059 3558 3420 11060 3562 3424 11061 3556 3418 11062 3559 3421 11063 3560 3422 11064 3564 3426 11065 3561 3423 11066 3565 3427 11067 3563 3425 11068 3566 3428 11069 3565 3427 11070 3562 3424 11071 3563 3425 11072 3567 3429 11073 3568 3430 11074 3564 3426 11075 3565 3427 11076 3566 3428 11077 3569 3431 11078 3560 3422 11079 3567 3429 11080 3564 3426 11081 3567 3429 11082 3570 3432 11083 3568 3430 11084 3571 3433 11085 3569 3431 11086 3572 3434 11087 3571 3433 11088 3565 3427 11089 3569 3431 11090 3573 3435 11091 3574 3436 11092 3570 3432 11093 3575 3437 11094 3572 3434 11095 3576 3438 11096 3567 3429 11097 3573 3435 11098 3570 3432 11099 3571 3433 11100 3572 3434 11101 3575 3437 11102 3573 3435 11103 3577 3439 11104 3574 3436 11105 3575 3437 11106 3576 3438 11107 3578 3440 11108 3579 3441 11109 3580 3442 11110 3577 3439 11111 3575 3437 11112 3578 3440 11113 3581 3443 11114 3573 3435 11115 3579 3441 11116 3577 3439 11117 3579 3441 11118 3582 3444 11119 3580 3442 11120 3444 3306 11121 3581 3443 11122 3583 3445 11123 3584 3446 11124 3581 3443 11125 3444 3306 11126 3585 3447 11127 3575 3437 11128 3581 3443 11129 3586 3448 11130 3585 3447 11131 3581 3443 11132 3584 3446 11133 3586 3448 11134 3581 3443 11135 3579 3441 11136 3587 3449 11137 3582 3444 11138 3444 3306 11139 3583 3445 11140 3588 3450 11141 3470 3332 11142 3589 3451 11143 3587 3449 11144 3444 3306 11145 3588 3450 11146 3590 3452 11147 3579 3441 11148 3470 3332 11149 3587 3449 11150 3470 3332 11151 3447 3309 11152 3589 3451 11153 3444 3306 11154 3590 3452 11155 3450 3312 11156 3468 3330 11157 3470 3332 11158 3579 3441 11159 3591 3453 11160 3579 3441 11161 3573 3435 11162 3591 3453 11163 3468 3330 11164 3579 3441 11165 3592 3454 11166 3573 3435 11167 3567 3429 11168 3592 3454 11169 3591 3453 11170 3573 3435 11171 3593 3455 11172 3567 3429 11173 3560 3422 11174 3593 3455 11175 3592 3454 11176 3567 3429 11177 3594 3456 11178 3560 3422 11179 3554 3416 11180 3594 3456 11181 3593 3455 11182 3560 3422 11183 3595 3457 11184 3554 3416 11185 3548 3410 11186 3595 3457 11187 3594 3456 11188 3554 3416 11189 3596 3458 11190 3548 3410 11191 3542 3404 11192 3596 3458 11193 3595 3457 11194 3548 3410 11195 3597 3459 11196 3542 3404 11197 3538 3400 11198 3597 3459 11199 3596 3458 11200 3542 3404 11201 3598 3460 11202 3538 3400 11203 3532 3394 11204 3598 3460 11205 3597 3459 11206 3538 3400 11207 3599 3461 11208 3532 3394 11209 3526 3388 11210 3599 3461 11211 3598 3460 11212 3532 3394 11213 3600 3462 11214 3526 3388 11215 3520 3382 11216 3600 3462 11217 3599 3461 11218 3526 3388 11219 3601 3463 11220 3520 3382 11221 3514 3376 11222 3601 3463 11223 3600 3462 11224 3520 3382 11225 3602 3464 11226 3514 3376 11227 3508 3370 11228 3602 3464 11229 3601 3463 11230 3514 3376 11231 3603 3465 11232 3508 3370 11233 3502 3364 11234 3603 3465 11235 3602 3464 11236 3508 3370 11237 3604 3466 11238 3502 3364 11239 3492 3354 11240 3604 3466 11241 3603 3465 11242 3502 3364 11243 3605 3467 11244 3492 3354 11245 3489 3351 11246 3605 3467 11247 3604 3466 11248 3492 3354 11249 3606 3468 11250 3489 3351 11251 2550 2419 11252 3606 3468 11253 3605 3467 11254 3489 3351 11255 2559 2428 11256 3606 3468 11257 2550 2419 11258 1882 1764 11259 3468 3330 11260 3591 3453 11261 1880 1762 11262 3591 3453 11263 3592 3454 11264 1880 1762 11265 1882 1764 11266 3591 3453 11267 1878 1760 11268 3592 3454 11269 3593 3455 11270 1878 1760 11271 1880 1762 11272 3592 3454 11273 1875 1757 11274 3593 3455 11275 3594 3456 11276 1875 1757 11277 1878 1760 11278 3593 3455 11279 1873 1755 11280 3594 3456 11281 3595 3457 11282 1873 1755 11283 1875 1757 11284 3594 3456 11285 1871 1753 11286 3595 3457 11287 3596 3458 11288 1871 1753 11289 1873 1755 11290 3595 3457 11291 1869 1751 11292 3596 3458 11293 3597 3459 11294 1869 1751 11295 1871 1753 11296 3596 3458 11297 1867 1749 11298 3597 3459 11299 3598 3460 11300 1867 1749 11301 1869 1751 11302 3597 3459 11303 1865 1747 11304 3598 3460 11305 3599 3461 11306 1865 1747 11307 1867 1749 11308 3598 3460 11309 1863 1745 11310 3599 3461 11311 3600 3462 11312 1863 1745 11313 1865 1747 11314 3599 3461 11315 1861 1743 11316 3600 3462 11317 3601 3463 11318 1861 1743 11319 1863 1745 11320 3600 3462 11321 1859 1741 11322 3601 3463 11323 3602 3464 11324 1859 1741 11325 1861 1743 11326 3601 3463 11327 1857 1739 11328 3602 3464 11329 3603 3465 11330 1857 1739 11331 1859 1741 11332 3602 3464 11333 1855 1737 11334 3603 3465 11335 3604 3466 11336 1855 1737 11337 1857 1739 11338 3603 3465 11339 1853 1735 11340 3604 3466 11341 3605 3467 11342 1853 1735 11343 1855 1737 11344 3604 3466 11345 1850 1732 11346 3605 3467 11347 3606 3468 11348 1850 1732 11349 1853 1735 11350 3605 3467 11351 1848 1730 11352 3606 3468 11353 2559 2428 11354 1848 1730 11355 1850 1732 11356 3606 3468 11357 1846 1728 11358 1848 1730 11359 2559 2428 11360 3607 3469 11361 3608 3470 11362 3609 3471 11363 3610 3472 11364 3611 3472 11365 3612 3472 11366 3610 3473 11367 3612 3473 11368 3613 3473 11369 3614 3474 11370 3609 3471 11371 3615 3475 11372 3614 3474 11373 3607 3469 11374 3609 3471 11375 3476 3338 11376 3616 3476 11377 3458 3320 11378 3614 3474 11379 3615 3475 11380 3617 3477 11381 3610 3478 11382 3618 3478 11383 3611 3478 11384 3610 3479 11385 3619 3479 11386 3618 3479 11387 3476 3338 11388 3620 3480 11389 3616 3476 11390 3621 3481 11391 3617 3477 11392 3622 3482 11393 3621 3481 11394 3614 3474 11395 3617 3477 11396 3476 3338 11397 3623 3483 11398 3620 3480 11399 3624 3484 11400 3622 3482 11401 3625 3485 11402 3624 3484 11403 3621 3481 11404 3622 3482 11405 3476 3338 11406 3626 3486 11407 3623 3483 11408 3627 3487 11409 3625 3485 11410 3628 3488 11411 3627 3487 11412 3624 3484 11413 3625 3485 11414 3629 3489 11415 3630 3490 11416 3626 3486 11417 3627 3487 11418 3628 3488 11419 3631 3491 11420 3476 3338 11421 3629 3489 11422 3626 3486 11423 3629 3489 11424 3632 3492 11425 3630 3490 11426 3633 3493 11427 3634 3493 11428 3635 3493 11429 3636 3494 11430 3627 3487 11431 3631 3491 11432 3629 3489 11433 3637 3495 11434 3632 3492 11435 3633 3496 11436 3635 3496 11437 3638 3496 11438 3639 3497 11439 3640 3498 11440 3641 3499 11441 3642 3500 11442 3633 3500 11443 3638 3500 11444 3643 3501 11445 3644 3502 11446 3640 3498 11447 3639 3497 11448 3643 3501 11449 3640 3498 11450 3639 3497 11451 3641 3499 11452 3480 3342 11453 3479 3341 11454 3639 3497 11455 3480 3342 11456 3645 3503 11457 3646 3504 11458 3647 3505 11459 3648 3506 11460 3649 3507 11461 3646 3504 11462 3645 3503 11463 3648 3506 11464 3646 3504 11465 3650 3508 11466 3647 3505 11467 3651 3509 11468 3650 3508 11469 3645 3503 11470 3647 3505 11471 3650 3508 11472 3651 3509 11473 3652 3510 11474 3650 3508 11475 3652 3510 11476 3653 3511 11477 3654 3512 11478 3655 3513 11479 3656 3514 11480 3654 3512 11481 3657 3515 11482 3655 3513 11483 3658 3516 11484 3656 3514 11485 3659 3517 11486 3658 3516 11487 3654 3512 11488 3656 3514 11489 3660 3518 11490 3659 3517 11491 3661 3519 11492 3660 3518 11493 3658 3516 11494 3659 3517 11495 3662 3520 11496 3661 3519 11497 3663 3521 11498 3662 3520 11499 3660 3518 11500 3661 3519 11501 3664 3522 11502 3663 3521 11503 3665 3523 11504 3664 3522 11505 3662 3520 11506 3663 3521 11507 3666 3524 11508 3665 3523 11509 3667 3525 11510 3666 3524 11511 3664 3522 11512 3665 3523 11513 3668 3526 11514 3667 3525 11515 3669 3527 11516 3668 3526 11517 3666 3524 11518 3667 3525 11519 3670 3528 11520 3669 3527 11521 3671 3529 11522 3670 3528 11523 3668 3526 11524 3669 3527 11525 3672 3530 11526 3671 3529 11527 3673 3531 11528 3672 3530 11529 3670 3528 11530 3671 3529 11531 3674 3532 11532 3673 3531 11533 3675 3533 11534 3674 3532 11535 3672 3530 11536 3673 3531 11537 3676 3534 11538 3675 3533 11539 3677 3535 11540 3676 3534 11541 3674 3532 11542 3675 3533 11543 3678 3536 11544 3677 3535 11545 3679 3537 11546 3678 3536 11547 3676 3534 11548 3677 3535 11549 3648 3506 11550 3679 3537 11551 3649 3507 11552 3680 3538 11553 3678 3536 11554 3679 3537 11555 3648 3506 11556 3680 3538 11557 3679 3537 11558 3681 3539 11559 3682 3539 11560 3683 3539 11561 3681 3540 11562 3684 3540 11563 3682 3540 11564 3685 3541 11565 3686 3542 11566 3687 3543 11567 3681 3544 11568 3683 3544 11569 3688 3544 11570 3689 3545 11571 3687 3543 11572 3657 3515 11573 3689 3545 11574 3685 3541 11575 3687 3543 11576 3654 3512 11577 3689 3545 11578 3657 3515 11579 3690 3546 11580 3691 3547 11581 3692 3548 11582 3693 3549 11583 3694 3550 11584 3691 3547 11585 3690 3546 11586 3693 3549 11587 3691 3547 11588 3690 3546 11589 3692 3548 11590 3695 3551 11591 3681 3552 11592 3696 3552 11593 3684 3552 11594 3690 3546 11595 3695 3551 11596 3697 3553 11597 3698 3554 11598 3699 3555 11599 2533 2402 11600 2529 2398 11601 2534 2403 11602 3700 3556 11603 3701 3557 11604 3698 3554 11605 2533 2402 11606 2532 2401 11607 3701 3557 11608 2533 2402 11609 3702 3558 11610 3703 3559 11611 3699 3555 11612 3704 3560 11613 3700 3556 11614 3705 3561 11615 3698 3554 11616 3702 3558 11617 3699 3555 11618 3704 3560 11619 2529 2398 11620 3700 3556 11621 3706 3562 11622 3707 3562 11623 3708 3562 11624 3709 3563 11625 3707 3563 11626 3706 3563 11627 3710 3564 11628 3705 3561 11629 3711 3565 11630 3710 3564 11631 3704 3560 11632 3705 3561 11633 3706 3566 11634 3708 3566 11635 3712 3566 11636 3713 3567 11637 3714 3568 11638 3715 3569 11639 3706 3570 11640 3712 3570 11641 3716 3570 11642 3717 3571 11643 3715 3569 11644 3718 3572 11645 3717 3571 11646 3713 3567 11647 3715 3569 11648 3719 3573 11649 3718 3572 11650 3720 3574 11651 3719 3573 11652 3717 3571 11653 3718 3572 11654 3693 3549 11655 3720 3574 11656 3694 3550 11657 3693 3549 11658 3719 3573 11659 3720 3574 11660 3721 3575 11661 3722 3575 11662 3723 3575 11663 3724 3576 11664 3725 3576 11665 3722 3576 11666 3721 3577 11667 3724 3577 11668 3722 3577 11669 3726 3578 11670 3723 3578 11671 3727 3578 11672 3726 3579 11673 3721 3579 11674 3723 3579 11675 3728 3580 11676 3727 3580 11677 3729 3580 11678 3726 3581 11679 3727 3581 11680 3728 3581 11681 3730 3582 11682 3729 3582 11683 3731 3582 11684 3728 3583 11685 3729 3583 11686 3730 3583 11687 3732 3584 11688 3731 3584 11689 3733 3584 11690 3730 3585 11691 3731 3585 11692 3732 3585 11693 3732 3586 11694 3733 3586 11695 3734 3586 11696 3735 3587 11697 3734 3587 11698 3733 3587 11699 3736 3588 11700 3633 3588 11701 3642 3588 11702 3737 3589 11703 3633 3589 11704 3736 3589 11705 3738 3590 11706 3725 3590 11707 3724 3590 11708 3739 3591 11709 3725 3591 11710 3738 3591 11711 3739 3592 11712 3738 3592 11713 3740 3592 11714 3741 3593 11715 3740 3593 11716 3742 3593 11717 3739 3594 11718 3740 3594 11719 3741 3594 11720 3743 3595 11721 3742 3595 11722 3744 3595 11723 3741 3596 11724 3742 3596 11725 3743 3596 11726 3745 3597 11727 3744 3597 11728 3746 3597 11729 3743 3598 11730 3744 3598 11731 3745 3598 11732 3747 3599 11733 3746 3599 11734 3748 3599 11735 3745 3600 11736 3746 3600 11737 3747 3600 11738 3749 3601 11739 3748 3601 11740 3750 3601 11741 3747 3602 11742 3748 3602 11743 3749 3602 11744 3751 3603 11745 3750 3603 11746 3752 3603 11747 3749 3604 11748 3750 3604 11749 3751 3604 11750 3753 3605 11751 3752 3605 11752 3754 3605 11753 3751 3606 11754 3752 3606 11755 3753 3606 11756 3735 3607 11757 3755 3607 11758 3734 3607 11759 3709 3608 11760 3706 3608 11761 3756 3608 11762 3757 3609 11763 3758 3610 11764 3759 3611 11765 3710 3564 11766 3711 3565 11767 3760 3612 11768 3710 3564 11769 3760 3612 11770 3761 3613 11771 3757 3609 11772 3762 3614 11773 3758 3610 11774 3763 3615 11775 3755 3615 11776 3735 3615 11777 3763 3616 11778 3764 3616 11779 3755 3616 11780 3643 3501 11781 3765 3617 11782 3644 3502 11783 3643 3501 11784 3766 3618 11785 3765 3617 11786 3767 3619 11787 3768 3620 11788 3769 3621 11789 3770 3622 11790 3771 3623 11791 3766 3618 11792 3772 3624 11793 3769 3621 11794 3773 3625 11795 3643 3501 11796 3770 3622 11797 3766 3618 11798 3774 3626 11799 3767 3619 11800 3769 3621 11801 3774 3626 11802 3769 3621 11803 3772 3624 11804 3770 3622 11805 3775 3627 11806 3771 3623 11807 3772 3624 11808 3773 3625 11809 3776 3628 11810 3710 3564 11811 3777 3629 11812 3775 3627 11813 3778 3630 11814 3776 3628 11815 3779 3631 11816 3770 3622 11817 3710 3564 11818 3775 3627 11819 3772 3624 11820 3776 3628 11821 3778 3630 11822 3710 3564 11823 3761 3613 11824 3777 3629 11825 3780 3632 11826 3779 3631 11827 3762 3614 11828 3778 3630 11829 3779 3631 11830 3780 3632 11831 3780 3632 11832 3762 3614 11833 3757 3609 11834 3781 3633 11835 2529 2398 11836 3704 3560 11837 3781 3633 11838 2602 2471 11839 2529 2398 11840 3782 3634 11841 3704 3560 11842 3710 3564 11843 3782 3634 11844 3781 3633 11845 3704 3560 11846 3782 3634 11847 3710 3564 11848 3770 3622 11849 3783 3635 11850 3770 3622 11851 3643 3501 11852 3783 3635 11853 3782 3634 11854 3770 3622 11855 3784 3636 11856 3643 3501 11857 3639 3497 11858 3784 3636 11859 3783 3635 11860 3643 3501 11861 3785 3637 11862 3639 3497 11863 3479 3341 11864 3785 3637 11865 3784 3636 11866 3639 3497 11867 3786 3638 11868 3787 3639 11869 3479 3341 11870 3788 3640 11871 3479 3341 11872 3787 3639 11873 3482 3344 11874 3786 3638 11875 3479 3341 11876 3788 3640 11877 3785 3637 11878 3479 3341 11879 3789 3641 11880 3790 3642 11881 3791 3643 11882 3792 3644 11883 3788 3640 11884 3787 3639 11885 3789 3641 11886 3793 3645 11887 3790 3642 11888 3473 3335 11889 3791 3643 11890 3483 3345 11891 3789 3641 11892 3791 3643 11893 3473 3335 11894 3794 3646 11895 2602 2471 11896 3781 3633 11897 3794 3646 11898 2597 2466 11899 2602 2471 11900 3795 3647 11901 3781 3633 11902 3782 3634 11903 3795 3647 11904 3794 3646 11905 3781 3633 11906 3796 3648 11907 3782 3634 11908 3783 3635 11909 3796 3648 11910 3795 3647 11911 3782 3634 11912 3796 3648 11913 3783 3635 11914 3784 3636 11915 3797 3649 11916 3784 3636 11917 3785 3637 11918 3797 3649 11919 3796 3648 11920 3784 3636 11921 3798 3650 11922 3785 3637 11923 3788 3640 11924 3798 3650 11925 3797 3649 11926 3785 3637 11927 3792 3644 11928 3799 3651 11929 3788 3640 11930 3800 3652 11931 3788 3640 11932 3799 3651 11933 3800 3652 11934 3798 3650 11935 3788 3640 11936 3801 3653 11937 3802 3654 11938 3793 3645 11939 3803 3655 11940 3800 3652 11941 3799 3651 11942 3801 3653 11943 3804 3656 11944 3802 3654 11945 3801 3653 11946 3793 3645 11947 3789 3641 11948 3805 3657 11949 2597 2466 11950 3794 3646 11951 3805 3657 11952 2594 2463 11953 2597 2466 11954 3806 3658 11955 3794 3646 11956 3795 3647 11957 3806 3658 11958 3805 3657 11959 3794 3646 11960 3806 3658 11961 3795 3647 11962 3796 3648 11963 3807 3659 11964 3796 3648 11965 3797 3649 11966 3807 3659 11967 3806 3658 11968 3796 3648 11969 3808 3660 11970 3797 3649 11971 3798 3650 11972 3808 3660 11973 3807 3659 11974 3797 3649 11975 3809 3661 11976 3798 3650 11977 3800 3652 11978 3809 3661 11979 3808 3660 11980 3798 3650 11981 3810 3662 11982 3800 3652 11983 3803 3655 11984 3810 3662 11985 3809 3661 11986 3800 3652 11987 3811 3663 11988 3810 3662 11989 3803 3655 11990 3812 3664 11991 3813 3665 11992 3804 3656 11993 3812 3664 11994 3804 3656 11995 3801 3653 11996 2901 2764 11997 2594 2463 11998 3805 3657 11999 2901 2764 12000 2588 2457 12001 2594 2463 12002 2897 2760 12003 3805 3657 12004 3806 3658 12005 2897 2760 12006 2901 2764 12007 3805 3657 12008 2897 2760 12009 3806 3658 12010 3807 3659 12011 2886 2749 12012 3807 3659 12013 3808 3660 12014 2886 2749 12015 2897 2760 12016 3807 3659 12017 2879 2742 12018 3808 3660 12019 3809 3661 12020 2879 2742 12021 2886 2749 12022 3808 3660 12023 2873 2736 12024 3809 3661 12025 3810 3662 12026 2873 2736 12027 2879 2742 12028 3809 3661 12029 3811 3663 12030 3814 3666 12031 3810 3662 12032 2868 2731 12033 3810 3662 12034 3814 3666 12035 2868 2731 12036 2873 2736 12037 3810 3662 12038 3812 3664 12039 3815 3667 12040 3813 3665 12041 3816 3668 12042 2868 2731 12043 3814 3666 12044 3812 3664 12045 3817 3669 12046 3815 3667 12047 3816 3668 12048 2870 2733 12049 2868 2731 12050 3818 3670 12051 3819 3671 12052 3817 3669 12053 3818 3670 12054 2867 2730 12055 3819 3671 12056 3818 3670 12057 3817 3669 12058 3812 3664 12059 2865 2728 12060 2867 2730 12061 3818 3670 12062 3820 3672 12063 3821 3672 12064 3764 3672 12065 3763 3673 12066 3820 3673 12067 3764 3673 12068 3820 3674 12069 3822 3674 12070 3821 3674 12071 3485 3347 12072 3332 3192 12073 3335 3195 12074 3823 3675 12075 3335 3195 12076 3338 3198 12077 3823 3675 12078 3485 3347 12079 3335 3195 12080 3824 3676 12081 3338 3198 12082 3340 3200 12083 3824 3676 12084 3823 3675 12085 3338 3198 12086 3825 3677 12087 3340 3200 12088 3343 3203 12089 3825 3677 12090 3824 3676 12091 3340 3200 12092 3826 3678 12093 3343 3203 12094 3349 3209 12095 3826 3678 12096 3825 3677 12097 3343 3203 12098 3827 3679 12099 3826 3678 12100 3349 3209 12101 3350 3210 12102 3828 3680 12103 3346 3206 12104 3473 3335 12105 3485 3347 12106 3823 3675 12107 3789 3641 12108 3823 3675 12109 3824 3676 12110 3789 3641 12111 3473 3335 12112 3823 3675 12113 3801 3653 12114 3824 3676 12115 3825 3677 12116 3801 3653 12117 3789 3641 12118 3824 3676 12119 3812 3664 12120 3825 3677 12121 3826 3678 12122 3812 3664 12123 3801 3653 12124 3825 3677 12125 3818 3670 12126 3826 3678 12127 3827 3679 12128 3818 3670 12129 3812 3664 12130 3826 3678 12131 2865 2728 12132 3818 3670 12133 3827 3679 12134 3829 3681 12135 2860 2723 12136 3828 3680 12137 3350 3210 12138 3829 3681 12139 3828 3680 12140 3829 3681 12141 2849 2712 12142 2860 2723 12143 3322 3182 12144 2691 2558 12145 2704 2571 12146 3830 3682 12147 2704 2571 12148 2789 2652 12149 3830 3682 12150 3322 3182 12151 2704 2571 12152 3831 3683 12153 2789 2652 12154 2849 2712 12155 3831 3683 12156 3830 3682 12157 2789 2652 12158 3829 3681 12159 3831 3683 12160 2849 2712 12161 3297 3156 12162 3322 3182 12163 3830 3682 12164 3354 3214 12165 3830 3682 12166 3831 3683 12167 3354 3214 12168 3297 3156 12169 3830 3682 12170 3352 3212 12171 3831 3683 12172 3829 3681 12173 3352 3212 12174 3354 3214 12175 3831 3683 12176 3350 3210 12177 3352 3212 12178 3829 3681 12179 865 779 12180 867 781 12181 3370 3231 12182 3832 3684 12183 3370 3231 12184 3372 3234 12185 3832 3684 12186 865 779 12187 3370 3231 12188 3833 3685 12189 3372 3234 12190 3374 3236 12191 3833 3685 12192 3832 3684 12193 3372 3234 12194 3834 3686 12195 3374 3236 12196 3376 3238 12197 3834 3686 12198 3833 3685 12199 3374 3236 12200 3835 3687 12201 3376 3238 12202 3378 3240 12203 3835 3687 12204 3834 3686 12205 3376 3238 12206 3836 3688 12207 3378 3240 12208 3380 3242 12209 3836 3688 12210 3835 3687 12211 3378 3240 12212 3837 3689 12213 3380 3242 12214 3382 3244 12215 3837 3689 12216 3836 3688 12217 3380 3242 12218 3838 3690 12219 3382 3244 12220 3385 3247 12221 3838 3690 12222 3837 3689 12223 3382 3244 12224 3839 3691 12225 3385 3247 12226 3387 3249 12227 3839 3691 12228 3838 3690 12229 3385 3247 12230 3840 3692 12231 3387 3249 12232 3389 3251 12233 3840 3692 12234 3839 3691 12235 3387 3249 12236 3841 3693 12237 3389 3251 12238 3391 3253 12239 3841 3693 12240 3840 3692 12241 3389 3251 12242 3842 3694 12243 3391 3253 12244 3393 3255 12245 3842 3694 12246 3841 3693 12247 3391 3253 12248 3843 3695 12249 3393 3255 12250 3395 3257 12251 3843 3695 12252 3842 3694 12253 3393 3255 12254 3844 3696 12255 3395 3257 12256 3397 3259 12257 3844 3696 12258 3843 3695 12259 3395 3257 12260 3845 3697 12261 3397 3259 12262 3399 3261 12263 3845 3697 12264 3844 3696 12265 3397 3259 12266 3846 3698 12267 3399 3261 12268 3401 3263 12269 3846 3698 12270 3845 3697 12271 3399 3261 12272 3847 3699 12273 3401 3263 12274 3403 3265 12275 3847 3699 12276 3846 3698 12277 3401 3263 12278 3848 3700 12279 3403 3265 12280 3405 3267 12281 3848 3700 12282 3847 3699 12283 3403 3265 12284 3849 3701 12285 3405 3267 12286 3407 3269 12287 3849 3701 12288 3848 3700 12289 3405 3267 12290 3850 3702 12291 3407 3269 12292 3409 3271 12293 3850 3702 12294 3849 3701 12295 3407 3269 12296 3851 3703 12297 3409 3271 12298 3411 3273 12299 3851 3703 12300 3850 3702 12301 3409 3271 12302 3852 3704 12303 3411 3273 12304 3413 3275 12305 3852 3704 12306 3851 3703 12307 3411 3273 12308 3853 3705 12309 3413 3275 12310 3415 3277 12311 3853 3705 12312 3852 3704 12313 3413 3275 12314 3854 3706 12315 3415 3277 12316 3417 3279 12317 3854 3706 12318 3853 3705 12319 3415 3277 12320 3855 3707 12321 3417 3279 12322 3419 3281 12323 3855 3707 12324 3854 3706 12325 3417 3279 12326 3856 3708 12327 3419 3281 12328 3421 3283 12329 3856 3708 12330 3855 3707 12331 3419 3281 12332 3857 3709 12333 3421 3283 12334 3423 3285 12335 3857 3709 12336 3856 3708 12337 3421 3283 12338 3858 3710 12339 3423 3285 12340 3425 3287 12341 3858 3710 12342 3857 3709 12343 3423 3285 12344 3859 3711 12345 3425 3287 12346 3427 3289 12347 3859 3711 12348 3858 3710 12349 3425 3287 12350 3860 3712 12351 3427 3289 12352 3429 3291 12353 3860 3712 12354 3859 3711 12355 3427 3289 12356 3861 3713 12357 3429 3291 12358 3431 3293 12359 3861 3713 12360 3860 3712 12361 3429 3291 12362 3862 3714 12363 3431 3293 12364 3433 3295 12365 3862 3714 12366 3861 3713 12367 3431 3293 12368 3863 3715 12369 3433 3295 12370 3435 3297 12371 3863 3715 12372 3862 3714 12373 3433 3295 12374 3864 3716 12375 3435 3297 12376 3437 3299 12377 3864 3716 12378 3863 3715 12379 3435 3297 12380 3865 3717 12381 3437 3299 12382 3440 3302 12383 3865 3717 12384 3864 3716 12385 3437 3299 12386 1373 3718 12387 1372 3718 12388 1114 3718 12389 3866 3719 12390 3865 3717 12391 3440 3302 12392 3867 3720 12393 865 779 12394 3832 3684 12395 3867 3720 12396 868 782 12397 865 779 12398 3868 3721 12399 3832 3684 12400 3833 3685 12401 557 492 12402 809 492 12403 558 492 12404 3869 3722 12405 3867 3720 12406 3832 3684 12407 3868 3721 12408 3869 3722 12409 3832 3684 12410 3870 3723 12411 3833 3685 12412 3834 3686 12413 3870 3723 12414 3868 3721 12415 3833 3685 12416 3871 3724 12417 3834 3686 12418 3835 3687 12419 3871 3724 12420 3870 3723 12421 3834 3686 12422 3872 3725 12423 3835 3687 12424 3836 3688 12425 3872 3725 12426 3871 3724 12427 3835 3687 12428 3873 3726 12429 3836 3688 12430 3837 3689 12431 3873 3726 12432 3872 3725 12433 3836 3688 12434 3874 3727 12435 3837 3689 12436 3838 3690 12437 3874 3727 12438 3873 3726 12439 3837 3689 12440 3875 3728 12441 3838 3690 12442 3839 3691 12443 3875 3728 12444 3874 3727 12445 3838 3690 12446 3876 3729 12447 3839 3691 12448 3840 3692 12449 3876 3729 12450 3875 3728 12451 3839 3691 12452 3877 3730 12453 3840 3692 12454 3841 3693 12455 3877 3730 12456 3876 3729 12457 3840 3692 12458 3878 3731 12459 3841 3693 12460 3842 3694 12461 3878 3731 12462 3877 3730 12463 3841 3693 12464 3879 3732 12465 3842 3694 12466 3843 3695 12467 3879 3732 12468 3878 3731 12469 3842 3694 12470 3880 3733 12471 3843 3695 12472 3844 3696 12473 3880 3733 12474 3879 3732 12475 3843 3695 12476 3881 3734 12477 3844 3696 12478 3845 3697 12479 3881 3734 12480 3880 3733 12481 3844 3696 12482 3882 3735 12483 3845 3697 12484 3846 3698 12485 3882 3735 12486 3881 3734 12487 3845 3697 12488 3883 3736 12489 3846 3698 12490 3847 3699 12491 3883 3736 12492 3882 3735 12493 3846 3698 12494 3884 3737 12495 3847 3699 12496 3848 3700 12497 3884 3737 12498 3883 3736 12499 3847 3699 12500 3885 3738 12501 3848 3700 12502 3849 3701 12503 3885 3738 12504 3884 3737 12505 3848 3700 12506 3886 3739 12507 3849 3701 12508 3850 3702 12509 3886 3739 12510 3885 3738 12511 3849 3701 12512 3887 3740 12513 3850 3702 12514 3851 3703 12515 3887 3740 12516 3886 3739 12517 3850 3702 12518 3888 3741 12519 3851 3703 12520 3852 3704 12521 3888 3741 12522 3887 3740 12523 3851 3703 12524 3889 3742 12525 3852 3704 12526 3853 3705 12527 3889 3742 12528 3888 3741 12529 3852 3704 12530 3890 3743 12531 3853 3705 12532 3854 3706 12533 3890 3743 12534 3889 3742 12535 3853 3705 12536 3891 3744 12537 3854 3706 12538 3855 3707 12539 3891 3744 12540 3890 3743 12541 3854 3706 12542 3892 3745 12543 3855 3707 12544 3856 3708 12545 3892 3745 12546 3891 3744 12547 3855 3707 12548 3893 3746 12549 3856 3708 12550 3857 3709 12551 3893 3746 12552 3892 3745 12553 3856 3708 12554 3894 3747 12555 3857 3709 12556 3858 3710 12557 3894 3747 12558 3893 3746 12559 3857 3709 12560 3895 3748 12561 3858 3710 12562 3859 3711 12563 3895 3748 12564 3894 3747 12565 3858 3710 12566 3896 3749 12567 3859 3711 12568 3860 3712 12569 3896 3749 12570 3895 3748 12571 3859 3711 12572 3897 3750 12573 3860 3712 12574 3861 3713 12575 3897 3750 12576 3896 3749 12577 3860 3712 12578 3898 3751 12579 3861 3713 12580 3862 3714 12581 3898 3751 12582 3897 3750 12583 3861 3713 12584 3899 3752 12585 3862 3714 12586 3863 3715 12587 3899 3752 12588 3898 3751 12589 3862 3714 12590 3900 3753 12591 3863 3715 12592 3864 3716 12593 3900 3753 12594 3899 3752 12595 3863 3715 12596 3901 3754 12597 3864 3716 12598 3865 3717 12599 3901 3754 12600 3900 3753 12601 3864 3716 12602 3901 3754 12603 3865 3717 12604 3866 3719 12605 3902 3755 12606 1374 3755 12607 1373 3755 12608 1253 1166 12609 3901 3754 12610 3866 3719 12611 869 783 12612 868 782 12613 3867 3720 12614 3903 3756 12615 3869 3722 12616 3868 3721 12617 3904 3757 12618 3868 3721 12619 3870 3723 12620 3904 3757 12621 3903 3756 12622 3868 3721 12623 3902 3758 12624 3905 3758 12625 1374 3758 12626 3906 492 12627 3905 492 12628 3902 492 12629 3907 3759 12630 3908 3759 12631 3906 3759 12632 3906 3760 12633 3908 3760 12634 3905 3760 12635 3909 3761 12636 3872 3725 12637 3873 3726 12638 3909 3761 12639 3871 3724 12640 3872 3725 12641 3910 3762 12642 3873 3726 12643 3874 3727 12644 3911 3763 12645 3909 3761 12646 3873 3726 12647 3910 3762 12648 3911 3763 12649 3873 3726 12650 3912 3764 12651 3874 3727 12652 3875 3728 12653 3912 3764 12654 3910 3762 12655 3874 3727 12656 3913 3765 12657 3875 3728 12658 3876 3729 12659 3914 3766 12660 3912 3764 12661 3875 3728 12662 3913 3765 12663 3914 3766 12664 3875 3728 12665 3915 3767 12666 3876 3729 12667 3877 3730 12668 3915 3767 12669 3913 3765 12670 3876 3729 12671 3916 3768 12672 3917 3768 12673 3907 3768 12674 3907 3769 12675 3917 3769 12676 3908 3769 12677 3918 3770 12678 3878 3731 12679 3879 3732 12680 3919 3771 12681 3877 3730 12682 3878 3731 12683 3918 3770 12684 3919 3771 12685 3878 3731 12686 3920 3772 12687 3879 3732 12688 3880 3733 12689 3920 3772 12690 3918 3770 12691 3879 3732 12692 3921 3773 12693 3880 3733 12694 3881 3734 12695 3921 3773 12696 3920 3772 12697 3880 3733 12698 3922 3774 12699 3881 3734 12700 3882 3735 12701 3923 3775 12702 3924 3775 12703 3916 3775 12704 3916 3776 12705 3925 3776 12706 3917 3776 12707 3926 3777 12708 3882 3735 12709 3883 3736 12710 3927 3778 12711 3922 3774 12712 3882 3735 12713 3926 3777 12714 3927 3778 12715 3882 3735 12716 3928 3779 12717 3883 3736 12718 3884 3737 12719 3928 3779 12720 3926 3777 12721 3883 3736 12722 3929 3780 12723 3884 3737 12724 3885 3738 12725 3929 3780 12726 3928 3779 12727 3884 3737 12728 3930 3781 12729 3885 3738 12730 3886 3739 12731 3930 3781 12732 3929 3780 12733 3885 3738 12734 3931 3782 12735 3886 3739 12736 3887 3740 12737 3931 3782 12738 3930 3781 12739 3886 3739 12740 3932 3783 12741 3887 3740 12742 3888 3741 12743 3932 3783 12744 3931 3782 12745 3887 3740 12746 3933 3784 12747 3888 3741 12748 3889 3742 12749 3934 3785 12750 3932 3783 12751 3888 3741 12752 3933 3784 12753 3934 3785 12754 3888 3741 12755 3935 3786 12756 3889 3742 12757 3890 3743 12758 3935 3786 12759 3933 3784 12760 3889 3742 12761 3936 3787 12762 3890 3743 12763 3891 3744 12764 3936 3787 12765 3935 3786 12766 3890 3743 12767 3937 3788 12768 3891 3744 12769 3892 3745 12770 3938 3789 12771 3936 3787 12772 3891 3744 12773 3937 3788 12774 3938 3789 12775 3891 3744 12776 3939 3790 12777 3892 3745 12778 3893 3746 12779 3939 3790 12780 3937 3788 12781 3892 3745 12782 3940 3791 12783 3893 3746 12784 3894 3747 12785 3941 3792 12786 3939 3790 12787 3893 3746 12788 3940 3791 12789 3941 3792 12790 3893 3746 12791 3942 3793 12792 3894 3747 12793 3895 3748 12794 3942 3793 12795 3940 3791 12796 3894 3747 12797 3943 3794 12798 3895 3748 12799 3896 3749 12800 3943 3794 12801 3942 3793 12802 3895 3748 12803 3944 3795 12804 3896 3749 12805 3897 3750 12806 3944 3795 12807 3943 3794 12808 3896 3749 12809 3945 3796 12810 3897 3750 12811 3898 3751 12812 3945 3796 12813 3944 3795 12814 3897 3750 12815 3946 3797 12816 3898 3751 12817 3899 3752 12818 3947 3798 12819 3945 3796 12820 3898 3751 12821 3946 3797 12822 3947 3798 12823 3898 3751 12824 3948 3799 12825 3899 3752 12826 3900 3753 12827 3948 3799 12828 3946 3797 12829 3899 3752 12830 1252 1165 12831 3900 3753 12832 3901 3754 12833 1252 1165 12834 3948 3799 12835 3900 3753 12836 1252 1165 12837 3901 3754 12838 1253 1166 12839 841 760 12840 843 762 12841 3949 3800 12842 841 760 12843 3949 3800 12844 3950 3801 12845 841 760 12846 3950 3801 12847 3951 3802 12848 841 760 12849 3951 3802 12850 3952 3803 12851 841 760 12852 3952 3803 12853 3953 3804 12854 841 760 12855 3953 3804 12856 3954 3805 12857 841 760 12858 3954 3805 12859 3955 3806 12860 841 760 12861 3955 3806 12862 3956 3807 12863 841 760 12864 3956 3807 12865 3957 3808 12866 3958 3809 12867 3957 3808 12868 3959 3810 12869 3958 3809 12870 841 760 12871 3957 3808 12872 3958 3809 12873 3959 3810 12874 3960 3811 12875 3958 3809 12876 3960 3811 12877 3961 3812 12878 3958 3809 12879 3961 3812 12880 3962 3813 12881 3958 3809 12882 3962 3813 12883 3963 3814 12884 3958 3809 12885 3963 3814 12886 3964 3815 12887 3958 3809 12888 3964 3815 12889 3965 3816 12890 3966 3817 12891 3965 3816 12892 3967 3818 12893 3966 3817 12894 3958 3809 12895 3965 3816 12896 3966 3817 12897 3967 3818 12898 3968 3819 12899 3966 3817 12900 3968 3819 12901 3969 3820 12902 3966 3817 12903 3969 3820 12904 3970 3821 12905 3966 3817 12906 3970 3821 12907 3971 3822 12908 3966 3817 12909 3971 3822 12910 3972 3823 12911 3966 3817 12912 3972 3823 12913 3973 3824 12914 3974 3825 12915 3973 3824 12916 3975 3826 12917 3974 3825 12918 3966 3817 12919 3973 3824 12920 3974 3825 12921 3975 3826 12922 3976 3827 12923 3974 3825 12924 3976 3827 12925 3977 3828 12926 3974 3825 12927 3977 3828 12928 3978 3829 12929 3974 3825 12930 3978 3829 12931 3979 3830 12932 3974 3825 12933 3979 3830 12934 3980 3831 12935 1249 1162 12936 3980 3831 12937 3981 3832 12938 3974 3825 12939 3980 3831 12940 1249 1162 12941 1249 1162 12942 3981 3832 12943 3982 3833 12944 1249 1162 12945 3982 3833 12946 3983 3834 12947 1249 1162 12948 3983 3834 12949 1255 1168 12950 3984 3835 12951 1249 1162 12952 1256 1169 12953 3974 3825 12954 1249 1162 12955 3984 3835 12956 3985 3836 12957 1256 1169 12958 1258 1171 12959 3984 3835 12960 1256 1169 12961 3985 3836 12962 3986 3837 12963 1258 1171 12964 1261 1174 12965 3985 3836 12966 1258 1171 12967 3986 3837 12968 3987 3838 12969 1261 1174 12970 1241 1154 12971 3986 3837 12972 1261 1174 12973 3987 3838 12974 3988 3839 12975 1241 1154 12976 1245 1158 12977 3987 3838 12978 1241 1154 12979 3988 3839 12980 3989 3840 12981 1245 1158 12982 1116 1027 12983 3988 3839 12984 1245 1158 12985 3989 3840 12986 3990 3841 12987 1116 1027 12988 1119 1030 12989 3989 3840 12990 1116 1027 12991 3990 3841 12992 3990 3841 12993 1119 1030 12994 3991 3842 12995 3992 3843 12996 817 736 12997 820 739 12998 3993 3844 12999 820 739 13000 823 742 13001 3993 3844 13002 3992 3843 13003 820 739 13004 3994 3845 13005 823 742 13006 825 744 13007 3994 3845 13008 3993 3844 13009 823 742 13010 3995 3846 13011 825 744 13012 828 747 13013 3995 3846 13014 3994 3845 13015 825 744 13016 3996 3847 13017 828 747 13018 831 750 13019 3996 3847 13020 3995 3846 13021 828 747 13022 3997 3848 13023 831 750 13024 833 752 13025 3997 3848 13026 3996 3847 13027 831 750 13028 3998 3849 13029 833 752 13030 835 754 13031 3998 3849 13032 3997 3848 13033 833 752 13034 3999 3850 13035 835 754 13036 837 756 13037 3999 3850 13038 3998 3849 13039 835 754 13040 4000 3851 13041 837 756 13042 839 758 13043 4000 3851 13044 3999 3850 13045 837 756 13046 3958 3809 13047 839 758 13048 841 760 13049 3958 3809 13050 4000 3851 13051 839 758 13052 4001 3852 13053 3992 3843 13054 3993 3844 13055 4002 3853 13056 3993 3844 13057 3994 3845 13058 4003 3854 13059 4001 3852 13060 3993 3844 13061 4002 3853 13062 4003 3854 13063 3993 3844 13064 4004 3855 13065 3994 3845 13066 3995 3846 13067 4004 3855 13068 4002 3853 13069 3994 3845 13070 4005 3856 13071 3995 3846 13072 3996 3847 13073 4005 3856 13074 4004 3855 13075 3995 3846 13076 4006 3857 13077 3996 3847 13078 3997 3848 13079 4006 3857 13080 4005 3856 13081 3996 3847 13082 4007 3858 13083 3997 3848 13084 3998 3849 13085 4007 3858 13086 4006 3857 13087 3997 3848 13088 4008 3859 13089 3998 3849 13090 3999 3850 13091 4008 3859 13092 4007 3858 13093 3998 3849 13094 4009 3860 13095 3999 3850 13096 4000 3851 13097 4009 3860 13098 4008 3859 13099 3999 3850 13100 3966 3817 13101 4000 3851 13102 3958 3809 13103 3966 3817 13104 4009 3860 13105 4000 3851 13106 3991 3842 13107 4001 3852 13108 4003 3854 13109 3990 3841 13110 4003 3854 13111 4002 3853 13112 3990 3841 13113 3991 3842 13114 4003 3854 13115 3989 3840 13116 4002 3853 13117 4004 3855 13118 3989 3840 13119 3990 3841 13120 4002 3853 13121 3988 3839 13122 4004 3855 13123 4005 3856 13124 3988 3839 13125 3989 3840 13126 4004 3855 13127 3987 3838 13128 4005 3856 13129 4006 3857 13130 3987 3838 13131 3988 3839 13132 4005 3856 13133 3986 3837 13134 4006 3857 13135 4007 3858 13136 3986 3837 13137 3987 3838 13138 4006 3857 13139 3985 3836 13140 4007 3858 13141 4008 3859 13142 3985 3836 13143 3986 3837 13144 4007 3858 13145 3984 3835 13146 4008 3859 13147 4009 3860 13148 3984 3835 13149 3985 3836 13150 4008 3859 13151 3974 3825 13152 4009 3860 13153 3966 3817 13154 3974 3825 13155 3984 3835 13156 4009 3860 13157 4010 3861 13158 2799 2662 13159 2803 2666 13160 4011 3862 13161 2802 2665 13162 4012 3863 13163 4011 3862 13164 2794 2657 13165 2802 2665 13166 4013 3864 13167 2803 2666 13168 2805 2668 13169 4013 3864 13170 4010 3861 13171 2803 2666 13172 4014 3865 13173 2805 2668 13174 2807 2670 13175 4015 3866 13176 4013 3864 13177 2805 2668 13178 4014 3865 13179 4015 3866 13180 2805 2668 13181 4016 3867 13182 2807 2670 13183 2809 2672 13184 4016 3867 13185 4014 3865 13186 2807 2670 13187 4017 3868 13188 2809 2672 13189 2811 2674 13190 4017 3868 13191 4016 3867 13192 2809 2672 13193 4018 3869 13194 2811 2674 13195 2813 2676 13196 4018 3869 13197 4017 3868 13198 2811 2674 13199 4018 3869 13200 2813 2676 13201 4019 3870 13202 4020 3871 13203 4021 3872 13204 2815 2678 13205 4020 3871 13206 2815 2678 13207 2818 2681 13208 4022 3873 13209 4023 3874 13210 4024 3875 13211 4025 3876 13212 4026 3877 13213 4027 3878 13214 4028 3879 13215 4022 3873 13216 4024 3875 13217 4029 3880 13218 4030 3881 13219 4031 3882 13220 4032 3883 13221 4033 3884 13222 4034 3885 13223 4035 3886 13224 4032 3883 13225 4034 3885 13226 4036 3887 13227 4031 3882 13228 4037 3888 13229 4038 3889 13230 4029 3880 13231 4031 3882 13232 4036 3887 13233 4038 3889 13234 4031 3882 13235 4039 3890 13236 4037 3888 13237 4040 3891 13238 4041 3892 13239 4036 3887 13240 4037 3888 13241 4039 3890 13242 4041 3892 13243 4037 3888 13244 4042 3893 13245 4040 3891 13246 4043 3894 13247 4044 3895 13248 4039 3890 13249 4040 3891 13250 4042 3893 13251 4044 3895 13252 4040 3891 13253 4045 3896 13254 4043 3894 13255 4046 3897 13256 4045 3896 13257 4042 3893 13258 4043 3894 13259 4022 3873 13260 4046 3897 13261 4023 3874 13262 4022 3873 13263 4045 3896 13264 4046 3897 13265 4047 3898 13266 2818 2681 13267 2822 2685 13268 4047 3898 13269 4020 3871 13270 2818 2681 13271 4048 3899 13272 2822 2685 13273 2820 2683 13274 4048 3899 13275 4047 3898 13276 2822 2685 13277 4048 3899 13278 2820 2683 13279 2827 2690 13280 4048 3899 13281 2827 2690 13282 4049 3900 13283 2828 2691 13284 4050 3901 13285 2824 2687 13286 4051 3902 13287 4052 3903 13288 4053 3904 13289 4054 3905 13290 4050 3901 13291 2828 2691 13292 4055 3906 13293 4056 3907 13294 4057 3908 13295 4058 3909 13296 4051 3902 13297 4053 3904 13298 4059 3910 13299 4027 3878 13300 4060 3911 13301 4025 3876 13302 4027 3878 13303 4061 3912 13304 4059 3910 13305 4061 3912 13306 4027 3878 13307 4062 3913 13308 4060 3911 13309 4052 3903 13310 4059 3910 13311 4060 3911 13312 4062 3913 13313 4062 3913 13314 4052 3903 13315 4051 3902 13316 4063 3914 13317 2828 2691 13318 2830 2693 13319 4063 3914 13320 4054 3905 13321 2828 2691 13322 4064 3915 13323 2830 2693 13324 2832 2695 13325 4065 3916 13326 4063 3914 13327 2830 2693 13328 4064 3915 13329 4065 3916 13330 2830 2693 13331 4066 3917 13332 2832 2695 13333 2834 2697 13334 4067 3918 13335 4064 3915 13336 2832 2695 13337 4066 3917 13338 4067 3918 13339 2832 2695 13340 4068 3919 13341 2834 2697 13342 2836 2699 13343 4069 3920 13344 4066 3917 13345 2834 2697 13346 4068 3919 13347 4069 3920 13348 2834 2697 13349 4070 3921 13350 2836 2699 13351 2842 2705 13352 4071 3922 13353 4068 3919 13354 2836 2699 13355 4072 3923 13356 4071 3922 13357 2836 2699 13358 4070 3921 13359 4072 3923 13360 2836 2699 13361 4070 3921 13362 2842 2705 13363 4073 3924 13364 2844 2707 13365 4074 3925 13366 2839 2702 13367 4075 3926 13368 4076 3927 13369 4077 3928 13370 4078 3929 13371 4074 3925 13372 2844 2707 13373 4079 3930 13374 4080 3931 13375 4081 3932 13376 4082 3933 13377 4075 3926 13378 4077 3928 13379 4083 3934 13380 4057 3908 13381 4084 3935 13382 4055 3906 13383 4057 3908 13384 4085 3936 13385 4086 3937 13386 4085 3936 13387 4057 3908 13388 4083 3934 13389 4086 3937 13390 4057 3908 13391 4087 3938 13392 4084 3935 13393 4088 3939 13394 4087 3938 13395 4083 3934 13396 4084 3935 13397 4089 3940 13398 4088 3939 13399 4090 3941 13400 4089 3940 13401 4087 3938 13402 4088 3939 13403 4091 3942 13404 4090 3941 13405 4092 3943 13406 4091 3942 13407 4089 3940 13408 4090 3941 13409 4093 3944 13410 4092 3943 13411 4094 3945 13412 4093 3944 13413 4091 3942 13414 4092 3943 13415 4095 3946 13416 4094 3945 13417 4096 3947 13418 4095 3946 13419 4093 3944 13420 4094 3945 13421 4097 3948 13422 4096 3947 13423 4098 3949 13424 4097 3948 13425 4095 3946 13426 4096 3947 13427 4099 3950 13428 4098 3949 13429 4100 3951 13430 4099 3950 13431 4097 3948 13432 4098 3949 13433 4101 3952 13434 4100 3951 13435 4102 3953 13436 4101 3952 13437 4099 3950 13438 4100 3951 13439 4075 3926 13440 4102 3953 13441 4076 3927 13442 4075 3926 13443 4101 3952 13444 4102 3953 13445 4078 3929 13446 2844 2707 13447 2961 2824 13448 4103 3954 13449 2961 2824 13450 2913 2776 13451 4103 3954 13452 4078 3929 13453 2961 2824 13454 4104 3955 13455 2913 2776 13456 2919 2782 13457 4104 3955 13458 4103 3954 13459 2913 2776 13460 4104 3955 13461 2919 2782 13462 4105 3956 13463 2920 2783 13464 4106 3957 13465 2916 2779 13466 4107 3958 13467 4108 3959 13468 4109 3960 13469 4110 3961 13470 4106 3957 13471 2920 2783 13472 4111 3962 13473 4112 3963 13474 4113 3964 13475 4107 3958 13476 4109 3960 13477 4114 3965 13478 4115 3966 13479 4081 3932 13480 4116 3967 13481 4117 3968 13482 4079 3930 13483 4081 3932 13484 4117 3968 13485 4081 3932 13486 4115 3966 13487 4107 3958 13488 4116 3967 13489 4108 3959 13490 4115 3966 13491 4116 3967 13492 4107 3958 13493 4118 3969 13494 2920 2783 13495 2923 2786 13496 4118 3969 13497 4110 3961 13498 2920 2783 13499 4119 3970 13500 2923 2786 13501 2925 2788 13502 4120 3971 13503 4118 3969 13504 2923 2786 13505 4119 3970 13506 4120 3971 13507 2923 2786 13508 4121 3972 13509 2925 2788 13510 2927 2790 13511 4122 3973 13512 4119 3970 13513 2925 2788 13514 4123 3974 13515 4122 3973 13516 2925 2788 13517 4121 3972 13518 4123 3974 13519 2925 2788 13520 4124 3975 13521 2927 2790 13522 2929 2792 13523 4125 3976 13524 4121 3972 13525 2927 2790 13526 4124 3975 13527 4125 3976 13528 2927 2790 13529 4126 3977 13530 2929 2792 13531 2931 2794 13532 4127 3978 13533 4124 3975 13534 2929 2792 13535 4126 3977 13536 4127 3978 13537 2929 2792 13538 4126 3977 13539 2931 2794 13540 4128 3979 13541 4129 3980 13542 4130 3981 13543 2933 2796 13544 4129 3980 13545 2933 2796 13546 2936 2799 13547 4131 3982 13548 4132 3983 13549 4133 3984 13550 4134 3985 13551 4135 3986 13552 4136 3987 13553 4137 3988 13554 4131 3982 13555 4133 3984 13556 4138 3989 13557 4113 3964 13558 4139 3990 13559 4140 3991 13560 4111 3962 13561 4113 3964 13562 4140 3991 13563 4113 3964 13564 4138 3989 13565 4141 3992 13566 4139 3990 13567 4142 3993 13568 4138 3989 13569 4139 3990 13570 4141 3992 13571 4141 3992 13572 4142 3993 13573 4143 3994 13574 4144 3995 13575 4143 3994 13576 4145 3996 13577 4141 3992 13578 4143 3994 13579 4144 3995 13580 4146 3997 13581 4145 3996 13582 4147 3998 13583 4144 3995 13584 4145 3996 13585 4146 3997 13586 4148 3999 13587 4147 3998 13588 4149 4000 13589 4146 3997 13590 4147 3998 13591 4148 3999 13592 4150 4001 13593 4149 4000 13594 4151 4002 13595 4148 3999 13596 4149 4000 13597 4150 4001 13598 4152 4003 13599 4151 4002 13600 4153 4004 13601 4150 4001 13602 4151 4002 13603 4152 4003 13604 4154 4005 13605 4153 4004 13606 4155 4006 13607 4152 4003 13608 4153 4004 13609 4154 4005 13610 4156 4007 13611 4155 4006 13612 4132 3983 13613 4154 4005 13614 4155 4006 13615 4156 4007 13616 4156 4007 13617 4132 3983 13618 4131 3982 13619 4157 4008 13620 2936 2799 13621 2938 2801 13622 4157 4008 13623 4129 3980 13624 2936 2799 13625 4158 4009 13626 2938 2801 13627 2940 2803 13628 4158 4009 13629 4157 4008 13630 2938 2801 13631 4159 4010 13632 2940 2803 13633 2942 2805 13634 4159 4010 13635 4158 4009 13636 2940 2803 13637 4159 4010 13638 2942 2805 13639 2948 2811 13640 4159 4010 13641 2948 2811 13642 4160 4011 13643 2949 2812 13644 4161 4012 13645 2945 2808 13646 4162 4013 13647 4163 4014 13648 4164 4015 13649 4165 4016 13650 4161 4012 13651 2949 2812 13652 4166 4017 13653 4167 4018 13654 4168 4019 13655 4169 4020 13656 4162 4013 13657 4164 4015 13658 4170 4021 13659 4136 4021 13660 4171 4021 13661 4170 4022 13662 4172 4023 13663 4136 3987 13664 4134 3985 13665 4136 3987 13666 4172 4023 13667 4173 4024 13668 4171 4024 13669 4174 4024 13670 4170 4025 13671 4171 4025 13672 4173 4025 13673 4175 4026 13674 4174 4026 13675 4163 4026 13676 4173 4027 13677 4174 4027 13678 4175 4027 13679 4175 4028 13680 4163 4028 13681 4162 4028 13682 4165 4016 13683 2949 2812 13684 2951 2814 13685 4176 4029 13686 2951 2814 13687 2953 2816 13688 4176 4029 13689 4165 4016 13690 2951 2814 13691 4177 4030 13692 2953 2816 13693 2955 2818 13694 4178 4031 13695 4176 4029 13696 2953 2816 13697 4177 4030 13698 4178 4031 13699 2953 2816 13700 4179 4032 13701 2955 2818 13702 2957 2820 13703 4179 4032 13704 4177 4030 13705 2955 2818 13706 4180 4033 13707 2957 2820 13708 2960 2823 13709 4180 4033 13710 4179 4032 13711 2957 2820 13712 4180 4033 13713 2960 2823 13714 4181 4034 13715 2855 2718 13716 4182 4035 13717 2858 2721 13718 4183 4036 13719 4184 4037 13720 4185 4038 13721 4186 4039 13722 4182 4035 13723 2855 2718 13724 4187 4040 13725 4188 4041 13726 4189 4042 13727 4183 4036 13728 4185 4038 13729 4190 4043 13730 4191 4044 13731 4168 4019 13732 4192 4045 13733 4193 4046 13734 4194 4047 13735 4168 4019 13736 4166 4017 13737 4168 4019 13738 4194 4047 13739 4193 4046 13740 4168 4019 13741 4191 4044 13742 4195 4048 13743 4192 4045 13744 4196 4049 13745 4191 4044 13746 4192 4045 13747 4195 4048 13748 4197 4050 13749 4196 4049 13750 4198 4051 13751 4199 4052 13752 4196 4049 13753 4197 4050 13754 4195 4048 13755 4196 4049 13756 4199 4052 13757 4200 4053 13758 4198 4051 13759 4201 4054 13760 4197 4050 13761 4198 4051 13762 4200 4053 13763 4183 4036 13764 4201 4054 13765 4184 4037 13766 4202 4055 13767 4201 4054 13768 4183 4036 13769 4200 4053 13770 4201 4054 13771 4202 4055 13772 4203 4056 13773 2855 2718 13774 2797 2660 13775 4203 4056 13776 4186 4039 13777 2855 2718 13778 4011 3862 13779 2797 2660 13780 2794 2657 13781 4011 3862 13782 4203 4056 13783 2797 2660 13784 4204 4057 13785 4189 4042 13786 4205 4058 13787 4204 4057 13788 4187 4040 13789 4189 4042 13790 4206 4059 13791 4205 4058 13792 4033 3884 13793 4206 4059 13794 4204 4057 13795 4205 4058 13796 4032 3883 13797 4206 4059 13798 4033 3884 13799 4207 4060 13800 4208 4061 13801 4209 4062 13802 4210 4063 13803 4208 4061 13804 4207 4060 13805 4211 4064 13806 4208 4061 13807 4210 4063 13808 4212 4065 13809 4213 4066 13810 4214 4067 13811 4215 4068 13812 4213 4066 13813 4212 4065 13814 4207 4060 13815 4209 4062 13816 4216 4069 13817 4207 4060 13818 4216 4069 13819 4217 4070 13820 4207 4060 13821 4217 4070 13822 4218 4071 13823 4219 4072 13824 4220 4073 13825 4221 4074 13826 4222 4075 13827 4221 4074 13828 4223 4076 13829 4222 4075 13830 4219 4072 13831 4221 4074 13832 4222 4075 13833 4223 4076 13834 4224 4077 13835 4225 4078 13836 4224 4077 13837 4226 4079 13838 4225 4078 13839 4222 4075 13840 4224 4077 13841 4227 4080 13842 4226 4079 13843 4228 4081 13844 4227 4080 13845 4225 4078 13846 4226 4079 13847 4227 4080 13848 4228 4081 13849 4229 4082 13850 4230 4083 13851 4229 4082 13852 4231 4084 13853 4230 4083 13854 4227 4080 13855 4229 4082 13856 4232 4085 13857 4231 4084 13858 4233 4086 13859 4232 4085 13860 4230 4083 13861 4231 4084 13862 4028 3879 13863 4234 4087 13864 4022 3873 13865 4235 4088 13866 4233 4086 13867 4236 4089 13868 4235 4088 13869 4232 4085 13870 4233 4086 13871 4237 4090 13872 4235 4088 13873 4236 4089 13874 4238 4091 13875 4239 4092 13876 4240 4093 13877 4241 4094 13878 4238 4091 13879 4240 4093 13880 4242 4095 13881 4219 4072 13882 4222 4075 13883 4243 4096 13884 4222 4075 13885 4225 4078 13886 4243 4096 13887 4242 4095 13888 4222 4075 13889 4244 4097 13890 4225 4078 13891 4227 4080 13892 4244 4097 13893 4243 4096 13894 4225 4078 13895 4245 4098 13896 4227 4080 13897 4230 4083 13898 4245 4098 13899 4244 4097 13900 4227 4080 13901 4246 4099 13902 4230 4083 13903 4232 4085 13904 4246 4099 13905 4245 4098 13906 4230 4083 13907 4247 4100 13908 4232 4085 13909 4235 4088 13910 4247 4100 13911 4246 4099 13912 4232 4085 13913 4247 4100 13914 4235 4088 13915 4237 4090 13916 4248 4101 13917 4247 4100 13918 4237 4090 13919 4249 4102 13920 4250 4103 13921 4239 4092 13922 4249 4102 13923 4239 4092 13924 4251 4104 13925 4238 4091 13926 4251 4104 13927 4239 4092 13928 4252 4105 13929 4253 4105 13930 4254 4105 13931 4255 4106 13932 4211 4064 13933 4210 4063 13934 4256 4107 13935 4257 4107 13936 4253 4107 13937 4258 4108 13938 4253 4108 13939 4252 4108 13940 4259 4109 13941 4260 4109 13942 4253 4109 13943 4261 4110 13944 4253 4110 13945 4260 4110 13946 4262 4111 13947 4259 4111 13948 4253 4111 13949 4263 4112 13950 4262 4112 13951 4253 4112 13952 4258 4113 13953 4263 4113 13954 4253 4113 13955 4261 4114 13956 4264 4114 13957 4253 4114 13958 4265 4115 13959 4253 4115 13960 4264 4115 13961 4265 4116 13962 4266 4116 13963 4253 4116 13964 4267 4117 13965 4253 4117 13966 4266 4117 13967 4267 4118 13968 4256 4118 13969 4253 4118 13970 4268 4119 13971 4254 4119 13972 4269 4119 13973 4268 4120 13974 4252 4120 13975 4254 4120 13976 4270 4121 13977 4269 4121 13978 4271 4121 13979 4270 4122 13980 4268 4122 13981 4269 4122 13982 4272 4123 13983 4271 4123 13984 4273 4123 13985 4272 4124 13986 4270 4124 13987 4271 4124 13988 4274 4125 13989 4273 4125 13990 4275 4125 13991 4274 4126 13992 4272 4126 13993 4273 4126 13994 4276 4127 13995 4275 4127 13996 4277 4127 13997 4276 4128 13998 4274 4128 13999 4275 4128 14000 4278 4129 14001 4279 4129 14002 4277 4129 14003 4276 4130 14004 4277 4130 14005 4279 4130 14006 4212 4065 14007 4214 4067 14008 4280 4131 14009 4281 4132 14010 4282 4132 14011 4257 4132 14012 4283 4133 14013 4281 4133 14014 4257 4133 14015 4256 4134 14016 4283 4134 14017 4257 4134 14018 4284 4135 14019 4285 4136 14020 4286 4137 14021 4284 4135 14022 4286 4137 14023 4287 4138 14024 4288 4139 14025 4289 4139 14026 4282 4139 14027 4215 4068 14028 4212 4065 14029 4290 4140 14030 4281 4141 14031 4288 4141 14032 4282 4141 14033 4291 4142 14034 4292 4142 14035 4289 4142 14036 4293 4143 14037 4290 4140 14038 4294 4144 14039 4288 4145 14040 4291 4145 14041 4289 4145 14042 4295 4146 14043 4215 4068 14044 4290 4140 14045 4293 4143 14046 4295 4146 14047 4290 4140 14048 4296 4147 14049 4297 4147 14050 4292 4147 14051 4298 4148 14052 4294 4144 14053 4299 4149 14054 4300 4150 14055 4296 4150 14056 4292 4150 14057 4291 4151 14058 4300 4151 14059 4292 4151 14060 4301 4152 14061 4293 4143 14062 4294 4144 14063 4298 4148 14064 4301 4152 14065 4294 4144 14066 4302 4153 14067 4303 4153 14068 4297 4153 14069 4304 4154 14070 4299 4149 14071 4305 4155 14072 4296 4156 14073 4302 4156 14074 4297 4156 14075 4306 4157 14076 4298 4148 14077 4299 4149 14078 4304 4154 14079 4306 4157 14080 4299 4149 14081 4307 4158 14082 4308 4158 14083 4303 4158 14084 4309 4159 14085 4305 4155 14086 4310 4160 14087 4302 4161 14088 4307 4161 14089 4303 4161 14090 4309 4159 14091 4304 4154 14092 4305 4155 14093 4307 4162 14094 4311 4162 14095 4308 4162 14096 4312 4163 14097 4313 4164 14098 4314 4165 14099 4315 4166 14100 4313 4164 14101 4312 4163 14102 4309 4159 14103 4310 4160 14104 4316 4167 14105 4312 4163 14106 4314 4165 14107 4317 4168 14108 4318 4169 14109 4319 4170 14110 4320 4171 14111 4321 4172 14112 4320 4171 14113 4322 4173 14114 4323 4174 14115 4318 4169 14116 4320 4171 14117 4324 4175 14118 4323 4174 14119 4320 4171 14120 4325 4176 14121 4324 4175 14122 4320 4171 14123 4321 4172 14124 4325 4176 14125 4320 4171 14126 4326 4177 14127 4322 4173 14128 4327 4178 14129 4328 4179 14130 4321 4172 14131 4322 4173 14132 4326 4177 14133 4328 4179 14134 4322 4173 14135 4329 4180 14136 4327 4178 14137 4330 4181 14138 4331 4182 14139 4326 4177 14140 4327 4178 14141 4329 4180 14142 4331 4182 14143 4327 4178 14144 4332 4183 14145 4330 4181 14146 4333 4184 14147 4334 4185 14148 4329 4180 14149 4330 4181 14150 4332 4183 14151 4334 4185 14152 4330 4181 14153 4335 4186 14154 4333 4184 14155 4336 4187 14156 4337 4188 14157 4332 4183 14158 4333 4184 14159 4335 4186 14160 4337 4188 14161 4333 4184 14162 4258 4189 14163 4252 4189 14164 4281 4189 14165 4338 4190 14166 4339 4191 14167 4340 4192 14168 4258 4193 14169 4281 4193 14170 4341 4193 14171 4342 4194 14172 4341 4194 14173 4281 4194 14174 4343 4195 14175 4342 4195 14176 4281 4195 14177 4344 4196 14178 4343 4196 14179 4281 4196 14180 4345 4197 14181 4344 4197 14182 4281 4197 14183 4346 4198 14184 4345 4198 14185 4281 4198 14186 4347 4199 14187 4346 4199 14188 4281 4199 14189 4283 4200 14190 4347 4200 14191 4281 4200 14192 4348 4201 14193 4339 4191 14194 4338 4190 14195 4335 4186 14196 4336 4187 14197 4349 4202 14198 4350 4203 14199 4351 4204 14200 4352 4205 14201 4353 4206 14202 4352 4205 14203 4354 4207 14204 4355 4208 14205 4350 4203 14206 4352 4205 14207 4353 4206 14208 4355 4208 14209 4352 4205 14210 4356 4209 14211 4354 4207 14212 4357 4210 14213 4356 4209 14214 4353 4206 14215 4354 4207 14216 4358 4211 14217 4357 4210 14218 4359 4212 14219 4358 4211 14220 4356 4209 14221 4357 4210 14222 4360 4213 14223 4359 4212 14224 4285 4136 14225 4360 4213 14226 4358 4211 14227 4359 4212 14228 4284 4135 14229 4360 4213 14230 4285 4136 14231 4342 4214 14232 4361 4214 14233 4341 4214 14234 4362 4215 14235 4363 4215 14236 4364 4215 14237 4369 4216 14238 4370 4216 14239 4371 4216 14240 4408 4217 14241 4409 4217 14242 4410 4217 14243 4411 4218 14244 4412 4218 14245 4413 4218 14246 4424 4219 14247 4425 4219 14248 4426 4219 14249 4434 4220 14250 4435 4220 14251 4436 4220 14252 4437 4221 14253 4436 4221 14254 4435 4221 14255 4441 4222 14256 4442 4222 14257 4443 4222 14258 4441 4223 14259 4444 4223 14260 4442 4223 14261 4445 4224 14262 4446 4224 14263 4444 4224 14264 4441 4225 14265 4445 4225 14266 4444 4225 14267 4447 4226 14268 4448 4226 14269 4446 4226 14270 4445 4227 14271 4447 4227 14272 4446 4227 14273 4449 4228 14274 4450 4228 14275 4448 4228 14276 4447 4229 14277 4449 4229 14278 4448 4229 14279 4451 4230 14280 4452 4230 14281 4450 4230 14282 4449 4231 14283 4451 4231 14284 4450 4231 14285 4453 4232 14286 4454 4232 14287 4452 4232 14288 4451 4233 14289 4453 4233 14290 4452 4233 14291 4455 4234 14292 4456 4234 14293 4454 4234 14294 4453 4235 14295 4455 4235 14296 4454 4235 14297 4457 4236 14298 4458 4236 14299 4456 4236 14300 4455 4237 14301 4457 4237 14302 4456 4237 14303 4457 4238 14304 4459 4238 14305 4458 4238 14306 4483 4239 14307 4484 4240 14308 4485 4241 14309 4486 4242 14310 4487 4243 14311 4488 4244 14312 4489 4245 14313 4483 4239 14314 4485 4241 14315 4490 4246 14316 4489 4245 14317 4485 4241 14318 4491 4247 14319 4487 4243 14320 4486 4242 14321 4492 4248 14322 4493 4248 14323 4494 4248 14324 4491 4247 14325 4486 4242 14326 4495 4249 14327 4491 4247 14328 4495 4249 14329 4496 4250 14330 4497 4251 14331 4496 4250 14332 4498 4252 14333 4491 4247 14334 4496 4250 14335 4497 4251 14336 4497 4251 14337 4498 4252 14338 4499 4253 14339 4500 4254 14340 4499 4253 14341 4501 4255 14342 4497 4251 14343 4499 4253 14344 4500 4254 14345 4500 4254 14346 4501 4255 14347 4502 4256 14348 4503 4257 14349 4502 4256 14350 4504 4258 14351 4500 4254 14352 4502 4256 14353 4503 4257 14354 4505 4259 14355 4504 4258 14356 4506 4260 14357 4503 4257 14358 4504 4258 14359 4505 4259 14360 4505 4259 14361 4506 4260 14362 4507 4261 14363 4508 4262 14364 4507 4261 14365 4509 4263 14366 4505 4259 14367 4507 4261 14368 4508 4262 14369 4508 4262 14370 4509 4263 14371 4510 4264 14372 4508 4262 14373 4510 4264 14374 4511 4265 14375 4512 4266 14376 4513 4267 14377 4514 4268 14378 4515 4269 14379 4516 4270 14380 4512 4266 14381 4514 4268 14382 4515 4269 14383 4512 4266 14384 4516 4270 14385 4517 4271 14386 4512 4266 14387 4518 4272 14388 4512 4266 14389 4517 4271 14390 4519 4273 14391 4520 4273 14392 4521 4273 14393 4522 4274 14394 4523 4275 14395 4524 4276 14396 4525 4277 14397 4526 4277 14398 4527 4277 14399 4528 4278 14400 4522 4274 14401 4524 4276 14402 4529 4279 14403 4530 4280 14404 4522 4274 14405 4531 4281 14406 4532 4281 14407 4533 4281 14408 4534 4282 14409 4529 4279 14410 4522 4274 14411 4535 4283 14412 4534 4282 14413 4522 4274 14414 4528 4278 14415 4535 4283 14416 4522 4274 14417 4536 4284 14418 4537 4284 14419 4538 4284 14420 4624 4285 14421 4625 4286 14422 4626 4287 14423 4624 4285 14424 4627 4288 14425 4625 4286 14426 4628 4289 14427 4626 4287 14428 4629 4290 14429 4630 4291 14430 4624 4285 14431 4626 4287 14432 4628 4289 14433 4630 4291 14434 4626 4287 14435 4631 4292 14436 4629 4290 14437 4632 4293 14438 4631 4292 14439 4628 4289 14440 4629 4290 14441 4633 4294 14442 4631 4292 14443 4632 4293 14444 4634 4295 14445 4633 4294 14446 4632 4293 14447 4635 4296 14448 4636 4297 14449 4637 4298 14450 4638 4299 14451 4637 4298 14452 4639 4300 14453 4638 4299 14454 4635 4296 14455 4637 4298 14456 4638 4299 14457 4639 4300 14458 4640 4301 14459 4641 4302 14460 4640 4301 14461 4642 4303 14462 4641 4302 14463 4638 4299 14464 4640 4301 14465 4643 4304 14466 4642 4303 14467 4644 4305 14468 4643 4304 14469 4641 4302 14470 4642 4303 14471 4645 4306 14472 4644 4305 14473 4646 4307 14474 4645 4306 14475 4643 4304 14476 4644 4305 14477 4647 4308 14478 4635 4296 14479 4638 4299 14480 4648 4309 14481 4638 4299 14482 4641 4302 14483 4648 4309 14484 4647 4308 14485 4638 4299 14486 4649 4310 14487 4641 4302 14488 4643 4304 14489 4649 4310 14490 4648 4309 14491 4641 4302 14492 4650 4311 14493 4643 4304 14494 4645 4306 14495 4650 4311 14496 4649 4310 14497 4643 4304 14498 4651 4312 14499 4652 4312 14500 4653 4312 14501 4654 4313 14502 4655 4314 14503 4656 4315 14504 4657 4316 14505 4658 4317 14506 4659 4318 14507 4654 4313 14508 4656 4315 14509 4660 4319 14510 4654 4313 14511 4660 4319 14512 4661 4320 14513 4654 4313 14514 4661 4320 14515 4662 4321 14516 4654 4313 14517 4662 4321 14518 4663 4322 14519 4664 4323 14520 4665 4324 14521 4666 4325 14522 4657 4316 14523 4659 4318 14524 4667 4326 14525 4668 4327 14526 4669 4328 14527 4670 4329 14528 4671 4330 14529 4666 4325 14530 4672 4331 14531 4673 4332 14532 4664 4323 14533 4666 4325 14534 4673 4332 14535 4666 4325 14536 4671 4330 14537 4674 4333 14538 4672 4331 14539 4675 4334 14540 4671 4330 14541 4672 4331 14542 4674 4333 14543 4676 4335 14544 4675 4334 14545 4677 4336 14546 4674 4333 14547 4675 4334 14548 4676 4335 14549 4678 4337 14550 4677 4336 14551 4679 4338 14552 4676 4335 14553 4677 4336 14554 4678 4337 14555 4680 4339 14556 4679 4338 14557 4681 4340 14558 4678 4337 14559 4679 4338 14560 4680 4339 14561 4680 4339 14562 4681 4340 14563 4682 4341 14564 4657 4316 14565 4667 4326 14566 4683 4342 14567 4668 4327 14568 4684 4343 14569 4669 4328 14570 4685 4344 14571 4657 4316 14572 4683 4342 14573 4686 4345 14574 4687 4346 14575 4688 4347 14576 4689 4348 14577 4684 4343 14578 4668 4327 14579 4690 4349 14580 4691 4350 14581 4692 4351 14582 4693 4352 14583 4687 4346 14584 4686 4345 14585 4694 4353 14586 4695 4354 14587 4696 4355 14588 4694 4353 14589 4697 4356 14590 4695 4354 14591 4698 4357 14592 4699 4358 14593 4700 4359 14594 4701 4360 14595 4702 4361 14596 4703 4362 14597 4704 4363 14598 4698 4357 14599 4700 4359 14600 4705 4364 14601 4706 4365 14602 4707 4366 14603 4705 4364 14604 4707 4366 14605 4708 4367 14606 4701 4360 14607 4709 4368 14608 4702 4361 14609 4710 4369 14610 4711 4370 14611 4699 4358 14612 4712 4371 14613 4703 4362 14614 4713 4372 14615 4698 4357 14616 4710 4369 14617 4699 4358 14618 4712 4371 14619 4701 4360 14620 4703 4362 14621 4714 4373 14622 4715 4374 14623 4711 4370 14624 4716 4375 14625 4713 4372 14626 4717 4376 14627 4710 4369 14628 4714 4373 14629 4711 4370 14630 4716 4375 14631 4712 4371 14632 4713 4372 14633 4689 4348 14634 4668 4327 14635 4715 4374 14636 4673 4332 14637 4717 4376 14638 4664 4323 14639 4714 4373 14640 4689 4348 14641 4715 4374 14642 4673 4332 14643 4716 4375 14644 4717 4376 14645 4718 4377 14646 4692 4351 14647 4719 4378 14648 4718 4377 14649 4690 4349 14650 4692 4351 14651 4720 4379 14652 4719 4378 14653 4721 4380 14654 4718 4377 14655 4719 4378 14656 4720 4379 14657 4722 4381 14658 4721 4380 14659 4723 4382 14660 4724 4383 14661 4721 4380 14662 4722 4381 14663 4720 4379 14664 4721 4380 14665 4724 4383 14666 4704 4363 14667 4725 4384 14668 4698 4357 14669 4726 4385 14670 4723 4382 14671 4727 4386 14672 4722 4381 14673 4723 4382 14674 4726 4385 14675 4705 4364 14676 4728 4387 14677 4706 4365 14678 4729 4388 14679 4728 4387 14680 4705 4364 14681 4730 4389 14682 4731 4390 14683 4732 4391 14684 4733 4392 14685 4734 4393 14686 4731 4390 14687 4735 4394 14688 4733 4392 14689 4731 4390 14690 4730 4389 14691 4735 4394 14692 4731 4390 14693 4736 4395 14694 4732 4391 14695 4737 4396 14696 4736 4395 14697 4730 4389 14698 4732 4391 14699 4738 4397 14700 4737 4396 14701 4739 4398 14702 4738 4397 14703 4736 4395 14704 4737 4396 14705 4740 4399 14706 4741 4400 14707 4739 4398 14708 4742 4401 14709 4739 4398 14710 4741 4400 14711 4743 4402 14712 4740 4399 14713 4739 4398 14714 4744 4403 14715 4743 4402 14716 4739 4398 14717 4745 4404 14718 4744 4403 14719 4739 4398 14720 4746 4405 14721 4745 4404 14722 4739 4398 14723 4747 4406 14724 4746 4405 14725 4739 4398 14726 4748 4407 14727 4747 4406 14728 4739 4398 14729 4749 4408 14730 4748 4407 14731 4739 4398 14732 4742 4401 14733 4738 4397 14734 4739 4398 14735 4750 4409 14736 4751 4410 14737 4752 4411 14738 4753 4412 14739 4742 4401 14740 4741 4400 14741 4750 4409 14742 4754 4413 14743 4751 4410 14744 4755 4414 14745 4752 4411 14746 4756 4415 14747 4750 4409 14748 4752 4411 14749 4755 4414 14750 4757 4416 14751 4756 4415 14752 4758 4417 14753 4755 4414 14754 4756 4415 14755 4757 4416 14756 4759 4418 14757 4758 4417 14758 4760 4419 14759 4757 4416 14760 4758 4417 14761 4759 4418 14762 4761 4420 14763 4760 4419 14764 4762 4421 14765 4759 4418 14766 4760 4419 14767 4761 4420 14768 4761 4420 14769 4762 4421 14770 4763 4422 14771 4764 4423 14772 4763 4422 14773 4765 4424 14774 4761 4420 14775 4763 4422 14776 4764 4423 14777 4766 4425 14778 4765 4424 14779 4767 4426 14780 4764 4423 14781 4765 4424 14782 4766 4425 14783 4766 4425 14784 4767 4426 14785 4768 4427 14786 4769 4428 14787 4770 4429 14788 4771 4430 14789 4769 4428 14790 4772 4431 14791 4770 4429 14792 4769 4428 14793 4771 4430 14794 4773 4432 14795 4774 4433 14796 4735 4394 14797 4730 4389 14798 4775 4434 14799 4773 4432 14800 4776 4435 14801 4775 4434 14802 4769 4428 14803 4773 4432 14804 4705 4364 14805 4730 4389 14806 4736 4395 14807 4708 4367 14808 4774 4433 14809 4730 4389 14810 4705 4364 14811 4708 4367 14812 4730 4389 14813 4777 4436 14814 4736 4395 14815 4738 4397 14816 4777 4436 14817 4705 4364 14818 4736 4395 14819 4778 4437 14820 4738 4397 14821 4742 4401 14822 4778 4437 14823 4777 4436 14824 4738 4397 14825 4779 4438 14826 4780 4439 14827 4742 4401 14828 4781 4440 14829 4742 4401 14830 4780 4439 14831 4782 4441 14832 4779 4438 14833 4742 4401 14834 4783 4442 14835 4782 4441 14836 4742 4401 14837 4784 4443 14838 4783 4442 14839 4742 4401 14840 4785 4444 14841 4784 4443 14842 4742 4401 14843 4786 4445 14844 4785 4444 14845 4742 4401 14846 4753 4412 14847 4786 4445 14848 4742 4401 14849 4781 4440 14850 4778 4437 14851 4742 4401 14852 4787 4446 14853 4788 4447 14854 4789 4448 14855 4790 4449 14856 4781 4440 14857 4780 4439 14858 4791 4450 14859 4792 4451 14860 4788 4447 14861 4791 4450 14862 4788 4447 14863 4787 4446 14864 4793 4452 14865 4789 4448 14866 4794 4453 14867 4787 4446 14868 4789 4448 14869 4793 4452 14870 4793 4452 14871 4794 4453 14872 4795 4454 14873 4796 4455 14874 4795 4454 14875 4797 4456 14876 4793 4452 14877 4795 4454 14878 4796 4455 14879 4798 4457 14880 4797 4456 14881 4799 4458 14882 4796 4455 14883 4797 4456 14884 4798 4457 14885 4800 4459 14886 4799 4458 14887 4801 4460 14888 4798 4457 14889 4799 4458 14890 4800 4459 14891 4802 4461 14892 4801 4460 14893 4754 4413 14894 4800 4459 14895 4801 4460 14896 4802 4461 14897 4802 4461 14898 4754 4413 14899 4750 4409 14900 4701 4360 14901 4776 4435 14902 4709 4368 14903 4701 4360 14904 4775 4434 14905 4776 4435 14906 4803 4462 14907 4705 4364 14908 4777 4436 14909 4804 4463 14910 4729 4388 14911 4705 4364 14912 4805 4464 14913 4804 4463 14914 4705 4364 14915 4806 4465 14916 4805 4464 14917 4705 4364 14918 4803 4462 14919 4806 4465 14920 4705 4364 14921 4807 4466 14922 4777 4436 14923 4778 4437 14924 4807 4466 14925 4803 4462 14926 4777 4436 14927 4808 4467 14928 4778 4437 14929 4781 4440 14930 4808 4467 14931 4807 4466 14932 4778 4437 14933 4809 4468 14934 4810 4469 14935 4781 4440 14936 4811 4470 14937 4781 4440 14938 4810 4469 14939 4812 4471 14940 4809 4468 14941 4781 4440 14942 4813 4472 14943 4812 4471 14944 4781 4440 14945 4814 4473 14946 4813 4472 14947 4781 4440 14948 4815 4474 14949 4814 4473 14950 4781 4440 14951 4816 4475 14952 4815 4474 14953 4781 4440 14954 4817 4476 14955 4816 4475 14956 4781 4440 14957 4818 4477 14958 4817 4476 14959 4781 4440 14960 4790 4449 14961 4818 4477 14962 4781 4440 14963 4811 4470 14964 4808 4467 14965 4781 4440 14966 4819 4478 14967 4820 4479 14968 4821 4480 14969 4822 4481 14970 4811 4470 14971 4810 4469 14972 4823 4482 14973 4822 4481 14974 4810 4469 14975 4824 4483 14976 4823 4482 14977 4810 4469 14978 4825 4484 14979 4824 4483 14980 4810 4469 14981 4826 4485 14982 4825 4484 14983 4810 4469 14984 4827 4486 14985 4826 4485 14986 4810 4469 14987 4828 4487 14988 4827 4486 14989 4810 4469 14990 4829 4488 14991 4828 4487 14992 4810 4469 14993 4819 4478 14994 4830 4489 14995 4820 4479 14996 4831 4490 14997 4821 4480 14998 4832 4491 14999 4819 4478 15000 4821 4480 15001 4831 4490 15002 4833 4492 15003 4832 4491 15004 4834 4493 15005 4831 4490 15006 4832 4491 15007 4833 4492 15008 4835 4494 15009 4834 4493 15010 4836 4495 15011 4833 4492 15012 4834 4493 15013 4835 4494 15014 4835 4494 15015 4836 4495 15016 4837 4496 15017 4838 4497 15018 4837 4496 15019 4839 4498 15020 4835 4494 15021 4837 4496 15022 4838 4497 15023 4840 4499 15024 4839 4498 15025 4841 4500 15026 4838 4497 15027 4839 4498 15028 4840 4499 15029 4840 4499 15030 4841 4500 15031 4842 4501 15032 4843 4502 15033 4842 4501 15034 4792 4451 15035 4840 4499 15036 4842 4501 15037 4843 4502 15038 4843 4502 15039 4792 4451 15040 4791 4450 15041 4722 4381 15042 4726 4385 15043 4844 4503 15044 4722 4381 15045 4844 4503 15046 4845 4504 15047 4846 4505 15048 4845 4504 15049 4847 4506 15050 4722 4381 15051 4845 4504 15052 4846 4505 15053 4848 4507 15054 4849 4508 15055 4850 4509 15056 4846 4505 15057 4847 4506 15058 4851 4510 15059 4852 4511 15060 4853 4512 15061 4854 4513 15062 4852 4511 15063 4854 4513 15064 4855 4514 15065 4856 4515 15066 4850 4509 15067 4857 4516 15068 4858 4517 15069 4859 4517 15070 4860 4517 15071 4861 4518 15072 4848 4507 15073 4850 4509 15074 4856 4515 15075 4861 4518 15076 4850 4509 15077 4862 4519 15078 4857 4516 15079 4863 4520 15080 4862 4519 15081 4856 4515 15082 4857 4516 15083 4811 4470 15084 4864 4521 15085 4808 4467 15086 4865 4522 15087 4863 4520 15088 4866 4523 15089 4865 4522 15090 4862 4519 15091 4863 4520 15092 4867 4524 15093 4868 4524 15094 4869 4524 15095 4865 4522 15096 4866 4523 15097 4870 4525 15098 4871 4526 15099 4872 4527 15100 4873 4528 15101 4874 4529 15102 4873 4528 15103 4875 4530 15104 4874 4529 15105 4871 4526 15106 4873 4528 15107 4874 4529 15108 4875 4530 15109 4876 4531 15110 4877 4532 15111 4876 4531 15112 4878 4533 15113 4874 4529 15114 4876 4531 15115 4877 4532 15116 4879 4534 15117 4880 4535 15118 4828 4487 15119 4881 4536 15120 4878 4533 15121 4882 4537 15122 4829 4488 15123 4879 4534 15124 4828 4487 15125 4877 4532 15126 4878 4533 15127 4881 4536 15128 4883 4538 15129 4884 4539 15130 4880 4535 15131 4885 4540 15132 4882 4537 15133 4886 4541 15134 4879 4534 15135 4883 4538 15136 4880 4535 15137 4881 4536 15138 4882 4537 15139 4885 4540 15140 4887 4542 15141 4886 4541 15142 4888 4543 15143 4885 4540 15144 4886 4541 15145 4887 4542 15146 4887 4542 15147 4888 4543 15148 4889 4544 15149 4890 4545 15150 4889 4544 15151 4830 4489 15152 4887 4542 15153 4889 4544 15154 4890 4545 15155 4890 4545 15156 4830 4489 15157 4819 4478 15158 4891 4546 15159 4772 4431 15160 4769 4428 15161 4891 4546 15162 4892 4547 15163 4772 4431 15164 4893 4548 15165 4769 4428 15166 4775 4434 15167 4893 4548 15168 4891 4546 15169 4769 4428 15170 4712 4371 15171 4775 4434 15172 4701 4360 15173 4712 4371 15174 4893 4548 15175 4775 4434 15176 4894 4549 15177 4892 4547 15178 4891 4546 15179 4894 4549 15180 4895 4550 15181 4892 4547 15182 4896 4551 15183 4891 4546 15184 4893 4548 15185 4896 4551 15186 4894 4549 15187 4891 4546 15188 4897 4552 15189 4893 4548 15190 4712 4371 15191 4897 4552 15192 4896 4551 15193 4893 4548 15194 4716 4375 15195 4897 4552 15196 4712 4371 15197 4678 4337 15198 4895 4550 15199 4894 4549 15200 4678 4337 15201 4680 4339 15202 4895 4550 15203 4676 4335 15204 4894 4549 15205 4896 4551 15206 4676 4335 15207 4678 4337 15208 4894 4549 15209 4674 4333 15210 4896 4551 15211 4897 4552 15212 4674 4333 15213 4676 4335 15214 4896 4551 15215 4671 4330 15216 4897 4552 15217 4716 4375 15218 4671 4330 15219 4674 4333 15220 4897 4552 15221 4673 4332 15222 4671 4330 15223 4716 4375 15224 4898 4553 15225 4899 4554 15226 4900 4555 15227 4901 4556 15228 4902 4557 15229 4903 4558 15230 4904 4559 15231 4898 4553 15232 4900 4555 15233 4905 4560 15234 4906 4561 15235 4907 4562 15236 4908 4563 15237 4905 4560 15238 4907 4562 15239 4898 4553 15240 4909 4564 15241 4899 4554 15242 4910 4565 15243 4903 4558 15244 4911 4566 15245 4910 4565 15246 4901 4556 15247 4903 4558 15248 4912 4567 15249 4913 4568 15250 4909 4564 15251 4914 4569 15252 4911 4566 15253 4915 4570 15254 4898 4553 15255 4912 4567 15256 4909 4564 15257 4910 4565 15258 4911 4566 15259 4914 4569 15260 4916 4571 15261 4851 4510 15262 4913 4568 15263 4917 4572 15264 4915 4570 15265 4853 4512 15266 4912 4567 15267 4916 4571 15268 4913 4568 15269 4914 4569 15270 4915 4570 15271 4917 4572 15272 4916 4571 15273 4846 4505 15274 4851 4510 15275 4917 4572 15276 4853 4512 15277 4852 4511 15278 4724 4383 15279 4846 4505 15280 4916 4571 15281 4724 4383 15282 4722 4381 15283 4846 4505 15284 4720 4379 15285 4916 4571 15286 4912 4567 15287 4720 4379 15288 4724 4383 15289 4916 4571 15290 4718 4377 15291 4912 4567 15292 4898 4553 15293 4718 4377 15294 4720 4379 15295 4912 4567 15296 4718 4377 15297 4898 4553 15298 4904 4559 15299 4718 4377 15300 4904 4559 15301 4690 4349 15302 4918 4573 15303 4686 4345 15304 4906 4561 15305 4905 4560 15306 4918 4573 15307 4906 4561 15308 4918 4573 15309 4693 4352 15310 4686 4345 15311 4694 4353 15312 4696 4355 15313 4919 4574 15314 4920 4575 15315 4921 4575 15316 4922 4575 15317 4923 4576 15318 4924 4577 15319 4905 4560 15320 4908 4563 15321 4923 4576 15322 4905 4560 15323 4925 4578 15324 4926 4578 15325 4859 4578 15326 4927 4579 15327 4928 4580 15328 4924 4577 15329 4929 4581 15330 4927 4579 15331 4924 4577 15332 4930 4582 15333 4929 4581 15334 4924 4577 15335 4931 4583 15336 4930 4582 15337 4924 4577 15338 4923 4576 15339 4931 4583 15340 4924 4577 15341 4932 4584 15342 4933 4585 15343 4928 4580 15344 4934 4586 15345 4932 4584 15346 4928 4580 15347 4935 4587 15348 4936 4587 15349 4926 4587 15350 4937 4588 15351 4934 4586 15352 4928 4580 15353 4927 4579 15354 4937 4588 15355 4928 4580 15356 4938 4589 15357 4939 4590 15358 4933 4585 15359 4940 4591 15360 4938 4589 15361 4933 4585 15362 4932 4584 15363 4940 4591 15364 4933 4585 15365 4941 4592 15366 4942 4593 15367 4939 4590 15368 4943 4594 15369 4944 4595 15370 4945 4596 15371 4938 4589 15372 4941 4592 15373 4939 4590 15374 4943 4594 15375 4946 4597 15376 4944 4595 15377 4941 4592 15378 4947 4598 15379 4942 4593 15380 4943 4594 15381 4945 4596 15382 4948 4599 15383 4949 4600 15384 4950 4601 15385 4951 4602 15386 4952 4603 15387 4953 4604 15388 4954 4605 15389 4955 4606 15390 4950 4601 15391 4949 4600 15392 4956 4607 15393 4957 4608 15394 4958 4609 15395 4956 4607 15396 4959 4610 15397 4957 4608 15398 4960 4611 15399 4961 4612 15400 4962 4613 15401 4963 4614 15402 4958 4609 15403 4964 4615 15404 4963 4614 15405 4956 4607 15406 4958 4609 15407 4965 4616 15408 4964 4615 15409 4966 4617 15410 4963 4614 15411 4964 4615 15412 4965 4616 15413 4967 4618 15414 4968 4619 15415 4969 4620 15416 4967 4618 15417 4970 4621 15418 4968 4619 15419 4971 4622 15420 4972 4622 15421 4973 4622 15422 4974 4623 15423 4969 4620 15424 4975 4624 15425 4967 4618 15426 4969 4620 15427 4974 4623 15428 4976 4625 15429 4977 4626 15430 4978 4627 15431 4976 4625 15432 4979 4628 15433 4977 4626 15434 4976 4625 15435 4978 4627 15436 4980 4629 15437 4981 4630 15438 4980 4629 15439 4982 4631 15440 4981 4630 15441 4976 4625 15442 4980 4629 15443 4981 4630 15444 4982 4631 15445 4983 4632 15446 4984 4633 15447 4983 4632 15448 4985 4634 15449 4981 4630 15450 4983 4632 15451 4984 4633 15452 4986 4635 15453 4987 4636 15454 4901 4556 15455 4973 4637 15456 4936 4637 15457 4935 4637 15458 4910 4565 15459 4986 4635 15460 4901 4556 15461 4952 4603 15462 4988 4638 15463 4953 4604 15464 4952 4603 15465 4989 4639 15466 4988 4638 15467 4990 4640 15468 4991 4641 15469 4992 4642 15470 4993 4643 15471 4994 4644 15472 4995 4644 15473 4996 4645 15474 4990 4640 15475 4992 4642 15476 4997 4646 15477 4996 4645 15478 4992 4642 15479 4998 4647 15480 4997 4646 15481 4992 4642 15482 4999 4648 15483 4998 4647 15484 4992 4642 15485 5000 4649 15486 4999 4648 15487 4992 4642 15488 5001 4650 15489 5000 4649 15490 4992 4642 15491 5002 4651 15492 5001 4650 15493 4992 4642 15494 5003 4652 15495 5002 4651 15496 4992 4642 15497 5004 4653 15498 5005 4654 15499 5006 4655 15500 5007 4656 15501 5008 4657 15502 5009 4658 15503 5010 4659 15504 5007 4656 15505 5009 4658 15506 5011 4660 15507 5012 4661 15508 5005 4654 15509 5013 4662 15510 5011 4660 15511 5005 4654 15512 5004 4653 15513 5013 4662 15514 5005 4654 15515 5004 4653 15516 5006 4655 15517 5014 4663 15518 5015 4664 15519 5016 4665 15520 5017 4666 15521 5018 4667 15522 5019 4668 15523 5020 4669 15524 5021 4670 15525 5018 4667 15526 5020 4669 15527 5022 4671 15528 5017 4666 15529 5023 4672 15530 5024 4673 15531 5015 4664 15532 5017 4666 15533 5022 4671 15534 5024 4673 15535 5017 4666 15536 5025 4674 15537 5023 4672 15538 5026 4675 15539 5022 4671 15540 5023 4672 15541 5025 4674 15542 5027 4676 15543 5026 4675 15544 5028 4677 15545 5025 4674 15546 5026 4675 15547 5027 4676 15548 5029 4678 15549 5028 4677 15550 5030 4679 15551 5027 4676 15552 5028 4677 15553 5029 4678 15554 5029 4678 15555 5030 4679 15556 5031 4680 15557 5032 4681 15558 5033 4682 15559 4989 4639 15560 5034 4683 15561 5029 4678 15562 5031 4680 15563 4952 4603 15564 5035 4684 15565 4989 4639 15566 5032 4681 15567 4989 4639 15568 5035 4684 15569 4993 4643 15570 5036 4685 15571 5037 4686 15572 5038 4687 15573 5039 4688 15574 5040 4689 15575 5041 4690 15576 5039 4688 15577 5038 4687 15578 5042 4691 15579 5043 4692 15580 5036 4685 15581 5044 4693 15582 5040 4689 15583 5045 4694 15584 5046 4695 15585 5042 4691 15586 5036 4685 15587 4993 4643 15588 5046 4695 15589 5036 4685 15590 5038 4687 15591 5040 4689 15592 5044 4693 15593 5047 4696 15594 5048 4697 15595 5043 4692 15596 5049 4698 15597 5045 4694 15598 5050 4699 15599 5042 4691 15600 5047 4696 15601 5043 4692 15602 5044 4693 15603 5045 4694 15604 5049 4698 15605 5049 4698 15606 5050 4699 15607 5051 4700 15608 5052 4701 15609 5053 4702 15610 5054 4703 15611 5052 4701 15612 5055 4704 15613 5053 4702 15614 5056 4705 15615 5054 4703 15616 5057 4706 15617 5056 4705 15618 5052 4701 15619 5054 4703 15620 5058 4707 15621 5057 4706 15622 5008 4657 15623 5058 4707 15624 5056 4705 15625 5057 4706 15626 5007 4656 15627 5058 4707 15628 5008 4657 15629 5051 4700 15630 5059 4708 15631 5060 4709 15632 5049 4698 15633 5060 4709 15634 5061 4710 15635 5049 4698 15636 5051 4700 15637 5060 4709 15638 5044 4693 15639 5061 4710 15640 5062 4711 15641 5044 4693 15642 5049 4698 15643 5061 4710 15644 5038 4687 15645 5062 4711 15646 5063 4712 15647 5038 4687 15648 5044 4693 15649 5062 4711 15650 5041 4690 15651 5038 4687 15652 5063 4712 15653 5064 4713 15654 5055 4704 15655 5052 4701 15656 5065 4714 15657 5052 4701 15658 5056 4705 15659 5065 4714 15660 5064 4713 15661 5052 4701 15662 5066 4715 15663 5056 4705 15664 5058 4707 15665 5066 4715 15666 5065 4714 15667 5056 4705 15668 5067 4716 15669 5058 4707 15670 5007 4656 15671 5067 4716 15672 5066 4715 15673 5058 4707 15674 5010 4659 15675 5068 4717 15676 5007 4656 15677 5069 4718 15678 5007 4656 15679 5068 4717 15680 5069 4718 15681 5067 4716 15682 5007 4656 15683 5070 4719 15684 5071 4720 15685 5012 4661 15686 5069 4718 15687 5068 4717 15688 5072 4721 15689 5073 4722 15690 5074 4723 15691 5071 4720 15692 5070 4719 15693 5073 4722 15694 5071 4720 15695 5011 4660 15696 5070 4719 15697 5012 4661 15698 5075 4724 15699 5069 4718 15700 5072 4721 15701 5076 4725 15702 5077 4726 15703 5074 4723 15704 5073 4722 15705 5076 4725 15706 5074 4723 15707 5078 4727 15708 5064 4713 15709 5065 4714 15710 5078 4727 15711 5079 4728 15712 5064 4713 15713 5080 4729 15714 5065 4714 15715 5066 4715 15716 5080 4729 15717 5078 4727 15718 5065 4714 15719 5081 4730 15720 5066 4715 15721 5067 4716 15722 5081 4730 15723 5080 4729 15724 5066 4715 15725 5082 4731 15726 5067 4716 15727 5069 4718 15728 5083 4732 15729 5081 4730 15730 5067 4716 15731 5082 4731 15732 5083 4732 15733 5067 4716 15734 5084 4733 15735 5069 4718 15736 5075 4724 15737 5084 4733 15738 5082 4731 15739 5069 4718 15740 5084 4733 15741 5075 4724 15742 5085 4734 15743 5086 4735 15744 5087 4736 15745 5077 4726 15746 5088 4737 15747 5086 4735 15748 5077 4726 15749 5076 4725 15750 5088 4737 15751 5077 4726 15752 5089 4738 15753 5090 4739 15754 5091 4740 15755 5092 4741 15756 5093 4742 15757 5094 4743 15758 5095 4744 15759 5093 4742 15760 5092 4741 15761 5089 4738 15762 5091 4740 15763 5096 4745 15764 5097 4746 15765 5098 4747 15766 5099 4748 15767 5097 4746 15768 5099 4748 15769 5100 4749 15770 5101 4750 15771 5100 4749 15772 5102 4751 15773 5101 4750 15774 5097 4746 15775 5100 4749 15776 5103 4752 15777 5102 4751 15778 5104 4753 15779 5103 4752 15780 5101 4750 15781 5102 4751 15782 5103 4752 15783 5104 4753 15784 5105 4754 15785 5089 4738 15786 5105 4754 15787 5090 4739 15788 5089 4738 15789 5103 4752 15790 5105 4754 15791 5106 4755 15792 5094 4743 15793 5107 4756 15794 5106 4755 15795 5092 4741 15796 5094 4743 15797 5108 4757 15798 5107 4756 15799 5109 4758 15800 5108 4757 15801 5106 4755 15802 5107 4756 15803 5110 4759 15804 5109 4758 15805 5111 4760 15806 5110 4759 15807 5108 4757 15808 5109 4758 15809 5112 4761 15810 5111 4760 15811 5113 4762 15812 5112 4761 15813 5110 4759 15814 5111 4760 15815 5112 4761 15816 5113 4762 15817 5114 4763 15818 5115 4764 15819 5114 4763 15820 5116 4765 15821 5115 4764 15822 5112 4761 15823 5114 4763 15824 5018 4667 15825 5116 4765 15826 5019 4668 15827 5018 4667 15828 5115 4764 15829 5116 4765 15830 5117 4766 15831 5118 4767 15832 5119 4768 15833 5120 4769 15834 5119 4768 15835 5118 4767 15836 5121 4770 15837 5117 4766 15838 5119 4768 15839 5122 4771 15840 5123 4772 15841 5118 4767 15842 5124 4773 15843 5118 4767 15844 5123 4772 15845 5117 4766 15846 5122 4771 15847 5118 4767 15848 5124 4773 15849 5120 4769 15850 5118 4767 15851 5125 4774 15852 5126 4775 15853 5123 4772 15854 5127 4776 15855 5123 4772 15856 5126 4775 15857 5122 4771 15858 5125 4774 15859 5123 4772 15860 5127 4776 15861 5124 4773 15862 5123 4772 15863 5128 4777 15864 5129 4778 15865 5126 4775 15866 5130 4779 15867 5126 4775 15868 5129 4778 15869 5125 4774 15870 5128 4777 15871 5126 4775 15872 5131 4780 15873 5127 4776 15874 5126 4775 15875 5130 4779 15876 5131 4780 15877 5126 4775 15878 5132 4781 15879 5133 4782 15880 5129 4778 15881 5134 4783 15882 5129 4778 15883 5133 4782 15884 5128 4777 15885 5132 4781 15886 5129 4778 15887 5134 4783 15888 5130 4779 15889 5129 4778 15890 5135 4784 15891 5136 4785 15892 5133 4782 15893 5137 4786 15894 5133 4782 15895 5136 4785 15896 5132 4781 15897 5135 4784 15898 5133 4782 15899 5137 4786 15900 5134 4783 15901 5133 4782 15902 5138 4787 15903 5139 4788 15904 5136 4785 15905 5140 4789 15906 5136 4785 15907 5139 4788 15908 5135 4784 15909 5138 4787 15910 5136 4785 15911 5141 4790 15912 5137 4786 15913 5136 4785 15914 5140 4789 15915 5141 4790 15916 5136 4785 15917 5142 4791 15918 5139 4788 15919 5143 4792 15920 5142 4791 15921 5140 4789 15922 5139 4788 15923 5144 4793 15924 5145 4794 15925 5143 4792 15926 5146 4795 15927 5143 4792 15928 5145 4794 15929 5147 4796 15930 5142 4791 15931 5143 4792 15932 5146 4795 15933 5147 4796 15934 5143 4792 15935 5148 4797 15936 5149 4798 15937 5145 4794 15938 5150 4799 15939 5145 4794 15940 5149 4798 15941 5151 4800 15942 5148 4797 15943 5145 4794 15944 5144 4793 15945 5151 4800 15946 5145 4794 15947 5152 4801 15948 5146 4795 15949 5145 4794 15950 5150 4799 15951 5152 4801 15952 5145 4794 15953 5095 4744 15954 5092 4741 15955 5149 4798 15956 5153 4802 15957 5149 4798 15958 5092 4741 15959 5148 4797 15960 5095 4744 15961 5149 4798 15962 5153 4802 15963 5150 4799 15964 5149 4798 15965 5154 4803 15966 5092 4741 15967 5106 4755 15968 5155 4804 15969 5153 4802 15970 5092 4741 15971 5154 4803 15972 5155 4804 15973 5092 4741 15974 5156 4805 15975 5106 4755 15976 5108 4757 15977 5156 4805 15978 5154 4803 15979 5106 4755 15980 5157 4806 15981 5108 4757 15982 5110 4759 15983 5157 4806 15984 5156 4805 15985 5108 4757 15986 5158 4807 15987 5110 4759 15988 5112 4761 15989 5158 4807 15990 5157 4806 15991 5110 4759 15992 5159 4808 15993 5112 4761 15994 5115 4764 15995 5160 4809 15996 5158 4807 15997 5112 4761 15998 5159 4808 15999 5160 4809 16000 5112 4761 16001 5161 4810 16002 5115 4764 16003 5018 4667 16004 5161 4810 16005 5159 4808 16006 5115 4764 16007 5162 4811 16008 5018 4667 16009 5021 4670 16010 5162 4811 16011 5161 4810 16012 5018 4667 16013 5163 4812 16014 5162 4811 16015 5021 4670 16016 5089 4738 16017 5096 4745 16018 5164 4813 16019 5089 4738 16020 5164 4813 16021 5165 4814 16022 5166 4815 16023 5167 4816 16024 5168 4817 16025 5169 4818 16026 5168 4817 16027 5170 4819 16028 5169 4818 16029 5166 4815 16030 5168 4817 16031 5171 4820 16032 5170 4819 16033 5172 4821 16034 5171 4820 16035 5169 4818 16036 5170 4819 16037 5171 4820 16038 5172 4821 16039 5173 4822 16040 5174 4823 16041 5173 4822 16042 5175 4824 16043 5174 4823 16044 5171 4820 16045 5173 4822 16046 5174 4823 16047 5175 4824 16048 5176 4825 16049 5174 4823 16050 5176 4825 16051 5177 4826 16052 5178 4827 16053 5177 4826 16054 5179 4828 16055 5178 4827 16056 5174 4823 16057 5177 4826 16058 5178 4827 16059 5179 4828 16060 5180 4829 16061 5178 4827 16062 5180 4829 16063 5181 4830 16064 5178 4827 16065 5181 4830 16066 5182 4831 16067 5183 4832 16068 5182 4831 16069 5184 4833 16070 5183 4832 16071 5178 4827 16072 5182 4831 16073 5183 4832 16074 5184 4833 16075 5185 4834 16076 5183 4832 16077 5185 4834 16078 5186 4835 16079 5183 4832 16080 5186 4835 16081 5187 4836 16082 5183 4832 16083 5187 4836 16084 5188 4837 16085 5189 4838 16086 5188 4837 16087 5190 4839 16088 5189 4838 16089 5183 4832 16090 5188 4837 16091 5189 4838 16092 5190 4839 16093 5191 4840 16094 5189 4838 16095 5191 4840 16096 5192 4841 16097 5189 4838 16098 5192 4841 16099 5193 4842 16100 5194 4843 16101 5193 4842 16102 5195 4844 16103 5194 4843 16104 5189 4838 16105 5193 4842 16106 5194 4843 16107 5195 4844 16108 5196 4845 16109 5194 4843 16110 5196 4845 16111 5197 4846 16112 5194 4843 16113 5197 4846 16114 5198 4847 16115 5199 4848 16116 5194 4843 16117 5198 4847 16118 5200 4849 16119 5201 4850 16120 5202 4851 16121 5203 4852 16122 5202 4851 16123 5204 4853 16124 5203 4852 16125 5200 4849 16126 5202 4851 16127 5205 4854 16128 5204 4853 16129 5206 4855 16130 5205 4854 16131 5203 4852 16132 5204 4853 16133 5207 4856 16134 5206 4855 16135 5208 4857 16136 5207 4856 16137 5205 4854 16138 5206 4855 16139 5209 4858 16140 5208 4857 16141 5210 4859 16142 5209 4858 16143 5207 4856 16144 5208 4857 16145 5211 4860 16146 5212 4861 16147 5194 4843 16148 5213 4862 16149 5210 4859 16150 5214 4863 16151 5215 4864 16152 5211 4860 16153 5194 4843 16154 5216 4865 16155 5215 4864 16156 5194 4843 16157 5217 4866 16158 5216 4865 16159 5194 4843 16160 5199 4848 16161 5217 4866 16162 5194 4843 16163 5213 4862 16164 5209 4858 16165 5210 4859 16166 4955 4606 16167 5218 4867 16168 5219 4868 16169 5220 4869 16170 5213 4862 16171 5214 4863 16172 4962 4613 16173 5221 4870 16174 5222 4871 16175 4960 4611 16176 4962 4613 16177 5222 4871 16178 4955 4606 16179 4949 4600 16180 5218 4867 16181 5034 4683 16182 5223 4872 16183 5029 4678 16184 5224 4873 16185 5200 4849 16186 5203 4852 16187 5225 4874 16188 5203 4852 16189 5205 4854 16190 5225 4874 16191 5224 4873 16192 5203 4852 16193 5226 4875 16194 5205 4854 16195 5207 4856 16196 5226 4875 16197 5225 4874 16198 5205 4854 16199 5227 4876 16200 5207 4856 16201 5209 4858 16202 5227 4876 16203 5226 4875 16204 5207 4856 16205 5228 4877 16206 5209 4858 16207 5213 4862 16208 5228 4877 16209 5227 4876 16210 5209 4858 16211 5228 4877 16212 5213 4862 16213 5220 4869 16214 5229 4878 16215 5228 4877 16216 5220 4869 16217 4962 4613 16218 5230 4879 16219 5221 4870 16220 5231 4880 16221 5224 4873 16222 5225 4874 16223 5232 4881 16224 5225 4874 16225 5226 4875 16226 5232 4881 16227 5231 4880 16228 5225 4874 16229 5233 4882 16230 5226 4875 16231 5227 4876 16232 5233 4882 16233 5232 4881 16234 5226 4875 16235 5234 4883 16236 5227 4876 16237 5228 4877 16238 5234 4883 16239 5233 4882 16240 5227 4876 16241 5234 4883 16242 5228 4877 16243 5229 4878 16244 5235 4884 16245 5234 4883 16246 5229 4878 16247 5236 4885 16248 5237 4886 16249 5230 4879 16250 5236 4885 16251 5230 4879 16252 4962 4613 16253 5238 4887 16254 5231 4880 16255 5232 4881 16256 5239 4888 16257 5232 4881 16258 5233 4882 16259 5239 4888 16260 5238 4887 16261 5232 4881 16262 5240 4889 16263 5233 4882 16264 5234 4883 16265 5240 4889 16266 5239 4888 16267 5233 4882 16268 5241 4890 16269 5234 4883 16270 5235 4884 16271 5241 4890 16272 5240 4889 16273 5234 4883 16274 5242 4891 16275 5241 4890 16276 5235 4884 16277 5243 4892 16278 5244 4893 16279 5237 4886 16280 5243 4892 16281 5237 4886 16282 5236 4885 16283 5245 4894 16284 5238 4887 16285 5239 4888 16286 5246 4895 16287 5239 4888 16288 5240 4889 16289 5246 4895 16290 5245 4894 16291 5239 4888 16292 5247 4896 16293 5240 4889 16294 5241 4890 16295 5248 4897 16296 5246 4895 16297 5240 4889 16298 5247 4896 16299 5248 4897 16300 5240 4889 16301 5249 4898 16302 5241 4890 16303 5242 4891 16304 5249 4898 16305 5247 4896 16306 5241 4890 16307 5250 4899 16308 5249 4898 16309 5242 4891 16310 5251 4900 16311 5252 4901 16312 5244 4893 16313 5251 4900 16314 5244 4893 16315 5253 4902 16316 5254 4903 16317 5253 4902 16318 5244 4893 16319 5254 4903 16320 5244 4893 16321 5243 4892 16322 5255 4904 16323 5256 4905 16324 5257 4906 16325 5258 4907 16326 5257 4906 16327 5259 4908 16328 5258 4907 16329 5255 4904 16330 5257 4906 16331 5258 4907 16332 5259 4908 16333 5260 4909 16334 5261 4910 16335 5260 4909 16336 5262 4911 16337 5261 4910 16338 5258 4907 16339 5260 4909 16340 5263 4912 16341 5261 4910 16342 5262 4911 16343 5258 4907 16344 5264 4913 16345 5255 4904 16346 5265 4914 16347 5266 4915 16348 5264 4913 16349 5258 4907 16350 5265 4914 16351 5264 4913 16352 5267 4916 16353 5268 4917 16354 5266 4915 16355 5265 4914 16356 5267 4916 16357 5266 4915 16358 5267 4916 16359 5269 4918 16360 5268 4917 16361 5270 4919 16362 5269 4918 16363 5267 4916 16364 5270 4919 16365 5271 4920 16366 5269 4918 16367 5272 4921 16368 5267 4916 16369 5265 4914 16370 5272 4921 16371 5270 4919 16372 5267 4916 16373 5261 4910 16374 5265 4914 16375 5258 4907 16376 5261 4910 16377 5272 4921 16378 5265 4914 16379 5273 4922 16380 5271 4920 16381 5270 4919 16382 5274 4923 16383 5275 4924 16384 5271 4920 16385 5276 4925 16386 5274 4923 16387 5271 4920 16388 5277 4926 16389 5276 4925 16390 5271 4920 16391 5273 4922 16392 5277 4926 16393 5271 4920 16394 5278 4927 16395 5270 4919 16396 5272 4921 16397 5278 4927 16398 5273 4922 16399 5270 4919 16400 5279 4928 16401 5272 4921 16402 5261 4910 16403 5279 4928 16404 5278 4927 16405 5272 4921 16406 5280 4929 16407 5279 4928 16408 5261 4910 16409 5281 4930 16410 5280 4929 16411 5261 4910 16412 5282 4931 16413 5281 4930 16414 5261 4910 16415 5283 4932 16416 5282 4931 16417 5261 4910 16418 5284 4933 16419 5283 4932 16420 5261 4910 16421 5263 4912 16422 5284 4933 16423 5261 4910 16424 5285 4934 16425 5286 4935 16426 5287 4936 16427 5288 4937 16428 5289 4937 16429 5290 4937 16430 5285 4934 16431 5291 4938 16432 5286 4935 16433 5292 4939 16434 5287 4936 16435 5293 4940 16436 5292 4939 16437 5285 4934 16438 5287 4936 16439 5294 4941 16440 5293 4940 16441 5295 4942 16442 5294 4941 16443 5292 4939 16444 5293 4940 16445 5296 4943 16446 5295 4942 16447 5297 4944 16448 5298 4945 16449 5299 4946 16450 5295 4942 16451 5294 4941 16452 5295 4942 16453 5299 4946 16454 5298 4945 16455 5295 4942 16456 5296 4943 16457 5300 4947 16458 5301 4948 16459 5302 4949 16460 5303 4950 16461 5304 4951 16462 5305 4952 16463 5300 4947 16464 5306 4953 16465 5301 4948 16466 5307 4954 16467 5302 4949 16468 5308 4955 16469 5300 4947 16470 5302 4949 16471 5307 4954 16472 5307 4954 16473 5308 4955 16474 5309 4956 16475 5310 4957 16476 5309 4956 16477 5311 4958 16478 5307 4954 16479 5309 4956 16480 5310 4957 16481 5312 4959 16482 5313 4959 16483 5314 4959 16484 5315 4960 16485 5316 4961 16486 5317 4962 16487 5318 4963 16488 5316 4961 16489 5315 4960 16490 5315 4960 16491 5317 4962 16492 5319 4964 16493 5285 4934 16494 5319 4964 16495 5291 4938 16496 5285 4934 16497 5315 4960 16498 5319 4964 16499 5320 4965 16500 5321 4965 16501 5322 4965 16502 5323 4966 16503 5315 4960 16504 5324 4967 16505 5325 4968 16506 5315 4960 16507 5323 4966 16508 5326 4969 16509 5315 4960 16510 5325 4968 16511 5318 4963 16512 5315 4960 16513 5326 4969 16514 5327 4970 16515 5328 4971 16516 5329 4972 16517 5330 4973 16518 5331 4973 16519 5332 4973 16520 5333 4974 16521 5334 4975 16522 5328 4971 16523 4865 4522 16524 5335 4976 16525 5336 4977 16526 5333 4974 16527 5337 4978 16528 5334 4975 16529 5333 4974 16530 5328 4971 16531 5327 4970 16532 5338 4979 16533 5339 4979 16534 5340 4979 16535 4865 4522 16536 5341 4980 16537 5342 4981 16538 4865 4522 16539 5343 4982 16540 5341 4980 16541 4865 4522 16542 5342 4981 16543 5344 4983 16544 4865 4522 16545 5344 4983 16546 5345 4984 16547 4865 4522 16548 5345 4984 16549 5346 4985 16550 4865 4522 16551 5346 4985 16552 5335 4976 16553 4865 4522 16554 4870 4525 16555 5347 4986 16556 4865 4522 16557 5347 4986 16558 5348 4987 16559 4865 4522 16560 5348 4987 16561 5349 4988 16562 4865 4522 16563 5349 4988 16564 5343 4982 16565 5350 4989 16566 4766 4425 16567 4768 4427 16568 5351 4990 16569 5350 4989 16570 4768 4427 16571 5352 4991 16572 4764 4423 16573 4766 4425 16574 5350 4989 16575 5352 4991 16576 4766 4425 16577 5353 4992 16578 4761 4420 16579 4764 4423 16580 5352 4991 16581 5353 4992 16582 4764 4423 16583 5354 4993 16584 4759 4418 16585 4761 4420 16586 5353 4992 16587 5354 4993 16588 4761 4420 16589 5355 4994 16590 4757 4416 16591 4759 4418 16592 5354 4993 16593 5355 4994 16594 4759 4418 16595 5356 4995 16596 4755 4414 16597 4757 4416 16598 5355 4994 16599 5356 4995 16600 4757 4416 16601 5357 4996 16602 4750 4409 16603 4755 4414 16604 5356 4995 16605 5357 4996 16606 4755 4414 16607 5358 4997 16608 4802 4461 16609 4750 4409 16610 5357 4996 16611 5358 4997 16612 4750 4409 16613 5359 4998 16614 4800 4459 16615 4802 4461 16616 5358 4997 16617 5359 4998 16618 4802 4461 16619 5360 4999 16620 4798 4457 16621 4800 4459 16622 5359 4998 16623 5360 4999 16624 4800 4459 16625 5361 5000 16626 4796 4455 16627 4798 4457 16628 5362 5001 16629 5361 5000 16630 4798 4457 16631 5360 4999 16632 5362 5001 16633 4798 4457 16634 5363 5002 16635 4793 4452 16636 4796 4455 16637 5361 5000 16638 5363 5002 16639 4796 4455 16640 5364 5003 16641 4787 4446 16642 4793 4452 16643 5363 5002 16644 5364 5003 16645 4793 4452 16646 5365 5004 16647 4791 4450 16648 4787 4446 16649 5364 5003 16650 5365 5004 16651 4787 4446 16652 5366 5005 16653 4843 4502 16654 4791 4450 16655 5365 5004 16656 5366 5005 16657 4791 4450 16658 5367 5006 16659 4840 4499 16660 4843 4502 16661 5366 5005 16662 5367 5006 16663 4843 4502 16664 5368 5007 16665 4838 4497 16666 4840 4499 16667 5367 5006 16668 5368 5007 16669 4840 4499 16670 5369 5008 16671 4835 4494 16672 4838 4497 16673 5368 5007 16674 5369 5008 16675 4838 4497 16676 5370 5009 16677 4833 4492 16678 4835 4494 16679 5369 5008 16680 5370 5009 16681 4835 4494 16682 5371 5010 16683 4831 4490 16684 4833 4492 16685 5372 5011 16686 5371 5010 16687 4833 4492 16688 5370 5009 16689 5372 5011 16690 4833 4492 16691 5373 5012 16692 4819 4478 16693 4831 4490 16694 5371 5010 16695 5373 5012 16696 4831 4490 16697 5374 5013 16698 4890 4545 16699 4819 4478 16700 5373 5012 16701 5374 5013 16702 4819 4478 16703 5375 5014 16704 4887 4542 16705 4890 4545 16706 5376 5015 16707 5375 5014 16708 4890 4545 16709 5374 5013 16710 5376 5015 16711 4890 4545 16712 5377 5016 16713 4885 4540 16714 4887 4542 16715 5375 5014 16716 5377 5016 16717 4887 4542 16718 5378 5017 16719 4881 4536 16720 4885 4540 16721 5377 5016 16722 5378 5017 16723 4885 4540 16724 5379 5018 16725 4877 4532 16726 4881 4536 16727 5378 5017 16728 5379 5018 16729 4881 4536 16730 5380 5019 16731 4874 4529 16732 4877 4532 16733 5379 5018 16734 5380 5019 16735 4877 4532 16736 5380 5019 16737 5381 5020 16738 4874 4529 16739 5382 5021 16740 5383 5022 16741 5384 5023 16742 5382 5021 16743 5384 5023 16744 5385 5024 16745 5382 5021 16746 5385 5024 16747 5386 5025 16748 5382 5021 16749 5386 5025 16750 5387 5026 16751 5382 5021 16752 5387 5026 16753 5388 5027 16754 5382 5021 16755 5388 5027 16756 5389 5028 16757 5390 5029 16758 5389 5028 16759 5391 5030 16760 5390 5029 16761 5382 5021 16762 5389 5028 16763 5390 5029 16764 5391 5030 16765 5392 5031 16766 5390 5029 16767 5392 5031 16768 5393 5032 16769 5390 5029 16770 5393 5032 16771 5394 5033 16772 5390 5029 16773 5394 5033 16774 5395 5034 16775 4935 492 16776 4926 492 16777 4925 492 16778 5396 5035 16779 4855 4514 16780 5397 5036 16781 4852 4511 16782 4855 4514 16783 5396 5035 16784 5398 5037 16785 5399 5038 16786 5400 5039 16787 5401 5040 16788 5402 5041 16789 5403 5042 16790 5404 5043 16791 5400 5039 16792 5405 5044 16793 5398 5037 16794 5400 5039 16795 5406 5045 16796 5404 5043 16797 5406 5045 16798 5400 5039 16799 5407 492 16800 5408 492 16801 4971 492 16802 5333 4974 16803 5405 5044 16804 5337 4978 16805 5333 4974 16806 5404 5043 16807 5405 5044 16808 4910 4565 16809 5409 5046 16810 4986 4635 16811 4981 4630 16812 4984 4633 16813 5410 5047 16814 4917 4572 16815 5411 5048 16816 5409 5046 16817 5412 5049 16818 5410 5047 16819 5413 5050 16820 4914 4569 16821 4917 4572 16822 5409 5046 16823 4910 4565 16824 4914 4569 16825 5409 5046 16826 4981 4630 16827 5410 5047 16828 5412 5049 16829 4852 4511 16830 5396 5035 16831 5411 5048 16832 5414 5051 16833 5413 5050 16834 5402 5041 16835 4917 4572 16836 4852 4511 16837 5411 5048 16838 5415 5052 16839 5413 5050 16840 5414 5051 16841 5412 5049 16842 5413 5050 16843 5415 5052 16844 5414 5051 16845 5402 5041 16846 5401 5040 16847 4976 4625 16848 5416 5053 16849 4979 4628 16850 4967 4618 16851 4974 4623 16852 5417 5054 16853 5418 5055 16854 5419 5056 16855 5416 5053 16856 5420 5057 16857 5417 5054 16858 5421 5058 16859 5422 5059 16860 5418 5055 16861 5416 5053 16862 4976 4625 16863 5422 5059 16864 5416 5053 16865 4967 4618 16866 5417 5054 16867 5420 5057 16868 5423 5060 16869 5424 5061 16870 5419 5056 16871 5425 5062 16872 5421 5058 16873 5426 5063 16874 5418 5055 16875 5423 5060 16876 5419 5056 16877 5427 5064 16878 5421 5058 16879 5425 5062 16880 5420 5057 16881 5421 5058 16882 5427 5064 16883 5428 5065 16884 5429 5066 16885 5424 5061 16886 5425 5062 16887 5426 5063 16888 5430 5067 16889 5423 5060 16890 5428 5065 16891 5424 5061 16892 5407 5068 16893 5431 5068 16894 5408 5068 16895 5432 5069 16896 5433 5070 16897 5434 5071 16898 5425 5062 16899 5430 5067 16900 5435 5072 16901 4971 5073 16902 5408 5073 16903 4972 5073 16904 5414 5051 16905 5423 5060 16906 5418 5055 16907 5436 5074 16908 5428 5065 16909 5423 5060 16910 5401 5040 16911 5436 5074 16912 5423 5060 16913 4973 492 16914 4972 492 16915 4936 492 16916 5414 5051 16917 5401 5040 16918 5423 5060 16919 5415 5052 16920 5418 5055 16921 5422 5059 16922 5415 5052 16923 5414 5051 16924 5418 5055 16925 5412 5049 16926 5422 5059 16927 4976 4625 16928 5412 5049 16929 5415 5052 16930 5422 5059 16931 4981 4630 16932 5412 5049 16933 4976 4625 16934 5404 5043 16935 5434 5071 16936 5406 5045 16937 5404 5043 16938 5432 5069 16939 5434 5071 16940 4967 4618 16941 5437 5075 16942 4970 4621 16943 4963 4614 16944 4965 4616 16945 5438 5076 16946 5420 5057 16947 5439 5077 16948 5437 5075 16949 5440 5078 16950 5438 5076 16951 5441 5079 16952 4967 4618 16953 5420 5057 16954 5437 5075 16955 4963 4614 16956 5438 5076 16957 5440 5078 16958 5425 5062 16959 5305 4952 16960 5439 5077 16961 5442 5080 16962 5441 5079 16963 5306 4953 16964 5427 5064 16965 5425 5062 16966 5439 5077 16967 5420 5057 16968 5427 5064 16969 5439 5077 16970 5440 5078 16971 5441 5079 16972 5442 5080 16973 5435 5072 16974 5303 4950 16975 5305 4952 16976 5425 5062 16977 5435 5072 16978 5305 4952 16979 5442 5080 16980 5306 4953 16981 5300 4947 16982 4956 4607 16983 5443 5081 16984 4959 4610 16985 5444 5082 16986 5445 5083 16987 5443 5081 16988 5446 5084 16989 5444 5082 16990 5443 5081 16991 4956 4607 16992 5446 5084 16993 5443 5081 16994 5307 4954 16995 5310 4957 16996 5445 5083 16997 5444 5082 16998 5307 4954 16999 5445 5083 17000 5300 4947 17001 5307 4954 17002 5444 5082 17003 5442 5080 17004 5444 5082 17005 5446 5084 17006 5442 5080 17007 5300 4947 17008 5444 5082 17009 5440 5078 17010 5446 5084 17011 4956 4607 17012 5440 5078 17013 5442 5080 17014 5446 5084 17015 4963 4614 17016 5440 5078 17017 4956 4607 17018 5333 4974 17019 5327 4970 17020 5447 5085 17021 5404 5043 17022 5447 5085 17023 5432 5069 17024 5333 4974 17025 5447 5085 17026 5404 5043 17027 5448 492 17028 5449 492 17029 5450 492 17030 5451 492 17031 5449 492 17032 5448 492 17033 5452 5086 17034 5449 5086 17035 5451 5086 17036 5453 492 17037 5450 492 17038 5454 492 17039 5455 5087 17040 5450 5087 17041 5453 5087 17042 5448 5088 17043 5450 5088 17044 5455 5088 17045 5456 492 17046 5454 492 17047 5457 492 17048 5453 492 17049 5454 492 17050 5456 492 17051 5458 5089 17052 5457 5089 17053 5459 5089 17054 5456 5090 17055 5457 5090 17056 5458 5090 17057 5460 492 17058 5459 492 17059 5461 492 17060 5458 5091 17061 5459 5091 17062 5460 5091 17063 5462 492 17064 5461 492 17065 5463 492 17066 5460 492 17067 5461 492 17068 5462 492 17069 5462 492 17070 5463 492 17071 5464 492 17072 5465 492 17073 5464 492 17074 5466 492 17075 5462 5092 17076 5464 5092 17077 5465 5092 17078 5467 492 17079 5466 492 17080 5468 492 17081 5465 5093 17082 5466 5093 17083 5467 5093 17084 5469 492 17085 5451 492 17086 5470 492 17087 5452 5094 17088 5451 5094 17089 5469 5094 17090 5471 492 17091 5470 492 17092 5472 492 17093 5469 492 17094 5470 492 17095 5471 492 17096 5473 5095 17097 5472 5095 17098 5474 5095 17099 5471 5096 17100 5472 5096 17101 5473 5096 17102 5475 492 17103 5474 492 17104 5476 492 17105 5473 5097 17106 5474 5097 17107 5475 5097 17108 5477 492 17109 5476 492 17110 5478 492 17111 5475 492 17112 5476 492 17113 5477 492 17114 5477 492 17115 5478 492 17116 5479 492 17117 5480 492 17118 5479 492 17119 5481 492 17120 5477 5098 17121 5479 5098 17122 5480 5098 17123 5482 492 17124 5481 492 17125 5483 492 17126 5480 5099 17127 5481 5099 17128 5482 5099 17129 5502 5100 17130 5503 5100 17131 5504 5100 17132 5505 5101 17133 5506 5101 17134 5507 5101 17135 5547 5102 17136 5548 5102 17137 5549 5102 17138 6002 5103 17139 6003 5103 17140 6004 5103 17141 6005 5104 17142 6006 5104 17143 6007 5104 17144 6008 5105 17145 6009 5105 17146 6010 5105 17147 6011 5106 17148 6012 5106 17149 6013 5106 17150 6275 5107 17151 6276 5107 17152 6277 5107 17153 6300 5108 17154 6301 5108 17155 6302 5108 17156 6303 5109 17157 6304 5109 17158 6305 5109 17159 6306 5110 17160 6303 5110 17161 6305 5110 17162 6319 5111 17163 6320 5111 17164 6321 5111 17165 6322 5112 17166 6323 5112 17167 6324 5112 17168 6325 5113 17169 6326 5113 17170 6327 5113 17171 6328 5114 17172 6329 5114 17173 6330 5114 17174 6338 5115 17175 6339 5115 17176 6340 5115 17177

-
- - - - -

4365 5116 17178 4366 5117 17179 4367 5118 17180 4365 5116 17181 4368 5119 17182 4366 5117 17183 4372 5120 17184 4373 5120 17185 4374 5120 17186 4375 5121 17187 4376 5121 17188 4377 5121 17189 4378 5122 17190 4379 5122 17191 4380 5122 17192 4381 5123 17193 4382 5124 17194 4383 5125 17195 4384 5126 17196 4381 5123 17197 4383 5125 17198 4385 5121 17199 4386 5121 17200 4387 5121 17201 4388 5127 17202 4389 5127 17203 4390 5127 17204 4391 5128 17205 4388 5128 17206 4390 5128 17207 4392 5129 17208 4393 5129 17209 4394 5129 17210 4395 5121 17211 4385 5121 17212 4387 5121 17213 4396 5130 17214 4397 5130 17215 4398 5130 17216 4392 5131 17217 4394 5131 17218 4399 5131 17219 4400 5121 17220 4401 5121 17221 4402 5121 17222 4396 5132 17223 4398 5132 17224 4403 5132 17225 4404 5133 17226 4405 5133 17227 4406 5133 17228 4400 5134 17229 4402 5134 17230 4407 5134 17231 4414 5135 17232 4415 5136 17233 4416 5135 17234 4414 5135 17235 4417 5136 17236 4415 5136 17237 4418 5137 17238 4419 5137 17239 4420 5137 17240 4421 5138 17241 4422 5138 17242 4423 5138 17243 4427 5139 17244 4428 5139 17245 4429 5139 17246 4430 5121 17247 4431 5121 17248 4432 5121 17249 4433 5121 17250 4430 5121 17251 4432 5121 17252 4438 5140 17253 4439 5140 17254 4440 5140 17255 4460 5141 17256 4461 5142 17257 4462 5143 17258 4460 5141 17259 4463 5144 17260 4461 5142 17261 4464 5145 17262 4462 5143 17263 4465 5146 17264 4464 5145 17265 4460 5141 17266 4462 5143 17267 4464 5145 17268 4465 5146 17269 4466 5147 17270 4467 5122 17271 4468 5122 17272 4469 5122 17273 4464 5145 17274 4466 5147 17275 4470 5148 17276 4471 5149 17277 4472 5149 17278 4473 5149 17279 4467 5150 17280 4469 5150 17281 4474 5150 17282 4471 5151 17283 4473 5151 17284 4475 5151 17285 4476 5121 17286 4477 5121 17287 4478 5121 17288 4479 5152 17289 4480 5152 17290 4481 5152 17291 4482 5153 17292 4479 5153 17293 4481 5153 17294 4539 5154 17295 4540 5154 17296 4541 5154 17297 4542 5155 17298 4543 5155 17299 4544 5155 17300 4545 5156 17301 4542 5156 17302 4544 5156 17303 4546 5157 17304 4547 5157 17305 4542 5157 17306 4548 5158 17307 4542 5158 17308 4545 5158 17309 4548 5159 17310 4549 5159 17311 4542 5159 17312 4546 5160 17313 4542 5160 17314 4549 5160 17315 4550 5161 17316 4551 5161 17317 4547 5161 17318 4552 5162 17319 4550 5162 17320 4547 5162 17321 4553 5163 17322 4552 5163 17323 4547 5163 17324 4546 5164 17325 4553 5164 17326 4547 5164 17327 4554 5165 17328 4555 5165 17329 4556 5165 17330 4548 5166 17331 4545 5166 17332 4555 5166 17333 4554 5167 17334 4548 5167 17335 4555 5167 17336 4557 5168 17337 4556 5168 17338 4558 5168 17339 4559 5169 17340 4554 5169 17341 4556 5169 17342 4560 5170 17343 4559 5170 17344 4556 5170 17345 4561 5171 17346 4560 5171 17347 4556 5171 17348 4557 5172 17349 4561 5172 17350 4556 5172 17351 4562 5173 17352 4558 5173 17353 4563 5173 17354 4564 5174 17355 4558 5174 17356 4562 5174 17357 4565 5175 17358 4557 5175 17359 4558 5175 17360 4566 5176 17361 4565 5176 17362 4558 5176 17363 4567 5177 17364 4566 5177 17365 4558 5177 17366 4568 5178 17367 4567 5178 17368 4558 5178 17369 4564 5179 17370 4568 5179 17371 4558 5179 17372 4569 5180 17373 4563 5180 17374 4570 5180 17375 4562 5181 17376 4563 5181 17377 4569 5181 17378 4571 5182 17379 4570 5182 17380 4572 5182 17381 4569 5183 17382 4570 5183 17383 4571 5183 17384 4573 5184 17385 4572 5184 17386 4574 5184 17387 4571 5185 17388 4572 5185 17389 4573 5185 17390 4564 5186 17391 4562 5186 17392 4551 5186 17393 4575 5187 17394 4564 5187 17395 4551 5187 17396 4576 5188 17397 4575 5188 17398 4551 5188 17399 4577 5189 17400 4576 5189 17401 4551 5189 17402 4550 5190 17403 4577 5190 17404 4551 5190 17405 4578 5191 17406 4579 5191 17407 4580 5191 17408 4581 5192 17409 4582 5192 17410 4583 5192 17411 4581 5193 17412 4583 5193 17413 4584 5193 17414 4585 5122 17415 4586 5122 17416 4587 5122 17417 4588 5194 17418 4578 5194 17419 4580 5194 17420 4589 5195 17421 4590 5196 17422 4591 5197 17423 4592 5122 17424 4585 5122 17425 4587 5122 17426 4593 5198 17427 4591 5197 17428 4594 5199 17429 4589 5195 17430 4591 5197 17431 4593 5198 17432 4595 5200 17433 4594 5199 17434 4596 5201 17435 4593 5198 17436 4594 5199 17437 4595 5200 17438 4597 5202 17439 4596 5201 17440 4598 5203 17441 4595 5200 17442 4596 5201 17443 4597 5202 17444 4599 5204 17445 4598 5203 17446 4600 5205 17447 4597 5202 17448 4598 5203 17449 4599 5204 17450 4601 5206 17451 4600 5205 17452 4602 5207 17453 4599 5204 17454 4600 5205 17455 4601 5206 17456 4603 5208 17457 4602 5207 17458 4604 5209 17459 4601 5206 17460 4602 5207 17461 4603 5208 17462 4605 5210 17463 4604 5209 17464 4606 5211 17465 4603 5208 17466 4604 5209 17467 4605 5210 17468 4607 5212 17469 4606 5211 17470 4608 5213 17471 4605 5210 17472 4606 5211 17473 4607 5212 17474 4609 5214 17475 4608 5213 17476 4610 5215 17477 4607 5212 17478 4608 5213 17479 4609 5214 17480 4611 5216 17481 4610 5215 17482 4612 5217 17483 4609 5214 17484 4610 5215 17485 4611 5216 17486 4613 5218 17487 4612 5217 17488 4614 5219 17489 4611 5216 17490 4612 5217 17491 4613 5218 17492 4615 5220 17493 4614 5219 17494 4616 5221 17495 4613 5218 17496 4614 5219 17497 4615 5220 17498 4617 5221 17499 4616 5221 17500 4618 5222 17501 4615 5220 17502 4616 5221 17503 4617 5221 17504 4619 5223 17505 4618 5222 17506 4620 5224 17507 4617 5221 17508 4618 5222 17509 4619 5223 17510 4621 5225 17511 4620 5224 17512 4622 5226 17513 4619 5223 17514 4620 5224 17515 4621 5225 17516 4621 5225 17517 4622 5226 17518 4623 5226 17519 5484 5227 17520 5485 5227 17521 5486 5227 17522 5487 5228 17523 5488 5228 17524 5489 5228 17525 5490 5229 17526 5491 5229 17527 5492 5229 17528 5493 5230 17529 5494 5230 17530 5495 5230 17531 5487 5231 17532 5489 5231 17533 5496 5231 17534 5497 5122 17535 5498 5122 17536 5499 5122 17537 5493 5232 17538 5495 5232 17539 5500 5232 17540 5497 5233 17541 5499 5233 17542 5501 5233 17543 5508 5234 17544 5509 5235 17545 5510 5236 17546 5508 5234 17547 5511 5237 17548 5509 5235 17549 5512 5238 17550 5513 5238 17551 5514 5238 17552 5515 5239 17553 5512 5239 17554 5514 5239 17555 5516 5240 17556 5517 5240 17557 5518 5240 17558 5519 5241 17559 5516 5241 17560 5518 5241 17561 5520 5242 17562 5519 5242 17563 5518 5242 17564 5521 5243 17565 5520 5243 17566 5518 5243 17567 5522 5244 17568 5523 5244 17569 5524 5244 17570 5525 5245 17571 5526 5245 17572 5523 5245 17573 5522 5246 17574 5525 5246 17575 5523 5246 17576 5522 5247 17577 5527 5247 17578 5525 5247 17579 5528 5248 17580 5529 5248 17581 5527 5248 17582 5530 5249 17583 5528 5249 17584 5527 5249 17585 5522 5250 17586 5530 5250 17587 5527 5250 17588 5530 5251 17589 5531 5251 17590 5528 5251 17591 5532 5252 17592 5533 5253 17593 5534 5252 17594 5535 5254 17595 5536 5255 17596 5533 5253 17597 5532 5252 17598 5535 5254 17599 5533 5253 17600 5537 5256 17601 5538 5256 17602 5539 5256 17603 5540 5257 17604 5541 5257 17605 5542 5257 17606 5543 5258 17607 5544 5259 17608 5545 5260 17609 5543 5258 17610 5546 5261 17611 5544 5259 17612 6278 5133 17613 6279 5133 17614 6280 5133 17615 6281 5262 17616 6282 5262 17617 6283 5262 17618 6284 5263 17619 6285 5263 17620 6286 5263 17621 6287 5264 17622 6288 5264 17623 6289 5264 17624 6290 5265 17625 6291 5265 17626 6292 5265 17627 6293 5266 17628 6294 5266 17629 6295 5266 17630 6296 5267 17631 6293 5267 17632 6295 5267 17633 6297 5268 17634 6298 5268 17635 6299 5268 17636 6307 5227 17637 6308 5227 17638 6309 5227 17639 6310 5256 17640 6311 5256 17641 6312 5256 17642 6313 5269 17643 6314 5269 17644 6315 5269 17645 6316 5270 17646 6317 5270 17647 6318 5270 17648 6331 5122 17649 6332 5122 17650 6333 5122 17651 6334 5271 17652 6335 5272 17653 6336 5273 17654 6334 5271 17655 6337 5274 17656 6335 5272 17657 6341 5121 17658 6342 5121 17659 6343 5121 17660 6344 5275 17661 6345 5275 17662 6346 5275 17663

-
- - - - -

5550 5276 17664 5551 5277 17665 5552 5278 17666 5553 5279 17667 5554 5280 17668 5555 5281 17669 5556 5282 17670 5550 5276 17671 5552 5278 17672 5557 5283 17673 5556 5282 17674 5552 5278 17675 5558 5284 17676 5559 5284 17677 5560 5284 17678 5558 5285 17679 5560 5285 17680 5561 5285 17681 5550 5276 17682 5562 5286 17683 5551 5277 17684 5563 5287 17685 5555 5281 17686 5564 5288 17687 5563 5287 17688 5553 5279 17689 5555 5281 17690 5550 5276 17691 5565 5289 17692 5562 5286 17693 5566 5290 17694 5564 5288 17695 5567 5291 17696 5566 5290 17697 5563 5287 17698 5564 5288 17699 5550 5276 17700 5568 5292 17701 5565 5289 17702 5569 5293 17703 5567 5291 17704 5570 5294 17705 5569 5293 17706 5566 5290 17707 5567 5291 17708 5550 5276 17709 5571 5295 17710 5568 5292 17711 5572 5296 17712 5570 5294 17713 5573 5297 17714 5572 5296 17715 5569 5293 17716 5570 5294 17717 5574 5298 17718 5575 5298 17719 5576 5298 17720 5577 5299 17721 5572 5296 17722 5573 5297 17723 5578 5300 17724 5550 5276 17725 5556 5282 17726 5579 5301 17727 5550 5276 17728 5578 5300 17729 5574 5302 17730 5576 5302 17731 5580 5302 17732 5557 5283 17733 5581 5303 17734 5556 5282 17735 5582 5304 17736 5556 5282 17737 5581 5303 17738 5583 5305 17739 5578 5300 17740 5556 5282 17741 5584 5306 17742 5583 5305 17743 5556 5282 17744 5585 5307 17745 5584 5306 17746 5556 5282 17747 5582 5304 17748 5585 5307 17749 5556 5282 17750 5586 5308 17751 5587 5309 17752 5581 5303 17753 5588 5310 17754 5581 5303 17755 5587 5309 17756 5557 5283 17757 5586 5308 17758 5581 5303 17759 5589 5311 17760 5582 5304 17761 5581 5303 17762 5590 5312 17763 5589 5311 17764 5581 5303 17765 5588 5310 17766 5590 5312 17767 5581 5303 17768 5591 5313 17769 5592 5314 17770 5587 5309 17771 5593 5315 17772 5587 5309 17773 5592 5314 17774 5594 5316 17775 5591 5313 17776 5587 5309 17777 5595 5317 17778 5594 5316 17779 5587 5309 17780 5596 5318 17781 5595 5317 17782 5587 5309 17783 5586 5308 17784 5596 5318 17785 5587 5309 17786 5597 5319 17787 5588 5310 17788 5587 5309 17789 5598 5320 17790 5597 5319 17791 5587 5309 17792 5593 5315 17793 5598 5320 17794 5587 5309 17795 5599 5321 17796 5600 5322 17797 5592 5314 17798 5601 5323 17799 5592 5314 17800 5600 5322 17801 5602 5324 17802 5599 5321 17803 5592 5314 17804 5603 5325 17805 5602 5324 17806 5592 5314 17807 5604 5326 17808 5603 5325 17809 5592 5314 17810 5605 5327 17811 5604 5326 17812 5592 5314 17813 5591 5313 17814 5605 5327 17815 5592 5314 17816 5606 5328 17817 5593 5315 17818 5592 5314 17819 5601 5323 17820 5606 5328 17821 5592 5314 17822 5607 5329 17823 5608 5330 17824 5600 5322 17825 5609 5331 17826 5600 5322 17827 5608 5330 17828 5599 5321 17829 5607 5329 17830 5600 5322 17831 5610 5332 17832 5601 5323 17833 5600 5322 17834 5609 5331 17835 5610 5332 17836 5600 5322 17837 5611 5333 17838 5612 5334 17839 5608 5330 17840 5613 5335 17841 5608 5330 17842 5612 5334 17843 5607 5329 17844 5611 5333 17845 5608 5330 17846 5614 5336 17847 5609 5331 17848 5608 5330 17849 5615 5337 17850 5614 5336 17851 5608 5330 17852 5613 5335 17853 5615 5337 17854 5608 5330 17855 5616 5338 17856 5617 5339 17857 5612 5334 17858 5618 5340 17859 5612 5334 17860 5617 5339 17861 5619 5341 17862 5616 5338 17863 5612 5334 17864 5620 5342 17865 5619 5341 17866 5612 5334 17867 5621 5343 17868 5620 5342 17869 5612 5334 17870 5622 5344 17871 5621 5343 17872 5612 5334 17873 5623 5345 17874 5622 5344 17875 5612 5334 17876 5611 5333 17877 5623 5345 17878 5612 5334 17879 5624 5346 17880 5613 5335 17881 5612 5334 17882 5625 5347 17883 5624 5346 17884 5612 5334 17885 5618 5340 17886 5625 5347 17887 5612 5334 17888 5626 5348 17889 5627 5348 17890 5628 5348 17891 5629 5349 17892 5618 5340 17893 5617 5339 17894 5630 5350 17895 5629 5349 17896 5617 5339 17897 5631 5351 17898 5630 5350 17899 5617 5339 17900 5626 5352 17901 5632 5352 17902 5627 5352 17903 5633 5353 17904 5634 5354 17905 5635 5355 17906 5626 5356 17907 5628 5356 17908 5636 5356 17909 5637 5357 17910 5635 5355 17911 5638 5358 17912 5633 5353 17913 5635 5355 17914 5637 5357 17915 5639 5359 17916 5638 5358 17917 5640 5360 17918 5641 5361 17919 5638 5358 17920 5639 5359 17921 5637 5357 17922 5638 5358 17923 5641 5361 17924 5642 5362 17925 5640 5360 17926 5643 5363 17927 5639 5359 17928 5640 5360 17929 5642 5362 17930 5642 5362 17931 5643 5363 17932 5644 5364 17933 5645 5365 17934 5646 5365 17935 5647 5365 17936 5642 5362 17937 5644 5364 17938 5648 5366 17939 5649 5367 17940 5647 5367 17941 5650 5367 17942 5645 5368 17943 5647 5368 17944 5649 5368 17945 5651 5369 17946 5650 5369 17947 5652 5369 17948 5649 5370 17949 5650 5370 17950 5651 5370 17951 5653 5371 17952 5654 5372 17953 5655 5373 17954 5656 5374 17955 5655 5373 17956 5657 5375 17957 5653 5371 17958 5655 5373 17959 5656 5374 17960 5656 5374 17961 5657 5375 17962 5658 5376 17963 5656 5374 17964 5658 5376 17965 5659 5377 17966 5660 5378 17967 5659 5377 17968 5661 5379 17969 5656 5374 17970 5659 5377 17971 5660 5378 17972 5660 5378 17973 5661 5379 17974 5662 5380 17975 5663 5381 17976 5662 5380 17977 5664 5382 17978 5660 5378 17979 5662 5380 17980 5663 5381 17981 5663 5381 17982 5664 5382 17983 5665 5383 17984 5666 5384 17985 5667 5384 17986 5668 5384 17987 5663 5381 17988 5665 5383 17989 5669 5385 17990 5558 5386 17991 5668 5386 17992 5559 5386 17993 5558 5387 17994 5666 5387 17995 5668 5387 17996 5579 5301 17997 5578 5300 17998 5670 5388 17999 5671 5389 18000 5672 5390 18001 5673 5391 18002 5574 5392 18003 5580 5392 18004 5674 5392 18005 5675 5393 18006 5574 5393 18007 5674 5393 18008 5676 5394 18009 5677 5394 18010 5678 5394 18011 5679 5395 18012 5676 5395 18013 5678 5395 18014 5671 5389 18015 5680 5396 18016 5672 5390 18017 5671 5389 18018 5673 5391 18019 5681 5397 18020 5682 5398 18021 5681 5397 18022 5683 5399 18023 5682 5398 18024 5671 5389 18025 5681 5397 18026 5682 5398 18027 5683 5399 18028 5684 5400 18029 5685 5401 18030 5684 5400 18031 5686 5402 18032 5687 5403 18033 5684 5400 18034 5685 5401 18035 5682 5398 18036 5684 5400 18037 5687 5403 18038 5687 5403 18039 5685 5401 18040 5688 5404 18041 5689 5405 18042 5688 5404 18043 5690 5406 18044 5687 5403 18045 5688 5404 18046 5689 5405 18047 5691 5407 18048 5690 5406 18049 5692 5408 18050 5689 5405 18051 5690 5406 18052 5691 5407 18053 5693 5409 18054 5692 5408 18055 5694 5410 18056 5691 5407 18057 5692 5408 18058 5693 5409 18059 5695 5411 18060 5694 5410 18061 5696 5412 18062 5693 5409 18063 5694 5410 18064 5695 5411 18065 5695 5411 18066 5696 5412 18067 5697 5413 18068 5695 5411 18069 5697 5413 18070 5698 5414 18071 5699 5415 18072 5698 5414 18073 5700 5416 18074 5701 5417 18075 5695 5411 18076 5698 5414 18077 5702 5418 18078 5701 5417 18079 5698 5414 18080 5703 5419 18081 5702 5418 18082 5698 5414 18083 5704 5420 18084 5703 5419 18085 5698 5414 18086 5705 5421 18087 5704 5420 18088 5698 5414 18089 5706 5422 18090 5705 5421 18091 5698 5414 18092 5707 5423 18093 5706 5422 18094 5698 5414 18095 5708 5424 18096 5707 5423 18097 5698 5414 18098 5709 5425 18099 5708 5424 18100 5698 5414 18101 5710 5426 18102 5709 5425 18103 5698 5414 18104 5711 5427 18105 5710 5426 18106 5698 5414 18107 5712 5428 18108 5711 5427 18109 5698 5414 18110 5713 5429 18111 5712 5428 18112 5698 5414 18113 5714 5430 18114 5713 5429 18115 5698 5414 18116 5715 5431 18117 5714 5430 18118 5698 5414 18119 5699 5415 18120 5715 5431 18121 5698 5414 18122 5716 5432 18123 5700 5416 18124 5717 5433 18125 5716 5432 18126 5699 5415 18127 5700 5416 18128 5716 5432 18129 5717 5433 18130 5718 5434 18131 5719 5435 18132 5718 5434 18133 5720 5436 18134 5719 5435 18135 5716 5432 18136 5718 5434 18137 5721 5437 18138 5720 5436 18139 5722 5438 18140 5721 5437 18141 5719 5435 18142 5720 5436 18143 5721 5437 18144 5722 5438 18145 5723 5439 18146 5724 5440 18147 5723 5439 18148 5725 5441 18149 5724 5440 18150 5721 5437 18151 5723 5439 18152 5726 5442 18153 5725 5441 18154 5727 5443 18155 5726 5442 18156 5724 5440 18157 5725 5441 18158 5726 5442 18159 5727 5443 18160 5728 5444 18161 5729 5445 18162 5728 5444 18163 5730 5446 18164 5726 5442 18165 5728 5444 18166 5729 5445 18167 5631 5351 18168 5731 5447 18169 5630 5350 18170 5732 5448 18171 5730 5446 18172 5733 5449 18173 5734 5450 18174 5730 5446 18175 5732 5448 18176 5735 5451 18177 5730 5446 18178 5734 5450 18179 5729 5445 18180 5730 5446 18181 5735 5451 18182 5626 5452 18183 5736 5452 18184 5632 5452 18185 5737 5453 18186 5738 5453 18187 5739 5453 18188 5740 5454 18189 5741 5454 18190 5742 5454 18191 5743 5455 18192 5742 5455 18193 5744 5455 18194 5743 5456 18195 5740 5456 18196 5742 5456 18197 5745 5457 18198 5746 5457 18199 5741 5457 18200 5747 5458 18201 5748 5458 18202 5746 5458 18203 5745 5459 18204 5747 5459 18205 5746 5459 18206 5740 5460 18207 5745 5460 18208 5741 5460 18209 5749 5461 18210 5744 5461 18211 5750 5461 18212 5749 5462 18213 5743 5462 18214 5744 5462 18215 5751 5463 18216 5750 5463 18217 5752 5463 18218 5751 5464 18219 5749 5464 18220 5750 5464 18221 5753 5465 18222 5752 5465 18223 5754 5465 18224 5753 5466 18225 5751 5466 18226 5752 5466 18227 5755 5467 18228 5754 5467 18229 5756 5467 18230 5755 5468 18231 5753 5468 18232 5754 5468 18233 5757 5469 18234 5756 5469 18235 5758 5469 18236 5757 5470 18237 5755 5470 18238 5756 5470 18239 5759 5471 18240 5757 5471 18241 5758 5471 18242 5760 5472 18243 5759 5472 18244 5758 5472 18245 5747 5473 18246 5761 5473 18247 5748 5473 18248 5760 5474 18249 5762 5474 18250 5759 5474 18251 5737 5475 18252 5739 5475 18253 5763 5475 18254 5764 5476 18255 5765 5476 18256 5762 5476 18257 5766 5477 18258 5767 5478 18259 5768 5479 18260 5760 5480 18261 5764 5480 18262 5762 5480 18263 5769 5481 18264 5770 5481 18265 5765 5481 18266 5771 5482 18267 5768 5479 18268 5772 5483 18269 5764 5484 18270 5769 5484 18271 5765 5484 18272 5773 5485 18273 5766 5477 18274 5768 5479 18275 5771 5482 18276 5773 5485 18277 5768 5479 18278 5769 5486 18279 5774 5486 18280 5770 5486 18281 5775 5487 18282 5772 5483 18283 5776 5488 18284 5775 5487 18285 5771 5482 18286 5772 5483 18287 5777 5489 18288 5778 5489 18289 5774 5489 18290 5779 5490 18291 5776 5488 18292 5780 5491 18293 5769 5492 18294 5777 5492 18295 5774 5492 18296 5779 5490 18297 5775 5487 18298 5776 5488 18299 5781 5493 18300 5782 5493 18301 5778 5493 18302 5783 5494 18303 5780 5491 18304 5784 5495 18305 5777 5496 18306 5781 5496 18307 5778 5496 18308 5783 5494 18309 5779 5490 18310 5780 5491 18311 5785 5497 18312 5786 5497 18313 5782 5497 18314 5787 5498 18315 5784 5495 18316 5788 5499 18317 5789 5500 18318 5785 5500 18319 5782 5500 18320 5781 5501 18321 5789 5501 18322 5782 5501 18323 5787 5498 18324 5783 5494 18325 5784 5495 18326 5790 5502 18327 5791 5502 18328 5786 5502 18329 5792 5503 18330 5788 5499 18331 5793 5504 18332 5785 5505 18333 5790 5505 18334 5786 5505 18335 5792 5503 18336 5787 5498 18337 5788 5499 18338 5794 5506 18339 5795 5506 18340 5791 5506 18341 5796 5507 18342 5793 5504 18343 5797 5508 18344 5790 5509 18345 5794 5509 18346 5791 5509 18347 5796 5507 18348 5792 5503 18349 5793 5504 18350 5798 5510 18351 5799 5510 18352 5795 5510 18353 5796 5507 18354 5797 5508 18355 5800 5511 18356 5794 5512 18357 5798 5512 18358 5795 5512 18359 5801 5513 18360 5802 5513 18361 5799 5513 18362 5803 5514 18363 5800 5511 18364 5804 5515 18365 5798 5516 18366 5801 5516 18367 5799 5516 18368 5803 5514 18369 5796 5507 18370 5800 5511 18371 5805 5517 18372 5806 5517 18373 5802 5517 18374 5807 5518 18375 5804 5515 18376 5808 5519 18377 5801 5520 18378 5805 5520 18379 5802 5520 18380 5807 5518 18381 5803 5514 18382 5804 5515 18383 5809 5521 18384 5810 5521 18385 5806 5521 18386 5811 5522 18387 5808 5519 18388 5812 5523 18389 5805 5524 18390 5809 5524 18391 5806 5524 18392 5811 5522 18393 5807 5518 18394 5808 5519 18395 5813 5525 18396 5814 5525 18397 5810 5525 18398 5815 5526 18399 5812 5523 18400 5816 5527 18401 5809 5528 18402 5813 5528 18403 5810 5528 18404 5815 5526 18405 5811 5522 18406 5812 5523 18407 5817 5529 18408 5818 5529 18409 5814 5529 18410 5819 5530 18411 5816 5527 18412 5820 5531 18413 5813 5532 18414 5817 5532 18415 5814 5532 18416 5819 5530 18417 5815 5526 18418 5816 5527 18419 5821 5533 18420 5822 5533 18421 5818 5533 18422 5823 5534 18423 5820 5531 18424 5824 5535 18425 5817 5536 18426 5821 5536 18427 5818 5536 18428 5825 5537 18429 5819 5530 18430 5820 5531 18431 5823 5534 18432 5825 5537 18433 5820 5531 18434 5826 5538 18435 5827 5538 18436 5822 5538 18437 5823 5534 18438 5824 5535 18439 5828 5539 18440 5829 5540 18441 5826 5540 18442 5822 5540 18443 5821 5541 18444 5829 5541 18445 5822 5541 18446 5830 5542 18447 5831 5542 18448 5827 5542 18449 5832 5543 18450 5828 5539 18451 5833 5544 18452 5826 5545 18453 5830 5545 18454 5827 5545 18455 5832 5543 18456 5823 5534 18457 5828 5539 18458 5834 5546 18459 5835 5546 18460 5831 5546 18461 5836 5547 18462 5833 5544 18463 5837 5548 18464 5830 5549 18465 5834 5549 18466 5831 5549 18467 5836 5547 18468 5832 5543 18469 5833 5544 18470 5838 5550 18471 5837 5548 18472 5839 5551 18473 5838 5550 18474 5836 5547 18475 5837 5548 18476 5840 5552 18477 5839 5551 18478 5841 5553 18479 5840 5552 18480 5838 5550 18481 5839 5551 18482 5842 5554 18483 5841 5553 18484 5843 5555 18485 5842 5554 18486 5840 5552 18487 5841 5553 18488 5844 5556 18489 5843 5555 18490 5845 5557 18491 5844 5556 18492 5842 5554 18493 5843 5555 18494 5846 5558 18495 5845 5557 18496 5847 5559 18497 5846 5558 18498 5844 5556 18499 5845 5557 18500 5848 5560 18501 5847 5559 18502 5849 5561 18503 5848 5560 18504 5846 5558 18505 5847 5559 18506 5850 5562 18507 5849 5561 18508 5851 5563 18509 5850 5562 18510 5848 5560 18511 5849 5561 18512 5852 5564 18513 5851 5563 18514 5853 5565 18515 5852 5564 18516 5850 5562 18517 5851 5563 18518 5854 5566 18519 5853 5565 18520 5855 5567 18521 5854 5566 18522 5852 5564 18523 5853 5565 18524 5856 5568 18525 5855 5567 18526 5857 5569 18527 5856 5568 18528 5854 5566 18529 5855 5567 18530 5858 5570 18531 5857 5569 18532 5859 5571 18533 5858 5570 18534 5856 5568 18535 5857 5569 18536 5860 5572 18537 5859 5571 18538 5861 5573 18539 5860 5572 18540 5858 5570 18541 5859 5571 18542 5862 5574 18543 5861 5573 18544 5863 5575 18545 5862 5574 18546 5860 5572 18547 5861 5573 18548 5864 5576 18549 5863 5575 18550 5865 5577 18551 5864 5576 18552 5862 5574 18553 5863 5575 18554 5864 5576 18555 5865 5577 18556 5866 5578 18557 5867 5579 18558 5866 5578 18559 5868 5580 18560 5867 5579 18561 5864 5576 18562 5866 5578 18563 5869 5581 18564 5868 5580 18565 5870 5582 18566 5869 5581 18567 5867 5579 18568 5868 5580 18569 5871 5583 18570 5870 5582 18571 5872 5584 18572 5871 5583 18573 5869 5581 18574 5870 5582 18575 5873 5585 18576 5872 5584 18577 5874 5586 18578 5873 5585 18579 5871 5583 18580 5872 5584 18581 5875 5587 18582 5874 5586 18583 5876 5588 18584 5875 5587 18585 5873 5585 18586 5874 5586 18587 5875 5587 18588 5876 5588 18589 5877 5589 18590 5671 5389 18591 5878 5590 18592 5680 5396 18593 5729 5445 18594 5735 5451 18595 5879 5591 18596 5729 5445 18597 5879 5591 18598 5880 5592 18599 5881 5593 18600 5880 5592 18601 5882 5594 18602 5881 5593 18603 5729 5445 18604 5880 5592 18605 5881 5593 18606 5882 5594 18607 5883 5595 18608 5884 5596 18609 5883 5595 18610 5885 5597 18611 5884 5596 18612 5881 5593 18613 5883 5595 18614 5886 5598 18615 5885 5597 18616 5887 5599 18617 5886 5598 18618 5884 5596 18619 5885 5597 18620 5886 5598 18621 5887 5599 18622 5888 5600 18623 5886 5598 18624 5888 5600 18625 5889 5601 18626 5890 5602 18627 5889 5601 18628 5891 5603 18629 5890 5602 18630 5886 5598 18631 5889 5601 18632 5890 5602 18633 5891 5603 18634 5892 5604 18635 5893 5605 18636 5892 5604 18637 5894 5606 18638 5893 5605 18639 5890 5602 18640 5892 5604 18641 5893 5605 18642 5894 5606 18643 5895 5607 18644 5893 5605 18645 5895 5607 18646 5896 5608 18647 5897 5609 18648 5896 5608 18649 5898 5610 18650 5897 5609 18651 5893 5605 18652 5896 5608 18653 5897 5609 18654 5898 5610 18655 5899 5611 18656 5900 5612 18657 5899 5611 18658 5901 5613 18659 5900 5612 18660 5897 5609 18661 5899 5611 18662 5902 5614 18663 5901 5613 18664 5903 5615 18665 5902 5614 18666 5900 5612 18667 5901 5613 18668 5904 5616 18669 5903 5615 18670 5905 5617 18671 5904 5616 18672 5902 5614 18673 5903 5615 18674 5904 5616 18675 5905 5617 18676 5906 5618 18677 5907 5619 18678 5906 5618 18679 5908 5620 18680 5907 5619 18681 5904 5616 18682 5906 5618 18683 5907 5619 18684 5908 5620 18685 5909 5621 18686 5907 5619 18687 5909 5621 18688 5910 5622 18689 5911 5623 18690 5910 5622 18691 5912 5624 18692 5911 5623 18693 5907 5619 18694 5910 5622 18695 5911 5623 18696 5912 5624 18697 5913 5625 18698 5914 5626 18699 5913 5625 18700 5915 5627 18701 5914 5626 18702 5911 5623 18703 5913 5625 18704 5914 5626 18705 5915 5627 18706 5916 5628 18707 5914 5626 18708 5916 5628 18709 5917 5629 18710 5918 5630 18711 5917 5629 18712 5919 5631 18713 5918 5630 18714 5914 5626 18715 5917 5629 18716 5920 5632 18717 5919 5631 18718 5921 5633 18719 5920 5632 18720 5918 5630 18721 5919 5631 18722 5920 5632 18723 5921 5633 18724 5922 5634 18725 5923 5635 18726 5922 5634 18727 5924 5636 18728 5923 5635 18729 5920 5632 18730 5922 5634 18731 5923 5635 18732 5924 5636 18733 5925 5637 18734 5671 5389 18735 5925 5637 18736 5926 5638 18737 5671 5389 18738 5923 5635 18739 5925 5637 18740 5671 5389 18741 5926 5638 18742 5878 5590 18743 5726 5442 18744 5729 5445 18745 5881 5593 18746 5927 5639 18747 5881 5593 18748 5884 5596 18749 5726 5442 18750 5881 5593 18751 5927 5639 18752 5928 5640 18753 5884 5596 18754 5886 5598 18755 5927 5639 18756 5884 5596 18757 5928 5640 18758 5929 5641 18759 5886 5598 18760 5890 5602 18761 5928 5640 18762 5886 5598 18763 5929 5641 18764 5930 5642 18765 5890 5602 18766 5893 5605 18767 5929 5641 18768 5890 5602 18769 5930 5642 18770 5931 5643 18771 5893 5605 18772 5897 5609 18773 5930 5642 18774 5893 5605 18775 5931 5643 18776 5932 5644 18777 5897 5609 18778 5900 5612 18779 5931 5643 18780 5897 5609 18781 5932 5644 18782 5933 5645 18783 5900 5612 18784 5902 5614 18785 5932 5644 18786 5900 5612 18787 5933 5645 18788 5934 5646 18789 5902 5614 18790 5904 5616 18791 5933 5645 18792 5902 5614 18793 5934 5646 18794 5935 5647 18795 5904 5616 18796 5907 5619 18797 5934 5646 18798 5904 5616 18799 5935 5647 18800 5936 5648 18801 5907 5619 18802 5911 5623 18803 5935 5647 18804 5907 5619 18805 5936 5648 18806 5937 5649 18807 5911 5623 18808 5914 5626 18809 5936 5648 18810 5911 5623 18811 5937 5649 18812 5938 5650 18813 5914 5626 18814 5918 5630 18815 5937 5649 18816 5914 5626 18817 5938 5650 18818 5939 5651 18819 5918 5630 18820 5920 5632 18821 5938 5650 18822 5918 5630 18823 5939 5651 18824 5940 5652 18825 5920 5632 18826 5923 5635 18827 5939 5651 18828 5920 5632 18829 5940 5652 18830 5941 5653 18831 5923 5635 18832 5671 5389 18833 5940 5652 18834 5923 5635 18835 5941 5653 18836 5941 5653 18837 5671 5389 18838 5682 5398 18839 5693 5409 18840 5695 5411 18841 5701 5417 18842 5942 5654 18843 5701 5417 18844 5702 5418 18845 5942 5654 18846 5693 5409 18847 5701 5417 18848 5943 5655 18849 5702 5418 18850 5703 5419 18851 5943 5655 18852 5942 5654 18853 5702 5418 18854 5944 5656 18855 5703 5419 18856 5704 5420 18857 5944 5656 18858 5943 5655 18859 5703 5419 18860 5945 5657 18861 5704 5420 18862 5705 5421 18863 5945 5657 18864 5944 5656 18865 5704 5420 18866 5946 5658 18867 5705 5421 18868 5706 5422 18869 5946 5658 18870 5945 5657 18871 5705 5421 18872 5947 5659 18873 5706 5422 18874 5707 5423 18875 5947 5659 18876 5946 5658 18877 5706 5422 18878 5948 5660 18879 5707 5423 18880 5708 5424 18881 5948 5660 18882 5947 5659 18883 5707 5423 18884 5949 5661 18885 5708 5424 18886 5709 5425 18887 5949 5661 18888 5948 5660 18889 5708 5424 18890 5950 5662 18891 5709 5425 18892 5710 5426 18893 5950 5662 18894 5949 5661 18895 5709 5425 18896 5951 5663 18897 5710 5426 18898 5711 5427 18899 5951 5663 18900 5950 5662 18901 5710 5426 18902 5952 5664 18903 5711 5427 18904 5712 5428 18905 5952 5664 18906 5951 5663 18907 5711 5427 18908 5953 5665 18909 5712 5428 18910 5713 5429 18911 5953 5665 18912 5952 5664 18913 5712 5428 18914 5954 5666 18915 5713 5429 18916 5714 5430 18917 5954 5666 18918 5953 5665 18919 5713 5429 18920 5955 5667 18921 5714 5430 18922 5715 5431 18923 5955 5667 18924 5954 5666 18925 5714 5430 18926 5956 5668 18927 5715 5431 18928 5699 5415 18929 5956 5668 18930 5955 5667 18931 5715 5431 18932 5716 5432 18933 5956 5668 18934 5699 5415 18935 5691 5407 18936 5693 5409 18937 5942 5654 18938 5957 5669 18939 5942 5654 18940 5943 5655 18941 5957 5669 18942 5691 5407 18943 5942 5654 18944 5958 5670 18945 5943 5655 18946 5944 5656 18947 5958 5670 18948 5957 5669 18949 5943 5655 18950 5959 5671 18951 5944 5656 18952 5945 5657 18953 5959 5671 18954 5958 5670 18955 5944 5656 18956 5960 5672 18957 5945 5657 18958 5946 5658 18959 5960 5672 18960 5959 5671 18961 5945 5657 18962 5961 5673 18963 5946 5658 18964 5947 5659 18965 5961 5673 18966 5960 5672 18967 5946 5658 18968 5962 5674 18969 5947 5659 18970 5948 5660 18971 5962 5674 18972 5961 5673 18973 5947 5659 18974 5963 5675 18975 5948 5660 18976 5949 5661 18977 5963 5675 18978 5962 5674 18979 5948 5660 18980 5964 5676 18981 5949 5661 18982 5950 5662 18983 5964 5676 18984 5963 5675 18985 5949 5661 18986 5965 5677 18987 5950 5662 18988 5951 5663 18989 5965 5677 18990 5964 5676 18991 5950 5662 18992 5966 5678 18993 5951 5663 18994 5952 5664 18995 5966 5678 18996 5965 5677 18997 5951 5663 18998 5967 5679 18999 5952 5664 19000 5953 5665 19001 5967 5679 19002 5966 5678 19003 5952 5664 19004 5968 5680 19005 5953 5665 19006 5954 5666 19007 5968 5680 19008 5967 5679 19009 5953 5665 19010 5969 5681 19011 5954 5666 19012 5955 5667 19013 5969 5681 19014 5968 5680 19015 5954 5666 19016 5970 5682 19017 5955 5667 19018 5956 5668 19019 5970 5682 19020 5969 5681 19021 5955 5667 19022 5971 5683 19023 5956 5668 19024 5716 5432 19025 5971 5683 19026 5970 5682 19027 5956 5668 19028 5719 5435 19029 5971 5683 19030 5716 5432 19031 5972 5684 19032 5691 5407 19033 5957 5669 19034 5972 5684 19035 5689 5405 19036 5691 5407 19037 5973 5685 19038 5957 5669 19039 5958 5670 19040 5973 5685 19041 5972 5684 19042 5957 5669 19043 5974 5686 19044 5958 5670 19045 5959 5671 19046 5974 5686 19047 5973 5685 19048 5958 5670 19049 5975 5687 19050 5959 5671 19051 5960 5672 19052 5975 5687 19053 5974 5686 19054 5959 5671 19055 5976 5688 19056 5960 5672 19057 5961 5673 19058 5976 5688 19059 5975 5687 19060 5960 5672 19061 5977 5689 19062 5961 5673 19063 5962 5674 19064 5977 5689 19065 5976 5688 19066 5961 5673 19067 5978 5690 19068 5962 5674 19069 5963 5675 19070 5978 5690 19071 5977 5689 19072 5962 5674 19073 5979 5691 19074 5963 5675 19075 5964 5676 19076 5979 5691 19077 5978 5690 19078 5963 5675 19079 5980 5692 19080 5964 5676 19081 5965 5677 19082 5980 5692 19083 5979 5691 19084 5964 5676 19085 5981 5693 19086 5965 5677 19087 5966 5678 19088 5981 5693 19089 5980 5692 19090 5965 5677 19091 5982 5694 19092 5966 5678 19093 5967 5679 19094 5982 5694 19095 5981 5693 19096 5966 5678 19097 5983 5695 19098 5967 5679 19099 5968 5680 19100 5983 5695 19101 5982 5694 19102 5967 5679 19103 5984 5696 19104 5968 5680 19105 5969 5681 19106 5984 5696 19107 5983 5695 19108 5968 5680 19109 5985 5697 19110 5969 5681 19111 5970 5682 19112 5985 5697 19113 5984 5696 19114 5969 5681 19115 5986 5698 19116 5970 5682 19117 5971 5683 19118 5986 5698 19119 5985 5697 19120 5970 5682 19121 5721 5437 19122 5971 5683 19123 5719 5435 19124 5721 5437 19125 5986 5698 19126 5971 5683 19127 5987 5699 19128 5689 5405 19129 5972 5684 19130 5987 5699 19131 5687 5403 19132 5689 5405 19133 5988 5700 19134 5972 5684 19135 5973 5685 19136 5988 5700 19137 5987 5699 19138 5972 5684 19139 5989 5701 19140 5973 5685 19141 5974 5686 19142 5989 5701 19143 5988 5700 19144 5973 5685 19145 5990 5702 19146 5974 5686 19147 5975 5687 19148 5990 5702 19149 5989 5701 19150 5974 5686 19151 5991 5703 19152 5975 5687 19153 5976 5688 19154 5991 5703 19155 5990 5702 19156 5975 5687 19157 5992 5704 19158 5976 5688 19159 5977 5689 19160 5992 5704 19161 5991 5703 19162 5976 5688 19163 5993 5705 19164 5977 5689 19165 5978 5690 19166 5993 5705 19167 5992 5704 19168 5977 5689 19169 5994 5706 19170 5978 5690 19171 5979 5691 19172 5994 5706 19173 5993 5705 19174 5978 5690 19175 5995 5707 19176 5979 5691 19177 5980 5692 19178 5995 5707 19179 5994 5706 19180 5979 5691 19181 5996 5708 19182 5980 5692 19183 5981 5693 19184 5996 5708 19185 5995 5707 19186 5980 5692 19187 5997 5709 19188 5981 5693 19189 5982 5694 19190 5997 5709 19191 5996 5708 19192 5981 5693 19193 5998 5710 19194 5982 5694 19195 5983 5695 19196 5998 5710 19197 5997 5709 19198 5982 5694 19199 5999 5711 19200 5983 5695 19201 5984 5696 19202 5999 5711 19203 5998 5710 19204 5983 5695 19205 6000 5712 19206 5984 5696 19207 5985 5697 19208 6000 5712 19209 5999 5711 19210 5984 5696 19211 6001 5713 19212 5985 5697 19213 5986 5698 19214 6001 5713 19215 6000 5712 19216 5985 5697 19217 5724 5440 19218 5986 5698 19219 5721 5437 19220 5724 5440 19221 6001 5713 19222 5986 5698 19223 5682 5398 19224 5687 5403 19225 5987 5699 19226 5941 5653 19227 5987 5699 19228 5988 5700 19229 5941 5653 19230 5682 5398 19231 5987 5699 19232 5940 5652 19233 5988 5700 19234 5989 5701 19235 5940 5652 19236 5941 5653 19237 5988 5700 19238 5939 5651 19239 5989 5701 19240 5990 5702 19241 5939 5651 19242 5940 5652 19243 5989 5701 19244 5938 5650 19245 5990 5702 19246 5991 5703 19247 5938 5650 19248 5939 5651 19249 5990 5702 19250 5937 5649 19251 5991 5703 19252 5992 5704 19253 5937 5649 19254 5938 5650 19255 5991 5703 19256 5936 5648 19257 5992 5704 19258 5993 5705 19259 5936 5648 19260 5937 5649 19261 5992 5704 19262 5935 5647 19263 5993 5705 19264 5994 5706 19265 5935 5647 19266 5936 5648 19267 5993 5705 19268 5934 5646 19269 5994 5706 19270 5995 5707 19271 5934 5646 19272 5935 5647 19273 5994 5706 19274 5933 5645 19275 5995 5707 19276 5996 5708 19277 5933 5645 19278 5934 5646 19279 5995 5707 19280 5932 5644 19281 5996 5708 19282 5997 5709 19283 5932 5644 19284 5933 5645 19285 5996 5708 19286 5931 5643 19287 5997 5709 19288 5998 5710 19289 5931 5643 19290 5932 5644 19291 5997 5709 19292 5930 5642 19293 5998 5710 19294 5999 5711 19295 5930 5642 19296 5931 5643 19297 5998 5710 19298 5929 5641 19299 5999 5711 19300 6000 5712 19301 5929 5641 19302 5930 5642 19303 5999 5711 19304 5928 5640 19305 6000 5712 19306 6001 5713 19307 5928 5640 19308 5929 5641 19309 6000 5712 19310 5927 5639 19311 6001 5713 19312 5724 5440 19313 5927 5639 19314 5928 5640 19315 6001 5713 19316 5726 5442 19317 5927 5639 19318 5724 5440 19319 6014 5714 19320 6015 5715 19321 6016 5716 19322 6017 5717 19323 6018 5718 19324 6019 5719 19325 6020 5720 19326 6014 5714 19327 6016 5716 19328 6021 5721 19329 6022 5721 19330 6023 5721 19331 6021 5722 19332 6023 5722 19333 6024 5722 19334 6014 5714 19335 6025 5723 19336 6015 5715 19337 6026 5724 19338 6019 5719 19339 6027 5725 19340 6028 5726 19341 6017 5717 19342 6019 5719 19343 6026 5724 19344 6028 5726 19345 6019 5719 19346 6014 5714 19347 6029 5727 19348 6025 5723 19349 6030 5728 19350 6027 5725 19351 6031 5729 19352 6030 5728 19353 6026 5724 19354 6027 5725 19355 6014 5714 19356 6032 5730 19357 6029 5727 19358 6033 5731 19359 6031 5729 19360 6034 5732 19361 6033 5731 19362 6030 5728 19363 6031 5729 19364 6014 5714 19365 6035 5733 19366 6032 5730 19367 6036 5734 19368 6034 5732 19369 6037 5735 19370 6036 5734 19371 6033 5731 19372 6034 5732 19373 6038 5736 19374 6039 5736 19375 6040 5736 19376 6041 5737 19377 6036 5734 19378 6037 5735 19379 6020 5720 19380 6042 5738 19381 6014 5714 19382 6043 5739 19383 6014 5714 19384 6042 5738 19385 6038 5740 19386 6040 5740 19387 6044 5740 19388 6045 5741 19389 6046 5742 19390 6042 5738 19391 6047 5743 19392 6042 5738 19393 6046 5742 19394 6020 5720 19395 6045 5741 19396 6042 5738 19397 6048 5744 19398 6043 5739 19399 6042 5738 19400 6047 5743 19401 6048 5744 19402 6042 5738 19403 6049 5745 19404 6050 5746 19405 6046 5742 19406 6051 5747 19407 6046 5742 19408 6050 5746 19409 6045 5741 19410 6049 5745 19411 6046 5742 19412 6051 5747 19413 6047 5743 19414 6046 5742 19415 6052 5748 19416 6053 5749 19417 6050 5746 19418 6054 5750 19419 6050 5746 19420 6053 5749 19421 6049 5745 19422 6052 5748 19423 6050 5746 19424 6054 5750 19425 6051 5747 19426 6050 5746 19427 6055 5751 19428 6056 5752 19429 6053 5749 19430 6057 5753 19431 6053 5749 19432 6056 5752 19433 6052 5748 19434 6055 5751 19435 6053 5749 19436 6058 5754 19437 6054 5750 19438 6053 5749 19439 6057 5753 19440 6058 5754 19441 6053 5749 19442 6059 5755 19443 6060 5756 19444 6056 5752 19445 6061 5757 19446 6056 5752 19447 6060 5756 19448 6055 5751 19449 6059 5755 19450 6056 5752 19451 6061 5757 19452 6057 5753 19453 6056 5752 19454 6062 5758 19455 6063 5759 19456 6060 5756 19457 6064 5760 19458 6060 5756 19459 6063 5759 19460 6065 5761 19461 6062 5758 19462 6060 5756 19463 6066 5762 19464 6065 5761 19465 6060 5756 19466 6067 5763 19467 6066 5762 19468 6060 5756 19469 6068 5764 19470 6067 5763 19471 6060 5756 19472 6069 5765 19473 6068 5764 19474 6060 5756 19475 6059 5755 19476 6069 5765 19477 6060 5756 19478 6070 5766 19479 6061 5757 19480 6060 5756 19481 6064 5760 19482 6070 5766 19483 6060 5756 19484 6062 5758 19485 6071 5767 19486 6063 5759 19487 6072 5768 19488 6073 5768 19489 6074 5768 19490 6072 5769 19491 6075 5769 19492 6073 5769 19493 6076 5770 19494 6077 5771 19495 6078 5772 19496 6072 5773 19497 6074 5773 19498 6079 5773 19499 6080 5774 19500 6078 5772 19501 6081 5775 19502 6082 5776 19503 6078 5772 19504 6080 5774 19505 6076 5770 19506 6078 5772 19507 6082 5776 19508 6083 5777 19509 6081 5775 19510 6084 5778 19511 6080 5774 19512 6081 5775 19513 6083 5777 19514 6085 5779 19515 6084 5778 19516 6086 5780 19517 6083 5777 19518 6084 5778 19519 6085 5779 19520 6087 5781 19521 6086 5780 19522 6088 5782 19523 6085 5779 19524 6086 5780 19525 6087 5781 19526 6089 5783 19527 6090 5783 19528 6091 5783 19529 6087 5781 19530 6088 5782 19531 6092 5784 19532 6093 5785 19533 6069 5765 19534 6059 5755 19535 6089 5786 19536 6091 5786 19537 6094 5786 19538 6093 5785 19539 6059 5755 19540 6055 5751 19541 6095 5787 19542 6055 5751 19543 6052 5748 19544 6095 5787 19545 6093 5785 19546 6055 5751 19547 6096 5788 19548 6052 5748 19549 6049 5745 19550 6097 5789 19551 6095 5787 19552 6052 5748 19553 6098 5790 19554 6097 5789 19555 6052 5748 19556 6096 5788 19557 6098 5790 19558 6052 5748 19559 6099 5791 19560 6049 5745 19561 6045 5741 19562 6100 5792 19563 6096 5788 19564 6049 5745 19565 6101 5793 19566 6100 5792 19567 6049 5745 19568 6099 5791 19569 6101 5793 19570 6049 5745 19571 6102 5794 19572 6045 5741 19573 6020 5720 19574 6102 5794 19575 6099 5791 19576 6045 5741 19577 6021 5795 19578 6103 5795 19579 6022 5795 19580 6038 5796 19581 6044 5796 19582 6104 5796 19583 6105 5797 19584 6048 5744 19585 6047 5743 19586 6038 5798 19587 6104 5798 19588 6106 5798 19589 6107 5799 19590 6047 5743 19591 6051 5747 19592 6108 5800 19593 6105 5797 19594 6047 5743 19595 6109 5801 19596 6108 5800 19597 6047 5743 19598 6110 5802 19599 6109 5801 19600 6047 5743 19601 6111 5803 19602 6110 5802 19603 6047 5743 19604 6112 5804 19605 6111 5803 19606 6047 5743 19607 6107 5799 19608 6112 5804 19609 6047 5743 19610 6113 5805 19611 6051 5747 19612 6054 5750 19613 6113 5805 19614 6107 5799 19615 6051 5747 19616 6114 5806 19617 6054 5750 19618 6058 5754 19619 6114 5806 19620 6113 5805 19621 6054 5750 19622 6115 5807 19623 6058 5754 19624 6057 5753 19625 6116 5808 19626 6114 5806 19627 6058 5754 19628 6115 5807 19629 6116 5808 19630 6058 5754 19631 6117 5809 19632 6057 5753 19633 6061 5757 19634 6117 5809 19635 6115 5807 19636 6057 5753 19637 6118 5810 19638 6061 5757 19639 6070 5766 19640 6118 5810 19641 6117 5809 19642 6061 5757 19643 6072 5811 19644 6119 5811 19645 6075 5811 19646 6120 5812 19647 6118 5810 19648 6070 5766 19649 6121 5813 19650 6120 5812 19651 6070 5766 19652 6122 5814 19653 6121 5813 19654 6070 5766 19655 6123 5815 19656 6122 5814 19657 6070 5766 19658 6124 5816 19659 6123 5816 19660 6070 5816 19661 6072 5817 19662 6125 5817 19663 6119 5817 19664 6126 5818 19665 6127 5819 19666 6128 5820 19667 6129 5821 19668 6038 5821 19669 6106 5821 19670 6130 5822 19671 6128 5820 19672 6131 5823 19673 6132 5824 19674 6128 5820 19675 6130 5822 19676 6126 5818 19677 6128 5820 19678 6132 5824 19679 6133 5825 19680 6131 5823 19681 6134 5826 19682 6130 5822 19683 6131 5823 19684 6133 5825 19685 6135 5827 19686 6134 5826 19687 6136 5828 19688 6133 5825 19689 6134 5826 19690 6135 5827 19691 6135 5827 19692 6136 5828 19693 6137 5829 19694 6138 5830 19695 6112 5804 19696 6107 5799 19697 6139 5831 19698 6137 5829 19699 6140 5832 19700 6135 5827 19701 6137 5829 19702 6139 5831 19703 6141 5833 19704 6107 5799 19705 6113 5805 19706 6142 5834 19707 6138 5830 19708 6107 5799 19709 6143 5835 19710 6142 5834 19711 6107 5799 19712 6144 5836 19713 6143 5835 19714 6107 5799 19715 6141 5833 19716 6144 5836 19717 6107 5799 19718 6145 5837 19719 6113 5805 19720 6114 5806 19721 6146 5838 19722 6141 5833 19723 6113 5805 19724 6147 5839 19725 6146 5838 19726 6113 5805 19727 6145 5837 19728 6147 5839 19729 6113 5805 19730 6148 5840 19731 6114 5806 19732 6116 5808 19733 6149 5841 19734 6145 5837 19735 6114 5806 19736 6148 5840 19737 6149 5841 19738 6114 5806 19739 6150 5842 19740 6116 5808 19741 6115 5807 19742 6151 5843 19743 6148 5840 19744 6116 5808 19745 6152 5844 19746 6151 5843 19747 6116 5808 19748 6150 5842 19749 6152 5844 19750 6116 5808 19751 6153 5845 19752 6115 5807 19753 6117 5809 19754 6154 5846 19755 6150 5842 19756 6115 5807 19757 6153 5845 19758 6154 5846 19759 6115 5807 19760 6155 5847 19761 6117 5809 19762 6118 5810 19763 6156 5848 19764 6153 5845 19765 6117 5809 19766 6157 5849 19767 6156 5848 19768 6117 5809 19769 6155 5847 19770 6157 5849 19771 6117 5809 19772 6158 5850 19773 6159 5851 19774 6160 5852 19775 6161 5853 19776 6155 5847 19777 6118 5810 19778 6162 5854 19779 6161 5853 19780 6118 5810 19781 6163 5855 19782 6162 5854 19783 6118 5810 19784 6158 5850 19785 6164 5856 19786 6159 5851 19787 6165 5857 19788 6160 5852 19789 6166 5858 19790 6158 5850 19791 6160 5852 19792 6165 5857 19793 6167 5859 19794 6166 5858 19795 6168 5860 19796 6165 5857 19797 6166 5858 19798 6167 5859 19799 6169 5861 19800 6168 5860 19801 6170 5862 19802 6167 5859 19803 6168 5860 19804 6169 5861 19805 6171 5863 19806 6170 5862 19807 6172 5864 19808 6169 5861 19809 6170 5862 19810 6171 5863 19811 6171 5863 19812 6172 5864 19813 6173 5865 19814 6139 5831 19815 6140 5832 19816 6174 5866 19817 6175 5867 19818 6174 5866 19819 6176 5868 19820 6139 5831 19821 6174 5866 19822 6175 5867 19823 6175 5867 19824 6176 5868 19825 6177 5869 19826 6178 5870 19827 6177 5869 19828 6179 5871 19829 6175 5867 19830 6177 5869 19831 6178 5870 19832 6178 5870 19833 6179 5871 19834 6180 5872 19835 6181 5873 19836 6180 5872 19837 6182 5874 19838 6178 5870 19839 6180 5872 19840 6181 5873 19841 6183 5875 19842 6182 5874 19843 6184 5876 19844 6181 5873 19845 6182 5874 19846 6183 5875 19847 6185 5877 19848 6184 5876 19849 6186 5878 19850 6183 5875 19851 6184 5876 19852 6185 5877 19853 6187 5879 19854 6186 5878 19855 6188 5880 19856 6185 5877 19857 6186 5878 19858 6187 5879 19859 6189 5881 19860 6188 5880 19861 6190 5882 19862 6187 5879 19863 6188 5880 19864 6189 5881 19865 6191 5883 19866 6190 5882 19867 6192 5884 19868 6193 5885 19869 6190 5882 19870 6191 5883 19871 6189 5881 19872 6190 5882 19873 6193 5885 19874 6194 5886 19875 6192 5884 19876 6195 5887 19877 6191 5883 19878 6192 5884 19879 6194 5886 19880 6196 5888 19881 6195 5887 19882 6197 5889 19883 6194 5886 19884 6195 5887 19885 6196 5888 19886 6198 5890 19887 6197 5889 19888 6199 5891 19889 6196 5888 19890 6197 5889 19891 6198 5890 19892 6200 5892 19893 6199 5891 19894 6201 5893 19895 6198 5890 19896 6199 5891 19897 6200 5892 19898 6200 5892 19899 6201 5893 19900 6202 5894 19901 6203 5895 19902 6202 5894 19903 6204 5896 19904 6200 5892 19905 6202 5894 19906 6203 5895 19907 6203 5895 19908 6204 5896 19909 6205 5897 19910 6206 5898 19911 6205 5897 19912 6207 5899 19913 6203 5895 19914 6205 5897 19915 6206 5898 19916 6206 5898 19917 6207 5899 19918 6164 5856 19919 6206 5898 19920 6164 5856 19921 6158 5850 19922 6208 5900 19923 6094 5900 19924 6209 5900 19925 6089 5901 19926 6094 5901 19927 6208 5901 19928 6210 5902 19929 6211 5903 19930 6212 5904 19931 6208 5905 19932 6209 5905 19933 6213 5905 19934 6214 5906 19935 6212 5904 19936 6215 5907 19937 6210 5902 19938 6212 5904 19939 6214 5906 19940 6216 5908 19941 6215 5907 19942 6217 5909 19943 6214 5906 19944 6215 5907 19945 6216 5908 19946 6218 5910 19947 6217 5909 19948 6219 5911 19949 6216 5908 19950 6217 5909 19951 6218 5910 19952 6220 5912 19953 6219 5911 19954 6221 5913 19955 6218 5910 19956 6219 5911 19957 6220 5912 19958 6220 5912 19959 6221 5913 19960 6222 5914 19961 6223 5915 19962 6224 5915 19963 6103 5915 19964 6220 5912 19965 6222 5914 19966 6225 5916 19967 6021 5917 19968 6223 5917 19969 6103 5917 19970 6226 5918 19971 6227 5918 19972 6228 5918 19973 6229 5919 19974 6230 5919 19975 6227 5919 19976 6226 5920 19977 6229 5920 19978 6227 5920 19979 6231 5921 19980 6228 5921 19981 6232 5921 19982 6231 5922 19983 6226 5922 19984 6228 5922 19985 6233 5923 19986 6232 5923 19987 6234 5923 19988 6233 5924 19989 6231 5924 19990 6232 5924 19991 6235 5925 19992 6234 5925 19993 6236 5925 19994 6235 5926 19995 6233 5926 19996 6234 5926 19997 6237 5927 19998 6236 5927 19999 6238 5927 20000 6237 5928 20001 6235 5928 20002 6236 5928 20003 6239 5929 20004 6238 5929 20005 6240 5929 20006 6239 5930 20007 6237 5930 20008 6238 5930 20009 6241 5931 20010 6239 5931 20011 6240 5931 20012 6242 5932 20013 6241 5932 20014 6240 5932 20015 6243 5933 20016 6244 5933 20017 6230 5933 20018 6245 5934 20019 6246 5934 20020 6244 5934 20021 6243 5935 20022 6245 5935 20023 6244 5935 20024 6229 5936 20025 6243 5936 20026 6230 5936 20027 6247 5937 20028 6248 5937 20029 6246 5937 20030 6245 5938 20031 6247 5938 20032 6246 5938 20033 6242 5939 20034 6249 5939 20035 6241 5939 20036 6250 5940 20037 6251 5940 20038 6249 5940 20039 6242 5941 20040 6250 5941 20041 6249 5941 20042 6252 5942 20043 6253 5942 20044 6251 5942 20045 6250 5943 20046 6252 5943 20047 6251 5943 20048 6254 5944 20049 6255 5944 20050 6253 5944 20051 6252 5945 20052 6254 5945 20053 6253 5945 20054 6256 5946 20055 6257 5946 20056 6255 5946 20057 6254 5947 20058 6256 5947 20059 6255 5947 20060 6258 5948 20061 6259 5948 20062 6257 5948 20063 6256 5949 20064 6258 5949 20065 6257 5949 20066 6260 5950 20067 6261 5950 20068 6259 5950 20069 6258 5951 20070 6260 5951 20071 6259 5951 20072 6262 5952 20073 6263 5952 20074 6261 5952 20075 6260 5953 20076 6262 5953 20077 6261 5953 20078 6264 5954 20079 6265 5954 20080 6263 5954 20081 6262 5955 20082 6264 5955 20083 6263 5955 20084 6266 5956 20085 6267 5956 20086 6265 5956 20087 6264 5957 20088 6266 5957 20089 6265 5957 20090 6268 5958 20091 6269 5958 20092 6267 5958 20093 6266 5959 20094 6268 5959 20095 6267 5959 20096 6270 5960 20097 6271 5960 20098 6269 5960 20099 6268 5961 20100 6270 5961 20101 6269 5961 20102 6272 5962 20103 6273 5962 20104 6271 5962 20105 6270 5963 20106 6272 5963 20107 6271 5963 20108 6272 5964 20109 6274 5964 20110 6273 5964 20111

-
-
-
-
- - - - - 7.54969e-11 -3.25837e-10 -9.99987e-4 0 0 9.99987e-4 -3.25837e-10 -0.2604 9.99987e-4 0 7.54969e-11 0 0 0 0 1 - - - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl deleted file mode 100644 index 5a3d19b65d0abf6b8ea391d05abf26586a20216b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4284 zcmb7{Z-^CD7{*UUf1o5&SHcQz1yYF;t|fMNX8I>veJWYML^nn6P5Z0us-^3CFVTn4 zqM{F5yDBB6SOonO3U=;*6>d;1Mj&R^mp(`l3+)#TZ9C67^UORm>k`d}yU))1{@&-D zGv~Z>@ABt2Zs^_As8=5A-SBkf?xz~h)Em7E7cW}6ta4M|<~5aDZ#Mty>ap3A6Wf!< zi`Rt!=RUbP9)0A^uw(bz0rfTe?hFsj>x>T%e;1zazR2eNV~J-|LL=03ghnL}sTDzK z7B%Wx9poOK$%rh%EO?NHHfHp6GupkRZv^DY+H=86e{YRzy9R^yu^quJ!vlfpulL_* z=dtqVW>kCl(8zl|qg~8G1oV&ZSK~bku5cQaPTg?UdK|GHU!@*pf?4YAXQ7{x6^nMG z^&WY4E3vg)Ryy{W^FWSjGOa`-93klGM&${NB+bhFv=Zy%Z_%S%mz6xRcG1fA?E1C{ zSzJ+$3M*~3o0ESYU`S{Lt3Vn#s*PEldMKe;>W%xxY+txHoVl$pvO7G$ZpRMS-46Z0 z>Yd@z&+oUpq(o#9(9F_G$oKme3X$>q2E$`pj^ji*zw~rv-ctz~Rlx&(r>f`NiE2d` zj{Vt5k1~NQ^>!Y~#T~1bq(uDd@9Vs=MwJJ)U=;Y)zPjwbC>1M|15@Z+(iLh*7a$X*ZZk%uNZ6 zs0Zq@lJ~gM5|fk7Lc?5%(KMRme2@Cg)FUve1Gfh;^5(#9ONZ-WCn`no30 zF8=~q4;^?tIPvkAJ9l!rgwW2Qb*a-npH(vE_?c#O$-!FJ2P2nP)tyAzMTLMz=Qn#k z!3uz2&!9$E(@Mx|Me|?X%Fd9D7g;(FRsvznqeH*7PtI((GbmZvPDIZ635{@6>{qOW z9AkQ{$1m0cnh{G#$0>U#L3f>pR)RKW|JoVt?w1GLE&-9QkDCW|{>(vqm=iH0@KDW4 zw!_&T0t%OXYVnG6mq7C!PVIN%@R?>Z@#^}n%ht`R zmIV2M90p%M5otLXji z_|8re>QSaSLfkjzf-iT4v%0q=S_^B%-Hsg9IiV4(G_%Uyo|tVtK+s+Nw30E^f$KlR zs7Op#mz6;07u@;ov+u!7BZK$zY`cTqs2C}~IeA|RuNlESL>K&WYPylApU>X={eom- zG{86gtS&Tv;~-15F(fnsKW0I5gx=#F>oH#PDAPs4bN-VNU1?nf&Gns{M0q5 - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T13:56:30 - 2019-01-15T13:56:30 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 77.5 642.6032 38.3792 50.47308 648.7558 42.62536 47.32196 643.5922 47.79023 35.42542 717.9 35.42658 47.32196 643.5922 47.79023 50.47308 648.7558 42.62536 77.5 639.1355 41.03991 47.32196 639.7785 50.22485 40.74011 643.5922 53.51185 47.32196 639.7785 50.22485 47.32196 643.5922 47.79023 32.20323 717.9 38.37903 40.74011 643.5922 53.51185 77.5 648.7792 32.20318 53.95177 653.757 36.08637 38.37838 717.9 32.20416 53.95177 653.757 36.08637 77.5 645.8261 35.42605 77.5 651.4399 28.73553 57.02378 657.8309 28.98574 45.52315 703.7416 27.85435 57.02378 657.8309 28.98574 41.03964 717.9 28.736 62.10222 659.8765 22.19279 59.41202 660.857 21.75381 48.57522 701.4026 23.37947 59.41202 660.857 21.75381 64.18595 656.2126 27.95369 62.00942 659.3376 23.41485 62.01773 658.7743 24.55237 62.11816 658.2664 25.47139 62.29016 657.8128 26.21096 62.55842 657.3568 26.87471 62.98109 656.881 27.46733 63.5478 656.4749 27.85109 45.74649 703.0996 27.77269 46.11853 702.5121 27.41659 46.58361 702.0513 26.83254 47.04394 701.7499 26.16085 47.50069 701.5541 25.41783 48.0111 701.4323 24.50188 62.75878 662.3268 15 61.0937 662.9323 14.49737 51.62331 702.0537 15 61.0937 662.9323 14.49737 62.46256 661.2213 18.63271 49.12485 701.4769 22.15966 50.49533 701.7933 18.61869 77.5 659.7387 8.700512 62.08981 664.1434 7.241837 49.33865 717.9 8.700526 62.08981 664.1434 7.241837 77.5 658.7927 12.96738 48.39268 717.9 12.96714 77.5 660.5 0 62.4189 664.541 0 49.90924 717.9 4.36768 62.4189 664.541 0 77.5 660.3093 4.367365 77.5 660.3093 -4.367365 62.4189 664.541 0 77.5 660.5 0 62.08983 664.1434 -7.241657 50.1 717.9 0 62.4189 664.541 0 62.08983 664.1434 -7.241657 50.1 717.9 0 77.5 655.4 0 77.5 660.5 0 77.5 660.3093 4.367365 77.5 654.6337 -8.269279 77.5 660.3093 -4.367365 77.5 654.6337 8.269279 77.5 659.7387 8.700512 77.5 658.7927 12.96738 68.53802 660.713 15 77.5 657.4785 17.13538 77.5 652.361 16.25649 77.5 657.4785 17.13538 65.66886 661.5147 15 67.89778 658.3236 21.85793 77.5 655.806 21.17293 77.5 655.806 21.17293 68.248 659.6306 18.46381 66.65319 656.5966 25.99156 77.5 653.7881 25.04945 77.5 648.6594 23.68981 77.5 653.7881 25.04945 67.05226 656.9118 25.1994 67.40803 657.3107 24.2416 67.70322 657.799 23.09259 77.5 651.4399 28.73553 64.84607 656.104 27.79201 65.52745 656.1467 27.3674 66.15838 656.3327 26.71948 77.5 643.6553 30.31632 77.5 648.7792 32.20318 77.5 645.8261 35.42605 77.5 637.5187 35.91052 77.5 642.6032 38.3792 77.5 630.4588 40.28202 77.5 639.1355 41.03991 77.5 635.4495 43.38809 77.5 622.7155 43.28194 77.5 635.4495 43.38809 47.32196 635.7871 52.35577 77.5 631.5729 45.40601 77.5 614.5524 44.808 77.5 631.5729 45.40601 77.5 589.2271 45.40601 77.5 627.5354 47.07843 47.32196 631.6422 54.1701 77.5 627.5354 47.07843 77.5 606.2476 44.808 77.5 593.2647 47.07843 77.5 623.3674 48.39265 47.32196 627.3689 55.65689 77.5 623.3674 48.39265 77.5 597.4326 48.39265 77.5 619.1005 49.33868 47.32196 622.9929 56.80713 77.5 619.1005 49.33868 77.5 601.6995 49.33868 77.5 614.7671 49.90929 47.32196 618.5408 57.61387 77.5 614.7671 49.90929 77.5 606.0329 49.90929 77.5 610.4 50.1 47.32196 614.0395 58.07224 77.5 610.4 50.1 47.32196 609.5162 58.17947 77.5 606.0329 49.90929 47.32196 600.5129 57.34001 77.5 601.6995 49.33868 47.32196 604.9982 57.93489 47.32196 596.0874 56.39839 77.5 597.4326 48.39265 47.32196 591.7484 55.11576 77.5 593.2647 47.07843 47.32196 587.5222 53.49986 77.5 589.2271 45.40601 47.32196 583.4343 51.56045 77.5 585.3505 43.38809 77.5 585.3505 43.38809 47.32196 579.5095 49.30928 77.5 581.6645 41.03991 77.5 598.0845 43.28194 77.5 581.6645 41.03991 47.32196 575.7714 46.75994 77.5 578.1968 38.3792 77.5 590.3413 40.28202 77.5 578.1968 38.3792 47.32196 572.2428 43.92787 77.5 574.9739 35.42605 77.5 583.2813 35.91052 77.5 574.9739 35.42605 47.32196 565.8976 37.48558 77.5 572.0208 32.20318 77.5 572.0208 32.20318 47.32196 568.9449 40.83017 47.32196 563.1195 33.91432 77.5 569.3601 28.73553 77.5 577.1447 30.31632 77.5 569.3601 28.73553 66.19887 564.5501 26.83977 77.5 567.0119 25.04945 77.5 567.0119 25.04945 47.32196 560.6272 30.138 64.23735 564.7014 28.1134 65.58666 564.7421 27.48444 64.90456 564.7985 27.92973 67.70588 563.0955 23.28385 77.5 564.994 21.17293 77.5 572.1406 23.68981 77.5 564.994 21.17293 67.41276 563.5829 24.41915 67.06282 563.9783 25.359 66.67414 564.2894 26.13252 68.26243 561.2156 18.57536 77.5 563.3216 17.13538 77.5 563.3216 17.13538 67.89778 562.5765 22.07587 68.56295 560.0941 15 77.5 562.0073 12.96738 77.5 568.439 16.25649 77.5 562.0073 12.96738 47.32196 553.7907 13.45434 77.5 561.0614 8.700512 77.5 561.0614 8.700512 62.78372 558.4802 15 65.6938 559.2923 15 47.32196 552.9165 9.015016 77.5 560.4907 4.367365 77.5 566.1663 8.269279 77.5 560.4907 4.367365 47.32196 552.2138 0 77.5 560.3 0 77.5 560.3 0 47.32196 552.3897 4.521177 47.32196 552.3897 -4.521177 77.5 560.3 0 47.32196 552.2138 0 77.5 560.4907 -4.367365 77.5 565.4 0 77.5 560.4907 -4.367365 38.81157 546.2232 0 47.32196 552.2138 0 47.32196 552.3897 4.521177 38.81157 546.8605 -9.02228 47.32196 552.3897 -4.521177 47.32196 552.2138 0 38.81157 546.2232 0 38.81157 546.8605 9.022282 47.32196 552.9165 9.015016 47.32196 553.7907 13.45434 47.32196 555.0073 17.81232 38.81157 548.76 17.86536 47.32196 555.0073 17.81232 62.47706 559.6246 18.74613 47.32196 556.5588 22.06258 47.32196 556.5588 22.06258 62.00885 561.5697 23.63809 47.32196 558.4359 26.17944 38.81157 551.8837 26.35358 47.32196 558.4359 26.17944 62.10222 561.0236 22.4144 63.02909 564.0618 27.68252 47.32196 560.6272 30.138 62.58525 563.5802 27.09823 62.30113 563.11 26.42594 62.12216 562.6474 25.68174 62.01863 562.1338 24.7637 38.81157 556.1698 34.31834 47.32196 563.1195 33.91432 63.60374 564.4553 28.03661 47.32196 565.8976 37.48558 38.81157 561.533 41.60146 47.32196 568.9449 40.83017 38.81157 567.8669 48.05825 47.32196 572.2428 43.92787 47.32196 575.7714 46.75994 38.81157 575.0455 53.56048 47.32196 579.5095 49.30928 47.32196 583.4343 51.56045 38.81157 582.9265 57.99885 47.32196 587.5222 53.49986 47.32196 591.7484 55.11576 38.81157 591.3531 61.2852 47.32196 596.0874 56.39839 47.32196 600.5129 57.34001 38.81157 600.158 63.35427 47.32196 604.9982 57.93489 38.81157 609.1664 64.16495 47.32196 609.5162 58.17947 47.32196 614.0395 58.07224 38.81157 618.1992 63.70113 47.32196 618.5408 57.61387 47.32196 622.9929 56.80713 38.81157 627.0772 61.97204 47.32196 627.3689 55.65689 47.32196 631.6422 54.1701 38.81157 635.6239 59.01202 47.32196 635.7871 52.35577 38.8449 643.5922 54.90309 62.10222 659.8765 15 62.75878 662.3268 15 62.46256 661.2213 18.63271 62.10222 659.8765 15 65.66886 661.5147 15 62.75878 662.3268 15 62.10222 659.8765 22.19279 62.10222 659.8765 15 62.10222 659.8765 22.19279 62.00942 659.3376 23.41485 62.01773 658.7743 24.55237 62.02574 658.7081 15 62.11816 658.2664 25.47139 62.29016 657.8128 26.21096 62.40221 657.5997 15 62.55842 657.3568 26.87471 62.98109 656.881 27.46733 63.174 656.7199 15 63.5478 656.4749 27.85109 64.18595 656.2126 27.95369 64.22358 656.2023 15 64.84607 656.104 27.79201 65.3913 656.1257 15 65.52745 656.1467 27.3674 66.15838 656.3327 26.71948 66.49959 656.5018 15 66.65319 656.5966 25.99156 67.05226 656.9118 25.1994 67.37981 657.2734 15 67.40803 657.3107 24.2416 67.70322 657.799 23.09259 67.89778 658.3236 21.85793 68.53802 660.713 15 67.89778 658.3236 21.85793 68.248 659.6306 18.46381 67.89778 658.3236 15 67.89778 658.3236 15 68.53802 660.713 15 62.02574 658.7081 15 67.89778 658.3236 15 67.89778 562.5765 15 68.56295 560.0941 15 68.26243 561.2156 18.57536 65.6938 559.2923 15 68.56295 560.0941 15 62.10222 561.0236 15 62.78372 558.4802 15 67.89778 562.5765 15 67.89778 562.5765 22.07587 67.89778 562.5765 15 67.89778 562.5765 22.07587 67.70588 563.0955 23.28385 67.41276 563.5829 24.41915 67.37981 563.6266 15 67.06282 563.9783 25.359 66.67414 564.2894 26.13252 66.49959 564.3983 15 66.19887 564.5501 26.83977 65.58666 564.7421 27.48444 65.3913 564.7742 15 64.90456 564.7985 27.92973 64.23735 564.7014 28.1134 64.22358 564.6976 15 63.60374 564.4553 28.03661 63.174 564.1801 15 63.02909 564.0618 27.68252 62.58525 563.5802 27.09823 62.40221 563.3004 15 62.30113 563.11 26.42594 62.12216 562.6474 25.68174 62.02574 562.192 15 62.01863 562.1338 24.7637 62.00885 561.5697 23.63809 62.10222 561.0236 22.4144 62.78372 558.4802 15 62.10222 561.0236 22.4144 62.47706 559.6246 18.74613 62.10222 561.0236 15 62.10222 561.0236 15 77.5 658.7927 -12.96738 61.09375 662.9324 -14.49705 49.33865 717.9 -8.700526 61.09375 662.9324 -14.49705 77.5 659.7387 -8.700512 49.90924 717.9 -4.36768 77.5 657.4785 -17.13538 59.41212 660.8571 -21.75345 48.39268 717.9 -12.96714 59.41212 660.8571 -21.75345 77.5 653.7881 -25.04945 57.02376 657.8309 -28.98578 45.40624 717.9 -21.17249 57.02376 657.8309 -28.98578 77.5 655.806 -21.17293 47.07857 717.9 -17.13495 77.5 651.4399 -28.73553 53.95239 653.7579 -36.08512 43.38824 717.9 -25.04928 53.95239 653.7579 -36.08512 77.5 645.8261 -35.42605 50.47417 648.7575 -42.62348 41.03964 717.9 -28.736 50.47417 648.7575 -42.62348 77.5 648.7792 -32.20318 77.5 639.1355 -41.03991 47.32196 643.5922 -47.79023 35.42542 717.9 -35.42658 47.32196 643.5922 -47.79023 77.5 642.6032 -38.3792 38.37838 717.9 -32.20416 77.5 635.4495 -43.38809 47.32196 639.7785 -50.22485 40.7393 643.5922 -53.51247 47.32196 643.5922 -47.79023 47.32196 639.7785 -50.22485 32.20323 717.9 -38.37903 40.7393 643.5922 -53.51247 47.32196 635.7871 -52.35577 38.84489 643.5922 -54.90309 47.32196 635.7871 -52.35577 77.5 631.5729 -45.40601 47.32196 631.6422 -54.1701 38.81157 635.6239 -59.01203 47.32196 631.6422 -54.1701 77.5 627.5354 -47.07843 47.32196 627.3689 -55.65689 47.32196 627.3689 -55.65689 77.5 623.3674 -48.39265 47.32196 622.9929 -56.80713 38.81157 627.0772 -61.97205 47.32196 622.9929 -56.80713 77.5 619.1005 -49.33868 47.32196 618.5408 -57.61387 47.32196 618.5408 -57.61387 77.5 614.7671 -49.90929 47.32196 614.0395 -58.07224 38.81157 618.1992 -63.70114 47.32196 614.0395 -58.07224 77.5 610.4 -50.1 47.32196 609.5162 -58.17947 47.32196 609.5162 -58.17947 77.5 606.0329 -49.90929 47.32196 604.9982 -57.93489 38.81157 609.1663 -64.16495 47.32196 604.9982 -57.93489 77.5 601.6995 -49.33868 47.32196 600.5129 -57.34001 38.81157 600.158 -63.35426 47.32196 600.5129 -57.34001 47.32196 596.0874 -56.39839 47.32196 596.0874 -56.39839 77.5 597.4326 -48.39265 47.32196 591.7484 -55.11576 38.81157 591.353 -61.2852 47.32196 591.7484 -55.11576 77.5 593.2647 -47.07843 47.32196 587.5222 -53.49986 47.32196 587.5222 -53.49986 77.5 589.2271 -45.40601 47.32196 583.4343 -51.56045 38.81157 582.9265 -57.99884 47.32196 583.4343 -51.56045 77.5 585.3505 -43.38809 47.32196 579.5095 -49.30928 47.32196 579.5095 -49.30928 77.5 581.6645 -41.03991 47.32196 575.7714 -46.75994 38.81157 575.0455 -53.56047 47.32196 575.7714 -46.75994 77.5 578.1968 -38.3792 47.32196 572.2428 -43.92787 47.32196 572.2428 -43.92787 77.5 574.9739 -35.42605 47.32196 568.9449 -40.83017 38.81157 567.8669 -48.05824 47.32196 568.9449 -40.83017 77.5 572.0208 -32.20318 47.32196 565.8976 -37.48558 38.81157 561.533 -41.60145 47.32196 565.8976 -37.48558 47.32196 563.1195 -33.91432 47.32196 563.1195 -33.91432 77.5 569.3601 -28.73553 47.32196 560.6272 -30.138 38.81157 556.1698 -34.31834 47.32196 560.6272 -30.138 77.5 567.0119 -25.04945 47.32196 558.4359 -26.17944 47.32196 558.4359 -26.17944 77.5 564.994 -21.17293 47.32196 556.5588 -22.06258 38.81157 551.8837 -26.35357 47.32196 556.5588 -22.06258 77.5 563.3216 -17.13538 47.32196 555.0073 -17.81232 47.32196 555.0073 -17.81232 77.5 562.0073 -12.96738 47.32196 553.7907 -13.45434 38.81157 548.76 -17.86535 47.32196 553.7907 -13.45434 77.5 561.0614 -8.700512 47.32196 552.9165 -9.015016 47.32196 552.9165 -9.015016 77.5 566.1663 -8.269279 77.5 561.0614 -8.700512 77.5 562.0073 -12.96738 77.5 568.439 -16.25649 77.5 563.3216 -17.13538 77.5 564.994 -21.17293 77.5 572.1406 -23.68981 77.5 567.0119 -25.04945 77.5 569.3601 -28.73553 77.5 577.1447 -30.31632 77.5 572.0208 -32.20318 77.5 574.9739 -35.42605 77.5 583.2813 -35.91052 77.5 578.1968 -38.3792 77.5 590.3413 -40.28202 77.5 581.6645 -41.03991 77.5 598.0845 -43.28194 77.5 585.3505 -43.38809 77.5 606.2476 -44.808 77.5 589.2271 -45.40601 77.5 631.5729 -45.40601 77.5 593.2647 -47.07843 77.5 614.5524 -44.808 77.5 627.5354 -47.07843 77.5 597.4326 -48.39265 77.5 623.3674 -48.39265 77.5 601.6995 -49.33868 77.5 619.1005 -49.33868 77.5 606.0329 -49.90929 77.5 614.7671 -49.90929 77.5 610.4 -50.1 77.5 635.4495 -43.38809 77.5 622.7155 -43.28194 77.5 639.1355 -41.03991 77.5 630.4588 -40.28202 77.5 642.6032 -38.3792 77.5 637.5187 -35.91052 77.5 645.8261 -35.42605 77.5 648.7792 -32.20318 77.5 643.6553 -30.31632 77.5 651.4399 -28.73553 77.5 653.7881 -25.04945 77.5 648.6594 -23.68981 77.5 655.806 -21.17293 77.5 657.4785 -17.13538 77.5 652.361 -16.25649 77.5 658.7927 -12.96738 77.5 659.7387 -8.700512 110 655.4 0 77.5 655.4 0 77.5 654.6337 8.269279 110 654.6336 -8.269443 77.5 654.6337 -8.269279 77.5 655.4 0 110 655.4 0 110 654.6336 8.269443 77.5 652.361 16.25649 110 652.361 16.25633 77.5 648.6594 23.68981 110 648.6597 23.68929 77.5 643.6553 30.31632 110 643.6558 30.31576 77.5 637.5187 35.91052 110 637.5191 35.91038 77.5 630.4588 40.28202 110 630.4579 40.28251 77.5 622.7155 43.28194 110 622.7141 43.2823 77.5 614.5524 44.808 110 614.5518 44.80796 77.5 606.2476 44.808 110 606.2483 44.80796 77.5 598.0845 43.28194 110 598.0859 43.2823 77.5 590.3413 40.28202 110 590.3421 40.28251 77.5 583.2813 35.91052 110 583.281 35.91038 77.5 577.1447 30.31632 110 577.1442 30.31576 77.5 572.1406 23.68981 110 572.1403 23.68929 77.5 568.439 16.25649 110 568.439 16.25633 77.5 566.1663 8.269279 110 566.1664 8.269443 77.5 565.4 0 110 565.4 0 77.5 565.4 0 77.5 566.1663 -8.269279 110 565.4 0 110 566.1664 -8.269443 77.5 568.439 -16.25649 110 568.439 -16.25633 77.5 572.1406 -23.68981 110 572.1403 -23.68929 77.5 577.1447 -30.31632 110 577.1442 -30.31576 77.5 583.2813 -35.91052 110 583.281 -35.91038 77.5 590.3413 -40.28202 110 590.3421 -40.28251 77.5 598.0845 -43.28194 110 598.0859 -43.2823 77.5 606.2476 -44.808 110 606.2483 -44.80796 77.5 614.5524 -44.808 110 614.5518 -44.80796 77.5 622.7155 -43.28194 110 622.7141 -43.2823 77.5 630.4588 -40.28202 110 630.4579 -40.28251 77.5 637.5187 -35.91052 110 637.5191 -35.91038 77.5 643.6553 -30.31632 110 643.6558 -30.31576 77.5 648.6594 -23.68981 110 648.6597 -23.68929 77.5 652.361 -16.25649 110 652.361 -16.25633 -12.01715 643.2918 66.32284 -2.000701 643.5922 67.22554 -11.12075 643.5922 66.32952 -4.365938 717.9 49.9093 -11.12075 643.5922 66.32952 -2.000701 643.5922 67.22554 -20.79582 641.5518 64.45455 -12.01715 643.2918 66.32284 -11.12075 643.5922 66.32952 -12.9663 717.9 48.39302 -20.79582 641.5518 64.45455 -8.698943 717.9 49.33895 -1.503472 636.2645 70.38302 -1.502664 643.5922 67.23851 -1.502664 643.5922 67.23851 -12.02569 633.3775 70.37342 7.146612 643.5922 66.87452 0 717.9 50.09988 7.146612 643.5922 66.87452 -1.503472 628.6304 72.73509 9.048579 634.6543 70.39072 9.051564 643.5922 66.64341 -12.02569 622.9602 72.95633 -1.50404 620.7918 74.26136 9.048579 625.2584 72.95446 -4.358844 619.9525 74.26136 -1.494158 620.793 57.9 -1.50404 620.7918 74.26136 -4.358844 619.9525 74.26136 0.001194 620.9 74.26136 0.001194 620.9 74.26136 -6.880674 618.3314 74.26136 -4.361477 619.9512 57.9 -6.880674 618.3314 74.26136 -8.838978 616.0677 74.26136 -8.832825 616.0772 57.9 -8.838978 616.0677 74.26136 -6.875587 618.3356 57.9 -12.02569 612.2788 74.00576 -10.07555 613.3552 74.26136 -10.07455 613.3586 57.9 -10.07555 613.3552 74.26136 -10.5 610.4 74.26136 -10.5 610.4 74.26136 -12.02569 601.5579 73.49967 -10.07569 607.4453 74.26136 -10.5 610.4 57.9 -10.5 610.4 74.26136 -10.07569 607.4453 74.26136 -10.5 610.4 57.9 -8.839447 604.733 74.26136 -10.07455 607.4414 57.9 -8.839447 604.733 74.26136 -6.880616 602.4686 74.26136 -8.832825 604.7229 57.9 -6.880616 602.4686 74.26136 -4.358481 600.8474 74.26136 -6.875587 602.4644 57.9 -4.358481 600.8474 74.26136 -12.02569 591.0229 71.44866 -1.50405 600.0083 74.26136 -4.361477 600.8488 57.9 -1.50405 600.0083 74.26136 -1.503472 589.5205 72.01934 0.001203954 599.9 74.26136 -1.494158 600.007 57.9 0.001203954 599.9 74.26136 -12.02569 580.8952 67.89588 -1.503472 579.4576 68.30305 9.048579 585.3692 70.11833 9.048579 595.1387 72.87124 -12.02569 571.3876 62.91597 -1.503472 570.028 63.18892 9.048579 576.0648 66.06224 -12.02569 562.7001 56.61362 -1.503472 561.4246 56.78161 9.048579 567.3986 60.77832 -12.02569 555.0152 49.12131 -1.503472 553.8236 49.21224 9.048579 559.5316 54.36479 -12.02569 548.4944 40.59651 -1.503472 547.3804 40.63573 9.048579 552.6101 46.94086 -12.02569 543.2748 31.21841 -1.503472 542.2269 31.22758 9.048579 546.7626 38.6445 -12.02569 539.4661 21.18412 -1.503472 538.4686 21.18036 9.048579 542.0978 29.6299 -12.02569 537.1484 10.70456 -1.503472 536.1824 10.69966 9.048579 538.7025 20.06462 -1.609086 535.4172 0 -1.503472 535.4151 0 9.048579 536.6397 10.12641 -12.02569 536.3704 0 -12.02569 537.1484 -10.70458 -1.503472 535.4151 0 -1.609086 535.4172 0 8.933217 535.9339 0 -1.503472 536.2016 -10.83232 8.933217 535.9339 0 -12.02569 536.3704 0 -22.30924 538.7949 0 -22.30924 539.5208 -10.16992 -22.30924 538.7949 0 -18.22507 539.2112 15 -22.30924 539.1934 7.543758 -18.56588 541.286 22.43991 -19.2432 544.8673 30.98637 -19.03967 544.1703 29.59924 -19.11506 544.5068 30.29371 -22.30924 551.7663 41.10218 -22.30847 546.6681 32.64316 -21.79627 546.6771 33.00472 -19.45848 545.278 31.7094 -19.7769 545.6984 32.36631 -20.14481 546.0416 32.82046 -20.60956 546.3424 33.11888 -21.1875 546.5719 33.1973 -22.30924 557.9962 48.7969 -22.30924 565.2279 55.55876 -22.30924 573.3231 61.25849 -22.30924 582.1272 65.78712 -22.30924 601.1782 71.00885 -22.30924 591.4718 69.05809 -22.30924 611.0609 71.60211 -22.30924 620.931 70.82653 -22.30924 630.5997 68.69696 -20.52479 640.4414 65.5839 -22.30034 639.8469 65.27307 -20.52479 640.4414 65.5839 4.365938 717.9 49.9093 9.051564 643.5922 66.64341 16.16083 643.5922 65.28479 8.698943 717.9 49.33895 16.16083 643.5922 65.28479 19.42106 633.9975 68.49073 19.4319 643.5922 64.38694 8.839296 616.0672 74.26136 9.102138 615.6346 74.26136 19.42106 623.839 71.18438 6.889374 618.3238 74.26136 4.377737 619.9439 74.26136 1.506638 620.7913 74.26136 10.07455 613.3586 57.9 9.102138 615.6346 74.26136 8.839296 616.0672 74.26136 19.42106 613.3977 72.37981 10.07566 613.3549 74.26136 10.07566 613.3549 74.26136 8.832825 616.0772 57.9 6.889374 618.3238 74.26136 6.875587 618.3356 57.9 4.377737 619.9439 74.26136 4.361477 619.9512 57.9 1.506638 620.7913 74.26136 1.494158 620.793 57.9 12.9663 717.9 48.39302 19.4319 643.5922 64.38694 29.40812 634.3891 64.68914 24.89033 643.5922 62.47997 17.13559 717.9 47.07846 24.89033 643.5922 62.47997 29.40812 624.5779 67.52149 29.40812 614.456 68.87461 9.102197 605.1655 74.26136 19.42106 602.8932 72.05186 29.40812 604.2453 68.71887 10.07558 607.4449 74.26136 10.5 610.4 74.26136 19.42106 592.5468 70.20745 29.40812 594.1694 67.05767 19.42106 582.5761 66.88536 29.40812 584.4491 63.9274 19.42106 573.191 62.15553 29.40812 575.2973 59.39665 19.42106 564.589 56.11752 29.40812 566.9145 53.56467 19.42106 556.9512 48.8984 19.42106 550.4384 40.65012 29.40812 559.4844 46.55923 19.40964 545.1973 31.57325 19.58107 545.4585 32.00284 29.40812 553.1697 38.53379 20.42887 546.2397 33.03202 19.96192 545.8854 32.62488 19.28491 544.96 31.15608 19.83661 545.7622 15 19.40964 545.1973 31.57325 19.28491 544.96 31.15608 19.58107 545.4585 32.00284 19.08872 544.4082 30.09496 19.20601 544.7763 15 19.08872 544.4082 30.09496 19.00259 543.8085 28.80062 19.00259 543.8085 28.80062 19.04578 543.1619 27.22683 19.00063 543.6239 15 19.04578 543.1619 27.22683 19.25207 542.4803 25.32335 19.25207 542.4803 25.32335 19.43515 542.0624 24.02561 20.42178 539.81 15 19.25207 542.4803 25.32335 19.43515 542.0624 24.02561 19.25207 542.4803 15 19.25207 542.4803 15 19.42106 539.7901 16.1883 19.91175 540.9743 20.21381 19.91175 540.9743 20.21381 19.42106 538.4176 8.145814 20.42178 539.81 15 19.29859 537.9254 0 19.42106 537.9581 0 29.40812 542.1618 10.1839 9.048579 535.9479 0 9.048579 536.7319 -10.77635 19.42106 537.9581 0 19.29859 537.9254 0 29.28174 541.3524 0 19.42106 538.7318 -10.55842 29.28174 541.3524 0 9.048579 535.9479 0 8.839051 604.7324 74.26136 1.506723 600.0087 74.26136 4.377624 600.8561 74.26136 6.889151 602.476 74.26136 10.07455 607.4414 57.9 9.102197 605.1655 74.26136 10.07558 607.4449 74.26136 8.832825 604.7229 57.9 8.839051 604.7324 74.26136 10.5 610.4 74.26136 10.5 610.4 57.9 10.5 610.4 74.26136 10.5 610.4 57.9 29.42342 643.5922 60.47758 21.17391 717.9 45.40562 29.42342 643.5922 60.47758 33.14047 643.5922 58.52336 33.14047 643.5922 58.52336 23.41555 546.3291 31.17099 29.40812 548.1088 29.66418 22.84083 546.5638 32.06598 22.22432 546.6756 32.71517 21.59967 546.6572 33.09516 20.97253 546.5026 33.20058 25.53974 543.0801 20.99402 29.40812 544.4125 20.1447 24.74793 544.8877 26.84546 24.38055 545.5097 28.63266 23.93071 545.9802 30.04009 26.13549 541.72 15 29.40812 541.4061 0 23.29965 540.7069 15 29.40812 541.4061 0 38.68494 546.1468 0 29.40812 542.1618 -10.1839 38.68494 546.1468 0 26.13549 541.72 15 20.42178 539.81 15 23.29965 540.7069 15 19.25207 542.4803 15 24.74793 544.8877 15 26.13549 541.72 15 25.53974 543.0801 20.99402 24.74793 544.8877 15 24.74793 544.8877 26.84546 24.74793 544.8877 15 24.74793 544.8877 26.84546 24.38055 545.5097 28.63266 24.07783 545.8479 15 23.93071 545.9802 30.04009 23.41555 546.3291 31.17099 23.0915 546.4783 15 22.84083 546.5638 32.06598 22.22432 546.6756 32.71517 21.93924 546.6833 15 21.59967 546.6572 33.09516 20.97253 546.5026 33.20058 20.79635 546.4318 15 20.42887 546.2397 33.03202 19.96192 545.8854 32.62488 25.05051 717.9 43.38747 38.8449 643.5922 54.90309 28.73621 717.9 41.03935 -74.2573 620.9288 0 -74.74909 616.5299 0 -75 610.4 0 -74.2573 620.8216 -1.498403 -75 610.4 0 -74.74909 616.5299 0 -74.2573 620.8216 1.498403 -74.2573 620.5023 2.966303 -74.2573 619.9773 4.373817 -74.2573 619.2574 5.692294 -74.2573 618.3571 6.894891 -74.2573 617.2949 7.957128 -74.2573 616.0923 8.857382 -74.2573 614.7738 9.577324 -74.2573 613.3663 10.1023 -74.2573 611.8984 10.42162 -74.2573 610.4 10.52879 -74.2573 608.9016 10.42162 -74.2573 607.4337 10.1023 -74.2573 606.0262 9.577324 -74.2573 604.7077 8.857382 -74.2573 603.5051 7.957128 -74.2573 602.4429 6.894891 -74.2573 601.5426 5.692294 -74.2573 600.8227 4.373817 -74.2573 600.2977 2.966303 -74.2573 599.9784 1.498403 -74.2573 599.8712 0 -74.2573 599.9784 -1.498403 -74.2573 599.8712 0 -74.2573 620.5023 -2.966303 -74.2573 619.9773 -4.373817 -74.2573 619.2574 -5.692294 -74.2573 618.3571 -6.894891 -74.2573 617.2949 -7.957128 -74.2573 616.0923 -8.857382 -74.2573 614.7738 -9.577324 -74.2573 613.3663 -10.1023 -74.2573 611.8984 -10.42162 -74.2573 610.4 -10.52879 -74.2573 608.9016 -10.42162 -74.2573 607.4337 -10.1023 -74.2573 606.0262 -9.577324 -74.2573 604.7077 -8.857382 -74.2573 603.5051 -7.957128 -74.2573 602.4429 -6.894891 -74.2573 601.5426 -5.692294 -74.2573 600.8227 -4.373817 -74.2573 600.2977 -2.966303 -74.2573 620.9288 0 -73.99801 622.6187 0 -73.98886 622.6217 -1.131711 -73.99801 622.6187 0 -73.96193 622.6306 2.246201 -73.98903 622.6216 1.120714 -73.85391 622.6665 4.48723 -73.91674 622.6456 3.370743 -73.66977 622.7275 6.767397 -73.77298 622.6932 5.605648 -73.36798 622.8276 9.364587 -72.92195 622.9755 12.21661 -72.2576 623.1959 15.4953 -72.04092 621.0845 17.91503 -72.0606 623.2612 16.33581 -72.04092 618.6578 19.155 -72.04092 616.0903 20.06805 -73.46936 611.9009 15 -73.42343 613.4 15 -73.48471 610.4 15 -73.42343 607.4 15 -73.46936 608.8992 15 -72.04092 604.4735 19.99957 -72.068 607.4 20.54919 -72.04092 601.6928 18.95498 -72.04092 599.0888 17.52602 -72.04092 596.714 15.74165 -72.04092 594.6168 13.63806 -72.04092 592.8397 11.25792 -72.04092 591.4187 8.649483 -72.04092 590.3825 5.865647 -72.04092 589.7523 2.962865 -72.04092 589.5408 0 -72.04092 589.5408 0 -68.39488 579.9673 4.581541 -68.39488 579.6243 0 -72.04092 589.7727 -3.101565 -68.39488 579.6243 0 -70.23377 630.6911 0 -73.99801 622.6187 0 -73.98903 622.6216 1.120714 -70.06282 630.7318 -4.760512 -73.98886 622.6217 -1.131711 -73.96193 622.6306 2.246201 -73.91674 622.6456 3.370743 -73.85391 622.6665 4.48723 -70.06282 630.7318 4.760514 -73.77298 622.6932 5.605648 -73.66977 622.7275 6.767397 -73.36798 622.8276 9.364587 -69.54856 630.854 9.512948 -72.92195 622.9755 12.21661 -72.2576 623.1959 15.4953 -68.69244 631.0565 14.22278 -72.0606 623.2612 16.33581 -71.26155 623.5264 19.35178 -71.26155 623.5264 19.35178 -69.82097 624.0044 23.76871 -68.39488 620.7763 28.97368 -68.40866 624.4733 27.33496 -72.26541 613.4 19.84262 -72.06803 613.4 20.54914 -68.39488 616.8218 30.0982 -73.42343 613.4 15 -72.06803 613.4 20.54914 -72.26541 613.4 19.84262 -70.25 613.4 26.09478 -70.25 613.4 26.09478 -70.25 613.4 15 -73.42343 613.4 15 -73.46936 611.9009 15 -70.25 613.4 15 -67.47837 611.5477 15 -73.48471 610.4 15 -69.10161 613.1715 15 -68.12844 612.5209 15 -67.25014 610.4 15 -73.46936 608.8992 15 -68.12844 608.2791 15 -73.42343 607.4 15 -67.47837 609.2523 15 -72.26533 607.4 19.84291 -70.25 607.4 15 -73.42343 607.4 15 -72.26533 607.4 19.84291 -69.10161 607.6286 15 -70.25 607.4 15 -72.068 607.4 20.54919 -68.39488 603.5045 29.9932 -69.6644 607.4577 27.62632 -70.25 607.4 26.09478 -70.25 607.4 26.09478 -68.39488 599.1163 28.63246 -68.39488 594.9795 26.6336 -68.39488 591.1864 24.04119 -68.39488 587.8215 20.91299 -68.39488 584.9598 17.31871 -68.39488 582.6651 13.33848 -68.39488 580.9885 9.060976 -63.39152 570.7169 5.636383 -63.39152 570.3187 0 -68.39488 579.9531 -4.486048 -63.39152 570.3187 0 -70.25 607.4 15 -70.25 607.4 26.09478 -69.6644 607.4577 27.62632 -69.15261 607.6079 28.89844 -69.15261 607.6079 28.89844 -68.72097 607.8189 29.92946 -69.10161 607.6286 15 -68.72097 607.8189 29.92946 -68.39242 608.0443 30.69081 -68.39242 608.0443 30.69081 -63.39152 604.0189 39.57014 -63.39152 609.6468 40.07427 -68.34957 608.0787 30.78881 -68.34957 608.0787 30.78881 -63.39152 598.5178 38.2796 -63.39152 593.2529 36.22831 -63.39152 588.3287 33.45702 -63.39152 583.8432 30.02082 -63.39152 579.8854 25.98799 -63.39152 576.5341 21.43868 -63.39152 573.8558 16.46331 -63.39152 571.9039 11.16075 -57.13015 562.0743 5.076511 -57.13015 561.8084 0 -63.39152 570.7169 -5.63583 -57.13015 561.8084 0 -68.00145 608.4141 31.57286 -68.12844 608.2791 15 -68.00145 608.4141 31.57286 -67.66099 608.8844 32.32186 -67.66099 608.8844 32.32186 -67.3945 609.4802 32.89564 -67.47837 609.2523 15 -67.3945 609.4802 32.89564 -67.26568 610.0937 33.1698 -67.26568 610.0937 33.1698 -63.39152 615.2897 39.78197 -67.26165 610.664 33.17856 -67.25014 610.4 15 -67.26165 610.664 33.17856 -67.37651 611.262 32.93401 -67.37651 611.262 32.93401 -67.62919 611.8599 32.39083 -67.47837 611.5477 15 -67.62919 611.8599 32.39083 -67.97679 612.3577 31.62765 -67.97679 612.3577 31.62765 -68.33828 612.712 30.81453 -68.12844 612.5209 15 -68.33828 612.712 30.81453 -68.39253 612.7558 30.69057 -68.39253 612.7558 30.69057 -68.71479 612.9774 29.94398 -68.71479 612.9774 29.94398 -63.39152 620.8354 38.69906 -69.14739 613.19 28.91108 -69.6615 613.3417 27.63368 -67.82604 624.6667 28.6547 -65.47879 625.4463 33.33375 -63.42197 626.1297 36.81345 -65.97993 631.6911 23.38922 -68.40866 624.4733 27.33496 -67.82604 624.6667 28.6547 -69.82097 624.0044 23.76871 -64.12982 632.1183 27.82041 -65.47879 625.4463 33.33375 -61.95378 632.6161 32.12916 -63.42197 626.1297 36.81345 -62.76384 626.3484 37.83317 -62.76384 626.3484 37.83317 -57.13015 621.4311 47.32294 -59.10451 627.5651 42.86042 -57.26454 628.1773 45.05265 -57.13015 614.3345 48.43207 -57.13015 607.1518 48.48294 -57.13015 600.0402 47.47441 -57.13015 593.1549 45.42853 -57.13015 586.6464 42.39 -57.13015 580.657 38.42522 -57.13015 575.3175 33.62082 -57.13514 570.762 28.09628 -59.24118 569.2998 20.64593 -57.3353 570.6715 27.55557 -57.80462 570.3815 26.11795 -60.34629 568.4676 15 -57.13015 562.8691 10.09746 -58.62241 566.0896 15 -57.13713 564.1914 15 -49.73501 554.8876 8.35443 -49.73501 554.2624 0 -57.13015 562.2779 -6.738749 -49.73501 554.2624 0 -59.46541 633.1798 36.28043 -59.10451 627.5651 42.86042 -56.68139 633.8043 40.24372 -57.26454 628.1773 45.05265 -53.80528 629.3286 48.70009 -53.60992 634.4871 44.00482 -53.80528 629.3286 48.70009 -49.73501 622.7445 54.76351 -49.83775 630.65 52.26025 -49.73501 614.4571 55.99079 -49.73501 606.0794 55.97106 -49.73501 597.7978 54.70478 -49.73501 589.7969 52.22013 -49.73501 582.255 48.57246 -49.73501 575.3398 43.84301 -56.79975 570.8765 28.92544 -55.61899 570.9607 31.24211 -54.99074 570.8101 32.15046 -49.73501 569.2055 38.1371 -56.22544 570.9765 30.15783 -56.74977 570.8898 15 -57.13514 570.762 28.09628 -57.3353 570.6715 27.55557 -56.79975 570.8765 28.92544 -57.80462 570.3815 26.11795 -60.34629 568.4676 15 -57.80462 570.3815 26.11795 -59.24118 569.2998 20.64593 -57.80462 570.3815 15 -57.80462 570.3815 15 -53.02935 567.5669 15 -60.34629 568.4676 15 -58.62241 566.0896 15 -53.60358 569.7896 15 -57.80462 570.3815 15 -53.09548 568.7354 15 -54.19538 565.5885 15 -57.13713 564.1914 15 -53.41547 566.4619 15 -56.72421 563.6842 15 -56.72421 563.6842 15 -49.73501 556.749 16.52279 -41.35287 548.4362 8.685245 -41.35287 547.8305 0 -49.73501 554.8875 -8.354279 -41.35287 547.8305 0 -49.73501 559.8054 24.32316 -55.63002 564.5082 20.5971 -54.19538 565.5885 15 -56.72421 563.6842 15 -55.63002 564.5082 20.5971 -54.19538 565.5885 26.07275 -54.19538 565.5885 26.07275 -49.73501 563.9886 31.58182 -53.78998 565.9562 27.50262 -54.19538 565.5885 15 -54.19538 565.5885 26.07275 -53.78998 565.9562 27.50262 -53.45192 566.4016 28.84482 -53.45192 566.4016 28.84482 -53.22024 566.8568 29.94317 -53.41547 566.4619 15 -53.22024 566.8568 29.94317 -53.07683 567.3104 30.84073 -53.07683 567.3104 30.84073 -53.00473 567.8165 31.65664 -53.02935 567.5669 15 -53.00473 567.8165 31.65664 -53.0339 568.4348 32.42361 -53.0339 568.4348 32.42361 -53.20914 569.0855 32.96821 -53.09548 568.7354 15 -53.20914 569.0855 32.96821 -53.50529 569.6513 33.19223 -53.50529 569.6513 33.19223 -53.89653 570.124 33.13631 -53.60358 569.7896 15 -53.89653 570.124 33.13631 -54.39794 570.5214 32.79579 -54.39794 570.5214 32.79579 -54.47632 570.5692 15 -54.99074 570.8101 32.15046 -55.58104 570.9555 15 -55.61899 570.9607 31.24211 -56.22544 570.9765 30.15783 -50.26397 635.2245 47.54362 -49.83775 630.65 52.26025 -41.35287 625.2471 60.78244 -46.71368 631.6912 54.67649 -46.65792 636.0131 50.84039 -46.71368 631.6912 54.67649 -41.35287 616.6661 62.25492 -41.35287 607.9639 62.52204 -41.35287 599.3088 61.57861 -41.35287 590.8685 59.44291 -41.35287 582.8063 56.15629 -41.35287 575.2785 51.78238 -41.35287 568.4306 46.40586 -41.35287 562.3953 40.13085 -41.35287 557.2894 33.07883 -41.35287 553.212 25.38634 -41.35287 550.2417 17.20233 -32.15007 543.3086 9.492854 -32.15007 542.6403 0 -41.35287 548.4362 -8.685099 -32.15007 542.6403 0 -41.33376 633.4856 58.16851 -42.81807 636.8469 53.86824 -41.33376 633.4856 58.16851 -32.15007 627.5878 65.54351 -38.48593 634.4362 59.7168 -38.7592 637.7229 56.61368 -38.48593 634.4362 59.7168 -32.15007 618.236 67.30506 -32.15007 608.7296 67.73908 -32.15007 599.2561 66.83702 -32.15007 590.0024 64.61663 -32.15007 581.151 61.12175 -32.15007 572.8765 56.42129 -32.15007 565.3422 50.60798 -32.15007 558.6966 43.79647 -32.15007 553.0708 36.12111 -32.15007 548.5758 27.7333 -32.15007 545.3002 18.79847 -32.15007 543.3085 -9.492728 -32.14546 636.554 62.51109 -34.50469 638.6359 59.05865 -32.14546 636.554 62.51109 -29.73155 637.361 63.35725 -30.07635 639.5817 61.18894 -29.73155 637.361 63.35725 -24.44622 545.4207 28.37372 -22.42555 546.6537 32.53459 -23.04883 546.4947 31.77834 -23.60556 546.2182 30.7973 -24.06015 545.8648 29.68694 -24.77742 542.0843 18.54829 -24.77209 544.831 26.6842 -24.97357 544.0814 24.55922 -24.96033 543.1977 22.04169 -24.62635 541.1646 15 -22.30891 540.3835 15 -25.49728 640.5556 62.99166 -22.30034 639.8469 65.27307 -21.31669 546.6051 15 -22.30847 546.6681 32.64316 -22.42555 546.6537 32.53459 -21.79627 546.6771 33.00472 -22.48626 546.6442 15 -23.04883 546.4947 31.77834 -23.58184 546.2329 15 -23.60556 546.2182 30.7973 -24.06015 545.8648 29.68694 -24.4368 545.4337 15 -24.44622 545.4207 28.37372 -24.77209 544.831 26.6842 -24.92097 544.368 15 -24.97357 544.0814 24.55922 -24.96033 543.1977 22.04169 -24.62635 541.1646 15 -24.96033 543.1977 22.04169 -24.77742 542.0843 18.54829 -24.96033 543.1977 15 -24.96033 543.1977 15 -19.03967 544.1703 15 -24.62635 541.1646 15 -22.30891 540.3835 15 -24.96033 543.1977 15 -21.44661 540.1146 15 -21.44661 540.1146 15 -18.22507 539.2112 15 -19.03967 544.1703 15 -18.22507 539.2112 15 -18.56588 541.286 22.43991 -19.03967 544.1703 29.59924 -19.03967 544.1703 15 -19.03967 544.1703 29.59924 -19.11506 544.5068 30.29371 -19.2432 544.8673 30.98637 -19.45133 545.2664 15 -19.45848 545.278 31.7094 -19.7769 545.6984 32.36631 -20.14481 546.0416 32.82046 -20.25098 546.1213 15 -20.60956 546.3424 33.11888 -21.1875 546.5719 33.1973 1.494158 600.007 57.9 1.506723 600.0087 74.26136 4.361477 600.8488 57.9 4.377624 600.8561 74.26136 6.875587 602.4644 57.9 6.889151 602.476 74.26136 -67.50106 631.3365 18.85424 -69.10161 613.1715 15 -69.14739 613.19 28.91108 -69.6615 613.3417 27.63368 -70.25 613.4 26.09478 -70.25 613.4 15 38.84489 643.5922 -54.90309 33.14016 643.5922 -58.52354 28.73621 717.9 -41.03935 33.14016 643.5922 -58.52354 29.40812 634.3891 -64.68914 29.42344 643.5922 -60.47757 29.40812 624.5779 -67.52149 29.40812 614.456 -68.87461 29.40812 604.2453 -68.71887 29.40812 594.1694 -67.05767 29.40812 584.4491 -63.9274 29.40812 575.2973 -59.39665 29.40812 566.9145 -53.56467 29.40812 559.4844 -46.55923 29.40812 553.1697 -38.53379 29.40812 548.1088 -29.66418 29.40812 544.4125 -20.1447 25.05051 717.9 -43.38747 29.42344 643.5922 -60.47757 24.89029 643.5922 -62.47998 21.17391 717.9 -45.40562 24.89029 643.5922 -62.47998 19.42106 633.9244 -68.51589 19.43191 643.5922 -64.38694 19.42106 623.687 -71.21292 19.42106 613.1658 -72.38904 19.42106 602.5855 -72.01914 19.42106 592.1721 -70.11111 19.42106 582.1481 -66.70571 19.42106 572.7274 -61.87565 19.42106 564.1113 -55.72412 19.42106 556.4838 -48.38246 19.42106 550.0078 -40.0075 19.42106 544.8215 -30.77809 19.42106 541.036 -20.89135 17.13559 717.9 -47.07846 19.43191 643.5922 -64.38694 16.16067 643.5922 -65.28482 12.9663 717.9 -48.39302 16.16067 643.5922 -65.28482 9.048579 633.6422 -70.73137 9.051488 643.5922 -66.64342 9.048579 623.1596 -73.35064 9.048579 612.4083 -74.42507 9.048579 601.6148 -73.93201 9.048579 591.0062 -71.88187 9.048579 580.8061 -68.31781 9.048579 571.2293 -63.3149 9.048579 562.4774 -56.97851 9.048579 554.7349 -49.44209 9.048579 548.1647 -40.86436 9.048579 542.9053 -31.42598 9.048579 539.0675 -21.32574 8.698943 717.9 -49.33895 9.051488 643.5922 -66.64342 7.146537 643.5922 -66.87453 7.146537 643.5922 -66.87453 -1.503472 633.5443 -71.32377 -1.502658 643.5922 -67.23851 -1.503472 622.9981 -73.91906 -1.503472 612.1876 -74.96363 -1.503472 601.3397 -74.43554 -1.503472 590.6818 -72.3459 -1.503472 580.4375 -68.73854 -1.503472 570.8218 -63.68914 -1.503472 562.0364 -57.30361 -1.503472 554.2656 -49.71594 -1.503472 547.6725 -41.08529 -1.503472 542.3953 -31.59273 -1.503472 538.5447 -21.43739 4.365938 717.9 -49.9093 -1.502658 643.5922 -67.23851 -2.000693 643.5922 -67.22554 0 717.9 -50.09988 -2.000693 643.5922 -67.22554 -12.02569 622.9604 -72.95629 -12.02569 633.3778 -70.37334 -12.02569 612.279 -74.00576 -12.02569 601.5581 -73.49969 -12.02569 591.0231 -71.44871 -12.02569 580.8953 -67.89595 -12.02569 571.3878 -62.91604 -12.02569 562.7002 -56.6137 -12.02569 555.0153 -49.12139 -12.02569 548.4945 -40.59658 -12.02569 543.2749 -31.21846 -12.02569 539.4661 -21.18416 -12.01718 643.2918 -66.32284 -11.12075 643.5922 -66.32952 -4.365938 717.9 -49.9093 -11.12075 643.5922 -66.32952 -20.79552 641.5518 -64.45463 -11.12075 643.5922 -66.32952 -12.01718 643.2918 -66.32284 -8.698943 717.9 -49.33895 -20.79552 641.5518 -64.45463 -20.6169 640.4105 -65.56913 -20.6169 640.4105 -65.56913 -22.30924 630.3144 -68.7802 -22.30049 639.8469 -65.27305 -22.30924 620.3438 -70.91135 -22.30924 610.1716 -71.60479 -22.30924 600.004 -70.84648 -22.30924 590.0473 -68.65176 -22.30924 580.5031 -65.06517 -22.30924 571.5651 -60.15938 -22.30924 563.4145 -54.0339 -22.30924 556.2165 -46.8129 -22.30924 550.1171 -38.64277 -22.30924 545.2398 -29.68918 -22.30924 541.6837 -20.13366 -73.91513 622.6461 -3.404045 -73.96121 622.6309 -2.268409 -73.85105 622.6674 -4.531647 -73.66295 622.7297 -6.837187 -73.76853 622.6948 -5.660743 -73.35289 622.8326 -9.475621 -72.89551 622.9843 -12.36451 -72.05484 623.2632 -16.35969 -72.22494 623.2067 -15.63799 -72.04092 620.7395 -18.11631 -72.04092 617.9309 -19.45231 -72.04092 614.9548 -20.35584 -72.04092 611.8774 -20.80681 -72.04092 608.7672 -20.7952 -72.04092 605.6933 -20.32125 -72.04092 602.7241 -19.39551 -72.04092 599.9255 -18.03857 -72.04092 597.3598 -16.28058 -72.04092 595.0839 -14.16064 -72.04092 593.1486 -11.72587 -72.04092 591.5969 -9.030405 -72.04092 590.4631 -6.134174 -68.39488 580.9322 -8.876266 -68.39488 582.5408 -13.07687 -68.39488 584.7445 -16.99813 -68.39488 587.4963 -20.55628 -68.39488 590.7373 -23.6753 -68.39488 594.3984 -26.28858 -68.39488 598.4013 -28.34028 -68.39488 602.6605 -29.78659 -68.39488 607.085 -30.5966 -68.39488 611.5804 -30.753 -68.39488 616.0505 -30.25247 -68.39488 620.4 -29.10569 -68.41205 624.4721 -27.32707 -71.27449 623.522 -19.30701 -69.9265 623.9694 -23.47676 -68.69245 631.0565 -14.22268 -72.05484 623.2632 -16.35969 -72.22494 623.2067 -15.63799 -67.50109 631.3365 -18.85409 -71.27449 623.522 -19.30701 -72.89551 622.9843 -12.36451 -69.54857 630.854 -9.512896 -73.35289 622.8326 -9.475621 -73.66295 622.7297 -6.837187 -73.76853 622.6948 -5.660743 -73.85105 622.6674 -4.531647 -73.91513 622.6461 -3.404045 -73.96121 622.6309 -2.268409 -69.9265 623.9694 -23.47676 -63.39152 571.9036 -11.15968 -63.39152 573.8552 -16.46178 -63.39152 576.533 -21.4368 -63.39152 579.8836 -25.98587 -63.39152 583.8407 -30.0186 -63.39152 588.3255 -33.45487 -63.39152 593.2489 -36.2264 -63.39152 598.513 -38.27811 -63.39152 604.0134 -39.56925 -63.39152 609.6407 -40.07415 -63.39152 615.283 -39.78279 -63.39152 620.8284 -38.70095 -67.95505 624.6239 -28.36889 -65.62387 625.3981 -33.06912 -63.41157 626.1331 -36.82989 -65.97998 631.6911 -23.38911 -68.41205 624.4721 -27.32707 -64.12979 632.1184 -27.82045 -67.95505 624.6239 -28.36889 -65.62387 625.3981 -33.06912 -57.13015 563.6774 -13.34727 -57.13015 565.9799 -19.69784 -57.13015 569.1409 -25.66773 -57.13015 573.0993 -31.14157 -57.13015 577.7784 -36.01357 -57.13015 583.088 -40.18957 -57.13015 588.9255 -43.58889 -57.13015 595.178 -46.1458 -57.13015 601.7246 -47.81091 -57.13015 608.4389 -48.55203 -57.13015 615.1911 -48.35484 -57.13015 621.8507 -47.22315 -62.93724 626.2908 -37.56842 -59.32432 627.492 -42.58505 -57.27402 628.1741 -45.04188 -61.95365 632.6161 -32.12939 -63.41157 626.1331 -36.82989 -59.4652 633.1798 -36.28075 -62.93724 626.2908 -37.56842 -59.32432 627.492 -42.58505 -49.73501 556.749 -16.5225 -49.73501 559.8052 -24.32276 -49.73501 563.9883 -31.58132 -49.73501 569.205 -38.13655 -49.73501 575.3391 -43.84244 -49.73501 582.254 -48.57194 -49.73501 589.7958 -52.21969 -49.73501 597.7965 -54.70448 -49.73501 606.0778 -55.97095 -49.73501 614.4555 -55.9909 -49.73501 622.7427 -54.7639 -54.08446 629.2357 -48.42613 -56.68117 633.8044 -40.24401 -57.27402 628.1741 -45.04188 -53.60979 634.4871 -44.00498 -54.08446 629.2357 -48.42613 -49.83535 630.6508 -52.26224 -50.26371 635.2246 -47.54389 -49.83535 630.6508 -52.26224 -41.35287 550.2416 -17.20204 -41.35287 553.2118 -25.38594 -41.35287 557.2891 -33.07833 -41.35287 562.3948 -40.13028 -41.35287 568.4299 -46.40527 -41.35287 575.2776 -51.7818 -41.35287 582.8052 -56.15577 -41.35287 590.8673 -59.4425 -41.35287 599.3074 -61.57835 -41.35287 607.9623 -62.52198 -41.35287 616.6644 -62.2551 -41.35287 625.2452 -60.78289 -47.01904 631.5894 -54.45383 -46.65755 636.0131 -50.8407 -47.01904 631.5894 -54.45383 -41.33788 633.4843 -58.16613 -42.81766 636.847 -53.86854 -41.33788 633.4843 -58.16613 -32.15007 545.3001 -18.79822 -32.15007 548.5756 -27.73295 -32.15007 553.0705 -36.12068 -32.15007 558.6962 -43.79598 -32.15007 565.3416 -50.60747 -32.15007 572.8758 -56.4208 -32.15007 581.1501 -61.12131 -32.15007 590.0013 -64.61629 -32.15007 599.2548 -66.83679 -32.15007 608.7282 -67.73905 -32.15007 618.2344 -67.30523 -32.15007 627.5863 -65.54393 -38.73876 634.3518 -59.58708 -38.75888 637.7229 -56.61388 -38.73876 634.3518 -59.58708 -32.14459 636.5543 -62.51141 -34.50445 638.636 -59.05878 -32.14459 636.5543 -62.51141 -29.90929 637.3016 -63.29882 -30.07608 639.5818 -61.18906 -29.90929 637.3016 -63.29882 -25.49694 640.5557 -62.99178 -22.30049 639.8469 -65.27305 -17.13559 717.9 -47.07846 -25.49694 640.5557 -62.99178 -12.9663 717.9 -48.39302 -21.17391 717.9 -45.40562 -30.07608 639.5818 -61.18906 -25.05051 717.9 -43.38747 -34.50445 638.636 -59.05878 -38.75888 637.7229 -56.61388 -28.73621 717.9 -41.03935 -42.81766 636.847 -53.86854 -32.20323 717.9 -38.37903 -46.65755 636.0131 -50.8407 -35.42542 717.9 -35.42658 -50.26371 635.2246 -47.54389 -38.37838 717.9 -32.20416 -53.60979 634.4871 -44.00498 -56.68117 633.8044 -40.24401 -41.03964 717.9 -28.736 -59.4652 633.1798 -36.28075 -43.38824 717.9 -25.04928 -61.95365 632.6161 -32.12939 -45.40624 717.9 -21.17249 -64.12979 632.1184 -27.82045 -47.07857 717.9 -17.13495 -65.97998 631.6911 -23.38911 -67.50109 631.3365 -18.85409 -48.39268 717.9 -12.96714 -68.69245 631.0565 -14.22268 -49.33865 717.9 -8.700526 -69.54857 630.854 -9.512896 -49.90924 717.9 -4.36768 -70.06282 630.7318 -4.760512 -70.23377 630.6911 0 -50.1 717.9 0 -70.23377 630.6911 0 -70.06282 630.7318 4.760514 -50.1 717.9 0 -49.90924 717.9 4.36768 -69.54856 630.854 9.512948 -49.33865 717.9 8.700526 -68.69244 631.0565 14.22278 -62.34753 657.1444 15 -67.50106 631.3365 18.85424 -61.04067 656.8427 19.87928 -65.97993 631.6911 23.38922 -59.36985 656.4569 24.65391 -64.12982 632.1183 27.82041 -58.76423 656.3808 26.10779 -61.95378 632.6161 32.12916 -56.89267 656.9818 29.66942 -59.46541 633.1798 36.28043 -58.23399 656.4157 27.25105 -57.76486 656.5278 28.17288 -57.33029 656.7084 28.95481 -45.4854 703.6893 27.93901 -56.68139 633.8043 40.24372 -56.43425 657.408 30.32435 -56.04573 657.9724 30.76682 -55.79978 658.5941 30.91602 -47.01517 701.7388 26.21781 -46.56807 702.0243 26.87203 -46.10879 702.4635 27.45482 -45.72483 703.0423 27.83376 -41.03964 717.9 28.736 -53.60992 634.4871 44.00482 -38.37838 717.9 32.20416 -50.26397 635.2245 47.54362 -35.42542 717.9 35.42658 -46.65792 636.0131 50.84039 -32.20323 717.9 38.37903 -42.81807 636.8469 53.86824 -28.73621 717.9 41.03935 -38.7592 637.7229 56.61368 -34.50469 638.6359 59.05865 -25.05051 717.9 43.38747 -30.07635 639.5817 61.18894 -21.17391 717.9 45.40562 -25.49728 640.5556 62.99166 -17.13559 717.9 47.07846 -44.808 717.9 4.152421 -50.1 717.9 0 -49.90924 717.9 4.36768 -44.808 717.9 -4.152421 -49.90924 717.9 -4.36768 -49.33865 717.9 8.700526 -60.96049 662.9819 15 -48.39268 717.9 12.96714 -43.28194 717.9 12.31547 -48.39268 717.9 12.96714 -61.65057 660.0786 15 -50.21664 707.8983 15 -47.07857 717.9 17.13495 -47.07857 717.9 17.13495 -59.66622 662.6832 19.74302 -51.62068 702.0646 15 -50.91425 705.0014 15 -47.72515 707.3231 21.97631 -45.40624 717.9 21.17249 -40.28202 717.9 20.05874 -45.40624 717.9 21.17249 -49.08933 707.6381 18.527 -45.95701 706.1412 26.02611 -43.38824 717.9 25.04928 -43.38824 717.9 25.04928 -46.28607 706.5287 25.2499 -46.69724 706.8699 24.31086 -47.19492 707.1473 23.18525 -35.91052 717.9 27.11875 -41.03964 717.9 28.736 -45.40032 704.3557 27.78344 -45.46807 705.0355 27.36919 -45.67605 705.6571 26.73769 -38.37838 717.9 32.20416 -30.31632 717.9 33.25526 -35.42542 717.9 35.42658 -23.68981 717.9 38.25945 -32.20323 717.9 38.37903 -28.73621 717.9 41.03935 -16.25649 717.9 41.96096 -25.05051 717.9 43.38747 -8.269279 717.9 44.23367 -21.17391 717.9 45.40562 21.17391 717.9 45.40562 -17.13559 717.9 47.07846 0 717.9 45 17.13559 717.9 47.07846 -12.9663 717.9 48.39302 12.9663 717.9 48.39302 -8.698943 717.9 49.33895 8.698943 717.9 49.33895 -4.365938 717.9 49.9093 4.365938 717.9 49.9093 0 717.9 50.09988 25.05051 717.9 43.38747 16.25649 717.9 41.96096 28.73621 717.9 41.03935 8.269279 717.9 44.23367 32.20323 717.9 38.37903 23.68981 717.9 38.25945 35.42542 717.9 35.42658 30.31632 717.9 33.25526 38.37838 717.9 32.20416 41.03964 717.9 28.736 45.74522 705.6978 26.60056 43.38824 717.9 25.04928 35.91052 717.9 27.11875 43.38824 717.9 25.04928 45.53133 705.0938 27.23746 45.45003 704.4136 27.67633 47.25069 707.1499 23.07005 45.40624 717.9 21.17249 45.40624 717.9 21.17249 46.75381 706.8745 24.19959 46.34671 706.5392 25.13329 46.02232 706.1625 25.90043 49.11193 707.6317 18.47118 47.07857 717.9 17.13495 40.28202 717.9 20.05874 47.07857 717.9 17.13495 47.77515 707.3231 21.8674 50.21927 707.8874 15 48.39268 717.9 12.96714 43.28194 717.9 12.31547 49.33865 717.9 8.700526 50.91688 704.9905 15 49.90924 717.9 4.36768 44.808 717.9 4.152421 50.1 717.9 0 44.808 717.9 -4.152421 49.90924 717.9 -4.36768 -59.36985 656.4569 15 -62.34753 657.1444 15 -61.04067 656.8427 19.87928 -55.73621 659.8749 15 -61.65057 660.0786 15 -62.34753 657.1444 15 -55.77202 658.7052 15 -56.25259 657.6382 15 -57.10491 656.8361 15 -59.36985 656.4569 15 -59.36985 656.4569 24.65391 -59.36985 656.4569 15 -59.36985 656.4569 24.65391 -58.76423 656.3808 26.10779 -58.23399 656.4157 27.25105 -58.19949 656.4212 15 -57.76486 656.5278 28.17288 -57.33029 656.7084 28.95481 -57.10491 656.8361 15 -56.89267 656.9818 29.66942 -56.43425 657.408 30.32435 -56.25259 657.6382 15 -56.04573 657.9724 30.76682 -55.79978 658.5941 30.91602 -47.46367 701.5499 25.48898 -55.69826 659.2402 30.79105 -55.77202 658.7052 15 -55.69826 659.2402 30.79105 -55.74392 659.9196 30.38207 -55.73621 659.8749 15 -55.74392 659.9196 30.38207 -55.94521 660.5794 29.68608 -55.94521 660.5794 29.68608 -47.96909 701.4311 24.5846 -56.28447 661.1659 28.7414 -56.15069 660.9694 15 -56.28447 661.1659 28.7414 -48.53236 701.4029 23.46816 -56.73226 661.6489 27.59294 -56.73226 661.6489 27.59294 -57.30456 662.0383 26.16809 -56.9526 661.8221 15 -57.30456 662.0383 26.16809 -49.07485 701.4769 22.27017 -58.02014 662.3031 24.38332 -58.02014 662.3031 24.38332 -60.96049 662.9819 15 -58.02014 662.3031 24.38332 -59.66622 662.6832 19.74302 -50.47284 701.7996 18.67533 -58.02014 662.3031 15 -58.02014 662.3031 15 -58.02014 662.3031 15 -60.96049 662.9819 15 -56.9526 661.8221 15 -56.15069 660.9694 15 -49.07485 701.4769 15 -51.62068 702.0646 15 -50.47284 701.7996 18.67533 -45.44121 704.8948 15 -50.91425 705.0014 15 -51.62068 702.0646 15 -45.47702 703.7252 15 -45.95759 702.6582 15 -46.80992 701.8562 15 -49.07485 701.4769 15 -49.07485 701.4769 22.27017 -49.07485 701.4769 15 -49.07485 701.4769 22.27017 -48.53236 701.4029 23.46816 -47.96909 701.4311 24.5846 -47.90449 701.4412 15 -47.46367 701.5499 25.48898 -47.01517 701.7388 26.21781 -46.80992 701.8562 15 -46.56807 702.0243 26.87203 -46.10879 702.4635 27.45482 -45.95759 702.6582 15 -45.72483 703.0423 27.83376 -45.4854 703.6893 27.93901 -45.47702 703.7252 15 -45.40032 704.3557 27.78344 -45.44121 704.8948 15 -45.46807 705.0355 27.36919 -45.67605 705.6571 26.73769 -45.85569 705.9894 15 -45.95701 706.1412 26.02611 -46.28607 706.5287 25.2499 -46.6576 706.8421 15 -46.69724 706.8699 24.31086 -47.19492 707.1473 23.18525 -47.72515 707.3231 21.97631 -50.21664 707.8983 15 -47.72515 707.3231 21.97631 -49.08933 707.6381 18.527 -47.72515 707.3231 15 -47.72515 707.3231 15 -47.72515 707.3231 15 -50.21664 707.8983 15 -46.6576 706.8421 15 -45.85569 705.9894 15 47.77515 707.3231 15 50.21927 707.8874 15 49.11193 707.6317 18.47118 45.90569 705.9894 15 50.91688 704.9905 15 50.21927 707.8874 15 46.7076 706.8421 15 47.77515 707.3231 15 47.77515 707.3231 21.8674 47.77515 707.3231 15 47.77515 707.3231 21.8674 47.25069 707.1499 23.07005 46.75381 706.8745 24.19959 46.7076 706.8421 15 46.34671 706.5392 25.13329 46.02232 706.1625 25.90043 45.90569 705.9894 15 45.74522 705.6978 26.60056 45.53133 705.0938 27.23746 45.49121 704.8948 15 45.45003 704.4136 27.67633 45.52315 703.7416 27.85435 45.52702 703.7252 15 45.74649 703.0996 27.77269 46.00759 702.6582 15 46.11853 702.5121 27.41659 46.58361 702.0513 26.83254 46.85992 701.8562 15 47.04394 701.7499 26.16085 47.50069 701.5541 25.41783 47.95449 701.4412 15 48.0111 701.4323 24.50188 48.57522 701.4026 23.37947 49.12485 701.4769 22.15966 51.62331 702.0537 15 49.12485 701.4769 22.15966 50.49533 701.7933 18.61869 49.12485 701.4769 15 49.12485 701.4769 15 46.00759 702.6582 15 51.62331 702.0537 15 46.85992 701.8562 15 49.12485 701.4769 15 45.52702 703.7252 15 45.49121 704.8948 15 49.33865 717.9 -8.700526 43.28194 717.9 -12.31547 48.39268 717.9 -12.96714 47.07857 717.9 -17.13495 40.28202 717.9 -20.05874 45.40624 717.9 -21.17249 43.38824 717.9 -25.04928 35.91052 717.9 -27.11875 41.03964 717.9 -28.736 38.37838 717.9 -32.20416 30.31632 717.9 -33.25526 35.42542 717.9 -35.42658 23.68981 717.9 -38.25945 32.20323 717.9 -38.37903 28.73621 717.9 -41.03935 16.25649 717.9 -41.96096 25.05051 717.9 -43.38747 8.269279 717.9 -44.23367 21.17391 717.9 -45.40562 -21.17391 717.9 -45.40562 17.13559 717.9 -47.07846 0 717.9 -45 -17.13559 717.9 -47.07846 12.9663 717.9 -48.39302 -12.9663 717.9 -48.39302 8.698943 717.9 -49.33895 -8.698943 717.9 -49.33895 4.365938 717.9 -49.9093 -4.365938 717.9 -49.9093 0 717.9 -50.09988 -25.05051 717.9 -43.38747 -16.25649 717.9 -41.96096 -28.73621 717.9 -41.03935 -8.269279 717.9 -44.23367 -32.20323 717.9 -38.37903 -23.68981 717.9 -38.25945 -35.42542 717.9 -35.42658 -30.31632 717.9 -33.25526 -38.37838 717.9 -32.20416 -41.03964 717.9 -28.736 -35.91052 717.9 -27.11875 -43.38824 717.9 -25.04928 -45.40624 717.9 -21.17249 -40.28202 717.9 -20.05874 -47.07857 717.9 -17.13495 -48.39268 717.9 -12.96714 -43.28194 717.9 -12.31547 -49.33865 717.9 -8.700526 0 750.4 -45 0 717.9 -45 -8.269279 717.9 -44.23367 8.269443 750.4 -44.23362 8.269279 717.9 -44.23367 0 717.9 -45 0 750.4 -45 -8.269443 750.4 -44.23362 -16.25649 717.9 -41.96096 -16.25633 750.4 -41.96097 -23.68981 717.9 -38.25945 -23.68929 750.4 -38.25974 -30.31632 717.9 -33.25526 -30.31576 750.4 -33.25579 -35.91052 717.9 -27.11875 -35.91038 750.4 -27.11904 -40.28202 717.9 -20.05874 -40.28251 750.4 -20.05788 -43.28194 717.9 -12.31547 -43.2823 750.4 -12.3141 -44.808 717.9 -4.152421 -44.80796 750.4 -4.151734 -44.808 717.9 4.152421 -44.80796 750.4 4.151734 -43.28194 717.9 12.31547 -43.2823 750.4 12.3141 -40.28202 717.9 20.05874 -40.28251 750.4 20.05788 -35.91052 717.9 27.11875 -35.91038 750.4 27.11904 -30.31632 717.9 33.25526 -30.31576 750.4 33.25579 -23.68981 717.9 38.25945 -23.68929 750.4 38.25974 -16.25649 717.9 41.96096 -16.25633 750.4 41.96097 -8.269279 717.9 44.23367 -8.269443 750.4 44.23362 0 717.9 45 0 750.4 45 0 717.9 45 8.269279 717.9 44.23367 0 750.4 45 8.269443 750.4 44.23362 16.25649 717.9 41.96096 16.25633 750.4 41.96097 23.68981 717.9 38.25945 23.68929 750.4 38.25974 30.31632 717.9 33.25526 30.31576 750.4 33.25579 35.91052 717.9 27.11875 35.91038 750.4 27.11904 40.28202 717.9 20.05874 40.28251 750.4 20.05788 43.28194 717.9 12.31547 43.2823 750.4 12.3141 44.808 717.9 4.152421 44.80796 750.4 4.151734 44.808 717.9 -4.152421 44.80796 750.4 -4.151734 43.28194 717.9 -12.31547 43.2823 750.4 -12.3141 40.28202 717.9 -20.05874 40.28251 750.4 -20.05788 35.91052 717.9 -27.11875 35.91038 750.4 -27.11904 30.31632 717.9 -33.25526 30.31576 750.4 -33.25579 23.68981 717.9 -38.25945 23.68929 750.4 -38.25974 16.25649 717.9 -41.96096 16.25633 750.4 -41.96097 10.07455 613.3586 57.9 -10.07455 613.3586 57.9 -10.5 610.4 57.9 10.5 610.4 57.9 -10.07455 607.4414 57.9 8.832825 616.0772 57.9 -8.832825 616.0772 57.9 6.875587 618.3356 57.9 -6.875587 618.3356 57.9 4.361477 619.9512 57.9 -4.361477 619.9512 57.9 1.494158 620.793 57.9 -1.494158 620.793 57.9 10.07455 607.4414 57.9 -8.832825 604.7229 57.9 8.832825 604.7229 57.9 -6.875587 602.4644 57.9 6.875587 602.4644 57.9 -4.361477 600.8488 57.9 4.361477 600.8488 57.9 -1.494158 600.007 57.9 1.494158 600.007 57.9 -54.47632 570.5692 15 -56.74977 570.8898 15 -55.58104 570.9555 15 -24.92097 544.368 15 -19.45133 545.2664 15 -24.4368 545.4337 15 -20.25098 546.1213 15 -23.58184 546.2329 15 -21.31669 546.6051 15 -22.48626 546.6442 15 19.00063 543.6239 15 19.20601 544.7763 15 19.83661 545.7622 15 24.07783 545.8479 15 20.79635 546.4318 15 23.0915 546.4783 15 21.93924 546.6833 15 -58.19949 656.4212 15 -47.90449 701.4412 15 47.95449 701.4412 15 62.40221 657.5997 15 67.37981 657.2734 15 63.174 656.7199 15 66.49959 656.5018 15 64.22358 656.2023 15 65.3913 656.1257 15 62.02574 562.192 15 62.40221 563.3004 15 67.37981 563.6266 15 63.174 564.1801 15 66.49959 564.3983 15 64.22358 564.6976 15 65.3913 564.7742 15 8.269443 750.4 44.23362 8.269443 750.4 -44.23362 0 750.4 -45 0 750.4 45 -8.269443 750.4 -44.23362 16.25633 750.4 41.96097 16.25633 750.4 -41.96097 23.68929 750.4 38.25974 23.68929 750.4 -38.25974 30.31576 750.4 33.25579 30.31576 750.4 -33.25579 35.91038 750.4 27.11904 35.91038 750.4 -27.11904 40.28251 750.4 20.05788 40.28251 750.4 -20.05788 43.2823 750.4 12.3141 43.2823 750.4 -12.3141 44.80796 750.4 4.151734 44.80796 750.4 -4.151734 -8.269443 750.4 44.23362 -16.25633 750.4 -41.96097 -16.25633 750.4 41.96097 -23.68929 750.4 -38.25974 -23.68929 750.4 38.25974 -30.31576 750.4 -33.25579 -30.31576 750.4 33.25579 -35.91038 750.4 -27.11904 -35.91038 750.4 27.11904 -40.28251 750.4 -20.05788 -40.28251 750.4 20.05788 -43.2823 750.4 -12.3141 -43.2823 750.4 12.3141 -44.80796 750.4 -4.151734 -44.80796 750.4 4.151734 110 566.1664 -8.269443 110 654.6336 -8.269443 110 655.4 0 110 565.4 0 110 654.6336 8.269443 110 568.439 -16.25633 110 652.361 -16.25633 110 572.1403 -23.68929 110 648.6597 -23.68929 110 577.1442 -30.31576 110 643.6558 -30.31576 110 583.281 -35.91038 110 637.5191 -35.91038 110 590.3421 -40.28251 110 630.4579 -40.28251 110 598.0859 -43.2823 110 622.7141 -43.2823 110 606.2483 -44.80796 110 614.5518 -44.80796 110 566.1664 8.269443 110 652.361 16.25633 110 568.439 16.25633 110 648.6597 23.68929 110 572.1403 23.68929 110 643.6558 30.31576 110 577.1442 30.31576 110 637.5191 35.91038 110 583.281 35.91038 110 630.4579 40.28251 110 590.3421 40.28251 110 622.7141 43.2823 110 598.0859 43.2823 110 614.5518 44.80796 110 606.2483 44.80796 -7.408469 609.2319 57.9 -7.499978 610.4 57.9 -7.408469 611.5682 57.9 -7.408469 611.5682 62.05 -7.408469 611.5682 57.9 -7.499978 610.4 57.9 -4.715887 616.2319 57.9 -4.715887 616.2319 62.05 -4.715887 616.2319 57.9 -7.408469 611.5682 57.9 -7.408469 611.5682 62.05 -7.499978 610.4 62.05 -7.408469 609.2319 57.9 -4.715887 604.5682 57.9 -7.408469 609.2319 62.05 -7.408469 609.2319 57.9 -4.715887 604.5682 57.9 -7.408469 609.2319 62.05 -3.755648 616.8919 57.9 -3.755648 603.9081 57.9 -4.715887 604.5682 62.05 -4.715887 604.5682 57.9 -3.755648 603.9081 57.9 -4.715887 604.5682 62.05 -2.692582 617.4 57.9 -2.692582 603.4 57.9 -3.755648 603.9081 62.05 -2.692582 603.4 57.9 2.692582 617.4 57.9 2.692582 603.4 57.9 -2.692582 603.4 62.05 -2.692582 603.4 57.9 2.692582 603.4 57.9 -2.692582 603.4 62.05 3.755648 616.8919 57.9 3.755648 603.9081 57.9 2.692582 603.4 62.05 2.692582 603.4 57.9 3.755648 603.9081 57.9 2.692582 603.4 62.05 4.715887 616.2319 57.9 4.715887 604.5682 57.9 3.755648 603.9081 62.05 4.715887 604.5682 57.9 7.408469 611.5682 57.9 7.408469 609.2319 57.9 4.715887 604.5682 62.05 4.715887 604.5682 57.9 7.408469 609.2319 57.9 4.715887 604.5682 62.05 7.499978 610.4 57.9 7.408469 609.2319 62.05 7.408469 609.2319 57.9 7.499978 610.4 57.9 7.408469 609.2319 62.05 7.499978 610.4 62.05 7.408469 611.5682 57.9 7.408469 611.5682 62.05 7.408469 611.5682 57.9 4.715887 616.2319 57.9 7.408469 611.5682 62.05 4.715887 616.2319 62.05 4.715887 616.2319 57.9 3.755648 616.8919 57.9 4.715887 616.2319 62.05 3.755648 616.8919 62.05 2.692582 617.4 57.9 2.692582 617.4 62.05 2.692582 617.4 57.9 -2.692582 617.4 57.9 2.692582 617.4 62.05 -2.692582 617.4 62.05 -2.692582 617.4 57.9 -3.755648 616.8919 57.9 -2.692582 617.4 62.05 -3.755648 616.8919 62.05 -4.715887 616.2319 57.9 -4.715887 616.2319 62.05 4.715887 616.2319 62.05 5.405114 613.0018 62.05 6 610.4 62.05 6 610.4 65.4 6 610.4 62.05 5.405114 613.0018 62.05 7.408469 609.2319 62.05 5.405114 607.7983 62.05 5.406202 607.8007 65.4 5.405114 607.7983 62.05 6 610.4 62.05 6 610.4 65.4 3.755648 616.8919 62.05 3.738611 615.0924 62.05 5.406202 612.9993 65.4 3.738611 615.0924 62.05 2.692582 617.4 62.05 1.337587 616.2481 62.05 3.738526 615.0904 65.4 1.337587 616.2481 62.05 -2.692582 617.4 62.05 -1.337587 616.2481 62.05 1.331379 616.25 65.4 -1.337587 616.2481 62.05 -3.738611 615.0924 62.05 -1.331379 616.25 65.4 -3.738611 615.0924 62.05 -4.715887 616.2319 62.05 -5.405114 613.0018 62.05 -3.738526 615.0904 65.4 -5.405114 613.0018 62.05 -3.755648 616.8919 62.05 -7.408469 611.5682 62.05 -6 610.4 62.05 -5.406202 612.9993 65.4 -6 610.4 62.05 -4.715887 604.5682 62.05 -5.405114 607.7983 62.05 -6 610.4 65.4 -6 610.4 62.05 -5.405114 607.7983 62.05 -6 610.4 65.4 -3.755648 603.9081 62.05 -3.738611 605.7076 62.05 -5.406202 607.8007 65.4 -3.738611 605.7076 62.05 -2.692582 603.4 62.05 -1.337587 604.552 62.05 -3.738526 605.7096 65.4 -1.337587 604.552 62.05 2.692582 603.4 62.05 1.337587 604.552 62.05 -1.331379 604.5501 65.4 1.337587 604.552 62.05 3.738611 605.7076 62.05 1.331379 604.5501 65.4 3.738611 605.7076 62.05 4.715887 604.5682 62.05 3.738526 605.7096 65.4 3.755648 603.9081 62.05 -7.408469 609.2319 62.05 -7.499978 610.4 62.05 7.408469 611.5682 62.05 7.499978 610.4 62.05 4.198536 607.9738 65.4 5.406202 607.8007 65.4 6 610.4 65.4 4.85 610.4 65.4 5.406202 612.9993 65.4 2.426187 606.2015 65.4 3.738526 605.7096 65.4 -1.331379 604.5501 65.4 1.331379 604.5501 65.4 0 605.55 65.4 -3.738526 605.7096 65.4 -2.426187 606.2015 65.4 -5.406202 607.8007 65.4 -4.85 610.4 65.4 -6 610.4 65.4 -4.198536 607.9738 65.4 -4.198536 612.8262 65.4 -5.406202 612.9993 65.4 -2.426187 614.5985 65.4 -3.738526 615.0904 65.4 1.331379 616.25 65.4 -1.331379 616.25 65.4 0 615.25 65.4 3.738526 615.0904 65.4 2.426187 614.5985 65.4 4.198536 612.8262 65.4 4.85 610.4 68.9 4.85 610.4 65.4 4.198536 612.8262 65.4 4.198776 607.9758 68.9 4.198536 607.9738 65.4 4.85 610.4 65.4 4.85 610.4 68.9 4.198776 612.8242 68.9 2.426187 614.5985 65.4 2.425 614.6002 68.9 0 615.25 65.4 0 615.2484 68.9 -2.426187 614.5985 65.4 -2.425 614.6002 68.9 -4.198536 612.8262 65.4 -4.198776 612.8242 68.9 -4.85 610.4 65.4 -4.85 610.4 68.9 -4.85 610.4 65.4 -4.198536 607.9738 65.4 -4.85 610.4 68.9 -4.198776 607.9758 68.9 -2.426187 606.2015 65.4 -2.425 606.1998 68.9 0 605.55 65.4 0 605.5517 68.9 2.426187 606.2015 65.4 2.425 606.1998 68.9 -4.198776 607.9758 68.9 4.198776 607.9758 68.9 4.85 610.4 68.9 -4.85 610.4 68.9 4.198776 612.8242 68.9 -2.425 606.1998 68.9 2.425 606.1998 68.9 0 605.5517 68.9 -4.198776 612.8242 68.9 2.425 614.6002 68.9 -2.425 614.6002 68.9 0 615.2484 68.9 - - - - - - - - - - 0.2592886 0.6202661 0.7402969 0.2568491 0.6376974 0.7262029 0.2580071 0.553766 0.7916916 0.6889472 0.2250813 0.6889777 0.6672602 0.2240681 0.7103221 0.7348856 0.2248086 0.6398471 0.258862 0.5541941 0.7911129 0.2587718 0.4878485 0.8336913 0.5683053 0.331809 0.7529488 0.5777567 0.4029434 0.7098127 0.591038 0.4340463 0.6799103 0.6264 0.2253513 0.7462171 0.6080943 0.2243158 0.7615142 0.2560263 0.7389637 0.623204 0.2567284 0.7314255 0.6317495 0.7467472 0.2245002 0.6260737 0.8001272 0.2243176 0.5563077 0.2558428 0.6856454 0.6814947 0.2594788 0.7906443 0.5545741 0.2486693 0.8173919 0.519648 0.8180819 0.2251136 0.5292125 0.8619323 0.2234334 0.4551376 0.7978351 0.2248966 0.5593574 0.2431437 0.8827276 0.402086 0.2454688 0.8860744 0.3932141 0.8794459 0.2225472 0.4207704 0.9110987 0.2234027 0.3463963 0.2591071 0.8107094 0.5249896 0.1934573 0.889617 0.4137101 0.2236147 0.8710812 0.4372802 0.240765 0.8571589 0.4553142 0.2502921 0.8467389 0.4694542 0.2555985 0.8381189 0.4818985 0.2580419 0.8310748 0.4926753 0.2587419 0.8264908 0.4999657 0.2588263 0.8257411 0.5011594 0.8235102 0.2191612 0.5232585 0.835522 0.2215688 0.5028025 0.8431143 0.2228793 0.4893701 0.8508869 0.2238919 0.4752514 0.8590477 0.2246195 0.4599817 0.8681073 0.2249236 0.4424921 0.2473914 0.9267562 0.2827025 0.2476974 0.9337484 0.2583793 0.9360261 0.2245913 0.2709501 0.9466669 0.223185 0.2324017 0.2115877 0.9252729 0.3148027 0.8931161 0.2222719 0.391074 0.9147678 0.2249534 0.3355532 0.2589263 0.9509838 0.1690773 0.2555978 0.9578434 0.1311713 0.9593877 0.2257167 0.169196 0.9676408 0.2237055 0.1167358 0.2602699 0.9331021 0.2481537 0.9409297 0.2272135 0.2510489 0.2512611 0.966713 0.04831123 0.2582804 0.9639052 0.06463873 0.9706016 0.2253231 0.08462965 0.9730945 0.2235507 0.05578851 0.2546836 0.9637079 0.08002156 0.2592278 0.9622316 -0.08313357 0.2533394 0.9654731 -0.06067204 0.2585869 0.9650695 -0.0421161 0.2553241 0.9574806 -0.1343152 0.9738255 0.2230621 -0.04367244 0.9728136 0.224587 -0.05652058 0.9675721 0.2241615 -0.1164297 0.9734908 0.2247409 0.04251277 1 0 0 0.2591665 0.924204 0.2804992 0.2612136 0.9067855 0.3309193 0.2591685 0.9287583 0.2650281 0.2594754 0.8824969 0.3922649 0.2607851 0.8750111 0.4078563 1 -2.75777e-6 0 0.2591995 0.9032459 0.3419981 0.2617017 0.8408943 0.4737183 0.26103 0.8361627 0.4823851 0.2685695 0.8434609 0.4652356 0.2631943 0.8554119 0.4460935 0.2596259 0.8673219 0.424673 1 2.7621e-6 0 0.2623454 0.8093461 0.5254845 0.2593792 0.8275473 0.4978834 0.258866 0.8337305 0.4877314 1 -1.39751e-6 0 1 1.18679e-6 0 1 7.69563e-7 0 0.2594434 0.4830268 0.836286 1 1.00742e-6 0 1 -4.78363e-7 0 0.2583492 0.421599 0.8692008 0.2598751 0.4082007 0.8751212 1 -3.7584e-7 0 0.2580387 0.3527699 0.8994274 0.2601479 0.3303121 0.9073131 0.2578538 0.2818111 0.9241721 0.2602949 0.2499184 0.932624 0.2577999 0.2090905 0.943303 0.2603 0.1676431 0.9508627 0.2578864 0.135108 0.9566821 0.260145 0.08408015 0.9619019 0.2580384 0.06033611 0.9642489 0.2598673 -1.22075e-4 0.9656443 0.2583467 -0.01480185 0.9659389 0.2593811 -0.08438503 0.9620814 0.2588649 -0.1639498 0.9518978 0.2593193 -0.1675183 0.9511526 0.2588359 -0.08987993 0.9617305 0.2584356 -0.2374689 0.9363864 0.259782 -0.2498021 0.9327981 0.2580991 -0.3095847 0.9151733 0.2601181 -0.3301605 0.9073768 0.2578889 -0.3798138 0.8883889 0.2602714 -0.4080169 0.8750892 0.2578254 -0.4477459 0.8561832 0.2603012 -0.4827582 0.8361746 0.2578557 -0.5129648 0.818766 0.260178 -0.5538663 0.7909106 1 -1.00742e-6 0 0.2580086 -0.5750412 0.7763758 0.2599307 -0.6207574 0.7396596 1 -1.18678e-6 0 0.2582858 -0.6336137 0.7292615 0.2593571 -0.6831243 0.6826971 1 -7.69558e-7 0 0.2589864 -0.7386272 0.6223794 0.259229 -0.7397518 0.620941 1 -1.20418e-6 0 0.258867 -0.6883691 0.6775957 0.2584988 -0.7848657 0.5631733 0.2598064 -0.7909553 0.553977 1 1.51667e-6 0 0.2638717 -0.8269264 0.4965526 0.2609737 -0.8356286 0.48334 0.2581896 -0.8263899 0.5004178 0.2583122 -0.8076226 0.5301139 0.265123 -0.8209749 0.5056778 0.2620693 -0.8150182 0.5167835 0.2619431 -0.8641712 0.4296441 0.2613332 -0.8749764 0.4075797 0.2627691 -0.8551744 0.4467989 0.2599353 -0.8469795 0.4637451 0.2588963 -0.8393758 0.4779342 0.2586189 -0.902694 0.3438892 0.2614311 -0.906799 0.3307107 0.2590212 -0.8809225 0.3960855 0.2590754 -0.9240531 0.2810796 0.2614864 -0.9325677 0.2488821 0.257433 -0.940218 0.2229763 0.2599955 -0.9509567 0.1675825 0.2589239 -0.9285736 0.2659127 0.2591664 -0.9287507 0.2650565 0.2582252 -0.9544354 0.1495759 0.2593216 -0.9621481 0.08380568 0.2591999 -0.9650797 0.03790485 0.2585865 -0.9650683 0.04214656 0.2588896 -0.9630157 0.07467907 0.2585849 -0.9630786 -0.07492339 0.2591706 -0.9649314 -0.04168945 0.2586168 -0.9652503 -0.03753817 0.2596244 -0.9620478 -0.08401858 0.5414974 -0.8388434 0.05588012 0.5753216 -0.81731 0.0317707 0.573674 -0.8166697 0.0628395 0.5139487 -0.8494803 -0.1193313 0.5647298 -0.8233507 -0.05633866 0.5649065 -0.8239822 -0.04397785 0.528198 -0.8454769 -0.07858723 0.5125615 -0.8501593 0.1204572 0.5750409 -0.8079627 0.1285464 0.5734872 -0.7975594 0.1871135 0.2568165 -0.9200838 0.2957892 0.5133051 -0.8243889 0.2385393 0.5733394 -0.7788577 0.2542885 0.2606024 -0.9063251 0.3326579 0.2570598 -0.8941398 0.3666529 0.5730038 -0.7597832 0.3072399 0.2569724 -0.8707764 0.4191824 0.2575498 -0.8628024 0.4350177 0.51423 -0.7821642 0.3518335 0.5704615 -0.731022 0.3744072 0.2578278 -0.8842079 0.3894885 0.2569435 -0.8295804 0.4957584 0.5722419 -0.7040558 0.4205291 0.2515982 -0.834205 0.4907142 0.2550789 -0.8424807 0.4745115 0.2574585 -0.8506566 0.4583652 0.2587134 -0.8596109 0.4406093 0.5152887 -0.7244073 0.4579429 0.5664703 -0.6654142 0.4861433 0.2587576 -0.8236073 0.5046935 0.2587721 -0.8242924 0.5035664 0.5710804 -0.6316005 0.5243551 0.5154113 -0.6538473 0.5539268 0.5737008 -0.5837111 0.5745858 0.5142852 -0.5687627 0.6418876 0.5753836 -0.5354641 0.6182329 0.5735853 -0.4889544 0.6572089 0.5146829 -0.4725353 0.7154104 0.5740977 -0.4321221 0.6954728 0.5732064 -0.3826462 0.7245802 0.5151978 -0.3669346 0.7745516 0.5716344 -0.3181681 0.7563091 0.5725699 -0.2671036 0.7751255 0.5158922 -0.2541312 0.8180908 0.5680539 -0.1960553 0.7992979 0.5715298 -0.1449043 0.807686 0.5157816 -0.1379181 0.8455461 0.5736996 -0.07565701 0.8155642 0.5146785 -0.01632785 0.8572278 0.5755623 -0.01190245 0.8176714 0.5736402 0.04999053 0.8175806 0.5147614 0.1046186 0.8509265 0.5746713 0.1168264 0.8100028 0.5733605 0.1745992 0.8004829 0.5150121 0.2234008 0.8275595 0.5726383 0.2430577 0.7829486 0.5728193 0.2953976 0.7646034 0.5169423 0.3344346 0.7879875 0.5694831 0.3639687 0.7370319 0.5378398 0.3764238 0.7543431 0.9659232 -0.2588289 0 0 0 1 0.9659262 -0.2588176 0 0.9978095 -0.06613403 0.001617491 0.985498 -0.1696872 0 0.999761 0.01815855 0.01217693 0.9860548 0.1664177 0.00112915 0.9915136 0.129982 0.002349972 0.9406982 0.3391921 0.005981743 0.8785292 0.4776884 4.5779e-4 0.865904 0.5001997 0.003234922 0.7732822 0.634056 0.002777159 0.6335718 0.773684 3.05189e-5 0.6080594 0.7938892 0.001922667 0.4577878 0.8890543 0.003601253 0.2784584 0.9604434 0.003082394 0.2600526 0.9655913 0.002471983 0.08191388 0.9966394 -3.96751e-4 -0.1304991 0.9914391 0.004303157 -0.1238469 0.9923013 -3.05192e-4 -0.3233237 0.9462879 0.001037657 -0.4995344 0.8662807 0.004821956 -0.5009496 0.8654764 -4.57795e-4 -0.6397392 0.7685903 0.001617491 -0.7943247 0.6074858 0.003082394 -0.7647806 0.6442908 -2.44154e-4 -0.8683908 0.4958745 0.002472043 -0.9256017 0.3783098 0.0119633 -0.9658939 0.2589383 3.45389e-5 -0.9659271 0.2588142 0 -0.8968614 0.4423117 0 -0.9659249 -0.2588227 -9.96392e-6 -0.9659251 -0.2588217 0 -0.8971441 -0.4417358 0.001464903 -0.9379533 -0.3467617 0 -0.8550837 -0.5183361 0.01263487 -0.7674247 -0.641138 0.00125122 -0.7936514 -0.6083694 0.002075254 -0.6369376 -0.7708867 0.006653189 -0.5104371 -0.859915 5.49349e-4 -0.4997153 -0.8661853 0.002807676 -0.334733 -0.9423063 0.003570675 -0.1423698 -0.9898136 3.05187e-4 -0.1296143 -0.9915634 0.00149542 0.06894278 -0.9976107 0.004455745 0.2590439 -0.9658603 0.003204464 0.2575214 -0.9662699 0.002258419 0.4449415 -0.8955596 -3.66232e-4 0.6087629 -0.7933419 0.004059016 0.6188306 -0.7855246 -2.44151e-4 0.7643744 -0.6447712 0.001434326 0.865722 -0.5005055 0.004455685 0.8734769 -0.4868655 -3.66225e-4 0.9414383 -0.3371806 0.001861691 0.9916357 -0.1290359 0.002899289 0.985446 -0.1699886 -2.74668e-4 0.9999718 0.007110774 0.002441465 0.990429 0.1375485 0.01144456 0.9659956 0.2585586 1.41289e-4 0.9659251 0.2588219 0 0.997865 0.0653097 0 0.2559924 0.9344882 -0.247386 0.2553558 0.9304452 -0.2628026 0.9593877 0.2257167 -0.169196 0.9464312 0.2237363 -0.232831 0.2556926 0.9514158 -0.1715502 0.9708496 0.2244695 -0.08405017 0.2593536 0.9077073 -0.3298534 0.2548096 0.8832421 -0.393644 0.9410062 0.2252945 -0.2524874 0.9110581 0.223858 -0.3462094 0.2574315 0.8379417 -0.4812305 0.2546223 0.8180692 -0.5156843 0.8831122 0.2253559 -0.4114944 0.8618001 0.2237054 -0.4552544 0.257459 0.8747684 -0.4104816 0.9156413 0.2249276 -0.3331797 0.2591704 0.7908787 -0.5543841 0.2546511 0.733312 -0.6304018 0.8436709 0.2256279 -0.4871464 0.8004847 0.2240405 -0.5559049 0.258983 0.6835003 -0.6824626 0.2570953 0.6362682 -0.7273685 0.7979774 0.2251683 -0.559045 0.7348821 0.2246549 -0.639905 0.2588049 0.7397913 -0.6210707 0.2572174 0.5554223 -0.7907878 0.2588638 0.5539234 -0.7913017 0.6889472 0.2250813 -0.6889777 0.6672602 0.2240681 -0.7103221 0.2575231 0.6196364 -0.7414396 0.7464497 0.2249603 -0.6262634 0.2593826 0.4830578 -0.8362869 0.2588315 0.4878764 -0.8336564 0.5682922 0.3318014 -0.7529621 0.591038 0.4340463 -0.6799103 0.5808408 0.4047757 -0.7062441 0.6262833 0.2250481 -0.7464066 0.6077044 0.2249287 -0.7616447 0.2583492 0.421599 -0.8692008 0.5362932 0.3784144 -0.7544483 0.5736751 0.3594282 -0.7360084 0.2598751 0.4082007 -0.8751212 0.2580387 0.3527699 -0.8994274 0.5162904 0.3339697 -0.7886118 0.573127 0.295582 -0.7643015 0.2601479 0.3303121 -0.9073131 0.2578538 0.2818111 -0.9241721 0.5729653 0.2427182 -0.7828145 0.2602949 0.2499184 -0.932624 0.2577999 0.2090905 -0.943303 0.5154421 0.2227305 -0.8274725 0.5701919 0.1723119 -0.8032371 0.2603 0.1676431 -0.9508627 0.2578864 0.135108 -0.9566821 0.5721709 0.1197261 -0.8113485 0.260145 0.08408015 -0.9619019 0.2580384 0.06033611 -0.9642489 0.5162311 0.1040092 -0.8501104 0.5660731 0.04422253 -0.8231681 0.2598673 -1.22075e-4 -0.9656443 0.2583467 -0.01480185 -0.9659389 0.5709485 -0.006561517 -0.8209598 0.2594103 -0.0843541 -0.9620763 0.258772 -0.08984839 -0.9617506 0.516143 -0.01492393 -0.8563725 0.5736996 -0.07565701 -0.8155642 0.2593811 -0.1675798 -0.9511249 0.2588351 -0.1639808 -0.9519006 0.5147027 -0.1369997 -0.8463524 0.5753078 -0.1402944 -0.8058155 0.2584356 -0.2374689 -0.9363864 0.5735477 -0.1996262 -0.7944762 0.259782 -0.2498021 -0.9327981 0.2580991 -0.3095847 -0.9151733 0.5148893 -0.2548658 -0.8184942 0.5739217 -0.2654903 -0.7746799 0.2601181 -0.3301605 -0.9073768 0.2578889 -0.3798138 -0.8883889 0.5731793 -0.3190467 -0.754768 0.2602714 -0.4080169 -0.8750892 0.2578254 -0.4477459 -0.8561832 0.5152323 -0.3675173 -0.7742524 0.57138 -0.3847247 -0.724922 0.2603012 -0.4827582 -0.8361746 0.2578557 -0.5129648 -0.818766 0.5725098 -0.4313279 -0.6972724 0.260178 -0.5538663 -0.7909106 0.2580086 -0.5750412 -0.7763758 0.5157526 -0.4726588 -0.714558 0.5676844 -0.4953237 -0.6575629 0.2599307 -0.6207574 -0.7396596 0.2582858 -0.6336137 -0.7292615 0.5714368 -0.5338985 -0.6232275 0.2595333 -0.6830145 -0.6827399 0.2586802 -0.6883288 -0.6777081 0.5154195 -0.5674864 -0.6421075 0.5737008 -0.5837111 -0.5745858 0.2593851 -0.7397924 -0.6208274 0.258808 -0.7387319 -0.6223294 0.5140293 -0.6536226 -0.5554739 0.5755314 -0.6258881 -0.5263344 0.2584988 -0.7848657 -0.5631733 0.5736327 -0.6647925 -0.4785358 0.2597166 -0.7909607 -0.5540113 0.2581663 -0.8263518 -0.5004928 0.5139147 -0.7253831 -0.4579423 0.5745542 -0.7014224 -0.4217751 0.2600554 -0.8361999 -0.4828467 0.257919 -0.8628126 -0.4347786 0.5733302 -0.7304116 -0.3712028 0.2602649 -0.8750675 -0.4080678 0.2578263 -0.8940297 -0.3663831 0.513887 -0.7826111 -0.3513402 0.5724261 -0.760366 -0.3068748 0.260298 -0.9073045 -0.3302174 0.2578266 -0.9198197 -0.2957316 0.5727816 -0.7790598 -0.2549256 0.2602365 -0.932664 -0.2498294 0.2579783 -0.9399897 -0.2233086 0.5140372 -0.8241443 -0.2378067 0.5691503 -0.8013394 -0.1841826 0.2599955 -0.9509567 -0.1675825 0.2582252 -0.9544354 -0.1495759 0.5718775 -0.8095951 -0.1323332 1 2.75781e-6 0 1 -2.76207e-6 0 1 1.39751e-6 0 1 4.78359e-7 0 1 3.75843e-7 0 1 1.20418e-6 0 1 -1.51667e-6 0 0 0.9957351 0.09225815 0 0.9829716 0.1837578 0 0.9829726 -0.1837523 0 0.9829716 -0.1837578 0 0.9957351 -0.09225815 0 0.9829726 0.1837523 0 0.932469 0.3612501 0 0.8502163 0.5264335 0 0.7390073 0.6736975 0 0.7390224 0.6736809 0 0.6026336 0.798018 0 0.4457358 0.8951646 0 0.2736608 0.9618263 0 0.2736327 0.9618343 0 0.09225815 0.9957351 0 -0.09225815 0.9957351 0 -0.2736689 0.9618241 0 -0.2736327 0.9618343 0 -0.4457603 0.8951524 0 -0.4457358 0.8951646 0 -0.6026336 0.798018 0 -0.7390224 0.6736809 0 -0.8502027 0.5264555 0 -0.8502249 0.5264198 0 -0.932469 0.3612501 0 -0.9829716 0.1837578 0 -0.9829726 0.1837523 0 -0.9957324 0.09228843 0 -0.9957324 -0.09228843 0 -0.9957351 -0.09225815 0 -0.9829716 -0.1837578 0 -0.9957351 0.09225815 0 -0.932469 -0.3612501 0 -0.8502163 -0.5264335 0 -0.7390224 -0.6736809 0 -0.6026336 -0.798018 0 -0.602653 -0.7980033 0 -0.4457358 -0.8951646 0 -0.2736608 -0.9618263 0 -0.2736327 -0.9618343 0 -0.09225815 -0.9957351 0 0.09225815 -0.9957351 0 0.2736689 -0.9618241 0 0.2736327 -0.9618343 0 0.4457603 -0.8951524 0 0.4457237 -0.8951706 0 0.6026336 -0.798018 0 0.7390224 -0.6736809 0 0.8502027 -0.5264555 0 0.8502249 -0.5264198 0 0.932469 -0.3612501 -0.1392265 0.3636919 0.921056 -0.06439518 0.38689 0.9198747 -0.0943641 0.2602643 0.9609152 -0.08499634 0.2252938 0.9705764 -0.1675496 0.2235215 0.9601903 -0.05935937 0.2247416 0.9726088 -0.3141324 0.6428224 0.6986417 -0.2730519 0.793123 0.5444251 -0.2722911 0.8006066 0.5337479 -0.2518128 0.2250781 0.9412387 -0.2892318 0.2241036 0.930657 -0.1693508 0.2248957 0.9595531 -0.02313351 0.3474918 0.9373977 0.007416129 0.3943394 0.918935 0.00701934 0.2250478 0.9743225 -0.160319 0.3068128 0.9381704 0.09677618 0.3345509 0.9373955 4.57782e-4 0.2248015 0.9744045 0.07968509 0.2246504 0.9711759 -0.02084481 0.2436676 0.9696349 0.1236622 0.3230417 0.9382706 0.1291275 0.3703221 0.9198846 -0.169929 0.1758191 0.9696453 -0.0321061 0.2132982 0.9764595 0.1292499 0.2066167 0.9698474 -0.07989776 0.2183303 0.9725987 0.1443254 -0.9895254 0.003112912 0.1779239 -0.9840443 3.05187e-5 0.4155773 -0.9095579 3.0519e-5 -0.01699888 0.3194396 0.9474542 -1.22078e-4 -1 3.35714e-4 -0.1207012 0.1427967 0.9823648 0.4154027 -0.9096377 0 0.6551839 -0.7554696 -3.05191e-5 -0.1732249 0.1030926 0.9794719 0.8412073 -0.5407129 6.10389e-5 0.8416602 -0.5400077 -3.05193e-5 0.6547912 -0.75581 0 -0.1994758 0.02719289 0.9795254 -0.1636111 0.06262445 0.9845352 0.9594957 -0.2817234 3.05193e-5 0.9596126 -0.2813252 0 -0.2050275 -0.02917629 0.9783213 0.98984 -0.1421861 0 -0.1815899 -0.1292187 0.9748476 -0.2406444 -0.04571783 0.969536 0.9898222 0.14231 3.0519e-5 0.9898486 0.1421263 0 0.9596315 0.2812607 0 0.9898179 -0.1423399 0 -0.1463686 -0.08942031 0.9851803 0.9594874 0.2817516 6.1038e-5 0.8416829 0.5399723 -3.0519e-5 -0.1174987 -0.1562581 0.9807026 0.8412073 0.5407129 6.10389e-5 0.6551839 0.7554696 -6.10382e-5 -0.08719384 -0.2086914 0.9740868 0.6547912 0.75581 0 0.4155773 0.9095579 0 -0.1615374 -0.2592899 0.9521946 -0.04751896 -0.2141253 0.9756497 0.4154027 0.9096377 3.05196e-5 0.1779239 0.9840443 0 -0.02285903 -0.2798331 0.9597765 0.009613335 -0.2185746 0.975773 0.1442956 0.9895297 0.003143489 -1.22078e-4 1 3.35714e-4 -0.1606857 -0.3928484 0.9054559 -0.02246224 -0.412866 0.9105148 0.1206132 -0.3335176 0.9349966 0.1266839 -0.2101225 0.9694327 -0.1598317 -0.5199031 0.8391392 -0.02246224 -0.5384846 0.8423359 0.1203674 -0.4579091 0.8808127 -0.1590982 -0.6359961 0.7551137 -0.02243149 -0.6531073 0.7569331 0.1201548 -0.573795 0.8101371 -0.1584231 -0.7386773 0.6551778 -0.02230983 -0.7544144 0.6560192 0.1199402 -0.6789287 0.7243412 -0.1567775 -0.8251494 0.5427241 -0.02212631 -0.8403115 0.5416521 0.1197564 -0.7713364 0.625059 -0.1459729 -0.8961631 0.4190273 -0.02188223 -0.9090143 0.4161903 0.1195424 -0.8493095 0.5141819 -0.1421582 -0.9480776 0.2844996 -0.02151608 -0.9591289 0.2821506 0.1179571 -0.9119164 0.393058 -0.1504609 -0.9792472 0.135781 -0.0210278 -0.9895897 0.1423727 0.1175588 -0.9562491 0.267895 -0.05539125 -0.9958835 0.07174926 0.01431322 -0.9973812 0.07089489 0.117132 -0.9840251 0.13407 -0.1598297 -0.9845535 0.07147622 -0.1594293 -0.9768406 -0.1427052 -0.002471983 -0.9959498 -0.08987778 -0.03759938 -0.9916232 -0.1235714 0.08441483 -0.9940871 0.06830096 -0.02002066 -0.9893144 -0.1444174 0.1012917 -0.9873726 -0.1218003 -0.1594612 -0.9846311 -0.07123106 -0.2916719 -0.9549149 0.0553618 -0.2963757 -0.9454359 -0.1353238 -0.2956369 -0.9528927 -0.06778252 -0.2196173 -0.9587963 0.1802168 -0.294964 -0.9511178 0.09149527 -0.201214 -0.9285206 0.3120298 -0.1938568 -0.8733632 0.4468291 -0.2030134 -0.9022685 0.3803908 -0.2080522 -0.8857401 0.4149446 -0.2957914 -0.7815339 0.5492833 -0.3440113 -0.7946564 0.5001776 -0.5184373 -0.3902853 0.760855 -0.1670008 -0.87413 0.4560784 -0.1903775 -0.8609108 0.4717934 -0.2126567 -0.846049 0.4888541 -0.2406099 -0.823793 0.5132951 -0.2978408 -0.7671104 0.5681836 -0.2954813 -0.6983883 0.6518779 -0.2950969 -0.6018831 0.742061 -0.2946366 -0.4938992 0.8180788 -0.2940548 -0.3765183 0.878502 -0.2947529 -0.1232969 0.9475857 -0.2940847 -0.2526699 0.9217766 -0.2953939 0.008484244 0.955338 -0.2959443 0.1401134 0.9448731 -0.2953659 0.2674103 0.9171972 -0.2432658 0.3265517 0.9133377 -0.2880411 0.3244201 0.9009906 -0.3061699 0.6410279 0.7038062 0.08435505 0.224896 0.9707245 0.1497551 0.2246479 0.9628639 0.2293509 0.3387619 0.9124903 0.1692265 0.2255641 0.9594181 0.2208699 0.2244407 0.9491274 0.2571507 0.3148615 0.9136387 0.2692998 0.3629626 0.8920402 0.2043235 0.1332147 0.9697968 0.1981904 0.1128287 0.9736479 0.2589541 0.1790857 0.9491423 0.1350458 0.142706 0.980509 0.07440543 0.1759424 0.9815845 0.02771121 0.2372544 0.9710523 -0.9594957 -0.2817234 2.44154e-4 -0.8862138 -0.4631274 0.0117498 -0.8123896 -0.583038 0.009491443 0.2640221 0.04025489 0.9636762 0.1967264 0.06039738 0.9785965 -0.9629368 -0.2697273 0 -0.84123 -0.5406774 9.15575e-5 -0.6560337 -0.7547317 -9.15566e-5 -0.6548086 -0.7557949 1.22075e-4 -0.4168061 -0.9089955 -1.22078e-4 -0.4153659 -0.9096544 1.22077e-4 -0.1785363 -0.9839334 -6.1038e-5 -0.1443254 -0.9895254 0.003143429 0.2520572 0.2255666 0.9410563 0.2896854 0.2245885 0.9303991 0.3909854 0.317708 0.8638241 0.3335731 0.3717219 0.866344 0.3332099 0.2256293 0.9154576 0.3579242 0.2245572 0.9063467 0.3896043 0.1894613 0.9012841 0.3892999 0.05435425 0.919506 0.2062796 -0.1042538 0.9729235 0.2603564 -0.1007122 0.9602456 0.3890593 -0.08194416 0.917561 0.2525769 -0.09207642 0.9631859 0.2085674 -0.006866753 0.977984 0.2608518 -0.2384808 0.9354588 0.3888456 -0.216534 0.8954955 0.2613379 -0.3712078 0.8910148 0.3886664 -0.3463969 0.8537843 0.2617627 -0.4960582 0.8278929 0.3885034 -0.4687066 0.7933343 0.26222 -0.6105344 0.747321 0.3882662 -0.5809038 0.7154022 0.262314 -0.7118031 0.6515579 0.2590172 -0.7967672 0.5459597 0.3883855 -0.6798425 0.6220699 0.1752703 -0.8668604 0.4667264 0.07880139 -0.8632445 0.4985973 0.3919324 -0.7610058 0.5169712 0.2373824 -0.8280003 0.5080009 0.1639186 -0.8532255 0.4951131 0.1807026 -0.8802882 0.4386792 0.7210799 -0.6928496 0.001861631 0.8437609 -0.5367085 0.003418087 0.8909832 -0.4540065 0.005218803 0.766801 -0.6418849 3.05194e-5 0.185495 -0.8900281 0.4164634 0.931324 -0.3641856 0.00213629 0.9517918 -0.3067451 -6.10377e-5 0.1745076 -0.9088255 0.378924 0.9921736 -0.1248228 0.003326535 0.1442345 -0.917748 0.3700474 0.9997852 0.02069211 0.00125128 0.9954504 0.09528148 -6.10387e-5 0.1677332 -0.925554 0.3394339 0.9628286 0.2700363 0.006439566 0.1801836 -0.9355571 0.3037546 0.9159121 0.4013792 3.29276e-5 0.9159732 0.4012395 0 0.9766729 0.2147325 0 0.2310905 -0.9478006 0.2197068 0.05276817 -0.9597467 0.2758657 0.9160165 0.4011409 0 0.2597163 -0.9604317 0.1005905 0.2642005 -0.9509631 0.1608336 0.2229418 -0.9732534 0.05545312 0.295213 -0.9536665 0.05804765 0.3997145 -0.9081092 0.1247639 0.1520459 -0.9862234 0.06515818 0.1202161 -0.9822991 -0.143655 0.2739713 -0.9577549 -0.08743762 0.2386281 -0.9636683 -0.1200007 0.3568325 -0.9315732 0.06958413 0.2581624 -0.955802 -0.1406937 0.3716915 -0.9206987 -0.1189938 0.1371233 -0.9865372 -0.08911639 0.2082597 -0.1357778 0.9686033 0.02801674 -0.2340223 0.9718275 0.0755645 -0.1768563 0.9813317 0.1377028 -0.1450884 0.9797895 -0.9598174 0.2806207 0.001678526 -0.889391 0.4571473 2.13635e-4 -0.9629447 0.269699 0 -0.8405964 0.5416587 0.001892149 -0.8084523 0.5885618 -3.05191e-5 -0.9898443 0.1421562 0 -0.9898222 -0.14231 3.0519e-5 -0.9898486 -0.1421263 0 -0.9898222 0.14231 0 0.4102427 0.3754506 0.8311063 0.4118848 0.2254135 0.8829154 0.4240014 0.2249866 0.8772706 0.4543347 0.3729713 0.8089947 0.4879438 0.2250193 0.8433725 0.3614097 -0.8194131 0.4449105 0.409326 -0.8219175 0.3961111 0.361959 -0.8105928 0.4603532 0.3366907 -0.8070567 0.4850763 0.2995219 -0.7970567 0.5243923 0.1670954 -0.7360132 0.6560211 0.3734069 -0.880398 0.2923469 0.4145762 -0.8691023 0.2697919 0.3881106 -0.8573715 0.3380594 0.3607343 -0.8501061 0.3836541 0.3546965 -0.8403823 0.4098145 0.3708733 -0.9112521 0.1790885 0.4213518 -0.9044445 0.0666545 0.3041896 -0.9473919 0.09958571 0.4054233 -0.9101576 -0.08511936 0.4842197 -0.8727307 0.06222885 0.3904916 -0.9105976 -0.1353826 0.4978032 -0.8593063 -0.1174084 -0.9159785 -0.4012273 5.88884e-6 -0.9159752 -0.4012348 0 -0.8215076 -0.5701845 0.003875851 -0.8610377 -0.5085411 0 -0.743605 -0.6686188 -7.62985e-4 -0.6923637 -0.7215403 0.003479182 -0.58234 -0.8129442 0.001434385 -0.4108506 -0.9117026 -4.2727e-4 -0.3636361 -0.9315372 0.002685666 -0.2171111 -0.9761455 0.001678526 -0.02688694 -0.9996386 0 0.02044743 -0.9997889 0.002075254 0.1637355 -0.9865029 0.001648008 0.3342164 -0.9424957 0.00125128 0.4012617 -0.915962 0.001709043 0.4963623 -0.8681151 8.54534e-4 0.6402873 -0.7681311 0.002594053 0.4873313 0.2249879 0.843735 0.5498293 0.224833 0.8044488 0.5585654 0.2252328 0.798295 -0.9933839 0.1128886 0.02108842 -0.9985184 0 0.05441522 -0.992581 0.1192696 -0.02362197 -0.9985226 -0.001312315 -0.05432391 -0.981483 0.04767024 -0.1855235 -0.9936226 0.1116097 0.01605319 -0.9934651 0.1093202 0.03280824 -0.9931412 0.105839 0.04968452 -0.9925801 0.1012936 0.06726455 -0.9917972 0.09500473 0.08551341 -0.9906629 0.08682793 0.1051091 -0.989838 0.07614606 0.1200941 -0.9896863 0.05948245 0.1303182 -0.9896687 0.04034602 0.1375795 -0.9914494 0.02539199 0.1279978 -0.9924604 -9.15582e-5 0.1225659 -0.9924171 -0.01760941 0.1216487 -0.9906008 -0.04477202 0.1292499 -0.989651 -0.05960428 0.1305312 -0.9896488 -0.07757997 0.1207342 -0.989649 -0.09396886 0.1084655 -0.989649 -0.1084655 0.09396886 -0.9896488 -0.1207342 0.07757997 -0.989647 -0.1305612 0.05960404 -0.9896478 -0.1377028 0.04043799 -0.9896465 -0.1420669 0.02041733 -0.9895924 -0.1435328 0.0102545 -0.9896515 -0.1420371 -0.02038693 -0.9895924 -0.1435328 -0.0102545 -0.9934115 0.1098975 -0.03250229 -0.9931362 0.1058722 -0.04971629 -0.9925627 0.1013834 -0.06738549 -0.9917638 0.0951876 -0.08569628 -0.9904898 0.08713132 -0.1064803 -0.9897148 0.07730573 -0.1203686 -0.9897045 0.05945122 -0.1301946 -0.9897079 0.04031586 -0.1373059 -0.989709 0.02035629 -0.1416398 -0.9897077 0 -0.1431046 -0.989709 -0.02035629 -0.1416398 -0.9897038 -0.04031568 -0.1373359 -0.9897027 -0.05948162 -0.1301943 -0.9896982 -0.07742649 -0.1204277 -0.9896935 -0.09378421 -0.1082196 -0.9896863 -0.1082832 -0.09378641 -0.989677 -0.1205814 -0.07745772 -0.9896728 -0.130408 -0.05951219 -0.9896592 -0.1376391 -0.04037618 -0.9912601 0.1316288 -0.008789479 -0.9886268 0.1501221 0.008972525 -0.9883763 0.1512808 -0.01504564 -0.9884104 0.1516171 -0.007568597 -0.9881684 0.1502441 0.03082394 -0.9885436 0.150276 0.01409977 -0.9874235 0.145852 0.06100821 -0.9878714 0.148231 0.04623633 -0.9858554 0.1355654 0.09854584 -0.9869861 0.1406012 0.0780372 -0.983507 0.1204892 0.1348942 -0.9792661 0.09451758 0.1791775 -0.9740871 0.07202571 0.2143986 -0.9649232 0.1294926 0.2283746 -0.97079 0.1223826 0.2063718 -0.9610437 0.1059315 0.2552915 -0.9577579 0.08408075 0.2750098 -0.9852673 0.02035599 0.1698063 -0.9564622 0.2772947 0.09103786 -0.985446 -1.83112e-4 0.1699886 -0.3726685 -0.9261626 0.05780309 -0.9853184 -0.02014279 0.1695352 -0.9597715 -0.07977747 0.2692109 -0.9569387 -0.09027665 0.2758962 -0.9599369 -0.1170089 0.2546179 -0.9599226 -0.1520165 0.2354561 -0.9599006 -0.1839718 0.2115309 -0.9598761 -0.2122275 0.1832957 -0.9598429 -0.2362145 0.1513421 -0.9598017 -0.2554466 0.1163091 -0.9597622 -0.2695135 0.07886111 -0.9596874 -0.2782468 0.03973644 -0.9594345 -0.2812046 0.02023428 -0.9594283 -0.2811723 -0.02096658 -0.9108523 -0.4081668 0.06122195 -0.9104072 -0.412584 0.03054934 -0.9596562 -0.2780635 -0.04172015 -0.9103188 -0.4127991 -0.03027474 -0.9057583 0.423794 -7.62988e-4 -0.9045397 0.4263749 -0.003540098 -0.9058886 0.4233258 0.01269578 -0.9035151 0.4247024 -0.05734515 -0.9019107 0.4317891 -0.01074284 -0.904617 0.4254669 0.02542239 -0.9025066 0.429005 0.0379045 -0.9034808 0.4261045 0.04644972 -0.9030927 0.4256203 0.05719292 -0.9037479 0.4235984 0.06167811 -0.9013141 0.4259215 0.07889127 -0.8988697 0.4262253 0.1018106 -0.8965288 0.4277251 0.1152706 -0.8928422 0.4291624 0.1365739 -0.8880102 0.4305615 0.1614148 -0.8859344 0.4314157 0.1702957 -0.8828603 0.4316335 0.1850686 -0.9501952 0.139169 0.278857 -0.8750467 0.433861 0.2146111 -0.9348363 0.09088641 0.3432504 -0.9133778 0.130561 0.3856098 -0.9263961 0.140142 0.3495005 -0.9666019 0.05975645 0.2492192 -0.9500869 0.07260465 0.3034199 -0.908069 0.09427386 0.4080725 0 -0.9999999 5.54139e-4 0 -1 0 -0.9379794 0.1348646 0.3193842 0 1 0 0 1 -1.28277e-5 -0.908842 -0.0994327 0.4051166 -0.9339969 -0.1089826 0.3402539 0.5586585 -0.8089791 -0.1829031 -0.9111202 -0.1511005 0.3834432 -0.9111251 -0.2065245 0.3566493 -0.9111145 -0.2573363 0.321945 -0.9110816 -0.3024731 0.2800722 -0.9110388 -0.3408727 0.231979 -0.9109912 -0.371721 0.178658 -0.9109166 -0.3943429 0.1213456 -0.8449942 -0.5295138 0.07483386 -0.8442729 -0.5346899 0.03619527 -0.9108043 -0.4084641 -0.05993896 -0.8432775 -0.5361317 -0.03802698 -0.1947425 0.980854 8.85054e-4 -0.09799575 0.9951869 0 -0.2831848 0.9590256 0.008728384 -0.9196479 -0.06653058 0.3870676 -0.4189903 0.9079904 7.62966e-4 -0.9123519 -0.06296181 0.4045368 -0.3822253 0.9240674 0.001770079 -0.5553656 0.8315988 0.003540217 -0.8893117 -0.0825833 0.449783 -0.6284837 0.7777839 0.007782399 -0.844168 -0.08517974 0.5292683 -0.8415482 -0.01217728 0.5400448 -0.7778571 -0.4028913 0.4823038 -0.6821593 0.7312033 8.24011e-4 -0.8441973 -0.158823 0.5119631 -0.844233 -0.2292632 0.484468 -0.8442645 -0.2951554 0.4473262 -0.844289 -0.3551544 0.4012997 -0.8443369 -0.4080382 0.347275 -0.8473293 -0.4467981 0.2870616 -0.8523074 -0.4759762 0.2168383 -0.8484988 -0.5100088 0.1412129 -0.7586989 -0.6482207 0.06469994 -0.7576554 -0.6515727 0.03756839 -0.8438678 -0.5312552 -0.07520037 -0.7594999 -0.648929 -0.04529041 -0.8292348 -0.2707961 0.4889162 -0.7071649 0.7070428 0.002899289 -0.7919673 0.6105626 0.001068115 -0.861307 -0.1408146 0.4881818 -0.8927055 0.4506406 -3.35707e-4 -0.8708642 -0.06567722 0.4871163 -0.9239811 0.3824286 0.002716124 -0.9639047 0.2662457 0.001098632 -0.8697956 -0.01483225 0.4931893 -0.9957689 0.09189224 4.27264e-4 -0.842497 0.06808704 0.534381 -0.8663279 0.01205521 0.4993303 -0.999997 0 0.002441525 -0.9968952 -0.07873839 4.883e-4 -0.8752236 0.04754859 0.481376 -0.9681239 -0.2504695 0.001159667 -0.880535 0.08191305 0.4668495 -0.9238779 -0.3826805 0.002288937 -0.9009814 -0.4338579 0 -0.8832253 0.1211612 0.4530268 -0.802423 -0.596751 0.00238049 -0.8835315 0.1519247 0.4430475 -0.7075769 -0.7066308 0.002838194 -0.6877277 -0.7259687 -3.35715e-4 -0.8934761 0.08023458 0.4418855 -0.6204499 -0.784245 0.001312255 -0.9128268 0.05975639 0.4039511 -0.5540154 -0.8325033 0.002319455 -0.8452553 0.1351383 0.5169925 -0.9199912 0.06421166 0.3866435 -0.9275686 0.07892251 0.3652227 -0.9011973 0.1646198 0.4009289 -0.8709028 0.09332841 0.4825124 -0.8619163 0.1561349 0.4824131 -0.8505086 0.445458 0.2796472 -0.845665 0.4453406 0.294147 -0.8341225 0.4490302 0.3203304 -0.8609681 0.4380985 0.2584643 -0.8273082 0.4534203 0.3316191 -0.8135673 0.4549116 0.3621653 -0.7997944 0.4639577 0.3808836 -0.7914754 0.4653207 0.396287 -0.8289253 0.1776813 0.5303889 -0.7756747 0.4700254 0.4211948 -0.7603346 0.1441135 0.6333425 -0.7852614 0.1252816 0.6063573 -0.7698152 0.1782013 0.6128857 -0.7593778 0.05282866 0.6485017 -0.7593796 -0.04330676 0.6492051 -0.759372 -0.1385254 0.6357398 -0.7593914 -0.230729 0.6083493 -0.7594335 -0.3178548 0.5676524 -0.7594964 -0.3979986 0.5145507 -0.7643817 -0.4584886 0.4533309 -0.8040043 -0.4610267 0.3755418 -0.8150266 -0.5079076 0.2788578 -0.811563 -0.4517432 0.3705319 -0.8103842 -0.4753717 0.3424898 -0.8146561 -0.55579 0.1656291 -0.7607849 -0.6350759 0.1337355 -0.7897156 -0.610934 0.05575859 -0.7855723 -0.6010819 0.1468904 -0.6609591 -0.7422629 0.1103582 -0.6611884 -0.7481972 0.05505573 -0.7604108 -0.6432484 -0.08948159 -0.6599241 -0.7492853 -0.05542343 -0.7690511 0.4737177 0.4291293 -0.7466478 0.4791486 0.4614475 -0.7349529 0.4874762 0.4713928 -0.7179282 0.4902262 0.4942241 -0.7053664 0.1772571 0.6863222 -0.6974835 0.5006963 0.5126598 -0.6830503 0.5017662 0.5307289 -0.6622961 0.1646203 0.7309337 -0.6635757 0.1999608 0.7208904 -0.6629085 0.05408006 0.7467449 -0.6631869 -0.05765116 0.7462303 -0.6633714 -0.1680707 0.7291713 -0.6634494 -0.2746697 0.6959825 -0.6634327 -0.3751761 0.6473793 -0.6633683 -0.4673731 0.5843842 -0.7909184 -0.471377 0.3901945 -0.7566455 -0.4953965 0.4266965 -0.7326811 -0.4882506 0.47412 -0.6570242 -0.548863 0.516787 -0.7728328 -0.4863203 0.4077033 0.2510781 -0.9679647 0.002044737 0.3336979 -0.9426799 6.10386e-4 0.419061 -0.9079504 0.00375384 0.1921765 -0.9813604 -2.13631e-4 0.5037474 -0.8638111 0.008301138 0.6013387 -0.7989944 0 0.6015329 -0.7988481 0 0.4341037 -0.9008629 0 -0.7284022 -0.6574755 0.1927593 -0.6605671 -0.7174862 0.2210537 -0.5496477 -0.8274015 0.1153008 -0.5488809 -0.8338657 0.05829089 -0.6614169 -0.741805 -0.1106939 -0.5497152 -0.8332709 -0.0589329 -0.6549453 -0.6831452 0.3230473 -0.6974662 -0.6673128 0.2612179 -0.6015505 0.7988348 0 -0.6897028 -0.6388579 0.3408381 -0.6015471 0.7988374 0 -0.6479886 -0.6292497 0.4291337 -0.6762436 -0.6410551 0.3629644 -0.7454948 0.6665108 0.001068174 -0.6718111 0.7407226 0 -0.7967177 0.6042981 0.008056879 -0.685106 -0.6181763 0.3853416 -0.8802651 0.4744819 6.10384e-4 -0.6759641 -0.604153 0.4219855 -0.8612732 0.5081393 0.001739561 -0.9492083 0.3146225 0.004059016 -0.5779815 -0.6854413 0.4428404 -0.985781 0.1680353 1.52593e-4 -0.6296113 -0.6311984 0.4529662 -0.9902402 0.1393483 0.002533018 -0.9998818 -0.01528978 0.001678466 -0.6607698 -0.5920102 0.4614188 -0.9776033 -0.2104564 -2.44149e-4 -0.6804329 -0.5619562 0.4703365 -0.9681299 -0.2504405 0.002075254 -0.9152087 -0.402975 0.002044737 -0.6952788 -0.533041 0.4821357 -0.8279328 -0.5608262 0.001159727 -0.7146973 -0.4829349 0.5059463 -0.7987267 -0.6016926 0.001281797 -0.7146042 -0.6995278 0.001342833 -0.7614641 -0.2136677 0.6119791 -0.575398 -0.8178684 0.002929747 -0.50854 -0.8610358 0.00213629 -0.3961724 -0.9181762 -3.35713e-4 -0.1397454 -0.9901812 0.003540158 -0.1984984 -0.9801012 -1.52597e-4 0.001861631 -0.9999983 2.74675e-4 -0.6574766 0.5150126 0.5499877 -0.6419302 0.5175055 0.5657861 -0.5493078 0.1960833 0.8122883 -0.6223208 0.1995052 0.7569112 -0.6141098 0.5313109 0.5835905 -0.6019055 0.5310392 0.596412 -0.549923 0.0837748 0.8310034 -0.5494903 -0.03241091 0.8348713 -0.5491623 -0.1480791 0.8224922 -0.5489111 -0.2609662 0.7940991 -0.5487417 -0.3688289 0.7502319 -0.5486461 -0.4695399 0.6917513 -0.5486108 -0.5611236 0.6198118 -0.5486514 -0.6417668 0.5358331 -0.5487734 -0.709917 0.4414359 -0.5489802 -0.7642019 0.33855 -0.549308 -0.8035906 0.2291352 -0.4327574 -0.8929209 0.1241507 -0.4298973 -0.9008738 0.06012332 -0.5501153 -0.8271414 -0.1149367 -0.4264783 -0.902276 -0.0633583 -0.5435149 0.2453431 0.8027443 -0.5713906 0.5442281 0.6142708 -0.5525145 0.5498288 0.6264313 -0.427303 0.2271258 0.875115 -0.5036547 0.2400928 0.829872 -0.5222808 0.5650387 0.6387128 -0.5103482 0.5639405 0.6492427 -0.4286376 0.104283 0.8974379 -0.4287942 -0.02246206 0.903123 -0.4289801 -0.1487513 0.8909821 -0.4291546 -0.2721052 0.8612695 -0.4293155 -0.3900371 0.8145916 -0.4294962 -0.5002701 0.7518396 -0.4296562 -0.6006276 0.6742715 -0.4297981 -0.6891174 0.5834304 -0.429986 -0.7639888 0.4810752 -0.4351723 -0.8211173 0.3693121 -0.4394201 -0.8631226 0.2488561 -0.427363 -0.8951946 -0.1264418 -0.4200645 0.2823929 0.8624384 -0.4780235 0.5748612 0.6640996 -0.4550444 0.5858201 0.6706336 -0.3773959 0.2822381 0.8819943 -0.4244629 0.6008952 0.6773155 -0.4140513 0.5980503 0.6862197 -0.3908604 -0.8430036 0.3695579 -0.409568 -0.7400608 0.5334455 -0.3924738 -0.7851001 0.4791476 -0.3814655 -0.8145093 0.4371029 -0.3772199 -0.8309824 0.4088685 -0.3888489 -0.8923594 0.2291098 -0.4400581 -0.821397 0.3628442 -0.4071897 -0.8528643 0.3268321 -0.3857342 -0.8769738 0.2865768 -0.3604881 -0.9232243 0.133062 -0.3207586 -0.9372805 0.1364521 -0.3793613 0.5985242 0.7055877 -0.3517072 0.626078 0.6959371 -0.2275778 -0.9737595 0.00100708 0.04342848 -0.9990388 0.005981683 0.1413321 -0.9899352 0.007324457 -0.1063908 -0.9943239 0.001129209 0.1612601 -0.9869099 0.002014219 0.2857235 -0.958312 -2.13636e-4 0.5271642 -0.8497558 0.00363177 0.472738 -0.8812031 -9.15567e-5 0.6341249 -0.7732307 2.44152e-4 0.8121083 -0.5834912 0.004272639 0.7714411 -0.6363008 -6.1039e-5 0.8878447 -0.4601435 3.05196e-5 0.9740056 -0.2265101 0.002533018 0.9744521 -0.2245918 -0.001342833 0.9999834 -0.002563536 0.005157649 0.9867671 0.1621443 -2.04058e-5 0.9867741 0.1621017 0 0.9994353 -0.03360134 0 -0.2800095 -0.9482784 0.1495418 -0.9867758 -0.1620911 8.16201e-7 -0.9867753 -0.1620945 0 -0.936916 -0.3495391 0.003326594 -0.975813 -0.2186073 0 -0.9464322 -0.3228936 0.002411007 -0.8962872 -0.4434741 4.27268e-4 -0.8491957 -0.528073 0.00238049 -0.8154333 -0.5788511 3.05189e-5 -0.7060005 -0.7081979 0.004364192 -0.5858735 -0.8104019 0.00112915 -0.5830348 -0.8124461 0.001312315 -0.437039 -0.8994396 0.002319455 -0.2789142 -0.9603143 0.001831114 -0.1442956 0.9895297 0.003143489 -0.1785363 0.9839334 -6.1038e-5 -0.4153659 0.9096544 1.22077e-4 -0.4167945 0.9090008 -1.22075e-4 -0.6548236 0.7557817 1.22077e-4 -0.6560012 0.7547599 -9.15563e-5 -0.8701474 0.4378663 0.22609 -0.3817957 -0.9242447 0.001953184 -0.4209481 -0.9070848 -1.52595e-4 -0.262376 -0.9649648 0.001342833 -0.1224119 -0.9924492 0.007751822 -0.1951417 -0.9807751 0 0.5500165 0.225445 -0.8041496 0.4543399 0.3729451 -0.809004 0.558751 0.2248677 -0.798268 0.4880328 0.2249571 -0.8433376 0.3909778 0.3177629 -0.8638073 0.4102475 0.3754244 -0.831116 0.3896707 0.1895555 -0.9012355 0.3894861 0.05444622 -0.9194217 0.389304 -0.08179163 -0.9174708 0.3892063 -0.2163172 -0.8953912 0.3891482 -0.3461164 -0.8536786 0.3891259 -0.468355 -0.7932369 0.3891568 -0.5803323 -0.715382 0.3892425 -0.6795721 -0.6218296 0.3893929 -0.763923 -0.5145822 0.3896068 -0.8314623 -0.3960769 0.3898836 -0.8807554 -0.2688137 0.4874228 0.2250184 -0.843674 0.4239738 0.2248966 -0.8773071 0.3335769 0.3716956 -0.8663539 0.4118227 0.225535 -0.8829133 0.3579242 0.2245572 -0.9063467 0.2583411 0.3114743 -0.9144636 0.2812635 0.3737362 -0.8838621 0.2576451 0.1770128 -0.9498872 0.2576735 0.03668403 -0.9655355 0.2577046 -0.1044369 -0.9605631 0.2577338 -0.2433287 -0.9350746 0.2577975 -0.3770063 -0.8896104 0.257826 -0.5026509 -0.8251471 0.2578855 -0.6175213 -0.7430765 0.2579507 -0.7192223 -0.6451209 0.2580112 -0.8055604 -0.5333881 0.258072 -0.874686 -0.4102723 0.2581293 -0.9251212 -0.2784245 0.3332099 0.2256293 -0.9154576 0.2896574 0.2245905 -0.9304074 0.2048155 0.3716955 -0.9054795 0.2520572 0.2255666 -0.9410563 0.2208699 0.2244407 -0.9491274 0.1197879 0.3083052 -0.9437154 0.1468266 0.3734298 -0.9159651 0.1194519 0.1698696 -0.9782001 0.1195126 0.0264905 -0.9924793 0.1195738 -0.117407 -0.9858589 0.1196351 -0.258833 -0.9584848 0.119695 -0.3948226 -0.9109272 0.1197857 -0.5225102 -0.8441769 0.1198508 -0.6391741 -0.7596659 0.1199406 -0.7423808 -0.6591548 0.1200001 -0.8299606 -0.5447618 0.1200609 -0.9000598 -0.4189007 0.1201549 -0.9511981 -0.2842271 0.1691372 0.2254452 -0.9594619 0.1495756 0.224928 -0.9628263 0.07199454 0.372394 -0.9252781 0.07983833 0.2249574 -0.9710922 -0.01971548 0.3076662 -0.9512901 0.009888231 0.374412 -0.9272098 -0.02017325 0.1677646 -0.9856207 -0.02014231 0.02362143 -0.999518 -0.02014267 -0.1209477 -0.9924546 -0.02011179 -0.2630409 -0.9645751 -0.02011215 -0.3996183 -0.9164609 -0.02008122 -0.5278194 -0.8491194 -0.02005094 -0.6449269 -0.7639814 -0.02005106 -0.7485139 -0.662816 -0.02002072 -0.8364146 -0.5477316 -0.02002072 -0.9067618 -0.4211677 -0.01998996 -0.9580864 -0.285781 0.08438384 0.2247083 -0.9707655 0.007355093 0.2246216 -0.9744184 -0.05951219 0.3745915 -0.9252782 5.49342e-4 0.2247725 -0.9744111 -0.05966466 0.2242538 -0.9727026 -0.1572951 0.1679768 -0.9731609 -0.1567739 0.305369 -0.93924 -0.1574179 0.02545297 -0.9872041 -0.1575406 -0.1175298 -0.9804936 -0.1576906 -0.2580974 -0.953163 -0.1578462 -0.3932421 -0.9057844 -0.1580263 -0.5201013 -0.8393584 -0.158214 -0.6360303 -0.7552707 -0.1584247 -0.7385627 -0.6553066 -0.1586363 -0.8255622 -0.5415549 -0.158883 -0.8951894 -0.4164041 -0.1591269 -0.9459722 -0.282516 -0.1395336 0.3636969 -0.9210076 -0.09439492 0.2603566 -0.9608872 -0.08502548 0.2253512 -0.9705604 -0.1679775 0.2241021 -0.9599802 -0.3132169 0.6422731 -0.6995574 -0.2722933 0.8006436 -0.5336912 -0.2730842 0.7930673 -0.5444899 -0.170205 0.2237355 -0.9596733 -0.2889524 0.2245271 -0.9306417 -0.2439414 0.3259165 -0.9133843 -0.3075123 0.6397148 -0.7044156 -0.2958893 0.2637215 -0.9180962 -0.288983 0.3227673 -0.9012826 -0.2968578 0.1322386 -0.9457211 -0.2968323 -0.003418147 -0.9549236 -0.2968312 -0.1390156 -0.9447571 -0.2967958 -0.2718008 -0.9154434 -0.2967681 -0.3990682 -0.8675674 -0.2967372 -0.5182449 -0.8021031 -0.296706 -0.6269219 -0.7203712 -0.296646 -0.7229068 -0.6240248 -0.2965828 -0.8042039 -0.5150677 -0.2965238 -0.8692151 -0.3956499 -0.296463 -0.9166119 -0.2682023 -0.988037 0.1472564 -0.04580968 -0.9884701 0.1478936 -0.03247189 -0.9874086 0.1456972 -0.06161761 -0.9858236 0.1349243 -0.09973597 -0.9869828 0.1401125 -0.07895249 -0.9834176 0.1191466 -0.1367256 -0.9790541 0.09232038 -0.1814668 -0.9713333 0.1196351 -0.2054244 -0.9741925 0.0484029 -0.2204682 -0.9631741 0.1246694 -0.2382299 -0.9598431 0.1012305 -0.2616367 -0.9598088 0.06128323 -0.2738823 -0.9597992 0.01986801 -0.2799834 -0.9597816 -0.02197343 -0.2798867 -0.9597705 -0.063358 -0.2735443 -0.9597594 -0.1033371 -0.26112 -0.9597397 -0.1410601 -0.2429029 -0.9597302 -0.1756367 -0.2192483 -0.9597222 -0.2063065 -0.1907114 -0.9597103 -0.2324045 -0.1579374 -0.9596914 -0.2533663 -0.1216475 -0.9596849 -0.2686629 -0.0826162 -0.9109094 -0.3951028 -0.1189032 -0.9109618 -0.3734305 -0.1752096 -0.9110198 -0.3437954 -0.2277015 -0.9110619 -0.306841 -0.275345 -0.9110973 -0.2633829 -0.3170666 -0.9111307 -0.2143083 -0.3520125 -0.9111582 -0.1606544 -0.3794484 -0.9111816 -0.1036127 -0.398764 -0.9111853 -0.04437512 -0.4096 -0.9111925 0.0157786 -0.4116786 -0.911187 0.07562702 -0.4049924 -0.9131574 0.1262568 -0.3875601 -0.9279105 0.1372761 -0.3466084 -0.9507015 0.1444165 -0.274428 -0.9340667 0.0197153 -0.3565543 -0.8853381 0.432094 -0.1716718 -0.8821075 0.4327372 -0.1860778 -0.888113 0.4292851 -0.1642246 -0.87047 0.4374629 -0.2256287 -0.8750577 0.4348431 -0.2125689 -0.8936467 0.427367 -0.1369417 -0.8965208 0.428118 -0.1138657 -0.8988724 0.4258298 -0.1034284 -0.8994109 0.4304476 -0.07599365 -0.9019337 0.4269635 -0.0649448 -0.9045493 0.4235106 -0.04928797 -0.9045365 0.4248312 -0.03650128 -0.9036616 0.4275988 -0.02356046 -0.8616725 0.4378251 -0.256573 -0.8438217 -0.5154365 -0.1492993 -0.8437999 -0.4893478 -0.2203194 -0.8437869 -0.453511 -0.2869693 -0.8437808 -0.40866 -0.3478951 -0.8437669 -0.3556718 -0.4019391 -0.8437679 -0.2956102 -0.4479627 -0.8437835 -0.2296538 -0.4850656 -0.8437875 -0.1591562 -0.512535 -0.8437952 -0.08548426 -0.5298135 -0.843823 -0.01013231 -0.536526 -0.8438463 0.06540185 -0.5325845 -0.8452658 0.1350484 -0.5169989 -0.903237 0.163276 -0.3968676 -0.8728262 0.1061467 -0.4763478 -0.8622495 0.1566533 -0.4816488 -0.8505312 0.4453012 -0.2798278 -0.8458124 0.4458262 -0.2929854 -0.8274343 0.4533004 -0.3314681 -0.8351204 0.4494525 -0.3171223 -0.8148558 0.4542744 -0.3600625 -0.7606928 -0.6243023 -0.1777442 -0.7609446 -0.5933311 -0.2625294 -0.7611168 -0.5509926 -0.3422111 -0.761223 -0.4980514 -0.4153124 -0.7612754 -0.4355115 -0.4804055 -0.7612715 -0.3645521 -0.5362533 -0.7612072 -0.2865743 -0.5817549 -0.7610833 -0.203043 -0.6160568 -0.7609024 -0.1155758 -0.6384902 -0.7606663 -0.02581942 -0.6486295 -0.7603549 0.064426 -0.6463047 -0.7623115 0.1479576 -0.6300714 -0.8312793 0.1782926 -0.5264851 -0.7876552 0.1296736 -0.6023156 -0.7714049 0.1805214 -0.6102021 -0.7998116 0.4638583 -0.3809687 -0.7919584 0.4653965 -0.3952315 -0.7691805 0.4737527 -0.4288586 -0.7772315 0.469934 -0.4184177 -0.7484857 0.4783289 -0.4593154 -0.6618767 -0.7164761 -0.2204119 -0.6619758 -0.6755571 -0.3246703 -0.662058 -0.6196055 -0.4216259 -0.6620809 -0.5499233 -0.5091498 -0.662113 -0.4680112 -0.5852963 -0.6621276 -0.3757296 -0.6483937 -0.6621169 -0.2750707 -0.6970921 -0.6621145 -0.1682829 -0.7302639 -0.6620711 -0.05768018 -0.7472181 -0.6620136 0.05423188 -0.7475273 -0.6599567 0.1628223 -0.733448 -0.7164142 0.1974915 -0.6691396 -0.7347214 0.4877288 -0.4714925 -0.7189815 0.4899927 -0.4929226 -0.6973406 0.5008254 -0.512728 -0.6849406 0.5011239 -0.5288963 -0.6584447 0.2085965 -0.7231447 -0.6578359 0.5143968 -0.5501345 -0.6430817 0.5171877 -0.564768 -0.549308 -0.8035906 -0.2291352 -0.5489859 -0.7642099 -0.338523 -0.5487734 -0.709917 -0.4414359 -0.5486407 -0.6417848 -0.5358226 -0.5486108 -0.5611236 -0.6198118 -0.5486382 -0.4695637 -0.6917413 -0.5487356 -0.3688553 -0.7502235 -0.54892 -0.2610009 -0.7940815 -0.5491598 -0.1481089 -0.8224884 -0.5495043 -0.03241175 -0.8348621 -0.549923 0.0837748 -0.8310034 -0.5493782 0.1962087 -0.8122105 -0.624764 0.195996 -0.7558146 -0.6138373 0.5312212 -0.5839588 -0.6040645 0.5302388 -0.5949394 -0.5449797 0.2444885 -0.8020116 -0.5720184 0.5432389 -0.6145619 -0.5535879 0.5494373 -0.6258268 -0.4274573 -0.8686178 -0.2505658 -0.4275149 -0.8249377 -0.3697417 -0.4275783 -0.7649716 -0.4816589 -0.4276657 -0.6899478 -0.5840156 -0.4277207 -0.6013115 -0.6748923 -0.4277616 -0.5008253 -0.7524588 -0.4278208 -0.390465 -0.8151728 -0.4278561 -0.2724191 -0.8618162 -0.427906 -0.1489934 -0.8914581 -0.4279412 -0.02264529 -0.9035229 -0.4279671 0.1041306 -0.8977757 -0.4269016 0.2270929 -0.8753193 -0.5056465 0.2377466 -0.829336 -0.5219169 0.5648887 -0.639143 -0.5122376 0.5631439 -0.6484456 -0.4210076 0.2816585 -0.8622188 -0.4786395 0.5737388 -0.6646262 -0.4557475 0.5855163 -0.6704215 -0.3782854 0.2805324 -0.8821574 -0.4240266 0.6006688 -0.6777895 -0.4155239 0.597329 -0.6859578 -0.3798742 0.5972024 -0.7064312 -0.35198 0.6258609 -0.6959944 -0.3332077 0.2256583 -0.9154514 -0.3697451 0.2245938 -0.9015799 -0.25108 0.223857 -0.9417255 -0.4117946 0.2255669 -0.8829184 -0.4337698 0.2247436 -0.8725447 -0.4872105 0.2253547 -0.8437069 -0.4952363 0.2249576 -0.8391277 -0.5536866 0.2248989 -0.8017804 -0.5587363 0.2254111 -0.798125 -0.609255 0.2246824 -0.7604777 -0.6261743 0.2256022 -0.7463307 -0.6615305 0.2246201 -0.7154881 -0.688878 0.2255975 -0.688878 -0.7102469 0.2247141 -0.667123 -0.7464123 0.225355 -0.626166 -0.7552307 0.2249883 -0.6156353 -0.7961069 0.2249913 -0.5617765 -0.7980155 0.2253231 -0.5589283 -0.8331773 0.2247442 -0.5052778 -0.8437038 0.2255675 -0.4871172 -0.8660964 0.2246497 -0.4465528 -0.8829702 0.225595 -0.4116682 -0.8947383 0.2247451 -0.3859183 -0.9155508 0.2253856 -0.333119 -0.9189767 0.2249602 -0.3238438 -0.9388101 0.2249286 -0.2608501 -0.9410409 0.2253871 -0.2522749 -0.9544033 0.2247145 -0.1965145 -0.9594166 0.2255942 -0.1691957 -0.9655418 0.2246837 -0.1313249 -0.9706032 0.2252929 -0.08469086 -0.9721447 0.2250453 -0.06549322 -0.973729 0.2252583 -0.03332638 -0.9733996 0.2251988 0.04217708 -0.9738439 0.224806 0.03302198 -0.9721834 0.2248336 0.0656464 -0.9734908 0.2247409 -0.04251277 -0.9705404 0.2255062 0.08484327 -0.9655418 0.2246837 0.1313249 -0.9594125 0.2256309 0.1691698 -0.9545879 0.224196 0.1962096 -0.947617 0.22578 0.2259326 -0.9390591 0.2238238 0.260904 -0.9265846 0.2266029 0.3001534 -0.9190943 0.2239519 0.3242085 -0.9048498 0.2257851 0.3609266 -0.8947783 0.2241294 0.3861838 -0.890787 0.2235208 0.3956476 -0.8660654 0.2244665 0.4467052 -0.8623631 0.2224193 0.4548181 -0.8331773 0.2247442 0.5052778 -0.8834356 0.2225756 0.4123127 -0.8759683 0.2241041 0.4271498 -0.8694856 0.2248027 0.4398394 -0.8162754 0.22499 0.532047 -0.7961372 0.2249608 0.5617458 -0.8573141 0.2214776 0.4647154 -0.8525212 0.2227286 0.4728633 -0.8440361 0.22459 0.4869932 -0.850403 0.2246866 0.4757422 -0.8430871 0.2247113 0.4885785 -0.8366037 0.224899 0.4995145 -0.8320098 0.2249557 0.5071042 -0.8312656 0.2249563 0.5083229 -0.7974382 0.2263004 0.5593573 -0.7552269 0.2249261 0.6156628 -0.7463885 0.2254181 0.6261717 -0.710262 0.2247092 0.6671085 -0.688878 0.2255975 0.688878 -0.6615305 0.2246201 0.7154881 -0.6261743 0.2256022 0.7463307 -0.6092883 0.2246834 0.7604506 -0.5587133 0.2253226 0.7981662 -0.553679 0.2249569 0.8017694 -0.4952619 0.2250469 0.8390886 -0.4872638 0.2252901 0.8436934 -0.4337698 0.2247436 0.8725447 -0.4117946 0.2255669 0.8829184 -0.3697451 0.2245938 0.9015799 -0.3332077 0.2256583 0.9154514 0 1 -1.50389e-5 0 1 1.50389e-5 0 1 1.64769e-5 -0.9457005 0.2253543 0.2342354 -0.9409672 0.2271236 0.2509897 0 1 1.63326e-5 -0.950261 0.2257163 0.2146075 0 1 -1.11163e-5 -0.9321379 0.2251682 0.2835813 -0.9148411 0.2270011 0.3339707 0 1 -5.50934e-6 -0.9247225 0.2242528 0.3075694 -0.9667802 0.2143042 0.1393191 -0.9367473 0.2253211 0.2678339 -0.8890648 0.225692 0.39828 -0.8828865 0.22636 0.4114277 0 1 1.08258e-5 -0.9104314 0.2254486 0.3468252 0 1 -1.11336e-5 -0.8470622 0.2278873 0.4801596 -0.8436836 0.2269436 0.4865128 0 1 1.10405e-5 -0.8498927 0.2349046 0.4717015 -0.861643 0.2296249 0.4525967 -0.873503 0.225998 0.4311817 0 1 -1.07513e-5 -0.8143165 0.2287423 0.5334472 -0.8331739 0.2257199 0.5048484 -0.8396565 0.2250518 0.4942961 0 1 5.60048e-6 0 1 1.91327e-5 0 1 -2.11716e-5 0 1 -1.88474e-5 0 1 1.24108e-5 0 1 -4.78916e-5 0 1 6.22409e-5 0 1 -2.75705e-5 0 1 -9.9749e-5 0 1 -1.08383e-5 0 1 -1.99051e-5 0 1 1.14587e-4 0 1 -9.84151e-5 0 1 1.96088e-4 0 1 -3.3063e-5 0 1 3.25469e-5 0 1 2.91069e-5 0.8358281 0.2301754 0.4984083 0.8431195 0.2266345 0.4876335 0.829701 0.2315813 0.5079042 0.8232536 0.2283746 0.5197103 0.873227 0.2281035 0.4306316 0.8827561 0.2271513 0.4112712 0 1 9.83907e-6 0.8641453 0.2292587 0.4479883 0.8557884 0.2262997 0.4652039 0.848232 0.2251127 0.4794024 0.9110857 0.225017 0.3453842 0.9148631 0.2273653 0.3336624 0.8898761 0.2253531 0.3966568 0.9321758 0.2252005 0.283431 0 1 -4.98559e-6 0.9367473 0.2253211 0.2678339 0 1 1.51451e-5 0.2249661 0.9743666 8.18651e-6 0.2249865 0.974362 0 0.03082406 0.9995246 7.93491e-4 0.1246695 0.9921984 0 -0.06729519 0.9976783 0.01046812 -0.2086014 0.9780002 0.001129209 -0.1644086 0.9863909 0.001709043 -0.3695232 0.9292098 0.004669368 -0.5038691 0.86378 2.74671e-4 -0.5300627 0.8479539 0.002807736 -0.6537585 0.7567008 0.001922726 -0.7891567 0.614192 -1.83113e-4 -0.8144693 0.5802029 0.002075314 -0.8982068 0.4395662 0.002441525 -0.9647405 0.2631971 0.001800596 -0.8584105 0.2249867 0.4609909 -0.8537144 0.2249878 0.4696299 -0.9742033 0.2256589 0.002441525 -0.9973093 0.07330733 -3.96751e-4 -0.8549686 0.2249885 0.4673425 -0.9863 -0.1649225 0.003601193 -0.9916917 -0.1286385 -1.22077e-4 -0.8600385 0.2249284 0.457975 -0.941726 -0.3363808 1.22076e-4 -0.867367 0.2249904 0.4439076 -0.8670814 0.2249571 0.4444819 -0.8480687 -0.529875 0.003479182 -0.8449133 -0.5349032 -5.49339e-4 -0.8773659 0.224957 0.4238201 -0.8758403 0.2249571 0.4269638 -0.7136971 -0.7004517 0.001953244 -0.8863022 0.2248945 0.4048345 -0.5799345 -0.8146612 0.001831173 -0.5332349 -0.8459672 -3.96752e-4 -0.8921847 0.2254114 0.3914028 -0.9020193 0.2244977 0.3687304 -0.36382 -0.9314477 0.006347954 -0.2255848 -0.9742236 1.32027e-4 -0.9142122 0.2257834 0.3365082 -0.224932 -0.9743745 0 -0.4107885 -0.9117307 0 0.2249127 0.974379 -1.27119e-5 0.2249128 0.974379 0 0.03131282 0.9995084 0.001617491 0.1351976 0.9908186 0 -0.05215615 0.9985666 0.01202428 -0.2009966 0.9795913 0.001159667 -0.1645272 0.9863699 0.002319395 -0.3723309 0.9280806 0.006012201 -0.5090007 0.860766 4.88309e-4 -0.5301197 0.8479169 0.003173947 -0.6616594 0.7497992 0.002838253 -0.7958464 0.6054988 6.10382e-5 -0.8146322 0.579975 0.001892149 -0.9048362 0.4257442 0.003662288 -0.9699384 0.2433314 0.003082454 -0.9740896 0.2261492 0.002472043 -0.998993 0.04486358 -3.66233e-4 -0.9862865 -0.1649864 0.004303157 -0.9869661 -0.1609286 -3.05194e-4 -0.9337363 -0.3579602 0.001068115 -0.8483331 -0.5294414 0.004791438 -0.8466978 -0.532074 -4.27271e-4 -0.7450327 -0.6670259 0.001648008 -0.5794008 -0.815037 0.003051877 -0.6163149 -0.7874999 -2.44158e-4 -0.4645962 -0.8855192 0.00250256 -0.3450445 -0.9385113 0.01187175 -0.2253741 -0.9742724 0 -0.2249479 -0.9743709 0 0.2249512 -0.9743701 0 0.2249327 -0.9743744 0 0.4101155 -0.9120324 0.001525938 0.3136172 -0.9495496 0 0.4883074 -0.8725749 0.01300114 0.6134012 -0.7897704 0.001281797 0.5802925 -0.8144055 0.00213629 0.7475928 -0.6641234 0.006744682 0.8408728 -0.5412325 5.49351e-4 0.8482005 -0.5296675 0.002899348 0.9294065 -0.3690403 0.003570735 0.983883 -0.1788129 2.74674e-4 0.9864323 -0.1641612 0.001556456 0.9994747 0.03210622 0.004455804 0.9746868 0.223552 0.003234982 0.9746677 0.2236462 0.002319455 0.9110446 0.4123078 -3.96743e-4 0.8140954 0.5807163 0.004150569 0.807319 0.5901153 -2.44152e-4 0.6719381 0.740606 0.001434385 0.5304186 0.8477236 0.004577815 0.5179743 0.8553962 -3.66232e-4 0.3705322 0.9288179 0.001861631 0.1635222 0.9865351 0.002990841 0.2045367 0.978859 -2.74669e-4 0.02798551 0.9996052 0.002502501 -0.1022069 0.9946938 0.01174962 -0.224696 0.974429 1.23244e-4 -0.2249389 0.9743729 0 -0.03048866 0.9995352 0 0 1 -1.64769e-5 0 1 -1.63326e-5 0 1 1.11163e-5 0 1 5.50934e-6 0 1 -1.08258e-5 0 1 1.11336e-5 0 1 -1.10405e-5 0 1 1.07513e-5 0 1 -5.60048e-6 0 1 -1.91327e-5 0 1 2.11716e-5 0 1 1.88474e-5 0 1 -1.24108e-5 0 1 4.78916e-5 0 1 -6.22409e-5 0 1 2.75705e-5 0 1 9.9749e-5 0 1 1.08383e-5 0 1 1.99051e-5 0 1 -1.14587e-4 0 1 9.84151e-5 0 1 -1.96088e-4 0 1 3.3063e-5 0 1 -3.25469e-5 0 1 -2.91069e-5 0 1 -9.83907e-6 0 1 4.98559e-6 0 1 -1.51451e-5 -0.09225815 0 -0.9957351 -0.1837523 0 -0.9829726 0.1837578 0 -0.9829716 0.1837523 0 -0.9829726 0.09225815 0 -0.9957351 -0.1837578 0 -0.9829716 -0.3612501 0 -0.932469 -0.5264335 0 -0.8502163 -0.5264198 0 -0.8502249 -0.6736975 0 -0.7390073 -0.6736809 0 -0.7390224 -0.798018 0 -0.6026336 -0.8951646 0 -0.4457358 -0.9618263 0 -0.2736608 -0.9618343 0 -0.2736327 -0.9957351 0 -0.09225815 -0.9957351 0 0.09225815 -0.9618241 0 0.2736689 -0.9618343 0 0.2736327 -0.8951646 0 0.4457358 -0.798018 0 0.6026336 -0.6736975 0 0.7390073 -0.6736809 0 0.7390224 -0.5264335 0 0.8502163 -0.5264198 0 0.8502249 -0.3612501 0 0.932469 -0.1837523 0 0.9829726 -0.1837578 0 0.9829716 -0.09225815 0 0.9957351 0.09225815 0 0.9957351 0.1837523 0 0.9829726 0.1837578 0 0.9829716 0.3612501 0 0.932469 0.5264335 0 0.8502163 0.5264198 0 0.8502249 0.6736975 0 0.7390073 0.6736809 0 0.7390224 0.798018 0 0.6026336 0.8951646 0 0.4457358 0.9618263 0 0.2736608 0.9618343 0 0.2736327 0.9957351 0 0.09225815 0.9957351 0 -0.09225815 0.9618241 0 -0.2736689 0.9618343 0 -0.2736327 0.8951646 0 -0.4457358 0.798018 0 -0.6026336 0.6736975 0 -0.7390073 0.6736809 0 -0.7390224 0.5264335 0 -0.8502163 0.5264198 0 -0.8502249 0.3612501 0 -0.932469 0 0 -1 -0.9969457 0.07809907 0 -1 0 0 4.85135e-6 0 -1 -0.8660256 0.4999998 0 -0.8660262 0.4999986 0 -0.9969457 -0.07809907 0 -1.94345e-6 0 -1 -0.8660256 -0.4999998 0 4.89553e-6 0 -1 -0.56649 -0.8240687 0 -0.5003696 -0.8658119 0 -0.8660262 -0.4999986 0 3.07576e-6 0 -1 -0.4311996 -0.9022567 0 -8.84392e-6 0 -1 5.52745e-6 0 -1 0.4311996 -0.9022567 0 0.5003696 -0.8658119 0 -8.20203e-6 0 -1 -5.44965e-6 0 -1 0.56649 -0.8240687 0 0.8660256 -0.4999998 0 1.94347e-6 0 -1 0.9969457 -0.07809907 0 0.8660262 -0.4999986 0 0.9969457 0.07809907 0 0.8660256 0.4999998 0 0.5664343 0.8241069 0 0.5003696 0.8658119 0 0.8660262 0.4999986 0 0.4312363 0.902239 0 -0.4312363 0.902239 0 -0.5003696 0.8658119 0 -0.5664343 0.8241069 0 -2.37982e-4 0 1 0.9748669 0.2227883 -6.10379e-5 0.9748455 0.222882 0 0.9009045 0.4340175 6.1039e-5 0.9009518 -0.4339193 6.1038e-5 0.9008629 -0.4341037 6.10382e-5 0.9748603 -0.2228173 -6.10375e-5 0.9748883 -0.2226947 0 0.9009933 0.4338331 6.10388e-5 0.6234101 0.7818949 4.27265e-4 3.52232e-6 0 1 0.6235108 0.7818148 3.96752e-4 0.2227593 0.9748736 -3.05192e-5 -1.58801e-5 0 1 0.2223043 0.9749773 -1.22078e-4 -0.2226657 0.9748949 -1.22075e-4 -3.52232e-6 0 1 -0.2222397 0.9749922 -6.10381e-5 -0.6235108 0.7818148 3.96752e-4 -0.6235964 0.7817463 4.27267e-4 -0.9008629 0.4341037 6.10382e-5 -8.77316e-6 0 1 7.93985e-6 0 1 -0.9009518 0.4339193 6.1038e-5 -0.9748603 0.2228173 -6.10375e-5 2.78297e-6 0 1 2.38095e-4 0 1 -0.9748669 -0.2227883 -6.10379e-5 -0.9748455 -0.222882 0 -0.9009045 -0.4340175 6.1039e-5 2.27269e-6 0 1 -0.9748883 0.2226947 0 -1.00567e-5 0 1 -0.9009933 -0.4338331 6.10388e-5 -0.6234101 -0.7818949 3.96746e-4 -0.6235108 -0.7818148 3.96752e-4 -0.2227303 -0.9748802 -3.05194e-5 -0.2222977 -0.9749789 -9.15559e-5 0.2226657 -0.9748949 -1.22075e-4 0.2222107 -0.9749988 -3.05193e-5 0.6235108 -0.7818148 3.96752e-4 7.74162e-6 0 1 0.6235964 -0.7817463 4.27267e-4 -7.94018e-6 0 1 -2.78297e-6 0 1 -9.70233e-6 0 1 9.70271e-6 0 1 9.41354e-6 0 1 -1.00299e-5 0 1 1.55891e-6 0 1 -2.33779e-6 0 1 0.965775 0.2593813 3.0519e-5 0.9657903 0.2593244 0 0.8658328 0.5003336 1.83116e-4 0.8660789 -0.4999074 1.83116e-4 0.8659218 -0.5001795 9.15577e-5 0.9657827 -0.2593529 3.05193e-5 0.9657675 -0.2594098 0 0.8660107 0.5000254 6.10383e-5 0.5004154 0.8657855 -9.15562e-5 0.5001205 0.8659559 0 -2.1363e-4 1 1.83111e-4 -2.13636e-4 1 1.83117e-4 -0.5001205 0.8659559 0 -0.4998123 0.8661338 -9.15575e-5 -0.8659218 0.5001795 6.10384e-5 -0.8660789 0.4999074 1.83116e-4 -0.9657827 0.2593529 3.05193e-5 -0.965775 -0.2593813 3.0519e-5 -0.9657924 -0.2593168 0 -0.8658328 -0.5003336 1.83116e-4 -0.9657675 0.2594098 0 -0.8660107 -0.5000254 9.15574e-5 -0.5004154 -0.8657855 -9.15562e-5 -0.5001205 -0.8659559 3.05193e-5 2.13636e-4 -1 2.13636e-4 0.5000844 -0.8659768 0 0.4998123 -0.8661338 -9.15575e-5 - - - - - - - - - - 0.07212901 0.182382 0.114509 0.1885679 0.118756 0.197077 0.142846 0.172404 0.118756 0.197077 0.114509 0.1885679 0.07148396 0.186815 0.07212901 0.182382 0.118756 0.197077 0.11832 0.201286 0.07148396 0.186815 0.118756 0.197077 0.128935 0.205946 0.11832 0.201286 0.118756 0.197077 0.147325 0.176512 0.128935 0.205946 0.118756 0.197077 0.142846 0.172404 0.147325 0.176512 0.118756 0.197077 0.07326 0.172402 0.109813 0.178112 0.114509 0.1885679 0.1387439 0.167921 0.114509 0.1885679 0.109813 0.178112 0.07272195 0.177565 0.07326 0.172402 0.114509 0.1885679 0.07212901 0.182382 0.07272195 0.177565 0.114509 0.1885679 0.1387439 0.167921 0.142846 0.172404 0.114509 0.1885679 0.07374095 0.16693 0.105684 0.167026 0.109813 0.178112 0.127555 0.162633 0.109813 0.178112 0.105684 0.167026 0.07326 0.172402 0.07374095 0.16693 0.109813 0.178112 0.135048 0.163097 0.1387439 0.167921 0.109813 0.178112 0.127555 0.162633 0.135048 0.163097 0.109813 0.178112 0.09831696 0.1566269 0.102492 0.15593 0.105684 0.167026 0.123008 0.156397 0.105684 0.167026 0.102492 0.15593 0.09464997 0.165527 0.105684 0.167026 0.07374095 0.16693 0.09837996 0.158498 0.09831696 0.1566269 0.105684 0.167026 0.09828799 0.160245 0.09837996 0.158498 0.105684 0.167026 0.098064 0.16166 0.09828799 0.160245 0.105684 0.167026 0.097741 0.1628029 0.098064 0.16166 0.105684 0.167026 0.09727096 0.163833 0.097741 0.1628029 0.105684 0.167026 0.096565 0.164756 0.09727096 0.163833 0.105684 0.167026 0.09565097 0.165359 0.096565 0.164756 0.105684 0.167026 0.09464997 0.165527 0.09565097 0.165359 0.105684 0.167026 0.12718 0.162553 0.127555 0.162633 0.105684 0.167026 0.126598 0.162079 0.12718 0.162553 0.105684 0.167026 0.125896 0.161274 0.126598 0.162079 0.105684 0.167026 0.125214 0.160335 0.125896 0.161274 0.105684 0.167026 0.124548 0.159288 0.125214 0.160335 0.105684 0.167026 0.123812 0.157992 0.124548 0.159288 0.105684 0.167026 0.123008 0.156397 0.123812 0.157992 0.105684 0.167026 0.09767895 0.145699 0.100255 0.144929 0.102492 0.15593 0.118752 0.144461 0.102492 0.15593 0.100255 0.144929 0.09796595 0.151203 0.09767895 0.145699 0.102492 0.15593 0.09831696 0.1566269 0.09796595 0.151203 0.102492 0.15593 0.122236 0.154658 0.123008 0.156397 0.102492 0.15593 0.120324 0.149612 0.122236 0.154658 0.102492 0.15593 0.118752 0.144461 0.120324 0.149612 0.102492 0.15593 0.075217 0.1362529 0.098935 0.134012 0.100255 0.144929 0.123534 0.135246 0.100255 0.144929 0.098935 0.134012 0.075051 0.142702 0.075217 0.1362529 0.100255 0.144929 0.09767895 0.145699 0.075051 0.142702 0.100255 0.144929 0.123534 0.135246 0.124845 0.141176 0.100255 0.144929 0.118752 0.144461 0.100255 0.144929 0.124845 0.141176 0.07535099 0.123156 0.098499 0.123156 0.098935 0.134012 0.122743 0.129225 0.098935 0.134012 0.098499 0.123156 0.07531696 0.129725 0.07535099 0.123156 0.098935 0.134012 0.075217 0.1362529 0.07531696 0.129725 0.098935 0.134012 0.122743 0.129225 0.123534 0.135246 0.098935 0.134012 0.07531696 0.116587 0.098499 0.123156 0.07535099 0.123156 0.07531696 0.116587 0.098935 0.1123 0.098499 0.123156 0.122478 0.123156 0.098499 0.123156 0.098935 0.1123 0.122478 0.123156 0.122743 0.129225 0.098499 0.123156 0.07444995 0.123156 0.07535099 0.123156 0.07531696 0.129725 0.07431399 0.110612 0.07531696 0.116587 0.07535099 0.123156 0.07431399 0.110612 0.07535099 0.123156 0.07444995 0.123156 0.07431399 0.1357 0.07531696 0.129725 0.075217 0.1362529 0.07431399 0.1357 0.07444995 0.123156 0.07531696 0.129725 0.07431399 0.1357 0.075217 0.1362529 0.075051 0.142702 0.08878797 0.145734 0.07481896 0.149033 0.075051 0.142702 0.07390695 0.147896 0.075051 0.142702 0.07481896 0.149033 0.09320598 0.145717 0.075051 0.142702 0.09767895 0.145699 0.09320598 0.145717 0.08878797 0.145734 0.075051 0.142702 0.07390695 0.147896 0.07431399 0.1357 0.075051 0.142702 0.08937799 0.156171 0.07452297 0.155207 0.07481896 0.149033 0.07390695 0.147896 0.07481896 0.149033 0.07452297 0.155207 0.089055 0.150991 0.08937799 0.156171 0.07481896 0.149033 0.08878797 0.145734 0.089055 0.150991 0.07481896 0.149033 0.09098595 0.162519 0.07416296 0.161186 0.07452297 0.155207 0.07323896 0.159403 0.07452297 0.155207 0.07416296 0.161186 0.090433 0.1613 0.09098595 0.162519 0.07452297 0.155207 0.08995795 0.1598269 0.090433 0.1613 0.07452297 0.155207 0.08958899 0.1580629 0.08995795 0.1598269 0.07452297 0.155207 0.08937799 0.156171 0.08958899 0.1580629 0.07452297 0.155207 0.07323896 0.159403 0.07390695 0.147896 0.07452297 0.155207 0.09464997 0.165527 0.07374095 0.16693 0.07416296 0.161186 0.07323896 0.159403 0.07416296 0.161186 0.07374095 0.16693 0.09363698 0.165285 0.09464997 0.165527 0.07416296 0.161186 0.092615 0.164635 0.09363698 0.165285 0.07416296 0.161186 0.09169095 0.163639 0.092615 0.164635 0.07416296 0.161186 0.09098595 0.162519 0.09169095 0.163639 0.07416296 0.161186 0.07232296 0.169884 0.07374095 0.16693 0.07326 0.172402 0.07232296 0.169884 0.07323896 0.159403 0.07374095 0.16693 0.07232296 0.169884 0.07326 0.172402 0.07272195 0.177565 0.07118099 0.179015 0.07272195 0.177565 0.07212901 0.182382 0.07118099 0.179015 0.07232296 0.169884 0.07272195 0.177565 0.069839 0.186487 0.07212901 0.182382 0.07148396 0.186815 0.069839 0.186487 0.07118099 0.179015 0.07212901 0.182382 0.11832 0.201286 0.070791 0.19083 0.07148396 0.186815 0.06833398 0.1920199 0.07148396 0.186815 0.070791 0.19083 0.06833398 0.1920199 0.069839 0.186487 0.07148396 0.186815 0.117859 0.205093 0.07005298 0.194394 0.070791 0.19083 0.066706 0.195369 0.070791 0.19083 0.07005298 0.194394 0.11832 0.201286 0.117859 0.205093 0.070791 0.19083 0.066706 0.195369 0.06833398 0.1920199 0.070791 0.19083 0.06137496 0.19941 0.07005298 0.194394 0.06927496 0.197474 0.117373 0.208469 0.06927496 0.197474 0.07005298 0.194394 0.06500595 0.196339 0.07005298 0.194394 0.06137496 0.19941 0.117859 0.205093 0.117373 0.208469 0.07005298 0.194394 0.06500595 0.196339 0.066706 0.195369 0.07005298 0.194394 0.06225496 0.201681 0.06927496 0.197474 0.06846195 0.200042 0.116865 0.21139 0.06846195 0.200042 0.06927496 0.197474 0.06137496 0.19941 0.06927496 0.197474 0.06225496 0.201681 0.117373 0.208469 0.116865 0.21139 0.06927496 0.197474 0.063151 0.203312 0.06846195 0.200042 0.06761795 0.202069 0.116339 0.213829 0.06761795 0.202069 0.06846195 0.200042 0.06225496 0.201681 0.06846195 0.200042 0.063151 0.203312 0.116865 0.21139 0.116339 0.213829 0.06846195 0.200042 0.06405597 0.204304 0.06761795 0.202069 0.06674998 0.203529 0.115795 0.215764 0.06674998 0.203529 0.06761795 0.202069 0.063151 0.203312 0.06761795 0.202069 0.06405597 0.204304 0.116339 0.213829 0.115795 0.215764 0.06761795 0.202069 0.06496196 0.204664 0.06674998 0.203529 0.06586199 0.2044 0.115238 0.217173 0.06586199 0.2044 0.06674998 0.203529 0.06405597 0.204304 0.06674998 0.203529 0.06496196 0.204664 0.115795 0.215764 0.115238 0.217173 0.06674998 0.203529 0.114669 0.2180359 0.06496196 0.204664 0.06586199 0.2044 0.115238 0.217173 0.114669 0.2180359 0.06586199 0.2044 0.113512 0.21806 0.06405597 0.204304 0.06496196 0.204664 0.114093 0.218336 0.113512 0.21806 0.06496196 0.204664 0.114669 0.2180359 0.114093 0.218336 0.06496196 0.204664 0.112931 0.217195 0.063151 0.203312 0.06405597 0.204304 0.113512 0.21806 0.112931 0.217195 0.06405597 0.204304 0.112352 0.215735 0.06225496 0.201681 0.063151 0.203312 0.112931 0.217195 0.112352 0.215735 0.063151 0.203312 0.111781 0.213674 0.06137496 0.19941 0.06225496 0.201681 0.112352 0.215735 0.111781 0.213674 0.06225496 0.201681 0.11122 0.211014 0.0605179 0.196506 0.06137496 0.19941 0.06500595 0.196339 0.06137496 0.19941 0.0605179 0.196506 0.111781 0.213674 0.11122 0.211014 0.06137496 0.19941 0.110674 0.207759 0.05969399 0.19298 0.0605179 0.196506 0.06328999 0.194801 0.0605179 0.196506 0.05969399 0.19298 0.11122 0.211014 0.110674 0.207759 0.0605179 0.196506 0.06328999 0.194801 0.06500595 0.196339 0.0605179 0.196506 0.110148 0.20392 0.05890893 0.18885 0.05969399 0.19298 0.06161898 0.190708 0.05969399 0.19298 0.05890893 0.18885 0.110674 0.207759 0.110148 0.20392 0.05969399 0.19298 0.06161898 0.190708 0.06328999 0.194801 0.05969399 0.19298 0.109644 0.199511 0.05817097 0.184141 0.05890893 0.18885 0.06005698 0.18411 0.05890893 0.18885 0.05817097 0.184141 0.110148 0.20392 0.109644 0.199511 0.05890893 0.18885 0.06005698 0.18411 0.06161898 0.190708 0.05890893 0.18885 0.108723 0.1890709 0.05748796 0.1788859 0.05817097 0.184141 0.06005698 0.18411 0.05817097 0.184141 0.05748796 0.1788859 0.109168 0.194552 0.108723 0.1890709 0.05817097 0.184141 0.109644 0.199511 0.109168 0.194552 0.05817097 0.184141 0.108314 0.183098 0.05686599 0.173123 0.05748796 0.1788859 0.05866897 0.17517 0.05748796 0.1788859 0.05686599 0.173123 0.108723 0.1890709 0.108314 0.183098 0.05748796 0.1788859 0.05866897 0.17517 0.06005698 0.18411 0.05748796 0.1788859 0.07542598 0.170339 0.05631196 0.166899 0.05686599 0.173123 0.05866897 0.17517 0.05686599 0.173123 0.05631196 0.166899 0.108314 0.183098 0.1079429 0.176672 0.05686599 0.173123 0.07888495 0.172581 0.05686599 0.173123 0.1079429 0.176672 0.07653498 0.171461 0.07542598 0.170339 0.05686599 0.173123 0.07773798 0.172244 0.07653498 0.171461 0.05686599 0.173123 0.07888495 0.172581 0.07773798 0.172244 0.05686599 0.173123 0.072488 0.164187 0.05583298 0.160266 0.05631196 0.166899 0.05751496 0.164164 0.05631196 0.166899 0.05583298 0.160266 0.07310301 0.166151 0.072488 0.164187 0.05631196 0.166899 0.073798 0.167776 0.07310301 0.166151 0.05631196 0.166899 0.07454198 0.1691139 0.073798 0.167776 0.05631196 0.166899 0.07542598 0.170339 0.07454198 0.1691139 0.05631196 0.166899 0.05751496 0.164164 0.05866897 0.17517 0.05631196 0.166899 0.071114 0.156 0.05543392 0.153282 0.05583298 0.160266 0.05751496 0.164164 0.05583298 0.160266 0.05543392 0.153282 0.07204198 0.1620939 0.071114 0.156 0.05583298 0.160266 0.072488 0.164187 0.07204198 0.1620939 0.05583298 0.160266 0.07034498 0.149733 0.05511796 0.146009 0.05543392 0.153282 0.05664891 0.151485 0.05543392 0.153282 0.05511796 0.146009 0.071114 0.156 0.07034498 0.149733 0.05543392 0.153282 0.05664891 0.151485 0.05751496 0.164164 0.05543392 0.153282 0.106908 0.147358 0.05488991 0.138516 0.05511796 0.146009 0.05664891 0.151485 0.05511796 0.146009 0.05488991 0.138516 0.08020299 0.1498399 0.106908 0.147358 0.05511796 0.146009 0.07522898 0.1497859 0.05511796 0.146009 0.07034498 0.149733 0.07522898 0.1497859 0.08020299 0.1498399 0.05511796 0.146009 0.106774 0.1394 0.05475199 0.130874 0.05488991 0.138516 0.05611199 0.137626 0.05488991 0.138516 0.05475199 0.130874 0.106908 0.147358 0.106774 0.1394 0.05488991 0.138516 0.05611199 0.137626 0.05664891 0.151485 0.05488991 0.138516 0.106666 0.123156 0.05470591 0.123156 0.05475199 0.130874 0.05611199 0.137626 0.05475199 0.130874 0.05470591 0.123156 0.106693 0.1313109 0.106666 0.123156 0.05475199 0.130874 0.106774 0.1394 0.106693 0.1313109 0.05475199 0.130874 0.106693 0.115001 0.05470591 0.123156 0.106666 0.123156 0.05475199 0.115438 0.05470591 0.123156 0.106693 0.115001 0.05592989 0.123156 0.05470591 0.123156 0.05475199 0.115438 0.05592989 0.123156 0.05611199 0.137626 0.05470591 0.123156 0.121217 0.123156 0.106666 0.123156 0.106693 0.1313109 0.121299 0.106701 0.106693 0.115001 0.106666 0.123156 0.121299 0.106701 0.106666 0.123156 0.121217 0.123156 0.121299 0.139611 0.106693 0.1313109 0.106774 0.1394 0.121217 0.123156 0.106693 0.1313109 0.121299 0.139611 0.121299 0.139611 0.106774 0.1394 0.106908 0.147358 0.08020299 0.1498399 0.107094 0.1551229 0.106908 0.147358 0.121544 0.155619 0.106908 0.147358 0.107094 0.1551229 0.121299 0.139611 0.106908 0.147358 0.121544 0.155619 0.08097195 0.156435 0.10733 0.162634 0.107094 0.1551229 0.121544 0.155619 0.107094 0.1551229 0.10733 0.162634 0.08020299 0.1498399 0.08097195 0.156435 0.107094 0.1551229 0.08217698 0.16497 0.107614 0.169835 0.10733 0.162634 0.121942 0.170754 0.10733 0.162634 0.107614 0.169835 0.08190596 0.162845 0.08217698 0.16497 0.10733 0.162634 0.08097195 0.156435 0.08190596 0.162845 0.10733 0.162634 0.121544 0.155619 0.10733 0.162634 0.121942 0.170754 0.08087199 0.171891 0.1079429 0.176672 0.107614 0.169835 0.121942 0.170754 0.107614 0.169835 0.1079429 0.176672 0.08155596 0.170908 0.08087199 0.171891 0.107614 0.169835 0.081963 0.169766 0.08155596 0.170908 0.107614 0.169835 0.08218699 0.168494 0.081963 0.169766 0.107614 0.169835 0.08226895 0.1669149 0.08218699 0.168494 0.107614 0.169835 0.08217698 0.16497 0.08226895 0.1669149 0.107614 0.169835 0.122481 0.184634 0.1079429 0.176672 0.108314 0.183098 0.07994395 0.172474 0.07888495 0.172581 0.1079429 0.176672 0.08087199 0.171891 0.07994395 0.172474 0.1079429 0.176672 0.121942 0.170754 0.1079429 0.176672 0.122481 0.184634 0.122481 0.184634 0.108314 0.183098 0.108723 0.1890709 0.123145 0.196931 0.108723 0.1890709 0.109168 0.194552 0.122481 0.184634 0.108723 0.1890709 0.123145 0.196931 0.123912 0.2073889 0.109168 0.194552 0.109644 0.199511 0.123145 0.196931 0.109168 0.194552 0.123912 0.2073889 0.123912 0.2073889 0.109644 0.199511 0.110148 0.20392 0.124761 0.21582 0.110148 0.20392 0.110674 0.207759 0.123912 0.2073889 0.110148 0.20392 0.124761 0.21582 0.124761 0.21582 0.110674 0.207759 0.11122 0.211014 0.12567 0.222108 0.11122 0.211014 0.111781 0.213674 0.124761 0.21582 0.11122 0.211014 0.12567 0.222108 0.12567 0.222108 0.111781 0.213674 0.112352 0.215735 0.126614 0.226203 0.112352 0.215735 0.112931 0.217195 0.12567 0.222108 0.112352 0.215735 0.126614 0.226203 0.126614 0.226203 0.112931 0.217195 0.113512 0.21806 0.127573 0.228112 0.113512 0.21806 0.114093 0.218336 0.126614 0.226203 0.113512 0.21806 0.127573 0.228112 0.128526 0.227891 0.114093 0.218336 0.114669 0.2180359 0.127573 0.228112 0.114093 0.218336 0.128526 0.227891 0.128526 0.227891 0.114669 0.2180359 0.115238 0.217173 0.129453 0.225636 0.115238 0.217173 0.115795 0.215764 0.128526 0.227891 0.115238 0.217173 0.129453 0.225636 0.129453 0.225636 0.115795 0.215764 0.116339 0.213829 0.130338 0.221476 0.116339 0.213829 0.116865 0.21139 0.129453 0.225636 0.116339 0.213829 0.130338 0.221476 0.130338 0.221476 0.116865 0.21139 0.117373 0.208469 0.1311669 0.215561 0.117373 0.208469 0.117859 0.205093 0.130338 0.221476 0.117373 0.208469 0.1311669 0.215561 0.1311669 0.215561 0.117859 0.205093 0.11832 0.201286 0.1311669 0.215561 0.11832 0.201286 0.131869 0.208103 0.128935 0.205946 0.131869 0.208103 0.11832 0.201286 0.09831696 0.145784 0.09767895 0.145699 0.09796595 0.151203 0.09831696 0.145784 0.09320598 0.145717 0.09767895 0.145699 0.09831696 0.145784 0.09796595 0.151203 0.09831696 0.1566269 0.09831696 0.145784 0.09831696 0.1566269 0.09837996 0.158498 0.09831696 0.145784 0.09837996 0.158498 0.09828799 0.160245 0.098266 0.145824 0.09828799 0.160245 0.098064 0.16166 0.09831696 0.145784 0.09828799 0.160245 0.098266 0.145824 0.098266 0.145824 0.098064 0.16166 0.097741 0.1628029 0.09754198 0.14586 0.097741 0.1628029 0.09727096 0.163833 0.098266 0.145824 0.097741 0.1628029 0.09754198 0.14586 0.09754198 0.14586 0.09727096 0.163833 0.096565 0.164756 0.09625101 0.145888 0.096565 0.164756 0.09565097 0.165359 0.09754198 0.14586 0.096565 0.164756 0.09625101 0.145888 0.09625101 0.145888 0.09565097 0.165359 0.09464997 0.165527 0.09459096 0.145902 0.09464997 0.165527 0.09363698 0.165285 0.09625101 0.145888 0.09464997 0.165527 0.09459096 0.145902 0.092817 0.145901 0.09363698 0.165285 0.092615 0.164635 0.09459096 0.145902 0.09363698 0.165285 0.092817 0.145901 0.092817 0.145901 0.092615 0.164635 0.09169095 0.163639 0.09120297 0.145884 0.09169095 0.163639 0.09098595 0.162519 0.092817 0.145901 0.09169095 0.163639 0.09120297 0.145884 0.09120297 0.145884 0.09098595 0.162519 0.090433 0.1613 0.08999496 0.145855 0.090433 0.1613 0.08995795 0.1598269 0.09120297 0.145884 0.090433 0.1613 0.08999496 0.145855 0.08999496 0.145855 0.08995795 0.1598269 0.08958899 0.1580629 0.08999496 0.145855 0.08958899 0.1580629 0.08937799 0.156171 0.08878797 0.145734 0.08937799 0.156171 0.089055 0.150991 0.08937799 0.145817 0.08937799 0.156171 0.08878797 0.145734 0.08999496 0.145855 0.08937799 0.156171 0.08937799 0.145817 0.09831696 0.145784 0.08878797 0.145734 0.09320598 0.145717 0.098266 0.145824 0.08937799 0.145817 0.08878797 0.145734 0.09831696 0.145784 0.098266 0.145824 0.08878797 0.145734 0.07204198 0.149621 0.07034498 0.149733 0.071114 0.156 0.07522898 0.1497859 0.07034498 0.149733 0.08190596 0.149724 0.08190596 0.149724 0.08020299 0.1498399 0.07522898 0.1497859 0.07204198 0.149621 0.08190596 0.149724 0.07034498 0.149733 0.07204198 0.149621 0.071114 0.156 0.07204198 0.1620939 0.07204198 0.149621 0.07204198 0.1620939 0.072488 0.164187 0.07204198 0.149621 0.072488 0.164187 0.07310301 0.166151 0.07317 0.1495749 0.07310301 0.166151 0.073798 0.167776 0.07204198 0.149621 0.07310301 0.166151 0.07317 0.1495749 0.07317 0.1495749 0.073798 0.167776 0.07454198 0.1691139 0.07486897 0.149544 0.07454198 0.1691139 0.07542598 0.170339 0.07317 0.1495749 0.07454198 0.1691139 0.07486897 0.149544 0.07486897 0.149544 0.07542598 0.170339 0.07653498 0.171461 0.076882 0.149533 0.07653498 0.171461 0.07773798 0.172244 0.07486897 0.149544 0.07653498 0.171461 0.076882 0.149533 0.076882 0.149533 0.07773798 0.172244 0.07888495 0.172581 0.07890796 0.149543 0.07888495 0.172581 0.07994395 0.172474 0.076882 0.149533 0.07888495 0.172581 0.07890796 0.149543 0.08064198 0.149572 0.07994395 0.172474 0.08087199 0.171891 0.07890796 0.149543 0.07994395 0.172474 0.08064198 0.149572 0.08064198 0.149572 0.08087199 0.171891 0.08155596 0.170908 0.08182197 0.149617 0.08155596 0.170908 0.081963 0.169766 0.08064198 0.149572 0.08155596 0.170908 0.08182197 0.149617 0.08182197 0.149617 0.081963 0.169766 0.08218699 0.168494 0.08226799 0.14967 0.08218699 0.168494 0.08226895 0.1669149 0.08182197 0.149617 0.08218699 0.168494 0.08226799 0.14967 0.08226799 0.14967 0.08226895 0.1669149 0.08217698 0.16497 0.08226799 0.14967 0.08217698 0.16497 0.08190596 0.162845 0.08020299 0.1498399 0.08190596 0.162845 0.08097195 0.156435 0.08190596 0.149724 0.08190596 0.162845 0.08020299 0.1498399 0.08226799 0.14967 0.08190596 0.162845 0.08190596 0.149724 0.075051 0.10361 0.100255 0.101384 0.098935 0.1123 0.123534 0.111066 0.098935 0.1123 0.100255 0.101384 0.075217 0.110059 0.075051 0.10361 0.098935 0.1123 0.07531696 0.116587 0.075217 0.110059 0.098935 0.1123 0.122743 0.117087 0.122478 0.123156 0.098935 0.1123 0.123534 0.111066 0.122743 0.117087 0.098935 0.1123 0.07481896 0.09727895 0.102492 0.09038299 0.100255 0.101384 0.124845 0.105136 0.100255 0.101384 0.102492 0.09038299 0.075051 0.10361 0.07481896 0.09727895 0.100255 0.101384 0.124845 0.105136 0.123534 0.111066 0.100255 0.101384 0.07416296 0.08512598 0.105684 0.07928597 0.102492 0.09038299 0.128988 0.09373098 0.102492 0.09038299 0.105684 0.07928597 0.07452297 0.09110498 0.07416296 0.08512598 0.102492 0.09038299 0.07481896 0.09727895 0.07452297 0.09110498 0.102492 0.09038299 0.126668 0.09934395 0.124845 0.105136 0.102492 0.09038299 0.128988 0.09373098 0.126668 0.09934395 0.102492 0.09038299 0.07374095 0.079382 0.109812 0.06820195 0.105684 0.07928597 0.131788 0.08834099 0.105684 0.07928597 0.109812 0.06820195 0.07416296 0.08512598 0.07374095 0.079382 0.105684 0.07928597 0.131788 0.08834099 0.128988 0.09373098 0.105684 0.07928597 0.07272195 0.06874698 0.114507 0.05774688 0.109812 0.06820195 0.135048 0.08321499 0.109812 0.06820195 0.114507 0.05774688 0.07326 0.07390999 0.07272195 0.06874698 0.109812 0.06820195 0.07374095 0.079382 0.07326 0.07390999 0.109812 0.06820195 0.135048 0.08321499 0.131788 0.08834099 0.109812 0.06820195 0.07148396 0.05949693 0.118756 0.04923492 0.114507 0.05774688 0.142846 0.07390797 0.114507 0.05774688 0.118756 0.04923492 0.07212901 0.06392997 0.07148396 0.05949693 0.114507 0.05774688 0.07272195 0.06874698 0.07212901 0.06392997 0.114507 0.05774688 0.1387439 0.07839095 0.135048 0.08321499 0.114507 0.05774688 0.142846 0.07390797 0.1387439 0.07839095 0.114507 0.05774688 0.070791 0.05548197 0.11832 0.045026 0.118756 0.04923492 0.128937 0.04036498 0.118756 0.04923492 0.11832 0.045026 0.07148396 0.05949693 0.070791 0.05548197 0.118756 0.04923492 0.147325 0.06979995 0.118756 0.04923492 0.128937 0.04036498 0.147325 0.06979995 0.142846 0.07390797 0.118756 0.04923492 0.070791 0.05548197 0.117859 0.04121893 0.11832 0.045026 0.131869 0.03820896 0.11832 0.045026 0.117859 0.04121893 0.131869 0.03820896 0.128937 0.04036498 0.11832 0.045026 0.07005298 0.05191797 0.117373 0.03784292 0.117859 0.04121893 0.1311669 0.03075093 0.117859 0.04121893 0.117373 0.03784292 0.070791 0.05548197 0.07005298 0.05191797 0.117859 0.04121893 0.1311669 0.03075093 0.131869 0.03820896 0.117859 0.04121893 0.06927496 0.0488379 0.116865 0.034922 0.117373 0.03784292 0.1311669 0.03075093 0.117373 0.03784292 0.116865 0.034922 0.07005298 0.05191797 0.06927496 0.0488379 0.117373 0.03784292 0.06846195 0.04626995 0.116339 0.03248298 0.116865 0.034922 0.130338 0.024836 0.116865 0.034922 0.116339 0.03248298 0.06927496 0.0488379 0.06846195 0.04626995 0.116865 0.034922 0.130338 0.024836 0.1311669 0.03075093 0.116865 0.034922 0.06761795 0.04424291 0.115795 0.03054797 0.116339 0.03248298 0.130338 0.024836 0.116339 0.03248298 0.115795 0.03054797 0.06846195 0.04626995 0.06761795 0.04424291 0.116339 0.03248298 0.06674998 0.04278296 0.115238 0.02913898 0.115795 0.03054797 0.129453 0.02067589 0.115795 0.03054797 0.115238 0.02913898 0.06761795 0.04424291 0.06674998 0.04278296 0.115795 0.03054797 0.129453 0.02067589 0.130338 0.024836 0.115795 0.03054797 0.06586199 0.0419119 0.114669 0.0282759 0.115238 0.02913898 0.129453 0.02067589 0.115238 0.02913898 0.114669 0.0282759 0.06674998 0.04278296 0.06586199 0.0419119 0.115238 0.02913898 0.06496196 0.04164797 0.114093 0.02797597 0.114669 0.0282759 0.128526 0.01842099 0.114669 0.0282759 0.114093 0.02797597 0.06586199 0.0419119 0.06496196 0.04164797 0.114669 0.0282759 0.128526 0.01842099 0.129453 0.02067589 0.114669 0.0282759 0.06405597 0.04200798 0.113512 0.028252 0.114093 0.02797597 0.127573 0.01820099 0.114093 0.02797597 0.113512 0.028252 0.06496196 0.04164797 0.06405597 0.04200798 0.114093 0.02797597 0.127573 0.01820099 0.128526 0.01842099 0.114093 0.02797597 0.06405597 0.04200798 0.112931 0.02911692 0.113512 0.028252 0.127573 0.01820099 0.113512 0.028252 0.112931 0.02911692 0.063151 0.04299998 0.112352 0.030577 0.112931 0.02911692 0.126614 0.02010893 0.112931 0.02911692 0.112352 0.030577 0.06405597 0.04200798 0.063151 0.04299998 0.112931 0.02911692 0.126614 0.02010893 0.127573 0.01820099 0.112931 0.02911692 0.06225496 0.04463189 0.111781 0.03263795 0.112352 0.030577 0.126614 0.02010893 0.112352 0.030577 0.111781 0.03263795 0.063151 0.04299998 0.06225496 0.04463189 0.112352 0.030577 0.06137496 0.046902 0.11122 0.03529793 0.111781 0.03263795 0.12567 0.02420395 0.111781 0.03263795 0.11122 0.03529793 0.06225496 0.04463189 0.06137496 0.046902 0.111781 0.03263795 0.12567 0.02420395 0.126614 0.02010893 0.111781 0.03263795 0.0605179 0.04980593 0.110674 0.03855293 0.11122 0.03529793 0.12567 0.02420395 0.11122 0.03529793 0.110674 0.03855293 0.06137496 0.046902 0.0605179 0.04980593 0.11122 0.03529793 0.05969399 0.05333197 0.110148 0.04239189 0.110674 0.03855293 0.124761 0.03049188 0.110674 0.03855293 0.110148 0.04239189 0.0605179 0.04980593 0.05969399 0.05333197 0.110674 0.03855293 0.124761 0.03049188 0.12567 0.02420395 0.110674 0.03855293 0.05890893 0.05746191 0.109644 0.04680097 0.110148 0.04239189 0.124761 0.03049188 0.110148 0.04239189 0.109644 0.04680097 0.05969399 0.05333197 0.05890893 0.05746191 0.110148 0.04239189 0.05817097 0.06217098 0.109168 0.05175989 0.109644 0.04680097 0.123912 0.03892296 0.109644 0.04680097 0.109168 0.05175989 0.05890893 0.05746191 0.05817097 0.06217098 0.109644 0.04680097 0.123912 0.03892296 0.124761 0.03049188 0.109644 0.04680097 0.05748796 0.06742596 0.108723 0.05724096 0.109168 0.05175989 0.123145 0.04938089 0.109168 0.05175989 0.108723 0.05724096 0.05817097 0.06217098 0.05748796 0.06742596 0.109168 0.05175989 0.123145 0.04938089 0.123912 0.03892296 0.109168 0.05175989 0.05748796 0.06742596 0.108314 0.063214 0.108723 0.05724096 0.123145 0.04938089 0.108723 0.05724096 0.108314 0.063214 0.05686599 0.07318896 0.1079429 0.06963998 0.108314 0.063214 0.122481 0.06167799 0.108314 0.063214 0.1079429 0.06963998 0.05748796 0.06742596 0.05686599 0.07318896 0.108314 0.063214 0.122481 0.06167799 0.123145 0.04938089 0.108314 0.063214 0.05631196 0.07941299 0.107614 0.07647699 0.1079429 0.06963998 0.122481 0.06167799 0.1079429 0.06963998 0.107614 0.07647699 0.05686599 0.07318896 0.05631196 0.07941299 0.1079429 0.06963998 0.05583298 0.08604598 0.10733 0.083678 0.107614 0.07647699 0.121942 0.075558 0.107614 0.07647699 0.10733 0.083678 0.05631196 0.07941299 0.05583298 0.08604598 0.107614 0.07647699 0.121942 0.075558 0.122481 0.06167799 0.107614 0.07647699 0.05543392 0.09303098 0.107094 0.09118896 0.10733 0.083678 0.121942 0.075558 0.10733 0.083678 0.107094 0.09118896 0.05583298 0.08604598 0.05543392 0.09303098 0.10733 0.083678 0.05511796 0.100303 0.106908 0.09895396 0.107094 0.09118896 0.121544 0.09069299 0.107094 0.09118896 0.106908 0.09895396 0.05543392 0.09303098 0.05511796 0.100303 0.107094 0.09118896 0.121544 0.09069299 0.121942 0.075558 0.107094 0.09118896 0.05488991 0.107796 0.106774 0.106912 0.106908 0.09895396 0.121544 0.09069299 0.106908 0.09895396 0.106774 0.106912 0.05511796 0.100303 0.05488991 0.107796 0.106908 0.09895396 0.05475199 0.115438 0.106693 0.115001 0.106774 0.106912 0.121299 0.106701 0.106774 0.106912 0.106693 0.115001 0.05488991 0.107796 0.05475199 0.115438 0.106774 0.106912 0.121299 0.106701 0.121544 0.09069299 0.106774 0.106912 0.05611199 0.108686 0.05475199 0.115438 0.05488991 0.107796 0.05611199 0.108686 0.05592989 0.123156 0.05475199 0.115438 0.05611199 0.108686 0.05488991 0.107796 0.05511796 0.100303 0.05664891 0.09482699 0.05511796 0.100303 0.05543392 0.09303098 0.05664891 0.09482699 0.05611199 0.108686 0.05511796 0.100303 0.05664891 0.09482699 0.05543392 0.09303098 0.05583298 0.08604598 0.05751496 0.08214795 0.05583298 0.08604598 0.05631196 0.07941299 0.05751496 0.08214795 0.05664891 0.09482699 0.05583298 0.08604598 0.05751496 0.08214795 0.05631196 0.07941299 0.05686599 0.07318896 0.05866897 0.07114195 0.05686599 0.07318896 0.05748796 0.06742596 0.05866897 0.07114195 0.05751496 0.08214795 0.05686599 0.07318896 0.05866897 0.07114195 0.05748796 0.06742596 0.05817097 0.06217098 0.06005698 0.06220191 0.05817097 0.06217098 0.05890893 0.05746191 0.06005698 0.06220191 0.05866897 0.07114195 0.05817097 0.06217098 0.06161898 0.05560398 0.05890893 0.05746191 0.05969399 0.05333197 0.06161898 0.05560398 0.06005698 0.06220191 0.05890893 0.05746191 0.06328999 0.05151093 0.05969399 0.05333197 0.0605179 0.04980593 0.06328999 0.05151093 0.06161898 0.05560398 0.05969399 0.05333197 0.06500595 0.04997295 0.0605179 0.04980593 0.06137496 0.046902 0.06500595 0.04997295 0.06328999 0.05151093 0.0605179 0.04980593 0.07005298 0.05191797 0.06137496 0.046902 0.06225496 0.04463189 0.066706 0.05094289 0.06137496 0.046902 0.07005298 0.05191797 0.066706 0.05094289 0.06500595 0.04997295 0.06137496 0.046902 0.06927496 0.0488379 0.06225496 0.04463189 0.063151 0.04299998 0.07005298 0.05191797 0.06225496 0.04463189 0.06927496 0.0488379 0.06846195 0.04626995 0.063151 0.04299998 0.06405597 0.04200798 0.06927496 0.0488379 0.063151 0.04299998 0.06846195 0.04626995 0.06761795 0.04424291 0.06405597 0.04200798 0.06496196 0.04164797 0.06846195 0.04626995 0.06405597 0.04200798 0.06761795 0.04424291 0.06674998 0.04278296 0.06496196 0.04164797 0.06586199 0.0419119 0.06761795 0.04424291 0.06496196 0.04164797 0.06674998 0.04278296 0.066706 0.05094289 0.07005298 0.05191797 0.070791 0.05548197 0.06833398 0.05429196 0.070791 0.05548197 0.07148396 0.05949693 0.06833398 0.05429196 0.066706 0.05094289 0.070791 0.05548197 0.069839 0.059825 0.07148396 0.05949693 0.07212901 0.06392997 0.069839 0.059825 0.06833398 0.05429196 0.07148396 0.05949693 0.07118099 0.06729698 0.07212901 0.06392997 0.07272195 0.06874698 0.07118099 0.06729698 0.069839 0.059825 0.07212901 0.06392997 0.07118099 0.06729698 0.07272195 0.06874698 0.07326 0.07390999 0.07232296 0.07642799 0.07326 0.07390999 0.07374095 0.079382 0.07232296 0.07642799 0.07118099 0.06729698 0.07326 0.07390999 0.07232296 0.07642799 0.07374095 0.079382 0.07416296 0.08512598 0.07323896 0.08690899 0.07416296 0.08512598 0.07452297 0.09110498 0.07323896 0.08690899 0.07232296 0.07642799 0.07416296 0.08512598 0.07323896 0.08690899 0.07452297 0.09110498 0.07481896 0.09727895 0.07390695 0.09841597 0.07481896 0.09727895 0.075051 0.10361 0.07390695 0.09841597 0.07323896 0.08690899 0.07481896 0.09727895 0.07390695 0.09841597 0.075051 0.10361 0.075217 0.110059 0.07431399 0.110612 0.075217 0.110059 0.07531696 0.116587 0.07431399 0.110612 0.07390695 0.09841597 0.075217 0.110059 0.02586597 0.123156 0.07444995 0.123156 0.07431399 0.1357 0.02567398 0.1106989 0.07431399 0.110612 0.07444995 0.123156 0.02567398 0.1106989 0.07444995 0.123156 0.02586597 0.123156 0.02567398 0.135613 0.07431399 0.1357 0.07390695 0.147896 0.02567398 0.135613 0.02586597 0.123156 0.07431399 0.1357 0.02510493 0.147723 0.07390695 0.147896 0.07323896 0.159403 0.02567398 0.135613 0.07390695 0.147896 0.02510493 0.147723 0.02416998 0.159147 0.07323896 0.159403 0.07232296 0.169884 0.02510493 0.147723 0.07323896 0.159403 0.02416998 0.159147 0.02288889 0.169549 0.07232296 0.169884 0.07118099 0.179015 0.02416998 0.159147 0.07232296 0.169884 0.02288889 0.169549 0.02129089 0.178607 0.07118099 0.179015 0.069839 0.186487 0.02288889 0.169549 0.07118099 0.179015 0.02129089 0.178607 0.01941496 0.186016 0.069839 0.186487 0.06833398 0.1920199 0.02129089 0.178607 0.069839 0.186487 0.01941496 0.186016 0.01730996 0.191496 0.06833398 0.1920199 0.066706 0.195369 0.01941496 0.186016 0.06833398 0.1920199 0.01730996 0.191496 0.01503592 0.194804 0.066706 0.195369 0.06500595 0.196339 0.01730996 0.191496 0.066706 0.195369 0.01503592 0.194804 0.01266098 0.195751 0.06500595 0.196339 0.06328999 0.194801 0.01503592 0.194804 0.06500595 0.196339 0.01266098 0.195751 0.01026499 0.1942099 0.06328999 0.194801 0.06161898 0.190708 0.01266098 0.195751 0.06328999 0.194801 0.01026499 0.1942099 0.007931947 0.190137 0.06161898 0.190708 0.06005698 0.18411 0.01026499 0.1942099 0.06161898 0.190708 0.007931947 0.190137 0.005752921 0.183582 0.06005698 0.18411 0.05866897 0.17517 0.007931947 0.190137 0.06005698 0.18411 0.005752921 0.183582 0.003816962 0.174709 0.05866897 0.17517 0.05751496 0.164164 0.005752921 0.183582 0.05866897 0.17517 0.003816962 0.174709 0.002208948 0.163794 0.05751496 0.164164 0.05664891 0.151485 0.003816962 0.174709 0.05751496 0.164164 0.002208948 0.163794 0.001001954 0.151226 0.05664891 0.151485 0.05611199 0.137626 0.002208948 0.163794 0.05664891 0.151485 0.001001954 0.151226 2.54e-4 0.137493 0.05611199 0.137626 0.05592989 0.123156 0.001001954 0.151226 0.05611199 0.137626 2.54e-4 0.137493 0 0.123156 0.05592989 0.123156 0.05611199 0.108686 2.54e-4 0.137493 0.05592989 0.123156 0 0.123156 2.54e-4 0.108819 0.05611199 0.108686 0.05664891 0.09482699 0 0.123156 0.05611199 0.108686 2.54e-4 0.108819 0.001001954 0.09508597 0.05664891 0.09482699 0.05751496 0.08214795 2.54e-4 0.108819 0.05664891 0.09482699 0.001001954 0.09508597 0.002208948 0.08251798 0.05751496 0.08214795 0.05866897 0.07114195 0.001001954 0.09508597 0.05751496 0.08214795 0.002208948 0.08251798 0.003816962 0.071603 0.05866897 0.07114195 0.06005698 0.06220191 0.002208948 0.08251798 0.05866897 0.07114195 0.003816962 0.071603 0.005752921 0.06272995 0.06005698 0.06220191 0.06161898 0.05560398 0.003816962 0.071603 0.06005698 0.06220191 0.005752921 0.06272995 0.007931947 0.05617499 0.06161898 0.05560398 0.06328999 0.05151093 0.005752921 0.06272995 0.06161898 0.05560398 0.007931947 0.05617499 0.01026499 0.05210191 0.06328999 0.05151093 0.06500595 0.04997295 0.007931947 0.05617499 0.06328999 0.05151093 0.01026499 0.05210191 0.01266098 0.05056095 0.06500595 0.04997295 0.066706 0.05094289 0.01026499 0.05210191 0.06500595 0.04997295 0.01266098 0.05056095 0.01503592 0.05150789 0.066706 0.05094289 0.06833398 0.05429196 0.01266098 0.05056095 0.066706 0.05094289 0.01503592 0.05150789 0.01730996 0.05481588 0.06833398 0.05429196 0.069839 0.059825 0.01503592 0.05150789 0.06833398 0.05429196 0.01730996 0.05481588 0.01941496 0.06029593 0.069839 0.059825 0.07118099 0.06729698 0.01730996 0.05481588 0.069839 0.059825 0.01941496 0.06029593 0.02129089 0.06770497 0.07118099 0.06729698 0.07232296 0.07642799 0.01941496 0.06029593 0.07118099 0.06729698 0.02129089 0.06770497 0.02288889 0.07676297 0.07232296 0.07642799 0.07323896 0.08690899 0.02129089 0.06770497 0.07232296 0.07642799 0.02288889 0.07676297 0.02416998 0.08716499 0.07323896 0.08690899 0.07390695 0.09841597 0.02288889 0.07676297 0.07323896 0.08690899 0.02416998 0.08716499 0.02510493 0.098589 0.07390695 0.09841597 0.07431399 0.110612 0.02416998 0.08716499 0.07390695 0.09841597 0.02510493 0.098589 0.02510493 0.098589 0.07431399 0.110612 0.02567398 0.1106989 0.210831 0.225874 0.195261 0.227232 0.20943 0.22584 0.198234 0.192564 0.20943 0.22584 0.195261 0.227232 0.224556 0.2232339 0.210831 0.225874 0.20943 0.22584 0.210212 0.190452 0.224556 0.2232339 0.20943 0.22584 0.204269 0.19177 0.210212 0.190452 0.20943 0.22584 0.198234 0.192564 0.204269 0.19177 0.20943 0.22584 0.194515 0.233327 0.194487 0.227252 0.195261 0.227232 0.198234 0.192564 0.195261 0.227232 0.194487 0.227252 0.211136 0.2337909 0.194515 0.233327 0.195261 0.227232 0.210831 0.225874 0.211136 0.2337909 0.195261 0.227232 0.181048 0.226686 0.194487 0.227252 0.194515 0.233327 0.192152 0.19283 0.194487 0.227252 0.181048 0.226686 0.192152 0.19283 0.198234 0.192564 0.194487 0.227252 0.211136 0.2337909 0.194544 0.238348 0.194515 0.233327 0.177896 0.233605 0.194515 0.233327 0.194544 0.238348 0.178089 0.226327 0.181048 0.226686 0.194515 0.233327 0.177896 0.233605 0.178089 0.226327 0.194515 0.233327 0.211454 0.2397159 0.194575 0.242214 0.194544 0.238348 0.177681 0.239298 0.194544 0.238348 0.194575 0.242214 0.211136 0.2337909 0.211454 0.2397159 0.194544 0.238348 0.177681 0.239298 0.177896 0.233605 0.194544 0.238348 0.211454 0.2397159 0.199183 0.242371 0.194575 0.242214 0.194559 0.2161549 0.194575 0.242214 0.199183 0.242371 0.1921499 0.242193 0.177681 0.239298 0.194575 0.242214 0.194559 0.2161549 0.1921499 0.242193 0.194575 0.242214 0.211454 0.2397159 0.20328 0.242676 0.199183 0.242371 0.199187 0.216278 0.199183 0.242371 0.20328 0.242676 0.194559 0.2161549 0.199183 0.242371 0.199187 0.216278 0.211454 0.2397159 0.206499 0.243106 0.20328 0.242676 0.206488 0.216853 0.20328 0.242676 0.206499 0.243106 0.203271 0.216516 0.20328 0.242676 0.206488 0.216853 0.199187 0.216278 0.20328 0.242676 0.203271 0.216516 0.211791 0.243419 0.208578 0.243627 0.206499 0.243106 0.208576 0.217263 0.206499 0.243106 0.208578 0.243627 0.211454 0.2397159 0.211791 0.243419 0.206499 0.243106 0.206488 0.216853 0.206499 0.243106 0.208576 0.217263 0.211791 0.243419 0.209352 0.244203 0.208578 0.243627 0.208576 0.217263 0.208578 0.243627 0.209352 0.244203 0.21214 0.2447119 0.208738 0.244788 0.209352 0.244203 0.209352 0.217715 0.209352 0.244203 0.208738 0.244788 0.211791 0.243419 0.21214 0.2447119 0.209352 0.244203 0.208576 0.217263 0.209352 0.244203 0.209352 0.217715 0.21214 0.2447119 0.206768 0.245332 0.208738 0.244788 0.208736 0.218174 0.208738 0.244788 0.206768 0.245332 0.208736 0.218174 0.209352 0.217715 0.208738 0.244788 0.21214 0.2447119 0.203572 0.245791 0.206768 0.245332 0.206758 0.218601 0.206768 0.245332 0.203572 0.245791 0.208736 0.218174 0.206768 0.245332 0.206758 0.218601 0.21214 0.2447119 0.199406 0.246124 0.203572 0.245791 0.203564 0.218961 0.203572 0.245791 0.199406 0.246124 0.206758 0.218601 0.203572 0.245791 0.203564 0.218961 0.2124969 0.243437 0.1946589 0.246297 0.199406 0.246124 0.199411 0.2192209 0.199406 0.246124 0.1946589 0.246297 0.21214 0.2447119 0.2124969 0.243437 0.199406 0.246124 0.203564 0.218961 0.199406 0.246124 0.199411 0.2192209 0.2124969 0.243437 0.194702 0.244719 0.1946589 0.246297 0.1921499 0.2463189 0.1946589 0.246297 0.194702 0.244719 0.194642 0.219357 0.1946589 0.246297 0.1921499 0.2463189 0.199411 0.2192209 0.1946589 0.246297 0.194642 0.219357 0.212851 0.239485 0.194747 0.2404879 0.194702 0.244719 0.176695 0.242359 0.194702 0.244719 0.194747 0.2404879 0.2124969 0.243437 0.212851 0.239485 0.194702 0.244719 0.176949 0.24498 0.194702 0.244719 0.176695 0.242359 0.1921499 0.2463189 0.194702 0.244719 0.176949 0.24498 0.213196 0.232801 0.19479 0.233557 0.194747 0.2404879 0.176446 0.237322 0.194747 0.2404879 0.19479 0.233557 0.212851 0.239485 0.213196 0.232801 0.194747 0.2404879 0.176695 0.242359 0.194747 0.2404879 0.176446 0.237322 0.21352 0.223407 0.19483 0.223951 0.19479 0.233557 0.1762059 0.229853 0.19479 0.233557 0.19483 0.223951 0.213196 0.232801 0.21352 0.223407 0.19479 0.233557 0.176446 0.237322 0.19479 0.233557 0.1762059 0.229853 0.213816 0.21141 0.194867 0.211782 0.19483 0.223951 0.1759819 0.220001 0.19483 0.223951 0.194867 0.211782 0.21352 0.223407 0.213816 0.21141 0.19483 0.223951 0.1762059 0.229853 0.19483 0.223951 0.1759819 0.220001 0.214074 0.197018 0.194899 0.197257 0.194867 0.211782 0.175779 0.207885 0.194867 0.211782 0.194899 0.197257 0.213816 0.21141 0.214074 0.197018 0.194867 0.211782 0.1759819 0.220001 0.194867 0.211782 0.175779 0.207885 0.214284 0.180542 0.194925 0.180684 0.194899 0.197257 0.175604 0.193708 0.194899 0.197257 0.194925 0.180684 0.214074 0.197018 0.214284 0.180542 0.194899 0.197257 0.175779 0.207885 0.194899 0.197257 0.175604 0.193708 0.21444 0.162395 0.194944 0.16247 0.194925 0.180684 0.175462 0.177752 0.194925 0.180684 0.194944 0.16247 0.214284 0.180542 0.21444 0.162395 0.194925 0.180684 0.175604 0.193708 0.194925 0.180684 0.175462 0.177752 0.214536 0.143077 0.194956 0.143109 0.194944 0.16247 0.175357 0.16038 0.194944 0.16247 0.194956 0.143109 0.21444 0.162395 0.214536 0.143077 0.194944 0.16247 0.175462 0.177752 0.194944 0.16247 0.175357 0.16038 0.195157 0.123156 0.1949599 0.123156 0.194956 0.143109 0.175292 0.142021 0.194956 0.143109 0.1949599 0.123156 0.214569 0.123156 0.195157 0.123156 0.194956 0.143109 0.214536 0.143077 0.214569 0.123156 0.194956 0.143109 0.175357 0.16038 0.194956 0.143109 0.175292 0.142021 0.214536 0.103235 0.1949599 0.123156 0.195157 0.123156 0.175485 0.123156 0.175292 0.142021 0.1949599 0.123156 0.194956 0.102957 0.175485 0.123156 0.1949599 0.123156 0.214536 0.103235 0.194956 0.102957 0.1949599 0.123156 0.214536 0.103235 0.195157 0.123156 0.214569 0.123156 0.233534 0.123156 0.214569 0.123156 0.214536 0.143077 0.233479 0.104324 0.214569 0.123156 0.233534 0.123156 0.233479 0.104324 0.214536 0.103235 0.214569 0.123156 0.225939 0.150951 0.214536 0.143077 0.21444 0.162395 0.2335039 0.137134 0.233534 0.123156 0.214536 0.143077 0.225939 0.150951 0.2335039 0.137134 0.214536 0.143077 0.226438 0.164565 0.21444 0.162395 0.214284 0.180542 0.226438 0.164565 0.225939 0.150951 0.21444 0.162395 0.227455 0.179929 0.214284 0.180542 0.214074 0.197018 0.227126 0.1774629 0.226438 0.164565 0.214284 0.180542 0.227243 0.1787 0.227126 0.1774629 0.214284 0.180542 0.227455 0.179929 0.227243 0.1787 0.214284 0.180542 0.232563 0.19745 0.214074 0.197018 0.213816 0.21141 0.232938 0.182749 0.214074 0.197018 0.232563 0.19745 0.232002 0.183408 0.214074 0.197018 0.232938 0.182749 0.227822 0.181206 0.227455 0.179929 0.214074 0.197018 0.2283779 0.1823599 0.227822 0.181206 0.214074 0.197018 0.229028 0.183149 0.2283779 0.1823599 0.214074 0.197018 0.229857 0.183658 0.229028 0.183149 0.214074 0.197018 0.230897 0.183773 0.229857 0.183658 0.214074 0.197018 0.232002 0.183408 0.230897 0.183773 0.214074 0.197018 0.232112 0.210315 0.213816 0.21141 0.21352 0.223407 0.232563 0.19745 0.213816 0.21141 0.232112 0.210315 0.2316009 0.22106 0.21352 0.223407 0.213196 0.232801 0.232112 0.210315 0.21352 0.223407 0.2316009 0.22106 0.231045 0.22952 0.213196 0.232801 0.212851 0.239485 0.2316009 0.22106 0.213196 0.232801 0.231045 0.22952 0.230457 0.235608 0.212851 0.239485 0.2124969 0.243437 0.231045 0.22952 0.212851 0.239485 0.230457 0.235608 0.2292439 0.240647 0.2124969 0.243437 0.21214 0.2447119 0.229852 0.239304 0.2124969 0.243437 0.2292439 0.240647 0.230457 0.235608 0.2124969 0.243437 0.229852 0.239304 0.228645 0.239724 0.21214 0.2447119 0.211791 0.243419 0.2292439 0.240647 0.21214 0.2447119 0.228645 0.239724 0.228065 0.236658 0.211791 0.243419 0.211454 0.2397159 0.228645 0.239724 0.211791 0.243419 0.228065 0.236658 0.227515 0.2316 0.211454 0.2397159 0.211136 0.2337909 0.228065 0.236658 0.211454 0.2397159 0.227515 0.2316 0.224189 0.225153 0.211136 0.2337909 0.210831 0.225874 0.227515 0.2316 0.211136 0.2337909 0.2269909 0.224757 0.224189 0.225153 0.2269909 0.224757 0.211136 0.2337909 0.224556 0.2232339 0.224189 0.225153 0.210831 0.225874 0.186071 0.192564 0.181048 0.226686 0.178089 0.226327 0.186071 0.192564 0.192152 0.19283 0.181048 0.226686 0.167047 0.2242169 0.178089 0.226327 0.177896 0.233605 0.180036 0.19177 0.178089 0.226327 0.167047 0.2242169 0.180036 0.19177 0.186071 0.192564 0.178089 0.226327 0.161529 0.230719 0.177896 0.233605 0.177681 0.239298 0.1619679 0.222822 0.167047 0.2242169 0.177896 0.233605 0.161529 0.230719 0.1619679 0.222822 0.177896 0.233605 0.177805 0.243106 0.177368 0.243189 0.177681 0.239298 0.161031 0.236717 0.177681 0.239298 0.177368 0.243189 0.181011 0.242677 0.177805 0.243106 0.177681 0.239298 0.185091 0.242372 0.181011 0.242677 0.177681 0.239298 0.189725 0.242214 0.185091 0.242372 0.177681 0.239298 0.1921499 0.242193 0.189725 0.242214 0.177681 0.239298 0.161031 0.236717 0.161529 0.230719 0.177681 0.239298 0.175728 0.217263 0.177368 0.243189 0.177805 0.243106 0.160501 0.240553 0.161031 0.236717 0.177368 0.243189 0.175727 0.243628 0.160501 0.240553 0.177368 0.243189 0.175728 0.217263 0.175727 0.243628 0.177368 0.243189 0.177816 0.216853 0.177805 0.243106 0.181011 0.242677 0.175728 0.217263 0.177805 0.243106 0.177816 0.216853 0.181033 0.216516 0.181011 0.242677 0.185091 0.242372 0.177816 0.216853 0.181011 0.242677 0.181033 0.216516 0.185117 0.216278 0.185091 0.242372 0.189725 0.242214 0.181033 0.216516 0.185091 0.242372 0.185117 0.216278 0.189745 0.2161549 0.189725 0.242214 0.1921499 0.242193 0.185117 0.216278 0.189725 0.242214 0.189745 0.2161549 0.189745 0.2161549 0.1921499 0.242193 0.194559 0.2161549 0.174093 0.190452 0.167047 0.2242169 0.1619679 0.222822 0.174093 0.190452 0.180036 0.19177 0.167047 0.2242169 0.145829 0.224667 0.1619679 0.222822 0.161529 0.230719 0.145829 0.224667 0.153497 0.219861 0.1619679 0.222822 0.168288 0.1886219 0.1619679 0.222822 0.153497 0.219861 0.168288 0.1886219 0.174093 0.190452 0.1619679 0.222822 0.145102 0.230727 0.161529 0.230719 0.161031 0.236717 0.145102 0.230727 0.145829 0.224667 0.161529 0.230719 0.1443279 0.234654 0.161031 0.236717 0.160501 0.240553 0.1443279 0.234654 0.145102 0.230727 0.161031 0.236717 0.177112 0.245244 0.15995 0.242041 0.160501 0.240553 0.143521 0.236264 0.160501 0.240553 0.15995 0.242041 0.175567 0.244788 0.177112 0.245244 0.160501 0.240553 0.174952 0.244203 0.175567 0.244788 0.160501 0.240553 0.175727 0.243628 0.174952 0.244203 0.160501 0.240553 0.143521 0.236264 0.1443279 0.234654 0.160501 0.240553 0.176949 0.24498 0.159388 0.241028 0.15995 0.242041 0.142698 0.235404 0.15995 0.242041 0.159388 0.241028 0.177112 0.245244 0.176949 0.24498 0.15995 0.242041 0.142698 0.235404 0.143521 0.236264 0.15995 0.242041 0.176695 0.242359 0.158828 0.237402 0.159388 0.241028 0.1418769 0.231967 0.159388 0.241028 0.158828 0.237402 0.176949 0.24498 0.176695 0.242359 0.159388 0.241028 0.1418769 0.231967 0.142698 0.235404 0.159388 0.241028 0.176446 0.237322 0.1582829 0.23111 0.158828 0.237402 0.1410779 0.225903 0.158828 0.237402 0.1582829 0.23111 0.176695 0.242359 0.176446 0.237322 0.158828 0.237402 0.1410779 0.225903 0.1418769 0.231967 0.158828 0.237402 0.1762059 0.229853 0.1577669 0.222168 0.1582829 0.23111 0.140325 0.217235 0.1582829 0.23111 0.1577669 0.222168 0.176446 0.237322 0.1762059 0.229853 0.1582829 0.23111 0.140325 0.217235 0.1410779 0.225903 0.1582829 0.23111 0.1759819 0.220001 0.157296 0.210675 0.1577669 0.222168 0.140325 0.217235 0.1577669 0.222168 0.157296 0.210675 0.1762059 0.229853 0.1759819 0.220001 0.1577669 0.222168 0.175779 0.207885 0.156884 0.1968269 0.157296 0.210675 0.139638 0.2060689 0.157296 0.210675 0.156884 0.1968269 0.1759819 0.220001 0.175779 0.207885 0.157296 0.210675 0.139638 0.2060689 0.140325 0.217235 0.157296 0.210675 0.175604 0.193708 0.156566 0.180966 0.156884 0.1968269 0.156269 0.1817229 0.156884 0.1968269 0.156566 0.180966 0.175779 0.207885 0.175604 0.193708 0.156884 0.1968269 0.139039 0.192606 0.139638 0.2060689 0.156884 0.1968269 0.15477 0.183512 0.139039 0.192606 0.156884 0.1968269 0.1556 0.18281 0.15477 0.183512 0.156884 0.1968269 0.156269 0.1817229 0.1556 0.18281 0.156884 0.1968269 0.175462 0.177752 0.156779 0.18023 0.156566 0.180966 0.155822 0.150615 0.156566 0.180966 0.156779 0.18023 0.175604 0.193708 0.175462 0.177752 0.156566 0.180966 0.155822 0.150615 0.156269 0.1817229 0.156566 0.180966 0.175462 0.177752 0.157103 0.178346 0.156779 0.18023 0.156912 0.1506659 0.156779 0.18023 0.157103 0.178346 0.155822 0.150615 0.156779 0.18023 0.156912 0.1506659 0.175462 0.177752 0.157223 0.176035 0.157103 0.178346 0.156912 0.1506659 0.157103 0.178346 0.157223 0.176035 0.175357 0.16038 0.157102 0.17321 0.157223 0.176035 0.1572149 0.150725 0.157223 0.176035 0.157102 0.17321 0.175462 0.177752 0.175357 0.16038 0.157223 0.176035 0.156912 0.1506659 0.157223 0.176035 0.1572149 0.150725 0.175357 0.16038 0.156678 0.1697739 0.157102 0.17321 0.1572149 0.150725 0.157102 0.17321 0.156678 0.1697739 0.175357 0.16038 0.156313 0.167421 0.156678 0.1697739 0.154339 0.1509169 0.156678 0.1697739 0.156313 0.167421 0.156678 0.150782 0.156678 0.1697739 0.154339 0.1509169 0.1572149 0.150725 0.156678 0.1697739 0.156678 0.150782 0.175357 0.16038 0.156189 0.153118 0.156313 0.167421 0.155362 0.160479 0.156313 0.167421 0.156189 0.153118 0.154339 0.1509169 0.156313 0.167421 0.155362 0.160479 0.175292 0.142021 0.1560969 0.138274 0.156189 0.153118 0.154339 0.1509169 0.156189 0.153118 0.1560969 0.138274 0.175357 0.16038 0.175292 0.142021 0.156189 0.153118 0.154339 0.1509169 0.155362 0.160479 0.156189 0.153118 0.156292 0.123156 0.156066 0.123156 0.1560969 0.138274 0.1379629 0.14191 0.1560969 0.138274 0.156066 0.123156 0.17527 0.123156 0.156292 0.123156 0.1560969 0.138274 0.175292 0.142021 0.17527 0.123156 0.1560969 0.138274 0.154339 0.1509169 0.1560969 0.138274 0.1379629 0.14191 0.1752949 0.103084 0.156066 0.123156 0.156292 0.123156 0.138115 0.123156 0.1379629 0.14191 0.156066 0.123156 0.156118 0.103573 0.138115 0.123156 0.156066 0.123156 0.1752949 0.103084 0.156118 0.103573 0.156066 0.123156 0.1752949 0.103084 0.156292 0.123156 0.17527 0.123156 0.175485 0.123156 0.17527 0.123156 0.175292 0.142021 0.194956 0.102957 0.17527 0.123156 0.175485 0.123156 0.194956 0.102957 0.1752949 0.103084 0.17527 0.123156 0.177537 0.245332 0.176949 0.24498 0.177112 0.245244 0.1896409 0.246297 0.1921499 0.2463189 0.176949 0.24498 0.184867 0.246122 0.1896409 0.246297 0.176949 0.24498 0.180718 0.24579 0.184867 0.246122 0.176949 0.24498 0.177537 0.245332 0.180718 0.24579 0.176949 0.24498 0.175568 0.218174 0.177112 0.245244 0.175567 0.244788 0.177547 0.218601 0.177537 0.245332 0.177112 0.245244 0.177547 0.218601 0.177112 0.245244 0.175568 0.218174 0.175568 0.218174 0.175567 0.244788 0.174952 0.244203 0.174952 0.217715 0.174952 0.244203 0.175727 0.243628 0.175568 0.218174 0.174952 0.244203 0.174952 0.217715 0.174952 0.217715 0.175727 0.243628 0.175728 0.217263 0.145829 0.224667 0.146466 0.2167519 0.153497 0.219861 0.162666 0.1862919 0.153497 0.219861 0.146466 0.2167519 0.162666 0.1862919 0.168288 0.1886219 0.153497 0.219861 0.1311669 0.215561 0.146466 0.2167519 0.145829 0.224667 0.1311669 0.215561 0.140705 0.21372 0.146466 0.2167519 0.162666 0.1862919 0.146466 0.2167519 0.140705 0.21372 0.130338 0.221476 0.145829 0.224667 0.145102 0.230727 0.130338 0.221476 0.1311669 0.215561 0.145829 0.224667 0.129453 0.225636 0.145102 0.230727 0.1443279 0.234654 0.129453 0.225636 0.130338 0.221476 0.145102 0.230727 0.128526 0.227891 0.1443279 0.234654 0.143521 0.236264 0.128526 0.227891 0.129453 0.225636 0.1443279 0.234654 0.127573 0.228112 0.143521 0.236264 0.142698 0.235404 0.127573 0.228112 0.128526 0.227891 0.143521 0.236264 0.126614 0.226203 0.142698 0.235404 0.1418769 0.231967 0.126614 0.226203 0.127573 0.228112 0.142698 0.235404 0.12567 0.222108 0.1418769 0.231967 0.1410779 0.225903 0.12567 0.222108 0.126614 0.226203 0.1418769 0.231967 0.124761 0.21582 0.1410779 0.225903 0.140325 0.217235 0.124761 0.21582 0.12567 0.222108 0.1410779 0.225903 0.123912 0.2073889 0.140325 0.217235 0.139638 0.2060689 0.123912 0.2073889 0.124761 0.21582 0.140325 0.217235 0.123145 0.196931 0.139638 0.2060689 0.139039 0.192606 0.123145 0.196931 0.123912 0.2073889 0.139638 0.2060689 0.1493189 0.180097 0.13855 0.177147 0.139039 0.192606 0.122481 0.184634 0.139039 0.192606 0.13855 0.177147 0.150387 0.181706 0.1493189 0.180097 0.139039 0.192606 0.151521 0.182879 0.150387 0.181706 0.139039 0.192606 0.15266 0.183576 0.151521 0.182879 0.139039 0.192606 0.153795 0.183788 0.15266 0.183576 0.139039 0.192606 0.15477 0.183512 0.153795 0.183788 0.139039 0.192606 0.122481 0.184634 0.123145 0.196931 0.139039 0.192606 0.145159 0.161751 0.138187 0.160088 0.13855 0.177147 0.121942 0.170754 0.13855 0.177147 0.138187 0.160088 0.1467649 0.172333 0.145159 0.161751 0.13855 0.177147 0.147489 0.175544 0.1467649 0.172333 0.13855 0.177147 0.148349 0.178068 0.147489 0.175544 0.13855 0.177147 0.1493189 0.180097 0.148349 0.178068 0.13855 0.177147 0.121942 0.170754 0.122481 0.184634 0.13855 0.177147 0.143944 0.150806 0.1379629 0.14191 0.138187 0.160088 0.121544 0.155619 0.138187 0.160088 0.1379629 0.14191 0.145159 0.161751 0.143944 0.150806 0.138187 0.160088 0.121544 0.155619 0.121942 0.170754 0.138187 0.160088 0.138115 0.123156 0.137887 0.123156 0.1379629 0.14191 0.121299 0.139611 0.1379629 0.14191 0.137887 0.123156 0.149088 0.150865 0.154339 0.1509169 0.1379629 0.14191 0.143944 0.150806 0.149088 0.150865 0.1379629 0.14191 0.121299 0.139611 0.121544 0.155619 0.1379629 0.14191 0.156118 0.103573 0.137887 0.123156 0.138115 0.123156 0.121438 0.123156 0.121299 0.139611 0.137887 0.123156 0.1379629 0.104402 0.121438 0.123156 0.137887 0.123156 0.156118 0.103573 0.1379629 0.104402 0.137887 0.123156 0.143944 0.150806 0.154339 0.1509169 0.149088 0.150865 0.156678 0.150782 0.154339 0.1509169 0.143944 0.150806 0.1467649 0.150649 0.143944 0.150806 0.145159 0.161751 0.1467649 0.150649 0.156678 0.150782 0.143944 0.150806 0.1467649 0.150649 0.145159 0.161751 0.1467649 0.172333 0.1467649 0.150649 0.1467649 0.172333 0.147489 0.175544 0.14807 0.1506029 0.147489 0.175544 0.148349 0.178068 0.1467649 0.150649 0.147489 0.175544 0.14807 0.1506029 0.14807 0.1506029 0.148349 0.178068 0.1493189 0.180097 0.149922 0.150573 0.1493189 0.180097 0.150387 0.181706 0.14807 0.1506029 0.1493189 0.180097 0.149922 0.150573 0.149922 0.150573 0.150387 0.181706 0.151521 0.182879 0.152042 0.150565 0.151521 0.182879 0.15266 0.183576 0.149922 0.150573 0.151521 0.182879 0.152042 0.150565 0.152042 0.150565 0.15266 0.183576 0.153795 0.183788 0.154112 0.15058 0.153795 0.183788 0.15477 0.183512 0.152042 0.150565 0.153795 0.183788 0.154112 0.15058 0.154112 0.15058 0.15477 0.183512 0.1556 0.18281 0.155822 0.150615 0.1556 0.18281 0.156269 0.1817229 0.154112 0.15058 0.1556 0.18281 0.155822 0.150615 0.1311669 0.215561 0.131869 0.208103 0.140705 0.21372 0.157272 0.183483 0.140705 0.21372 0.131869 0.208103 0.157272 0.183483 0.162666 0.1862919 0.140705 0.21372 0.152145 0.180214 0.131869 0.208103 0.128935 0.205946 0.152145 0.180214 0.157272 0.183483 0.131869 0.208103 0.121438 0.123156 0.121217 0.123156 0.121299 0.139611 0.1379629 0.104402 0.121217 0.123156 0.121438 0.123156 0.1379629 0.104402 0.121299 0.106701 0.121217 0.123156 0.147325 0.176512 0.152145 0.180214 0.128935 0.205946 0.311178 0.123156 0.312805 0.123156 0.31441 0.123156 0.311198 0.12076 0.31441 0.123156 0.312805 0.123156 0.311198 0.125553 0.311178 0.123156 0.31441 0.123156 0.311259 0.127903 0.311198 0.125553 0.31441 0.123156 0.311358 0.130161 0.311259 0.127903 0.31441 0.123156 0.311496 0.132283 0.311358 0.130161 0.31441 0.123156 0.311668 0.134226 0.311496 0.132283 0.31441 0.123156 0.311872 0.135953 0.311668 0.134226 0.31441 0.123156 0.312103 0.137428 0.311872 0.135953 0.31441 0.123156 0.312358 0.138621 0.312103 0.137428 0.31441 0.123156 0.312631 0.139505 0.312358 0.138621 0.31441 0.123156 0.312917 0.140062 0.312631 0.139505 0.31441 0.123156 0.313211 0.140277 0.312917 0.140062 0.31441 0.123156 0.313506 0.140144 0.313211 0.140277 0.31441 0.123156 0.313796 0.139663 0.313506 0.140144 0.31441 0.123156 0.314076 0.138841 0.313796 0.139663 0.31441 0.123156 0.314339 0.137693 0.314076 0.138841 0.31441 0.123156 0.31458 0.136241 0.314339 0.137693 0.31441 0.123156 0.314794 0.134514 0.31458 0.136241 0.31441 0.123156 0.314976 0.132547 0.314794 0.134514 0.31441 0.123156 0.315121 0.130381 0.314976 0.132547 0.31441 0.123156 0.315228 0.12806 0.315121 0.130381 0.31441 0.123156 0.315293 0.125635 0.315228 0.12806 0.31441 0.123156 0.315314 0.123156 0.315293 0.125635 0.31441 0.123156 0.315293 0.120678 0.315314 0.123156 0.31441 0.123156 0.311259 0.118409 0.31441 0.123156 0.311198 0.12076 0.311358 0.116151 0.31441 0.123156 0.311259 0.118409 0.311496 0.11403 0.31441 0.123156 0.311358 0.116151 0.311668 0.1120859 0.31441 0.123156 0.311496 0.11403 0.311872 0.110359 0.31441 0.123156 0.311668 0.1120859 0.312103 0.108884 0.31441 0.123156 0.311872 0.110359 0.312358 0.107691 0.31441 0.123156 0.312103 0.108884 0.312631 0.106807 0.31441 0.123156 0.312358 0.107691 0.312917 0.10625 0.31441 0.123156 0.312631 0.106807 0.313211 0.106035 0.31441 0.123156 0.312917 0.10625 0.313506 0.106168 0.31441 0.123156 0.313211 0.106035 0.313796 0.106649 0.31441 0.123156 0.313506 0.106168 0.314076 0.107471 0.31441 0.123156 0.313796 0.106649 0.314339 0.108619 0.31441 0.123156 0.314076 0.107471 0.31458 0.110071 0.31441 0.123156 0.314339 0.108619 0.314794 0.111798 0.31441 0.123156 0.31458 0.110071 0.314976 0.113765 0.31441 0.123156 0.314794 0.111798 0.315121 0.115931 0.31441 0.123156 0.314976 0.113765 0.315228 0.118252 0.31441 0.123156 0.315121 0.115931 0.315293 0.120678 0.31441 0.123156 0.315228 0.118252 0.311198 0.12076 0.312805 0.123156 0.311178 0.123156 0.310447 0.123156 0.311178 0.123156 0.311198 0.125553 0.310432 0.121351 0.311178 0.123156 0.310447 0.123156 0.310432 0.121351 0.311198 0.12076 0.311178 0.123156 0.310388 0.126738 0.311198 0.125553 0.311259 0.127903 0.310432 0.124943 0.310447 0.123156 0.311198 0.125553 0.310388 0.126738 0.310432 0.124943 0.311198 0.125553 0.31021 0.130312 0.311259 0.127903 0.311358 0.130161 0.310313 0.128532 0.310388 0.126738 0.311259 0.127903 0.31021 0.130312 0.310313 0.128532 0.311259 0.127903 0.309907 0.133948 0.311358 0.130161 0.311496 0.132283 0.310077 0.1320959 0.31021 0.130312 0.311358 0.130161 0.309907 0.133948 0.310077 0.1320959 0.311358 0.130161 0.30941 0.138087 0.311496 0.132283 0.311668 0.134226 0.30941 0.138087 0.309907 0.133948 0.311496 0.132283 0.308676 0.1426309 0.311668 0.134226 0.311872 0.135953 0.308676 0.1426309 0.30941 0.138087 0.311668 0.134226 0.307584 0.14785 0.311872 0.135953 0.312103 0.137428 0.307584 0.14785 0.308676 0.1426309 0.311872 0.135953 0.307628 0.151801 0.312103 0.137428 0.312358 0.138621 0.30726 0.149187 0.307584 0.14785 0.312103 0.137428 0.307628 0.151801 0.30726 0.149187 0.312103 0.137428 0.308077 0.153901 0.312358 0.138621 0.312631 0.139505 0.308077 0.153901 0.307628 0.151801 0.312358 0.138621 0.308556 0.155498 0.312631 0.139505 0.312917 0.140062 0.308556 0.155498 0.308077 0.153901 0.312631 0.139505 0.311648 0.14749 0.312917 0.140062 0.313211 0.140277 0.311284 0.147432 0.308556 0.155498 0.312917 0.140062 0.311648 0.14749 0.311284 0.147432 0.312917 0.140062 0.311963 0.147549 0.313211 0.140277 0.313506 0.140144 0.311963 0.147549 0.311648 0.14749 0.313211 0.140277 0.31245 0.147668 0.313506 0.140144 0.313796 0.139663 0.312231 0.147608 0.311963 0.147549 0.313506 0.140144 0.31245 0.147668 0.312231 0.147608 0.313506 0.140144 0.310772 0.155998 0.313796 0.139663 0.314076 0.138841 0.31025 0.1567389 0.31245 0.147668 0.313796 0.139663 0.310772 0.155998 0.31025 0.1567389 0.313796 0.139663 0.311315 0.154425 0.314076 0.138841 0.314339 0.137693 0.311315 0.154425 0.310772 0.155998 0.314076 0.138841 0.311828 0.152193 0.314339 0.137693 0.31458 0.136241 0.311828 0.152193 0.311315 0.154425 0.314339 0.137693 0.3123 0.14934 0.31458 0.136241 0.314794 0.134514 0.3123 0.14934 0.311828 0.152193 0.31458 0.136241 0.31272 0.145921 0.314794 0.134514 0.314976 0.132547 0.31272 0.145921 0.3123 0.14934 0.314794 0.134514 0.313078 0.142005 0.314976 0.132547 0.315121 0.130381 0.313078 0.142005 0.31272 0.145921 0.314976 0.132547 0.313365 0.137673 0.315121 0.130381 0.315228 0.12806 0.313365 0.137673 0.313078 0.142005 0.315121 0.130381 0.313576 0.133018 0.315228 0.12806 0.315293 0.125635 0.313576 0.133018 0.313365 0.137673 0.315228 0.12806 0.313704 0.128143 0.315293 0.125635 0.315314 0.123156 0.313704 0.128143 0.313576 0.133018 0.315293 0.125635 0.313704 0.128143 0.315314 0.123156 0.313748 0.123156 0.315293 0.120678 0.313748 0.123156 0.315314 0.123156 0.309539 0.1310009 0.313704 0.128143 0.313748 0.123156 0.309539 0.1310009 0.313748 0.123156 0.309608 0.123156 0.3137 0.117936 0.309608 0.123156 0.313748 0.123156 0.3137 0.117936 0.313748 0.123156 0.315293 0.120678 0.303055 0.123156 0.310447 0.123156 0.310432 0.124943 0.30278 0.115655 0.310432 0.121351 0.310447 0.123156 0.303055 0.123156 0.30278 0.115655 0.310447 0.123156 0.303055 0.123156 0.310432 0.124943 0.310388 0.126738 0.303055 0.123156 0.310388 0.126738 0.310313 0.128532 0.303055 0.123156 0.310313 0.128532 0.31021 0.130312 0.30278 0.130657 0.31021 0.130312 0.310077 0.1320959 0.30278 0.130657 0.303055 0.123156 0.31021 0.130312 0.30278 0.130657 0.310077 0.1320959 0.309907 0.133948 0.30278 0.130657 0.309907 0.133948 0.30941 0.138087 0.301954 0.138144 0.30941 0.138087 0.308676 0.1426309 0.301954 0.138144 0.30278 0.130657 0.30941 0.138087 0.301954 0.138144 0.308676 0.1426309 0.307584 0.14785 0.300578 0.1455579 0.307584 0.14785 0.30726 0.149187 0.300578 0.1455579 0.301954 0.138144 0.307584 0.14785 0.305946 0.153982 0.30726 0.149187 0.307628 0.151801 0.300578 0.1455579 0.30726 0.149187 0.305946 0.153982 0.30358 0.160992 0.307628 0.151801 0.308077 0.153901 0.305946 0.153982 0.307628 0.151801 0.30358 0.160992 0.301886 0.169515 0.308077 0.153901 0.308556 0.155498 0.301263 0.1666409 0.308077 0.153901 0.301886 0.169515 0.30358 0.160992 0.308077 0.153901 0.301263 0.1666409 0.309423 0.1552709 0.309105 0.156415 0.308556 0.155498 0.302584 0.171616 0.308556 0.155498 0.309105 0.156415 0.311284 0.147432 0.309423 0.1552709 0.308556 0.155498 0.301886 0.169515 0.308556 0.155498 0.302584 0.171616 0.311284 0.147432 0.309105 0.156415 0.309423 0.1552709 0.306181 0.165396 0.309105 0.156415 0.311284 0.147432 0.306181 0.165396 0.302584 0.171616 0.309105 0.156415 0.306181 0.147446 0.311284 0.147432 0.311648 0.14749 0.306181 0.147446 0.306181 0.165396 0.311284 0.147432 0.302048 0.147531 0.311648 0.14749 0.311963 0.147549 0.304374 0.14746 0.306181 0.147446 0.311648 0.14749 0.302923 0.14749 0.304374 0.14746 0.311648 0.14749 0.302048 0.147531 0.302923 0.14749 0.311648 0.14749 0.301883 0.147577 0.311963 0.147549 0.312231 0.147608 0.301883 0.147577 0.302048 0.147531 0.311963 0.147549 0.303689 0.147658 0.312231 0.147608 0.31245 0.147668 0.302459 0.147622 0.301883 0.147577 0.312231 0.147608 0.303689 0.147658 0.302459 0.147622 0.312231 0.147608 0.31025 0.1567389 0.31057 0.155584 0.31245 0.147668 0.307297 0.147683 0.31245 0.147668 0.31057 0.155584 0.305389 0.147679 0.303689 0.147658 0.31245 0.147668 0.307297 0.147683 0.305389 0.147679 0.31245 0.147668 0.307297 0.147683 0.31057 0.155584 0.31025 0.1567389 0.305 0.172498 0.31025 0.1567389 0.310772 0.155998 0.306335 0.168308 0.307297 0.165807 0.31025 0.1567389 0.307297 0.147683 0.31025 0.1567389 0.307297 0.165807 0.305 0.172498 0.306335 0.168308 0.31025 0.1567389 0.30582 0.170603 0.310772 0.155998 0.311315 0.154425 0.30582 0.170603 0.305 0.172498 0.310772 0.155998 0.306603 0.167598 0.311315 0.154425 0.311828 0.152193 0.306603 0.167598 0.30582 0.170603 0.311315 0.154425 0.307331 0.163531 0.311828 0.152193 0.3123 0.14934 0.307331 0.163531 0.306603 0.167598 0.311828 0.152193 0.307984 0.15848 0.3123 0.14934 0.31272 0.145921 0.307984 0.15848 0.307331 0.163531 0.3123 0.14934 0.308546 0.152554 0.31272 0.145921 0.313078 0.142005 0.308546 0.152554 0.307984 0.15848 0.31272 0.145921 0.309 0.145888 0.313078 0.142005 0.313365 0.137673 0.309 0.145888 0.308546 0.152554 0.313078 0.142005 0.309334 0.138644 0.313365 0.137673 0.313576 0.133018 0.309334 0.138644 0.309 0.145888 0.313365 0.137673 0.309539 0.1310009 0.313576 0.133018 0.313704 0.128143 0.309539 0.1310009 0.309334 0.138644 0.313576 0.133018 0.302772 0.132971 0.309539 0.1310009 0.309608 0.123156 0.302772 0.132971 0.309608 0.123156 0.302849 0.123156 0.309542 0.115474 0.302849 0.123156 0.309608 0.123156 0.309542 0.115474 0.309608 0.123156 0.3137 0.117936 0.307297 0.147683 0.307297 0.165807 0.306335 0.168308 0.305 0.172498 0.305476 0.170377 0.306335 0.168308 0.307297 0.147683 0.306335 0.168308 0.305476 0.170377 0.305 0.172498 0.304736 0.172046 0.305476 0.170377 0.305389 0.147679 0.305476 0.170377 0.304736 0.172046 0.307297 0.147683 0.305476 0.170377 0.305389 0.147679 0.305 0.172498 0.304161 0.173272 0.304736 0.172046 0.305389 0.147679 0.304736 0.172046 0.304161 0.173272 0.296719 0.1882179 0.304161 0.173272 0.305 0.172498 0.295761 0.188444 0.304085 0.17343 0.304161 0.173272 0.305389 0.147679 0.304161 0.173272 0.304085 0.17343 0.296719 0.1882179 0.295761 0.188444 0.304161 0.173272 0.297673 0.186672 0.305 0.172498 0.30582 0.170603 0.297673 0.186672 0.296719 0.1882179 0.305 0.172498 0.298602 0.183803 0.30582 0.170603 0.306603 0.167598 0.298602 0.183803 0.297673 0.186672 0.30582 0.170603 0.299487 0.179637 0.306603 0.167598 0.307331 0.163531 0.299487 0.179637 0.298602 0.183803 0.306603 0.167598 0.300305 0.17423 0.307331 0.163531 0.307984 0.15848 0.300305 0.17423 0.299487 0.179637 0.307331 0.163531 0.301037 0.167677 0.307984 0.15848 0.308546 0.152554 0.301037 0.167677 0.300305 0.17423 0.307984 0.15848 0.301665 0.160102 0.308546 0.152554 0.309 0.145888 0.301665 0.160102 0.301037 0.167677 0.308546 0.152554 0.302172 0.151664 0.309 0.145888 0.309334 0.138644 0.302172 0.151664 0.301665 0.160102 0.309 0.145888 0.302545 0.14255 0.309334 0.138644 0.309539 0.1310009 0.302545 0.14255 0.302172 0.151664 0.309334 0.138644 0.302772 0.132971 0.302545 0.14255 0.309539 0.1310009 0.293446 0.1321409 0.302772 0.132971 0.302849 0.123156 0.293446 0.1321409 0.302849 0.123156 0.293494 0.123156 0.302772 0.113342 0.293494 0.123156 0.302849 0.123156 0.302772 0.113342 0.302849 0.123156 0.309542 0.115474 0.295761 0.188444 0.303459 0.174683 0.304085 0.17343 0.303689 0.147658 0.304085 0.17343 0.303459 0.174683 0.305389 0.147679 0.304085 0.17343 0.303689 0.147658 0.295761 0.188444 0.302821 0.175866 0.303459 0.174683 0.303689 0.147658 0.303459 0.174683 0.302821 0.175866 0.295761 0.188444 0.302282 0.176751 0.302821 0.175866 0.302459 0.147622 0.302821 0.175866 0.302282 0.176751 0.303689 0.147658 0.302821 0.175866 0.302459 0.147622 0.295761 0.188444 0.301963 0.177144 0.302282 0.176751 0.302459 0.147622 0.302282 0.176751 0.301963 0.177144 0.294817 0.1873829 0.301855 0.177109 0.301963 0.177144 0.301883 0.147577 0.301963 0.177144 0.301855 0.177109 0.295761 0.188444 0.294817 0.1873829 0.301963 0.177144 0.302459 0.147622 0.301963 0.177144 0.301883 0.147577 0.294817 0.1873829 0.301934 0.176659 0.301855 0.177109 0.301883 0.147577 0.301855 0.177109 0.301934 0.176659 0.294817 0.1873829 0.302236 0.175725 0.301934 0.176659 0.302048 0.147531 0.301934 0.176659 0.302236 0.175725 0.301883 0.147577 0.301934 0.176659 0.302048 0.147531 0.294817 0.1873829 0.302708 0.174445 0.302236 0.175725 0.302048 0.147531 0.302236 0.175725 0.302708 0.174445 0.294817 0.1873829 0.303227 0.173097 0.302708 0.174445 0.302923 0.14749 0.302708 0.174445 0.303227 0.173097 0.302048 0.147531 0.302708 0.174445 0.302923 0.14749 0.294817 0.1873829 0.303307 0.172892 0.303227 0.173097 0.302923 0.14749 0.303227 0.173097 0.303307 0.172892 0.294817 0.1873829 0.302584 0.171616 0.303307 0.172892 0.303786 0.1716639 0.303307 0.172892 0.302584 0.171616 0.302923 0.14749 0.303307 0.172892 0.303786 0.1716639 0.293906 0.185088 0.301886 0.169515 0.302584 0.171616 0.294817 0.1873829 0.293906 0.185088 0.302584 0.171616 0.304444 0.169973 0.303786 0.1716639 0.302584 0.171616 0.305245 0.167893 0.304444 0.169973 0.302584 0.171616 0.306181 0.165396 0.305245 0.167893 0.302584 0.171616 0.300308 0.1687279 0.301263 0.1666409 0.301886 0.169515 0.296463 0.176113 0.300308 0.1687279 0.301886 0.169515 0.2931 0.181585 0.296463 0.176113 0.301886 0.169515 0.293906 0.185088 0.2931 0.181585 0.301886 0.169515 0.296224 0.159965 0.301263 0.1666409 0.300308 0.1687279 0.296224 0.159965 0.30358 0.160992 0.301263 0.1666409 0.293258 0.1669149 0.300308 0.1687279 0.296463 0.176113 0.293258 0.1669149 0.296224 0.159965 0.300308 0.1687279 0.289774 0.173659 0.296463 0.176113 0.2931 0.181585 0.289774 0.173659 0.293258 0.1669149 0.296463 0.176113 0.292025 0.1831859 0.2931 0.181585 0.293906 0.185088 0.289774 0.173659 0.2931 0.181585 0.292025 0.1831859 0.283828 0.198843 0.293906 0.185088 0.294817 0.1873829 0.286056 0.191047 0.292025 0.1831859 0.293906 0.185088 0.283061 0.194458 0.286056 0.191047 0.293906 0.185088 0.283828 0.198843 0.283061 0.194458 0.293906 0.185088 0.284881 0.201493 0.294817 0.1873829 0.295761 0.188444 0.284881 0.201493 0.283828 0.198843 0.294817 0.1873829 0.285971 0.202491 0.295761 0.188444 0.296719 0.1882179 0.285971 0.202491 0.284881 0.201493 0.295761 0.188444 0.287077 0.201756 0.296719 0.1882179 0.297673 0.186672 0.287077 0.201756 0.285971 0.202491 0.296719 0.1882179 0.288172 0.199244 0.297673 0.186672 0.298602 0.183803 0.288172 0.199244 0.287077 0.201756 0.297673 0.186672 0.28923 0.19495 0.298602 0.183803 0.299487 0.179637 0.28923 0.19495 0.288172 0.199244 0.298602 0.183803 0.290225 0.1889179 0.299487 0.179637 0.300305 0.17423 0.290225 0.1889179 0.28923 0.19495 0.299487 0.179637 0.29113 0.181243 0.300305 0.17423 0.301037 0.167677 0.29113 0.181243 0.290225 0.1889179 0.300305 0.17423 0.291923 0.172098 0.301037 0.167677 0.301665 0.160102 0.291923 0.172098 0.29113 0.181243 0.301037 0.167677 0.295839 0.159211 0.301665 0.160102 0.302172 0.151664 0.292286 0.171163 0.291923 0.172098 0.301665 0.160102 0.293151 0.168682 0.292286 0.171163 0.301665 0.160102 0.295839 0.159211 0.293151 0.168682 0.301665 0.160102 0.297912 0.149389 0.302172 0.151664 0.302545 0.14255 0.297912 0.149389 0.295839 0.159211 0.302172 0.151664 0.293304 0.1410019 0.302545 0.14255 0.302772 0.132971 0.295341 0.149507 0.297912 0.149389 0.302545 0.14255 0.293081 0.149601 0.295341 0.149507 0.302545 0.14255 0.293304 0.1410019 0.293081 0.149601 0.302545 0.14255 0.293446 0.1321409 0.293304 0.1410019 0.302772 0.132971 0.281544 0.138151 0.293446 0.1321409 0.293494 0.123156 0.281544 0.138151 0.293494 0.123156 0.281644 0.123156 0.29341 0.111233 0.281644 0.123156 0.293494 0.123156 0.29341 0.111233 0.293494 0.123156 0.302772 0.113342 0.285793 0.180142 0.292025 0.1831859 0.286056 0.191047 0.285793 0.180142 0.289774 0.173659 0.292025 0.1831859 0.281345 0.186315 0.286056 0.191047 0.283061 0.194458 0.281345 0.186315 0.285793 0.180142 0.286056 0.191047 0.277441 0.200107 0.283061 0.194458 0.283828 0.198843 0.276445 0.192155 0.283061 0.194458 0.277441 0.200107 0.276445 0.192155 0.281345 0.186315 0.283061 0.194458 0.271847 0.210592 0.283828 0.198843 0.284881 0.201493 0.271014 0.205579 0.277441 0.200107 0.283828 0.198843 0.271847 0.210592 0.271014 0.205579 0.283828 0.198843 0.272917 0.213733 0.284881 0.201493 0.285971 0.202491 0.272917 0.213733 0.271847 0.210592 0.284881 0.201493 0.274029 0.214937 0.285971 0.202491 0.287077 0.201756 0.274029 0.214937 0.272917 0.213733 0.285971 0.202491 0.275158 0.2141 0.287077 0.201756 0.288172 0.199244 0.275158 0.2141 0.274029 0.214937 0.287077 0.201756 0.276279 0.211154 0.288172 0.199244 0.28923 0.19495 0.276279 0.211154 0.275158 0.2141 0.288172 0.199244 0.277363 0.206084 0.28923 0.19495 0.290225 0.1889179 0.277363 0.206084 0.276279 0.211154 0.28923 0.19495 0.278382 0.198931 0.290225 0.1889179 0.29113 0.181243 0.278382 0.198931 0.277363 0.206084 0.290225 0.1889179 0.291321 0.173533 0.29113 0.181243 0.291923 0.172098 0.289259 0.177563 0.288194 0.179162 0.29113 0.181243 0.279307 0.189803 0.29113 0.181243 0.288194 0.179162 0.290308 0.175671 0.289259 0.177563 0.29113 0.181243 0.291321 0.173533 0.290308 0.175671 0.29113 0.181243 0.279307 0.189803 0.278382 0.198931 0.29113 0.181243 0.291232 0.149296 0.291923 0.172098 0.292286 0.171163 0.291232 0.149296 0.291321 0.173533 0.291923 0.172098 0.291232 0.149296 0.292286 0.171163 0.293151 0.168682 0.297912 0.149389 0.293151 0.168682 0.295839 0.159211 0.293151 0.149314 0.293151 0.168682 0.297912 0.149389 0.291232 0.149296 0.293151 0.168682 0.293151 0.149314 0.285314 0.149464 0.297912 0.149389 0.295341 0.149507 0.285952 0.14936 0.293151 0.149314 0.297912 0.149389 0.285239 0.14941 0.285952 0.14936 0.297912 0.149389 0.285314 0.149464 0.285239 0.14941 0.297912 0.149389 0.287682 0.14955 0.295341 0.149507 0.293081 0.149601 0.286171 0.149513 0.285314 0.149464 0.295341 0.149507 0.287682 0.14955 0.286171 0.149513 0.295341 0.149507 0.292446 0.149627 0.293081 0.149601 0.293304 0.1410019 0.287682 0.14955 0.293081 0.149601 0.292446 0.149627 0.281544 0.138151 0.293304 0.1410019 0.293446 0.1321409 0.281247 0.152707 0.292446 0.149627 0.293304 0.1410019 0.281544 0.138151 0.281247 0.152707 0.293304 0.1410019 0.267411 0.1389459 0.281544 0.138151 0.281644 0.123156 0.267411 0.1389459 0.281644 0.123156 0.267494 0.123156 0.281544 0.108161 0.267494 0.123156 0.281644 0.123156 0.281544 0.108161 0.281644 0.123156 0.29341 0.111233 0.280763 0.166408 0.290381 0.159451 0.292446 0.149627 0.287682 0.14955 0.292446 0.149627 0.290381 0.159451 0.281247 0.152707 0.280763 0.166408 0.292446 0.149627 0.280763 0.166408 0.287682 0.169012 0.290381 0.159451 0.287682 0.14955 0.290381 0.159451 0.287682 0.169012 0.280109 0.178879 0.28691 0.171495 0.287682 0.169012 0.287682 0.14955 0.287682 0.169012 0.28691 0.171495 0.280763 0.166408 0.280109 0.178879 0.287682 0.169012 0.280109 0.178879 0.286245 0.1738139 0.28691 0.171495 0.287682 0.14955 0.28691 0.171495 0.286245 0.1738139 0.280109 0.178879 0.285764 0.1756989 0.286245 0.1738139 0.286171 0.149513 0.286245 0.1738139 0.285764 0.1756989 0.287682 0.14955 0.286245 0.1738139 0.286171 0.149513 0.279307 0.189803 0.285439 0.17723 0.285764 0.1756989 0.286171 0.149513 0.285764 0.1756989 0.285439 0.17723 0.280109 0.178879 0.279307 0.189803 0.285764 0.1756989 0.279307 0.189803 0.285231 0.178609 0.285439 0.17723 0.285314 0.149464 0.285439 0.17723 0.285231 0.178609 0.286171 0.149513 0.285439 0.17723 0.285314 0.149464 0.279307 0.189803 0.285181 0.179889 0.285231 0.178609 0.285314 0.149464 0.285231 0.178609 0.285181 0.179889 0.279307 0.189803 0.28538 0.180773 0.285181 0.179889 0.285239 0.14941 0.285181 0.179889 0.28538 0.180773 0.285314 0.149464 0.285181 0.179889 0.285239 0.14941 0.279307 0.189803 0.285804 0.181103 0.28538 0.180773 0.285239 0.14941 0.28538 0.180773 0.285804 0.181103 0.279307 0.189803 0.286407 0.1809549 0.285804 0.181103 0.285952 0.14936 0.285804 0.181103 0.286407 0.1809549 0.285239 0.14941 0.285804 0.181103 0.285952 0.14936 0.279307 0.189803 0.287213 0.1803179 0.286407 0.1809549 0.285952 0.14936 0.286407 0.1809549 0.287213 0.1803179 0.279307 0.189803 0.288194 0.179162 0.287213 0.1803179 0.287341 0.149321 0.287213 0.1803179 0.288194 0.179162 0.285952 0.14936 0.287213 0.1803179 0.287341 0.149321 0.289194 0.149298 0.288194 0.179162 0.289259 0.177563 0.287341 0.149321 0.288194 0.179162 0.289194 0.149298 0.289194 0.149298 0.289259 0.177563 0.290308 0.175671 0.291232 0.149296 0.290308 0.175671 0.291321 0.173533 0.289194 0.149298 0.290308 0.175671 0.291232 0.149296 0.271116 0.19763 0.277441 0.200107 0.271014 0.205579 0.271116 0.19763 0.276445 0.192155 0.277441 0.200107 0.258194 0.219855 0.271014 0.205579 0.271847 0.210592 0.258194 0.219855 0.265968 0.209263 0.271014 0.205579 0.265381 0.20271 0.271014 0.205579 0.265968 0.209263 0.265381 0.20271 0.271116 0.19763 0.271014 0.205579 0.259111 0.223545 0.271847 0.210592 0.272917 0.213733 0.259111 0.223545 0.258194 0.219855 0.271847 0.210592 0.260066 0.2254 0.272917 0.213733 0.274029 0.214937 0.260066 0.2254 0.259111 0.223545 0.272917 0.213733 0.261044 0.225305 0.274029 0.214937 0.275158 0.2141 0.261044 0.225305 0.260066 0.2254 0.274029 0.214937 0.262025 0.223178 0.275158 0.2141 0.276279 0.211154 0.262025 0.223178 0.261044 0.225305 0.275158 0.2141 0.262988 0.218975 0.276279 0.211154 0.277363 0.206084 0.262988 0.218975 0.262025 0.223178 0.276279 0.211154 0.263912 0.212697 0.277363 0.206084 0.278382 0.198931 0.263912 0.212697 0.262988 0.218975 0.277363 0.206084 0.264773 0.2044 0.278382 0.198931 0.279307 0.189803 0.264773 0.2044 0.263912 0.212697 0.278382 0.198931 0.26555 0.1942009 0.279307 0.189803 0.280109 0.178879 0.26555 0.1942009 0.264773 0.2044 0.279307 0.189803 0.26622 0.182281 0.280109 0.178879 0.280763 0.166408 0.26622 0.182281 0.26555 0.1942009 0.280109 0.178879 0.266764 0.1688849 0.280763 0.166408 0.281247 0.152707 0.266764 0.1688849 0.26622 0.182281 0.280763 0.166408 0.267165 0.154321 0.281247 0.152707 0.281544 0.138151 0.267165 0.154321 0.266764 0.1688849 0.281247 0.152707 0.267411 0.1389459 0.267165 0.154321 0.281544 0.138151 0.251258 0.140596 0.267411 0.1389459 0.267494 0.123156 0.251258 0.140596 0.267494 0.123156 0.25133 0.123156 0.267411 0.107366 0.25133 0.123156 0.267494 0.123156 0.267411 0.107366 0.267494 0.123156 0.281544 0.108161 0.258194 0.219855 0.257308 0.214529 0.265968 0.209263 0.259286 0.207352 0.265968 0.209263 0.257308 0.214529 0.259286 0.207352 0.265381 0.20271 0.265968 0.209263 0.243335 0.227081 0.257308 0.214529 0.258194 0.219855 0.243335 0.227081 0.25274 0.216834 0.257308 0.214529 0.252855 0.211536 0.257308 0.214529 0.25274 0.216834 0.252855 0.211536 0.259286 0.207352 0.257308 0.214529 0.244108 0.23145 0.258194 0.219855 0.259111 0.223545 0.244108 0.23145 0.243335 0.227081 0.258194 0.219855 0.244918 0.2338269 0.259111 0.223545 0.260066 0.2254 0.244918 0.2338269 0.244108 0.23145 0.259111 0.223545 0.245751 0.234072 0.260066 0.2254 0.261044 0.225305 0.245751 0.234072 0.244918 0.2338269 0.260066 0.2254 0.24659 0.23208 0.261044 0.225305 0.262025 0.223178 0.24659 0.23208 0.245751 0.234072 0.261044 0.225305 0.247417 0.227786 0.262025 0.223178 0.262988 0.218975 0.247417 0.227786 0.24659 0.23208 0.262025 0.223178 0.248214 0.221174 0.262988 0.218975 0.263912 0.212697 0.248214 0.221174 0.247417 0.227786 0.262988 0.218975 0.248959 0.212292 0.263912 0.212697 0.264773 0.2044 0.248959 0.212292 0.248214 0.221174 0.263912 0.212697 0.249634 0.201258 0.264773 0.2044 0.26555 0.1942009 0.249634 0.201258 0.248959 0.212292 0.264773 0.2044 0.250217 0.188264 0.26555 0.1942009 0.26622 0.182281 0.250217 0.188264 0.249634 0.201258 0.26555 0.1942009 0.250692 0.173582 0.26622 0.182281 0.266764 0.1688849 0.250692 0.173582 0.250217 0.188264 0.26622 0.182281 0.251042 0.1575559 0.266764 0.1688849 0.267165 0.154321 0.251042 0.1575559 0.250692 0.173582 0.266764 0.1688849 0.251258 0.140596 0.267165 0.154321 0.267411 0.1389459 0.251258 0.140596 0.251042 0.1575559 0.267165 0.154321 0.2335039 0.137134 0.251258 0.140596 0.25133 0.123156 0.2335039 0.137134 0.25133 0.123156 0.233534 0.123156 0.251258 0.105716 0.233534 0.123156 0.25133 0.123156 0.251258 0.105716 0.25133 0.123156 0.267411 0.107366 0.243335 0.227081 0.242608 0.220921 0.25274 0.216834 0.246128 0.215236 0.25274 0.216834 0.242608 0.220921 0.246128 0.215236 0.252855 0.211536 0.25274 0.216834 0.227515 0.2316 0.242608 0.220921 0.243335 0.227081 0.227515 0.2316 0.238766 0.222129 0.242608 0.220921 0.239143 0.2184309 0.242608 0.220921 0.238766 0.222129 0.239143 0.2184309 0.246128 0.215236 0.242608 0.220921 0.228065 0.236658 0.243335 0.227081 0.244108 0.23145 0.228065 0.236658 0.227515 0.2316 0.243335 0.227081 0.228645 0.239724 0.244108 0.23145 0.244918 0.2338269 0.228645 0.239724 0.228065 0.236658 0.244108 0.23145 0.2292439 0.240647 0.244918 0.2338269 0.245751 0.234072 0.2292439 0.240647 0.228645 0.239724 0.244918 0.2338269 0.229852 0.239304 0.245751 0.234072 0.24659 0.23208 0.229852 0.239304 0.2292439 0.240647 0.245751 0.234072 0.230457 0.235608 0.24659 0.23208 0.247417 0.227786 0.230457 0.235608 0.229852 0.239304 0.24659 0.23208 0.231045 0.22952 0.247417 0.227786 0.248214 0.221174 0.231045 0.22952 0.230457 0.235608 0.247417 0.227786 0.2316009 0.22106 0.248214 0.221174 0.248959 0.212292 0.2316009 0.22106 0.231045 0.22952 0.248214 0.221174 0.232112 0.210315 0.248959 0.212292 0.249634 0.201258 0.232112 0.210315 0.2316009 0.22106 0.248959 0.212292 0.232563 0.19745 0.249634 0.201258 0.250217 0.188264 0.232563 0.19745 0.232112 0.210315 0.249634 0.201258 0.232938 0.182749 0.250217 0.188264 0.250692 0.173582 0.232938 0.182749 0.232563 0.19745 0.250217 0.188264 0.236943 0.175079 0.250692 0.173582 0.251042 0.1575559 0.233152 0.182552 0.232938 0.182749 0.250692 0.173582 0.2343029 0.181189 0.233152 0.182552 0.250692 0.173582 0.235342 0.179427 0.2343029 0.181189 0.250692 0.173582 0.236201 0.177435 0.235342 0.179427 0.250692 0.173582 0.236943 0.175079 0.236201 0.177435 0.250692 0.173582 0.237828 0.157324 0.251042 0.1575559 0.251258 0.140596 0.237588 0.172044 0.236943 0.175079 0.251042 0.1575559 0.23802 0.168217 0.237588 0.172044 0.251042 0.1575559 0.238071 0.163669 0.23802 0.168217 0.251042 0.1575559 0.237828 0.157324 0.238071 0.163669 0.251042 0.1575559 0.237627 0.150838 0.237828 0.157324 0.251258 0.140596 0.233412 0.150883 0.237627 0.150838 0.251258 0.140596 0.2335039 0.137134 0.233412 0.150883 0.251258 0.140596 0.233479 0.104324 0.233534 0.123156 0.251258 0.105716 0.227515 0.2316 0.2269909 0.224757 0.238766 0.222129 0.231936 0.221103 0.238766 0.222129 0.2269909 0.224757 0.231936 0.221103 0.239143 0.2184309 0.238766 0.222129 0.224556 0.2232339 0.2269909 0.224757 0.224189 0.225153 0.224556 0.2232339 0.231936 0.221103 0.2269909 0.224757 0.231131 0.15057 0.232938 0.182749 0.233152 0.182552 0.231131 0.15057 0.232002 0.183408 0.232938 0.182749 0.233264 0.150566 0.233152 0.182552 0.2343029 0.181189 0.231131 0.15057 0.233152 0.182552 0.233264 0.150566 0.235297 0.150584 0.2343029 0.181189 0.235342 0.179427 0.233264 0.150566 0.2343029 0.181189 0.235297 0.150584 0.235297 0.150584 0.235342 0.179427 0.236201 0.177435 0.236925 0.150623 0.236201 0.177435 0.236943 0.175079 0.235297 0.150584 0.236201 0.177435 0.236925 0.150623 0.236925 0.150623 0.236943 0.175079 0.237588 0.172044 0.2379 0.1506749 0.237588 0.172044 0.23802 0.168217 0.236925 0.150623 0.237588 0.172044 0.2379 0.1506749 0.2379 0.1506749 0.23802 0.168217 0.238071 0.163669 0.237627 0.150838 0.238071 0.163669 0.237828 0.157324 0.238071 0.150734 0.238071 0.163669 0.237627 0.150838 0.2379 0.1506749 0.238071 0.163669 0.238071 0.150734 0.227126 0.1506969 0.237627 0.150838 0.233412 0.150883 0.227126 0.1506969 0.238071 0.150734 0.237627 0.150838 0.231839 0.1508989 0.233412 0.150883 0.2335039 0.137134 0.227126 0.1506969 0.233412 0.150883 0.231839 0.1508989 0.225939 0.150951 0.231839 0.1508989 0.2335039 0.137134 0.227126 0.1506969 0.231839 0.1508989 0.225939 0.150951 0.227126 0.1506969 0.225939 0.150951 0.226438 0.164565 0.227126 0.1506969 0.226438 0.164565 0.227126 0.1774629 0.227126 0.1506969 0.227126 0.1774629 0.227243 0.1787 0.227126 0.1506969 0.227243 0.1787 0.227455 0.179929 0.22781 0.150641 0.227455 0.179929 0.227822 0.181206 0.227126 0.1506969 0.227455 0.179929 0.22781 0.150641 0.22781 0.150641 0.227822 0.181206 0.2283779 0.1823599 0.22781 0.150641 0.2283779 0.1823599 0.229028 0.183149 0.2292169 0.150597 0.229028 0.183149 0.229857 0.183658 0.22781 0.150641 0.229028 0.183149 0.2292169 0.150597 0.2292169 0.150597 0.229857 0.183658 0.230897 0.183773 0.231131 0.15057 0.230897 0.183773 0.232002 0.183408 0.2292169 0.150597 0.230897 0.183773 0.231131 0.15057 0.189662 0.219357 0.1921499 0.2463189 0.1896409 0.246297 0.194642 0.219357 0.1921499 0.2463189 0.189662 0.219357 0.184893 0.2192209 0.1896409 0.246297 0.184867 0.246122 0.189662 0.219357 0.1896409 0.246297 0.184893 0.2192209 0.1807399 0.218961 0.184867 0.246122 0.180718 0.24579 0.184893 0.2192209 0.184867 0.246122 0.1807399 0.218961 0.177547 0.218601 0.180718 0.24579 0.177537 0.245332 0.1807399 0.218961 0.180718 0.24579 0.177547 0.218601 0.298665 0.152842 0.305946 0.153982 0.30358 0.160992 0.296224 0.159965 0.298665 0.152842 0.30358 0.160992 0.304374 0.14746 0.303786 0.1716639 0.304444 0.169973 0.302923 0.14749 0.303786 0.1716639 0.304374 0.14746 0.304374 0.14746 0.304444 0.169973 0.305245 0.167893 0.304374 0.14746 0.305245 0.167893 0.306181 0.165396 0.304374 0.14746 0.306181 0.165396 0.306181 0.147446 0.298665 0.152842 0.300578 0.1455579 0.305946 0.153982 0.147325 0.06979995 0.128937 0.04036498 0.131869 0.03820896 0.140705 0.03259193 0.131869 0.03820896 0.1311669 0.03075093 0.152145 0.06609797 0.131869 0.03820896 0.140705 0.03259193 0.152145 0.06609797 0.147325 0.06979995 0.131869 0.03820896 0.145829 0.02164489 0.1311669 0.03075093 0.130338 0.024836 0.146466 0.02955991 0.140705 0.03259193 0.1311669 0.03075093 0.145829 0.02164489 0.146466 0.02955991 0.1311669 0.03075093 0.145102 0.01558488 0.130338 0.024836 0.129453 0.02067589 0.145102 0.01558488 0.145829 0.02164489 0.130338 0.024836 0.1443279 0.01165795 0.129453 0.02067589 0.128526 0.01842099 0.1443279 0.01165795 0.145102 0.01558488 0.129453 0.02067589 0.143521 0.01004892 0.128526 0.01842099 0.127573 0.01820099 0.143521 0.01004892 0.1443279 0.01165795 0.128526 0.01842099 0.142698 0.01090788 0.127573 0.01820099 0.126614 0.02010893 0.142698 0.01090788 0.143521 0.01004892 0.127573 0.01820099 0.1418769 0.01434499 0.126614 0.02010893 0.12567 0.02420395 0.1418769 0.01434499 0.142698 0.01090788 0.126614 0.02010893 0.1410779 0.02040892 0.12567 0.02420395 0.124761 0.03049188 0.1410779 0.02040892 0.1418769 0.01434499 0.12567 0.02420395 0.140325 0.02907699 0.124761 0.03049188 0.123912 0.03892296 0.140325 0.02907699 0.1410779 0.02040892 0.124761 0.03049188 0.139638 0.04024291 0.123912 0.03892296 0.123145 0.04938089 0.139638 0.04024291 0.140325 0.02907699 0.123912 0.03892296 0.139039 0.05370599 0.123145 0.04938089 0.122481 0.06167799 0.139039 0.05370599 0.139638 0.04024291 0.123145 0.04938089 0.13855 0.06916499 0.122481 0.06167799 0.121942 0.075558 0.13855 0.06916499 0.139039 0.05370599 0.122481 0.06167799 0.138187 0.08622395 0.121942 0.075558 0.121544 0.09069299 0.138187 0.08622395 0.13855 0.06916499 0.121942 0.075558 0.1379629 0.104402 0.121544 0.09069299 0.121299 0.106701 0.1379629 0.104402 0.138187 0.08622395 0.121544 0.09069299 0.157272 0.06282895 0.140705 0.03259193 0.146466 0.02955991 0.157272 0.06282895 0.152145 0.06609797 0.140705 0.03259193 0.153497 0.02645099 0.146466 0.02955991 0.145829 0.02164489 0.162666 0.06001991 0.146466 0.02955991 0.153497 0.02645099 0.162666 0.06001991 0.157272 0.06282895 0.146466 0.02955991 0.161526 0.01554197 0.145829 0.02164489 0.145102 0.01558488 0.1619679 0.02348995 0.153497 0.02645099 0.145829 0.02164489 0.161526 0.01554197 0.1619679 0.02348995 0.145829 0.02164489 0.161023 0.009521961 0.145102 0.01558488 0.1443279 0.01165795 0.161023 0.009521961 0.161526 0.01554197 0.145102 0.01558488 0.160489 0.005699992 0.1443279 0.01165795 0.143521 0.01004892 0.160489 0.005699992 0.161023 0.009521961 0.1443279 0.01165795 0.159934 0.004264891 0.143521 0.01004892 0.142698 0.01090788 0.159934 0.004264891 0.160489 0.005699992 0.143521 0.01004892 0.159368 0.005370974 0.142698 0.01090788 0.1418769 0.01434499 0.159368 0.005370974 0.159934 0.004264891 0.142698 0.01090788 0.1588039 0.009130954 0.1418769 0.01434499 0.1410779 0.02040892 0.1588039 0.009130954 0.159368 0.005370974 0.1418769 0.01434499 0.158255 0.01559793 0.1410779 0.02040892 0.140325 0.02907699 0.158255 0.01559793 0.1588039 0.009130954 0.1410779 0.02040892 0.157738 0.02475088 0.140325 0.02907699 0.139638 0.04024291 0.157738 0.02475088 0.158255 0.01559793 0.140325 0.02907699 0.157267 0.03648293 0.139638 0.04024291 0.139039 0.05370599 0.157267 0.03648293 0.157738 0.02475088 0.139638 0.04024291 0.156856 0.05058896 0.139039 0.05370599 0.13855 0.06916499 0.156856 0.05058896 0.157267 0.03648293 0.139039 0.05370599 0.156521 0.06676 0.13855 0.06916499 0.138187 0.08622395 0.156521 0.06676 0.156856 0.05058896 0.13855 0.06916499 0.1562719 0.08458596 0.138187 0.08622395 0.1379629 0.104402 0.1562719 0.08458596 0.156521 0.06676 0.138187 0.08622395 0.156118 0.103573 0.1562719 0.08458596 0.1379629 0.104402 0.168288 0.05768996 0.153497 0.02645099 0.1619679 0.02348995 0.168288 0.05768996 0.162666 0.06001991 0.153497 0.02645099 0.167047 0.02209496 0.1619679 0.02348995 0.161526 0.01554197 0.174093 0.05585998 0.1619679 0.02348995 0.167047 0.02209496 0.174093 0.05585998 0.168288 0.05768996 0.1619679 0.02348995 0.177873 0.01200091 0.161526 0.01554197 0.161023 0.009521961 0.178089 0.01998496 0.167047 0.02209496 0.161526 0.01554197 0.177873 0.01200091 0.178089 0.01998496 0.161526 0.01554197 0.177633 0.005999982 0.161023 0.009521961 0.160489 0.005699992 0.177633 0.005999982 0.177873 0.01200091 0.161023 0.009521961 0.1773779 0.002233982 0.160489 0.005699992 0.159934 0.004264891 0.1773779 0.002233982 0.177633 0.005999982 0.160489 0.005699992 0.1771129 8.93e-4 0.159934 0.004264891 0.159368 0.005370974 0.1771129 8.93e-4 0.1773779 0.002233982 0.159934 0.004264891 0.176843 0.002137959 0.159368 0.005370974 0.1588039 0.009130954 0.176843 0.002137959 0.1771129 8.93e-4 0.159368 0.005370974 0.176574 0.006081998 0.1588039 0.009130954 0.158255 0.01559793 0.176574 0.006081998 0.176843 0.002137959 0.1588039 0.009130954 0.176313 0.01278096 0.158255 0.01559793 0.157738 0.02475088 0.176313 0.01278096 0.176574 0.006081998 0.158255 0.01559793 0.1760669 0.02221399 0.157738 0.02475088 0.157267 0.03648293 0.1760669 0.02221399 0.176313 0.01278096 0.157738 0.02475088 0.175842 0.03427499 0.157267 0.03648293 0.156856 0.05058896 0.175842 0.03427499 0.1760669 0.02221399 0.157267 0.03648293 0.175647 0.048756 0.156856 0.05058896 0.156521 0.06676 0.175647 0.048756 0.175842 0.03427499 0.156856 0.05058896 0.175487 0.06534397 0.156521 0.06676 0.1562719 0.08458596 0.175487 0.06534397 0.175647 0.048756 0.156521 0.06676 0.175368 0.08362197 0.1562719 0.08458596 0.156118 0.103573 0.175368 0.08362197 0.175487 0.06534397 0.1562719 0.08458596 0.1752949 0.103084 0.175368 0.08362197 0.156118 0.103573 0.180036 0.054542 0.167047 0.02209496 0.178089 0.01998496 0.180036 0.054542 0.174093 0.05585998 0.167047 0.02209496 0.181048 0.01962596 0.178089 0.01998496 0.177873 0.01200091 0.180036 0.054542 0.178089 0.01998496 0.181048 0.01962596 0.194525 0.01104897 0.177873 0.01200091 0.177633 0.005999982 0.194487 0.01905995 0.181048 0.01962596 0.177873 0.01200091 0.194525 0.01104897 0.194487 0.01905995 0.177873 0.01200091 0.1945649 0.00505799 0.177633 0.005999982 0.1773779 0.002233982 0.1945649 0.00505799 0.194525 0.01104897 0.177633 0.005999982 0.194608 0.001310884 0.1773779 0.002233982 0.1771129 8.93e-4 0.194608 0.001310884 0.1945649 0.00505799 0.1773779 0.002233982 0.194652 0 0.1771129 8.93e-4 0.176843 0.002137959 0.194652 0 0.194608 0.001310884 0.1771129 8.93e-4 0.194697 0.001284897 0.176843 0.002137959 0.176574 0.006081998 0.194697 0.001284897 0.194652 0 0.176843 0.002137959 0.194742 0.005279958 0.176574 0.006081998 0.176313 0.01278096 0.194742 0.005279958 0.194697 0.001284897 0.176574 0.006081998 0.194786 0.01204097 0.176313 0.01278096 0.1760669 0.02221399 0.194786 0.01204097 0.194742 0.005279958 0.176313 0.01278096 0.194827 0.02154994 0.1760669 0.02221399 0.175842 0.03427499 0.194827 0.02154994 0.194786 0.01204097 0.1760669 0.02221399 0.194865 0.03369891 0.175842 0.03427499 0.175647 0.048756 0.194865 0.03369891 0.194827 0.02154994 0.175842 0.03427499 0.1948969 0.04827892 0.175647 0.048756 0.175487 0.06534397 0.1948969 0.04827892 0.194865 0.03369891 0.175647 0.048756 0.1949239 0.06497496 0.175487 0.06534397 0.175368 0.08362197 0.1949239 0.06497496 0.1948969 0.04827892 0.175487 0.06534397 0.194944 0.08337098 0.175368 0.08362197 0.1752949 0.103084 0.194944 0.08337098 0.1949239 0.06497496 0.175368 0.08362197 0.194956 0.102957 0.194944 0.08337098 0.1752949 0.103084 0.186071 0.05374795 0.181048 0.01962596 0.194487 0.01905995 0.186071 0.05374795 0.180036 0.054542 0.181048 0.01962596 0.195261 0.01907998 0.194487 0.01905995 0.194525 0.01104897 0.192152 0.05348193 0.194487 0.01905995 0.195261 0.01907998 0.192152 0.05348193 0.186071 0.05374795 0.194487 0.01905995 0.211454 0.006595969 0.194525 0.01104897 0.1945649 0.00505799 0.211136 0.01252198 0.195261 0.01907998 0.194525 0.01104897 0.211454 0.006595969 0.211136 0.01252198 0.194525 0.01104897 0.21179 0.002892971 0.1945649 0.00505799 0.194608 0.001310884 0.21179 0.002892971 0.211454 0.006595969 0.1945649 0.00505799 0.21214 0.001599967 0.194608 0.001310884 0.194652 0 0.21214 0.001599967 0.21179 0.002892971 0.194608 0.001310884 0.2124969 0.00287497 0.194652 0 0.194697 0.001284897 0.2124969 0.00287497 0.21214 0.001599967 0.194652 0 0.212851 0.006826937 0.194697 0.001284897 0.194742 0.005279958 0.212851 0.006826937 0.2124969 0.00287497 0.194697 0.001284897 0.213196 0.013511 0.194742 0.005279958 0.194786 0.01204097 0.213196 0.013511 0.212851 0.006826937 0.194742 0.005279958 0.21352 0.02290499 0.194786 0.01204097 0.194827 0.02154994 0.21352 0.02290499 0.213196 0.013511 0.194786 0.01204097 0.213816 0.03490191 0.194827 0.02154994 0.194865 0.03369891 0.213816 0.03490191 0.21352 0.02290499 0.194827 0.02154994 0.214074 0.04929399 0.194865 0.03369891 0.1948969 0.04827892 0.214074 0.04929399 0.213816 0.03490191 0.194865 0.03369891 0.214284 0.06576997 0.1948969 0.04827892 0.1949239 0.06497496 0.214284 0.06576997 0.214074 0.04929399 0.1948969 0.04827892 0.21444 0.08391696 0.1949239 0.06497496 0.194944 0.08337098 0.21444 0.08391696 0.214284 0.06576997 0.1949239 0.06497496 0.214536 0.103235 0.194944 0.08337098 0.194956 0.102957 0.214536 0.103235 0.21444 0.08391696 0.194944 0.08337098 0.210831 0.02043795 0.20943 0.02047199 0.195261 0.01907998 0.198234 0.05374795 0.195261 0.01907998 0.20943 0.02047199 0.211136 0.01252198 0.210831 0.02043795 0.195261 0.01907998 0.198234 0.05374795 0.192152 0.05348193 0.195261 0.01907998 0.224555 0.02307695 0.20943 0.02047199 0.210831 0.02043795 0.204269 0.054542 0.20943 0.02047199 0.224555 0.02307695 0.204269 0.054542 0.198234 0.05374795 0.20943 0.02047199 0.224334 0.02117788 0.210831 0.02043795 0.211136 0.01252198 0.224555 0.02307695 0.210831 0.02043795 0.224334 0.02117788 0.227531 0.01453298 0.211136 0.01252198 0.211454 0.006595969 0.2269909 0.021555 0.211136 0.01252198 0.227531 0.01453298 0.224334 0.02117788 0.211136 0.01252198 0.2269909 0.021555 0.228099 0.009412944 0.211454 0.006595969 0.21179 0.002892971 0.227531 0.01453298 0.211454 0.006595969 0.228099 0.009412944 0.228698 0.006415963 0.21179 0.002892971 0.21214 0.001599967 0.228099 0.009412944 0.21179 0.002892971 0.228698 0.006415963 0.229317 0.005703985 0.21214 0.001599967 0.2124969 0.00287497 0.228698 0.006415963 0.21214 0.001599967 0.229317 0.005703985 0.229943 0.007408976 0.2124969 0.00287497 0.212851 0.006826937 0.229317 0.005703985 0.2124969 0.00287497 0.229943 0.007408976 0.2305639 0.01161897 0.212851 0.006826937 0.213196 0.013511 0.229943 0.007408976 0.212851 0.006826937 0.2305639 0.01161897 0.231164 0.018368 0.213196 0.013511 0.21352 0.02290499 0.2305639 0.01161897 0.213196 0.013511 0.231164 0.018368 0.231728 0.027619 0.21352 0.02290499 0.213816 0.03490191 0.231164 0.018368 0.21352 0.02290499 0.231728 0.027619 0.23224 0.039258 0.213816 0.03490191 0.214074 0.04929399 0.231728 0.027619 0.213816 0.03490191 0.23224 0.039258 0.232684 0.05308389 0.214074 0.04929399 0.214284 0.06576997 0.23224 0.039258 0.214074 0.04929399 0.232684 0.05308389 0.2330459 0.06880396 0.214284 0.06576997 0.21444 0.08391696 0.232684 0.05308389 0.214284 0.06576997 0.2330459 0.06880396 0.233314 0.08603596 0.21444 0.08391696 0.214536 0.103235 0.2330459 0.06880396 0.21444 0.08391696 0.233314 0.08603596 0.233314 0.08603596 0.214536 0.103235 0.233479 0.104324 0.31031 0.117727 0.311259 0.118409 0.311198 0.12076 0.310386 0.119538 0.31031 0.117727 0.311198 0.12076 0.310432 0.121351 0.310386 0.119538 0.311198 0.12076 0.310205 0.115929 0.311358 0.116151 0.311259 0.118409 0.31031 0.117727 0.310205 0.115929 0.311259 0.118409 0.309895 0.112253 0.311496 0.11403 0.311358 0.116151 0.310069 0.114129 0.309895 0.112253 0.311358 0.116151 0.310205 0.115929 0.310069 0.114129 0.311358 0.116151 0.309385 0.108048 0.311668 0.1120859 0.311496 0.11403 0.309895 0.112253 0.309385 0.108048 0.311496 0.11403 0.308633 0.103446 0.311872 0.110359 0.311668 0.1120859 0.309385 0.108048 0.308633 0.103446 0.311668 0.1120859 0.30725 0.09708696 0.312103 0.108884 0.311872 0.110359 0.30753 0.09823501 0.30725 0.09708696 0.311872 0.110359 0.308633 0.103446 0.30753 0.09823501 0.311872 0.110359 0.307692 0.09417396 0.312358 0.107691 0.312103 0.108884 0.30725 0.09708696 0.307692 0.09417396 0.312103 0.108884 0.308212 0.09189796 0.312631 0.106807 0.312358 0.107691 0.307692 0.09417396 0.308212 0.09189796 0.312358 0.107691 0.308769 0.09029096 0.312917 0.10625 0.312631 0.106807 0.308212 0.09189796 0.308769 0.09029096 0.312631 0.106807 0.30935 0.08939695 0.313211 0.106035 0.312917 0.10625 0.308769 0.09029096 0.30935 0.08939695 0.312917 0.10625 0.309943 0.08924597 0.313506 0.106168 0.313211 0.106035 0.30935 0.08939695 0.309943 0.08924597 0.313211 0.106035 0.310536 0.08985298 0.313796 0.106649 0.313506 0.106168 0.309943 0.08924597 0.310536 0.08985298 0.313506 0.106168 0.311113 0.09121495 0.314076 0.107471 0.313796 0.106649 0.310536 0.08985298 0.311113 0.09121495 0.313796 0.106649 0.311663 0.09331095 0.314339 0.108619 0.314076 0.107471 0.311113 0.09121495 0.311663 0.09331095 0.314076 0.107471 0.312171 0.09610396 0.31458 0.110071 0.314339 0.108619 0.311663 0.09331095 0.312171 0.09610396 0.314339 0.108619 0.312626 0.09953695 0.314794 0.111798 0.31458 0.110071 0.312171 0.09610396 0.312626 0.09953695 0.31458 0.110071 0.313015 0.103534 0.314976 0.113765 0.314794 0.111798 0.312626 0.09953695 0.313015 0.103534 0.314794 0.111798 0.313329 0.108005 0.315121 0.115931 0.314976 0.113765 0.313015 0.103534 0.313329 0.108005 0.314976 0.113765 0.31356 0.112844 0.315228 0.118252 0.315121 0.115931 0.313329 0.108005 0.31356 0.112844 0.315121 0.115931 0.3137 0.117936 0.315293 0.120678 0.315228 0.118252 0.31356 0.112844 0.3137 0.117936 0.315228 0.118252 0.309346 0.107983 0.3137 0.117936 0.31356 0.112844 0.309346 0.107983 0.309542 0.115474 0.3137 0.117936 0.309025 0.100865 0.31356 0.112844 0.313329 0.108005 0.309025 0.100865 0.309346 0.107983 0.31356 0.112844 0.308589 0.09429198 0.313329 0.108005 0.313015 0.103534 0.308589 0.09429198 0.309025 0.100865 0.313329 0.108005 0.308048 0.08841496 0.313015 0.103534 0.312626 0.09953695 0.308048 0.08841496 0.308589 0.09429198 0.313015 0.103534 0.307418 0.08336496 0.312626 0.09953695 0.312171 0.09610396 0.307418 0.08336496 0.308048 0.08841496 0.312626 0.09953695 0.306714 0.07924699 0.312171 0.09610396 0.311663 0.09331095 0.306714 0.07924699 0.307418 0.08336496 0.312171 0.09610396 0.305954 0.076137 0.311663 0.09331095 0.311113 0.09121495 0.305954 0.076137 0.306714 0.07924699 0.311663 0.09331095 0.305157 0.07408601 0.311113 0.09121495 0.310536 0.08985298 0.305157 0.07408601 0.305954 0.076137 0.311113 0.09121495 0.30434 0.07311499 0.310536 0.08985298 0.309943 0.08924597 0.30434 0.07311499 0.305157 0.07408601 0.310536 0.08985298 0.303522 0.07322496 0.309943 0.08924597 0.30935 0.08939695 0.303522 0.07322496 0.30434 0.07311499 0.309943 0.08924597 0.302721 0.07438695 0.30935 0.08939695 0.308769 0.09029096 0.302721 0.07438695 0.303522 0.07322496 0.30935 0.08939695 0.301952 0.07655799 0.308769 0.09029096 0.308212 0.09189796 0.301952 0.07655799 0.302721 0.07438695 0.308769 0.09029096 0.301269 0.079683 0.308212 0.09189796 0.307692 0.09417396 0.301269 0.079683 0.301952 0.07655799 0.308212 0.09189796 0.305968 0.09240198 0.307692 0.09417396 0.30725 0.09708696 0.303754 0.085783 0.307692 0.09417396 0.305968 0.09240198 0.303754 0.085783 0.301269 0.079683 0.307692 0.09417396 0.300578 0.100754 0.30725 0.09708696 0.30753 0.09823501 0.298665 0.09346997 0.305968 0.09240198 0.30725 0.09708696 0.300578 0.100754 0.298665 0.09346997 0.30725 0.09708696 0.300578 0.100754 0.30753 0.09823501 0.308633 0.103446 0.301954 0.108169 0.308633 0.103446 0.309385 0.108048 0.301954 0.108169 0.300578 0.100754 0.308633 0.103446 0.301954 0.108169 0.309385 0.108048 0.309895 0.112253 0.301954 0.108169 0.309895 0.112253 0.310069 0.114129 0.30278 0.115655 0.310069 0.114129 0.310205 0.115929 0.30278 0.115655 0.301954 0.108169 0.310069 0.114129 0.30278 0.115655 0.310205 0.115929 0.31031 0.117727 0.30278 0.115655 0.31031 0.117727 0.310386 0.119538 0.30278 0.115655 0.310386 0.119538 0.310432 0.121351 0.298665 0.09346997 0.303754 0.085783 0.305968 0.09240198 0.302545 0.1037639 0.309542 0.115474 0.309346 0.107983 0.302545 0.1037639 0.302772 0.113342 0.309542 0.115474 0.302172 0.09465098 0.309346 0.107983 0.309025 0.100865 0.302172 0.09465098 0.302545 0.1037639 0.309346 0.107983 0.301665 0.08621299 0.309025 0.100865 0.308589 0.09429198 0.301665 0.08621299 0.302172 0.09465098 0.309025 0.100865 0.301037 0.07863897 0.308589 0.09429198 0.308048 0.08841496 0.301037 0.07863897 0.301665 0.08621299 0.308589 0.09429198 0.300305 0.07208496 0.308048 0.08841496 0.307418 0.08336496 0.300305 0.07208496 0.301037 0.07863897 0.308048 0.08841496 0.299487 0.066679 0.307418 0.08336496 0.306714 0.07924699 0.299487 0.066679 0.300305 0.07208496 0.307418 0.08336496 0.298603 0.06251198 0.306714 0.07924699 0.305954 0.076137 0.298603 0.06251198 0.299487 0.066679 0.306714 0.07924699 0.297674 0.05964189 0.305954 0.076137 0.305157 0.07408601 0.297674 0.05964189 0.298603 0.06251198 0.305954 0.076137 0.29672 0.05809491 0.305157 0.07408601 0.30434 0.07311499 0.29672 0.05809491 0.297674 0.05964189 0.305157 0.07408601 0.295762 0.05786699 0.30434 0.07311499 0.303522 0.07322496 0.295762 0.05786699 0.29672 0.05809491 0.30434 0.07311499 0.294818 0.05892693 0.303522 0.07322496 0.302721 0.07438695 0.294818 0.05892693 0.295762 0.05786699 0.303522 0.07322496 0.293907 0.06121999 0.302721 0.07438695 0.301952 0.07655799 0.293907 0.06121999 0.294818 0.05892693 0.302721 0.07438695 0.30052 0.07803601 0.301952 0.07655799 0.301269 0.079683 0.296701 0.070616 0.301952 0.07655799 0.30052 0.07803601 0.293083 0.06470096 0.293907 0.06121999 0.301952 0.07655799 0.296701 0.070616 0.293083 0.06470096 0.301952 0.07655799 0.296225 0.08634698 0.301269 0.079683 0.303754 0.085783 0.293258 0.07939696 0.30052 0.07803601 0.301269 0.079683 0.296225 0.08634698 0.293258 0.07939696 0.301269 0.079683 0.298665 0.09346997 0.296225 0.08634698 0.303754 0.085783 0.293258 0.07939696 0.296701 0.070616 0.30052 0.07803601 0.29316 0.09960198 0.302772 0.113342 0.302545 0.1037639 0.29316 0.09960198 0.29341 0.111233 0.302772 0.113342 0.292752 0.08854299 0.302545 0.1037639 0.302172 0.09465098 0.292752 0.08854299 0.29316 0.09960198 0.302545 0.1037639 0.292197 0.07831299 0.302172 0.09465098 0.301665 0.08621299 0.292197 0.07831299 0.292752 0.08854299 0.302172 0.09465098 0.29151 0.06913799 0.301665 0.08621299 0.301037 0.07863897 0.29151 0.06913799 0.292197 0.07831299 0.301665 0.08621299 0.290711 0.06120693 0.301037 0.07863897 0.300305 0.07208496 0.290711 0.06120693 0.29151 0.06913799 0.301037 0.07863897 0.289819 0.05466598 0.300305 0.07208496 0.299487 0.066679 0.289819 0.05466598 0.290711 0.06120693 0.300305 0.07208496 0.288857 0.04961997 0.299487 0.066679 0.298603 0.06251198 0.288857 0.04961997 0.289819 0.05466598 0.299487 0.066679 0.287847 0.04613095 0.298603 0.06251198 0.297674 0.05964189 0.287847 0.04613095 0.288857 0.04961997 0.298603 0.06251198 0.286812 0.04421997 0.297674 0.05964189 0.29672 0.05809491 0.286812 0.04421997 0.287847 0.04613095 0.297674 0.05964189 0.285774 0.0438739 0.29672 0.05809491 0.295762 0.05786699 0.285774 0.0438739 0.286812 0.04421997 0.29672 0.05809491 0.284752 0.04505091 0.295762 0.05786699 0.294818 0.05892693 0.284752 0.04505091 0.285774 0.0438739 0.295762 0.05786699 0.283766 0.04767799 0.294818 0.05892693 0.293907 0.06121999 0.283766 0.04767799 0.284752 0.04505091 0.294818 0.05892693 0.292308 0.063542 0.293907 0.06121999 0.293083 0.06470096 0.286414 0.05569398 0.293907 0.06121999 0.292308 0.063542 0.283076 0.05186992 0.283766 0.04767799 0.293907 0.06121999 0.286414 0.05569398 0.283076 0.05186992 0.293907 0.06121999 0.289773 0.07265299 0.293083 0.06470096 0.296701 0.070616 0.285793 0.06616997 0.292308 0.063542 0.293083 0.06470096 0.289773 0.07265299 0.285793 0.06616997 0.293083 0.06470096 0.293258 0.07939696 0.289773 0.07265299 0.296701 0.070616 0.285793 0.06616997 0.286414 0.05569398 0.292308 0.063542 0.281544 0.108161 0.29341 0.111233 0.29316 0.09960198 0.281247 0.09360599 0.29316 0.09960198 0.292752 0.08854299 0.281247 0.09360599 0.281544 0.108161 0.29316 0.09960198 0.280763 0.07990497 0.292752 0.08854299 0.292197 0.07831299 0.280763 0.07990497 0.281247 0.09360599 0.292752 0.08854299 0.280109 0.06743395 0.292197 0.07831299 0.29151 0.06913799 0.280109 0.06743395 0.280763 0.07990497 0.292197 0.07831299 0.279307 0.05650889 0.29151 0.06913799 0.290711 0.06120693 0.279307 0.05650889 0.280109 0.06743395 0.29151 0.06913799 0.278382 0.04738193 0.290711 0.06120693 0.289819 0.05466598 0.278382 0.04738193 0.279307 0.05650889 0.290711 0.06120693 0.277363 0.04022896 0.289819 0.05466598 0.288857 0.04961997 0.277363 0.04022896 0.278382 0.04738193 0.289819 0.05466598 0.276279 0.03515791 0.288857 0.04961997 0.287847 0.04613095 0.276279 0.03515791 0.277363 0.04022896 0.288857 0.04961997 0.275158 0.03221189 0.287847 0.04613095 0.286812 0.04421997 0.275158 0.03221189 0.276279 0.03515791 0.287847 0.04613095 0.274029 0.03137499 0.286812 0.04421997 0.285774 0.0438739 0.274029 0.03137499 0.275158 0.03221189 0.286812 0.04421997 0.272918 0.032579 0.285774 0.0438739 0.284752 0.04505091 0.272918 0.032579 0.274029 0.03137499 0.285774 0.0438739 0.271847 0.03571891 0.284752 0.04505091 0.283766 0.04767799 0.271847 0.03571891 0.272918 0.032579 0.284752 0.04505091 0.277894 0.04662793 0.283766 0.04767799 0.283076 0.05186992 0.271847 0.03571891 0.283766 0.04767799 0.277894 0.04662793 0.281345 0.05999696 0.283076 0.05186992 0.286414 0.05569398 0.276445 0.05415689 0.277894 0.04662793 0.283076 0.05186992 0.281345 0.05999696 0.276445 0.05415689 0.283076 0.05186992 0.285793 0.06616997 0.281345 0.05999696 0.286414 0.05569398 0.27101 0.04072993 0.271847 0.03571891 0.277894 0.04662793 0.271115 0.04868096 0.27101 0.04072993 0.277894 0.04662793 0.276445 0.05415689 0.271115 0.04868096 0.277894 0.04662793 0.267165 0.091991 0.281544 0.108161 0.281247 0.09360599 0.267165 0.091991 0.267411 0.107366 0.281544 0.108161 0.266764 0.07742697 0.281247 0.09360599 0.280763 0.07990497 0.266764 0.07742697 0.267165 0.091991 0.281247 0.09360599 0.26622 0.06403195 0.280763 0.07990497 0.280109 0.06743395 0.26622 0.06403195 0.266764 0.07742697 0.280763 0.07990497 0.26555 0.05211198 0.280109 0.06743395 0.279307 0.05650889 0.26555 0.05211198 0.26622 0.06403195 0.280109 0.06743395 0.264774 0.04191297 0.279307 0.05650889 0.278382 0.04738193 0.264774 0.04191297 0.26555 0.05211198 0.279307 0.05650889 0.263912 0.03361588 0.278382 0.04738193 0.277363 0.04022896 0.263912 0.03361588 0.264774 0.04191297 0.278382 0.04738193 0.262988 0.0273379 0.277363 0.04022896 0.276279 0.03515791 0.262988 0.0273379 0.263912 0.03361588 0.277363 0.04022896 0.262025 0.02313399 0.276279 0.03515791 0.275158 0.03221189 0.262025 0.02313399 0.262988 0.0273379 0.276279 0.03515791 0.261044 0.021007 0.275158 0.03221189 0.274029 0.03137499 0.261044 0.021007 0.262025 0.02313399 0.275158 0.03221189 0.260066 0.02091199 0.274029 0.03137499 0.272918 0.032579 0.260066 0.02091199 0.261044 0.021007 0.274029 0.03137499 0.259111 0.02276599 0.272918 0.032579 0.271847 0.03571891 0.259111 0.02276599 0.260066 0.02091199 0.272918 0.032579 0.258195 0.02645593 0.271847 0.03571891 0.27101 0.04072993 0.258195 0.02645593 0.259111 0.02276599 0.271847 0.03571891 0.258195 0.02645593 0.27101 0.04072993 0.266461 0.0373879 0.26538 0.04360193 0.266461 0.0373879 0.27101 0.04072993 0.271115 0.04868096 0.26538 0.04360193 0.27101 0.04072993 0.257315 0.03178691 0.258195 0.02645593 0.266461 0.0373879 0.259285 0.03895998 0.257315 0.03178691 0.266461 0.0373879 0.26538 0.04360193 0.259285 0.03895998 0.266461 0.0373879 0.251258 0.105716 0.267411 0.107366 0.267165 0.091991 0.251042 0.08875596 0.267165 0.091991 0.266764 0.07742697 0.251042 0.08875596 0.251258 0.105716 0.267165 0.091991 0.250692 0.07273095 0.266764 0.07742697 0.26622 0.06403195 0.250692 0.07273095 0.251042 0.08875596 0.266764 0.07742697 0.250217 0.05804896 0.26622 0.06403195 0.26555 0.05211198 0.250217 0.05804896 0.250692 0.07273095 0.26622 0.06403195 0.249634 0.04505497 0.26555 0.05211198 0.264774 0.04191297 0.249634 0.04505497 0.250217 0.05804896 0.26555 0.05211198 0.248959 0.03402096 0.264774 0.04191297 0.263912 0.03361588 0.248959 0.03402096 0.249634 0.04505497 0.264774 0.04191297 0.248214 0.02513897 0.263912 0.03361588 0.262988 0.0273379 0.248214 0.02513897 0.248959 0.03402096 0.263912 0.03361588 0.247417 0.01852697 0.262988 0.0273379 0.262025 0.02313399 0.247417 0.01852697 0.248214 0.02513897 0.262988 0.0273379 0.24659 0.01423192 0.262025 0.02313399 0.261044 0.021007 0.24659 0.01423192 0.247417 0.01852697 0.262025 0.02313399 0.245751 0.01223999 0.261044 0.021007 0.260066 0.02091199 0.245751 0.01223999 0.24659 0.01423192 0.261044 0.021007 0.244918 0.0124849 0.260066 0.02091199 0.259111 0.02276599 0.244918 0.0124849 0.245751 0.01223999 0.260066 0.02091199 0.244108 0.01486092 0.259111 0.02276599 0.258195 0.02645593 0.244108 0.01486092 0.244918 0.0124849 0.259111 0.02276599 0.243336 0.01922988 0.258195 0.02645593 0.257315 0.03178691 0.243336 0.01922988 0.244108 0.01486092 0.258195 0.02645593 0.243336 0.01922988 0.257315 0.03178691 0.253145 0.02967 0.252854 0.03477489 0.253145 0.02967 0.257315 0.03178691 0.259285 0.03895998 0.252854 0.03477489 0.257315 0.03178691 0.2426069 0.02539098 0.243336 0.01922988 0.253145 0.02967 0.246128 0.031075 0.2426069 0.02539098 0.253145 0.02967 0.252854 0.03477489 0.246128 0.031075 0.253145 0.02967 0.233479 0.104324 0.251258 0.105716 0.251042 0.08875596 0.233314 0.08603596 0.251042 0.08875596 0.250692 0.07273095 0.233314 0.08603596 0.233479 0.104324 0.251042 0.08875596 0.2330459 0.06880396 0.250692 0.07273095 0.250217 0.05804896 0.2330459 0.06880396 0.233314 0.08603596 0.250692 0.07273095 0.232684 0.05308389 0.250217 0.05804896 0.249634 0.04505497 0.232684 0.05308389 0.2330459 0.06880396 0.250217 0.05804896 0.23224 0.039258 0.249634 0.04505497 0.248959 0.03402096 0.23224 0.039258 0.232684 0.05308389 0.249634 0.04505497 0.231728 0.027619 0.248959 0.03402096 0.248214 0.02513897 0.231728 0.027619 0.23224 0.039258 0.248959 0.03402096 0.231164 0.018368 0.248214 0.02513897 0.247417 0.01852697 0.231164 0.018368 0.231728 0.027619 0.248214 0.02513897 0.2305639 0.01161897 0.247417 0.01852697 0.24659 0.01423192 0.2305639 0.01161897 0.231164 0.018368 0.247417 0.01852697 0.229943 0.007408976 0.24659 0.01423192 0.245751 0.01223999 0.229943 0.007408976 0.2305639 0.01161897 0.24659 0.01423192 0.229317 0.005703985 0.245751 0.01223999 0.244918 0.0124849 0.229317 0.005703985 0.229943 0.007408976 0.245751 0.01223999 0.228698 0.006415963 0.244918 0.0124849 0.244108 0.01486092 0.228698 0.006415963 0.229317 0.005703985 0.244918 0.0124849 0.228099 0.009412944 0.244108 0.01486092 0.243336 0.01922988 0.228099 0.009412944 0.228698 0.006415963 0.244108 0.01486092 0.227531 0.01453298 0.243336 0.01922988 0.2426069 0.02539098 0.227531 0.01453298 0.228099 0.009412944 0.243336 0.01922988 0.227531 0.01453298 0.2426069 0.02539098 0.239049 0.024266 0.239142 0.0278809 0.239049 0.024266 0.2426069 0.02539098 0.246128 0.031075 0.239142 0.0278809 0.2426069 0.02539098 0.2269909 0.021555 0.227531 0.01453298 0.239049 0.024266 0.231936 0.02520895 0.2269909 0.021555 0.239049 0.024266 0.239142 0.0278809 0.231936 0.02520895 0.239049 0.024266 0.224555 0.02307695 0.224334 0.02117788 0.2269909 0.021555 0.231936 0.02520895 0.224555 0.02307695 0.2269909 0.021555 0.216017 0.05768996 0.224555 0.02307695 0.231936 0.02520895 0.210212 0.05585998 0.204269 0.054542 0.224555 0.02307695 0.216017 0.05768996 0.210212 0.05585998 0.224555 0.02307695 0.221638 0.06001991 0.231936 0.02520895 0.239142 0.0278809 0.221638 0.06001991 0.216017 0.05768996 0.231936 0.02520895 0.227032 0.06282895 0.239142 0.0278809 0.246128 0.031075 0.227032 0.06282895 0.221638 0.06001991 0.239142 0.0278809 0.227032 0.06282895 0.246128 0.031075 0.252854 0.03477489 0.232159 0.06609797 0.252854 0.03477489 0.259285 0.03895998 0.232159 0.06609797 0.227032 0.06282895 0.252854 0.03477489 0.23698 0.06979995 0.259285 0.03895998 0.26538 0.04360193 0.23698 0.06979995 0.232159 0.06609797 0.259285 0.03895998 0.2414579 0.07390797 0.26538 0.04360193 0.271115 0.04868096 0.2414579 0.07390797 0.23698 0.06979995 0.26538 0.04360193 0.245561 0.07839095 0.271115 0.04868096 0.276445 0.05415689 0.245561 0.07839095 0.2414579 0.07390797 0.271115 0.04868096 0.245561 0.07839095 0.276445 0.05415689 0.281345 0.05999696 0.249256 0.08321499 0.281345 0.05999696 0.285793 0.06616997 0.249256 0.08321499 0.245561 0.07839095 0.281345 0.05999696 0.252516 0.08834099 0.285793 0.06616997 0.289773 0.07265299 0.252516 0.08834099 0.249256 0.08321499 0.285793 0.06616997 0.255317 0.09373098 0.289773 0.07265299 0.293258 0.07939696 0.255317 0.09373098 0.252516 0.08834099 0.289773 0.07265299 0.257637 0.09934395 0.293258 0.07939696 0.296225 0.08634698 0.257637 0.09934395 0.255317 0.09373098 0.293258 0.07939696 0.257637 0.09934395 0.296225 0.08634698 0.298665 0.09346997 0.259459 0.105136 0.298665 0.09346997 0.300578 0.100754 0.259459 0.105136 0.257637 0.09934395 0.298665 0.09346997 0.260771 0.111066 0.300578 0.100754 0.301954 0.108169 0.260771 0.111066 0.259459 0.105136 0.300578 0.100754 0.261562 0.117087 0.301954 0.108169 0.30278 0.115655 0.261562 0.117087 0.260771 0.111066 0.301954 0.108169 0.261562 0.117087 0.30278 0.115655 0.303055 0.123156 0.261826 0.123156 0.303055 0.123156 0.30278 0.130657 0.261562 0.117087 0.303055 0.123156 0.261826 0.123156 0.261562 0.129225 0.30278 0.130657 0.301954 0.138144 0.261562 0.129225 0.261826 0.123156 0.30278 0.130657 0.260771 0.135246 0.301954 0.138144 0.300578 0.1455579 0.260771 0.135246 0.261562 0.129225 0.301954 0.138144 0.286745 0.145876 0.300578 0.1455579 0.298665 0.152842 0.286745 0.145876 0.260771 0.135246 0.300578 0.1455579 0.284816 0.153282 0.298665 0.152842 0.296224 0.159965 0.284816 0.153282 0.286745 0.145876 0.298665 0.152842 0.282347 0.160542 0.296224 0.159965 0.293258 0.1669149 0.282347 0.160542 0.284816 0.153282 0.296224 0.159965 0.281442 0.162752 0.293258 0.1669149 0.289774 0.173659 0.281442 0.162752 0.282347 0.160542 0.293258 0.1669149 0.278534 0.168118 0.289774 0.173659 0.285793 0.180142 0.280636 0.164485 0.281442 0.162752 0.289774 0.173659 0.279912 0.165877 0.280636 0.164485 0.289774 0.173659 0.279231 0.167052 0.279912 0.165877 0.289774 0.173659 0.278534 0.168118 0.279231 0.167052 0.289774 0.173659 0.256701 0.162756 0.285793 0.180142 0.281345 0.186315 0.277786 0.169082 0.278534 0.168118 0.285793 0.180142 0.277127 0.169714 0.277786 0.169082 0.285793 0.180142 0.276676 0.169897 0.277127 0.169714 0.285793 0.180142 0.25905 0.160416 0.276676 0.169897 0.285793 0.180142 0.258389 0.1613309 0.25905 0.160416 0.285793 0.180142 0.257697 0.162136 0.258389 0.1613309 0.285793 0.180142 0.257099 0.162642 0.257697 0.162136 0.285793 0.180142 0.256701 0.162756 0.257099 0.162642 0.285793 0.180142 0.249256 0.163097 0.281345 0.186315 0.276445 0.192155 0.256701 0.162756 0.281345 0.186315 0.249256 0.163097 0.245561 0.167921 0.276445 0.192155 0.271116 0.19763 0.245561 0.167921 0.249256 0.163097 0.276445 0.192155 0.2414579 0.172404 0.271116 0.19763 0.265381 0.20271 0.2414579 0.172404 0.245561 0.167921 0.271116 0.19763 0.23698 0.176512 0.265381 0.20271 0.259286 0.207352 0.23698 0.176512 0.2414579 0.172404 0.265381 0.20271 0.232159 0.180214 0.259286 0.207352 0.252855 0.211536 0.232159 0.180214 0.23698 0.176512 0.259286 0.207352 0.232159 0.180214 0.252855 0.211536 0.246128 0.215236 0.227032 0.183483 0.246128 0.215236 0.239143 0.2184309 0.227032 0.183483 0.232159 0.180214 0.246128 0.215236 0.221638 0.1862919 0.239143 0.2184309 0.231936 0.221103 0.221638 0.1862919 0.227032 0.183483 0.239143 0.2184309 0.216017 0.1886219 0.231936 0.221103 0.224556 0.2232339 0.216017 0.1886219 0.221638 0.1862919 0.231936 0.221103 0.210212 0.190452 0.216017 0.1886219 0.224556 0.2232339 0.254487 0.128929 0.261826 0.123156 0.261562 0.129225 0.254487 0.117383 0.261562 0.117087 0.261826 0.123156 0.254487 0.128929 0.254487 0.117383 0.261826 0.123156 0.254487 0.128929 0.261562 0.129225 0.260771 0.135246 0.283843 0.145682 0.259459 0.141176 0.260771 0.135246 0.252369 0.140278 0.260771 0.135246 0.259459 0.141176 0.285281 0.145778 0.260771 0.135246 0.286745 0.145876 0.285281 0.145778 0.283843 0.145682 0.260771 0.135246 0.252369 0.140278 0.254487 0.128929 0.260771 0.135246 0.262971 0.144289 0.257637 0.146969 0.259459 0.141176 0.252369 0.140278 0.259459 0.141176 0.257637 0.146969 0.283843 0.145682 0.281947 0.15282 0.259459 0.141176 0.265547 0.144461 0.259459 0.141176 0.281947 0.15282 0.264246 0.144374 0.259459 0.141176 0.265547 0.144461 0.264246 0.144374 0.262971 0.144289 0.259459 0.141176 0.259523 0.154145 0.255317 0.152581 0.257637 0.146969 0.2482039 0.151046 0.257637 0.146969 0.255317 0.152581 0.261412 0.149269 0.259523 0.154145 0.257637 0.146969 0.262971 0.144289 0.261412 0.149269 0.257637 0.146969 0.2482039 0.151046 0.252369 0.140278 0.257637 0.146969 0.257142 0.159918 0.252516 0.157971 0.255317 0.152581 0.2482039 0.151046 0.255317 0.152581 0.252516 0.157971 0.257571 0.158802 0.257142 0.159918 0.255317 0.152581 0.258118 0.15746 0.257571 0.158802 0.255317 0.152581 0.258793 0.1558589 0.258118 0.15746 0.255317 0.152581 0.259523 0.154145 0.258793 0.1558589 0.255317 0.152581 0.256701 0.162756 0.249256 0.163097 0.252516 0.157971 0.242132 0.160866 0.252516 0.157971 0.249256 0.163097 0.25652 0.162499 0.256701 0.162756 0.252516 0.157971 0.256553 0.161876 0.25652 0.162499 0.252516 0.157971 0.25679 0.160949 0.256553 0.161876 0.252516 0.157971 0.257142 0.159918 0.25679 0.160949 0.252516 0.157971 0.242132 0.160866 0.2482039 0.151046 0.252516 0.157971 0.242132 0.160866 0.249256 0.163097 0.245561 0.167921 0.234356 0.169405 0.245561 0.167921 0.2414579 0.172404 0.234356 0.169405 0.242132 0.160866 0.245561 0.167921 0.225139 0.17637 0.2414579 0.172404 0.23698 0.176512 0.225139 0.17637 0.234356 0.169405 0.2414579 0.172404 0.225139 0.17637 0.23698 0.176512 0.232159 0.180214 0.214793 0.181524 0.232159 0.180214 0.227032 0.183483 0.214793 0.181524 0.225139 0.17637 0.232159 0.180214 0.20367 0.1846899 0.227032 0.183483 0.221638 0.1862919 0.20367 0.1846899 0.214793 0.181524 0.227032 0.183483 0.162666 0.1862919 0.221638 0.1862919 0.216017 0.1886219 0.192152 0.185757 0.221638 0.1862919 0.162666 0.1862919 0.192152 0.185757 0.20367 0.1846899 0.221638 0.1862919 0.168288 0.1886219 0.216017 0.1886219 0.210212 0.190452 0.162666 0.1862919 0.216017 0.1886219 0.168288 0.1886219 0.174093 0.190452 0.210212 0.190452 0.204269 0.19177 0.168288 0.1886219 0.210212 0.190452 0.174093 0.190452 0.180036 0.19177 0.204269 0.19177 0.198234 0.192564 0.174093 0.190452 0.204269 0.19177 0.180036 0.19177 0.186071 0.192564 0.198234 0.192564 0.192152 0.19283 0.180036 0.19177 0.198234 0.192564 0.186071 0.192564 0.192152 0.185757 0.162666 0.1862919 0.157272 0.183483 0.169512 0.181524 0.157272 0.183483 0.152145 0.180214 0.180634 0.1846899 0.192152 0.185757 0.157272 0.183483 0.169512 0.181524 0.180634 0.1846899 0.157272 0.183483 0.169512 0.181524 0.152145 0.180214 0.147325 0.176512 0.159165 0.17637 0.147325 0.176512 0.142846 0.172404 0.159165 0.17637 0.169512 0.181524 0.147325 0.176512 0.149948 0.169405 0.142846 0.172404 0.1387439 0.167921 0.149948 0.169405 0.159165 0.17637 0.142846 0.172404 0.149948 0.169405 0.1387439 0.167921 0.135048 0.163097 0.12742 0.160753 0.131788 0.157971 0.135048 0.163097 0.142172 0.160866 0.135048 0.163097 0.131788 0.157971 0.127667 0.161686 0.12742 0.160753 0.135048 0.163097 0.1277199 0.162344 0.127667 0.161686 0.135048 0.163097 0.127555 0.162633 0.1277199 0.162344 0.135048 0.163097 0.142172 0.160866 0.149948 0.169405 0.135048 0.163097 0.125433 0.155696 0.128988 0.152581 0.131788 0.157971 0.142172 0.160866 0.131788 0.157971 0.128988 0.152581 0.126107 0.157303 0.125433 0.155696 0.131788 0.157971 0.126649 0.158637 0.126107 0.157303 0.131788 0.157971 0.127072 0.15974 0.126649 0.158637 0.131788 0.157971 0.12742 0.160753 0.127072 0.15974 0.131788 0.157971 0.12286 0.14919 0.126668 0.146969 0.128988 0.152581 0.1360999 0.151046 0.128988 0.152581 0.126668 0.146969 0.124711 0.1539919 0.12286 0.14919 0.128988 0.152581 0.125433 0.155696 0.124711 0.1539919 0.128988 0.152581 0.1360999 0.151046 0.142172 0.160866 0.128988 0.152581 0.121328 0.14429 0.124845 0.141176 0.126668 0.146969 0.1360999 0.151046 0.126668 0.146969 0.124845 0.141176 0.12286 0.14919 0.121328 0.14429 0.126668 0.146969 0.131935 0.140278 0.124845 0.141176 0.123534 0.135246 0.120054 0.144374 0.124845 0.141176 0.121328 0.14429 0.120054 0.144374 0.118752 0.144461 0.124845 0.141176 0.131935 0.140278 0.1360999 0.151046 0.124845 0.141176 0.131935 0.140278 0.123534 0.135246 0.122743 0.129225 0.129818 0.128929 0.122743 0.129225 0.122478 0.123156 0.129818 0.128929 0.131935 0.140278 0.122743 0.129225 0.129818 0.117383 0.122478 0.123156 0.122743 0.117087 0.129818 0.117383 0.129818 0.128929 0.122478 0.123156 0.282347 0.145909 0.286745 0.145876 0.284816 0.153282 0.276417 0.145803 0.285281 0.145778 0.286745 0.145876 0.27662 0.145843 0.276417 0.145803 0.286745 0.145876 0.277482 0.145878 0.27662 0.145843 0.286745 0.145876 0.278873 0.145903 0.277482 0.145878 0.286745 0.145876 0.282347 0.145909 0.278873 0.145903 0.286745 0.145876 0.282347 0.145909 0.284816 0.153282 0.282347 0.160542 0.282347 0.145909 0.282347 0.160542 0.281442 0.162752 0.282347 0.145909 0.281442 0.162752 0.280636 0.164485 0.280583 0.145914 0.280636 0.164485 0.279912 0.165877 0.282347 0.145909 0.280636 0.164485 0.280583 0.145914 0.280583 0.145914 0.279912 0.165877 0.279231 0.167052 0.278873 0.145903 0.279231 0.167052 0.278534 0.168118 0.280583 0.145914 0.279231 0.167052 0.278873 0.145903 0.278873 0.145903 0.278534 0.168118 0.277786 0.169082 0.277482 0.145878 0.277786 0.169082 0.277127 0.169714 0.278873 0.145903 0.277786 0.169082 0.277482 0.145878 0.277482 0.145878 0.277127 0.169714 0.276676 0.169897 0.259705 0.15939 0.276441 0.169664 0.276676 0.169897 0.27662 0.145843 0.276676 0.169897 0.276441 0.169664 0.25905 0.160416 0.259705 0.15939 0.276676 0.169897 0.277482 0.145878 0.276676 0.169897 0.27662 0.145843 0.259705 0.15939 0.276423 0.169 0.276441 0.169664 0.276417 0.145803 0.276441 0.169664 0.276423 0.169 0.27662 0.145843 0.276441 0.169664 0.276417 0.145803 0.259705 0.15939 0.276642 0.167905 0.276423 0.169 0.276417 0.145803 0.276423 0.169 0.276642 0.167905 0.260433 0.158109 0.277077 0.166443 0.276642 0.167905 0.276901 0.145765 0.276642 0.167905 0.277077 0.166443 0.259705 0.15939 0.260433 0.158109 0.276642 0.167905 0.276417 0.145803 0.276642 0.167905 0.276901 0.145765 0.261235 0.156523 0.277687 0.164683 0.277077 0.166443 0.276901 0.145765 0.277077 0.166443 0.277687 0.164683 0.260433 0.158109 0.261235 0.156523 0.277077 0.166443 0.261235 0.156523 0.278495 0.162515 0.277687 0.164683 0.277995 0.1457329 0.277687 0.164683 0.278495 0.162515 0.276901 0.145765 0.277687 0.164683 0.277995 0.1457329 0.261998 0.154816 0.279533 0.159815 0.278495 0.162515 0.277995 0.1457329 0.278495 0.162515 0.279533 0.159815 0.261235 0.156523 0.261998 0.154816 0.278495 0.162515 0.283843 0.145682 0.279533 0.159815 0.281947 0.15282 0.263948 0.1496919 0.281947 0.15282 0.279533 0.159815 0.279533 0.145714 0.279533 0.159815 0.283843 0.145682 0.261998 0.154816 0.263948 0.1496919 0.279533 0.159815 0.277995 0.1457329 0.279533 0.159815 0.279533 0.145714 0.263948 0.1496919 0.265547 0.144461 0.281947 0.15282 0.279533 0.145714 0.283843 0.145682 0.285281 0.145778 0.277995 0.1457329 0.279533 0.145714 0.285281 0.145778 0.276901 0.145765 0.277995 0.1457329 0.285281 0.145778 0.276417 0.145803 0.276901 0.145765 0.285281 0.145778 0.261998 0.144484 0.265547 0.144461 0.263948 0.1496919 0.256528 0.144389 0.264246 0.144374 0.265547 0.144461 0.256686 0.144424 0.256528 0.144389 0.265547 0.144461 0.257464 0.144455 0.256686 0.144424 0.265547 0.144461 0.258748 0.144477 0.257464 0.144455 0.265547 0.144461 0.261998 0.144484 0.258748 0.144477 0.265547 0.144461 0.261998 0.144484 0.263948 0.1496919 0.261998 0.154816 0.261998 0.144484 0.261998 0.154816 0.261235 0.156523 0.261998 0.144484 0.261235 0.156523 0.260433 0.158109 0.260341 0.144488 0.260433 0.158109 0.259705 0.15939 0.261998 0.144484 0.260433 0.158109 0.260341 0.144488 0.260341 0.144488 0.259705 0.15939 0.25905 0.160416 0.258748 0.144477 0.25905 0.160416 0.258389 0.1613309 0.260341 0.144488 0.25905 0.160416 0.258748 0.144477 0.258748 0.144477 0.258389 0.1613309 0.257697 0.162136 0.257464 0.144455 0.257697 0.162136 0.257099 0.162642 0.258748 0.144477 0.257697 0.162136 0.257464 0.144455 0.257464 0.144455 0.257099 0.162642 0.256701 0.162756 0.256686 0.144424 0.256701 0.162756 0.25652 0.162499 0.257464 0.144455 0.256701 0.162756 0.256686 0.144424 0.256528 0.144389 0.25652 0.162499 0.256553 0.161876 0.256686 0.144424 0.25652 0.162499 0.256528 0.144389 0.256528 0.144389 0.256553 0.161876 0.25679 0.160949 0.257013 0.1443549 0.25679 0.160949 0.257142 0.159918 0.256528 0.144389 0.25679 0.160949 0.257013 0.1443549 0.257013 0.1443549 0.257142 0.159918 0.257571 0.158802 0.258065 0.1443279 0.257571 0.158802 0.258118 0.15746 0.257013 0.1443549 0.257571 0.158802 0.258065 0.1443279 0.258065 0.1443279 0.258118 0.15746 0.258793 0.1558589 0.258065 0.1443279 0.258793 0.1558589 0.259523 0.154145 0.262971 0.144289 0.259523 0.154145 0.261412 0.149269 0.259523 0.144311 0.259523 0.154145 0.262971 0.144289 0.258065 0.1443279 0.259523 0.154145 0.259523 0.144311 0.259523 0.144311 0.262971 0.144289 0.264246 0.144374 0.258065 0.1443279 0.259523 0.144311 0.264246 0.144374 0.257013 0.1443549 0.258065 0.1443279 0.264246 0.144374 0.256528 0.144389 0.257013 0.1443549 0.264246 0.144374 0.124711 0.144311 0.121328 0.14429 0.12286 0.14919 0.12722 0.1443549 0.120054 0.144374 0.121328 0.14429 0.126169 0.1443279 0.12722 0.1443549 0.121328 0.14429 0.124711 0.144311 0.126169 0.1443279 0.121328 0.14429 0.124711 0.144311 0.12286 0.14919 0.124711 0.1539919 0.124711 0.144311 0.124711 0.1539919 0.125433 0.155696 0.124711 0.144311 0.125433 0.155696 0.126107 0.157303 0.126169 0.1443279 0.126107 0.157303 0.126649 0.158637 0.124711 0.144311 0.126107 0.157303 0.126169 0.1443279 0.126169 0.1443279 0.126649 0.158637 0.127072 0.15974 0.12722 0.1443549 0.127072 0.15974 0.12742 0.160753 0.126169 0.1443279 0.127072 0.15974 0.12722 0.1443549 0.12722 0.1443549 0.12742 0.160753 0.127667 0.161686 0.127705 0.144388 0.127667 0.161686 0.1277199 0.162344 0.12722 0.1443549 0.127667 0.161686 0.127705 0.144388 0.127705 0.144388 0.1277199 0.162344 0.127555 0.162633 0.127548 0.144423 0.127555 0.162633 0.12718 0.162553 0.127705 0.144388 0.127555 0.162633 0.127548 0.144423 0.126769 0.144455 0.12718 0.162553 0.126598 0.162079 0.127548 0.144423 0.12718 0.162553 0.126769 0.144455 0.126769 0.144455 0.126598 0.162079 0.125896 0.161274 0.125485 0.144477 0.125896 0.161274 0.125214 0.160335 0.126769 0.144455 0.125896 0.161274 0.125485 0.144477 0.125485 0.144477 0.125214 0.160335 0.124548 0.159288 0.123893 0.144488 0.124548 0.159288 0.123812 0.157992 0.125485 0.144477 0.124548 0.159288 0.123893 0.144488 0.123893 0.144488 0.123812 0.157992 0.123008 0.156397 0.123893 0.144488 0.123008 0.156397 0.122236 0.154658 0.118752 0.144461 0.122236 0.154658 0.120324 0.149612 0.122236 0.144484 0.122236 0.154658 0.118752 0.144461 0.123893 0.144488 0.122236 0.154658 0.122236 0.144484 0.126769 0.144455 0.118752 0.144461 0.120054 0.144374 0.125485 0.144477 0.122236 0.144484 0.118752 0.144461 0.126769 0.144455 0.125485 0.144477 0.118752 0.144461 0.127548 0.144423 0.126769 0.144455 0.120054 0.144374 0.127705 0.144388 0.127548 0.144423 0.120054 0.144374 0.12722 0.1443549 0.127705 0.144388 0.120054 0.144374 0.129818 0.117383 0.122743 0.117087 0.123534 0.111066 0.131935 0.106034 0.123534 0.111066 0.124845 0.105136 0.131935 0.106034 0.129818 0.117383 0.123534 0.111066 0.131935 0.106034 0.124845 0.105136 0.126668 0.09934395 0.1360999 0.09526598 0.126668 0.09934395 0.128988 0.09373098 0.1360999 0.09526598 0.131935 0.106034 0.126668 0.09934395 0.1360999 0.09526598 0.128988 0.09373098 0.131788 0.08834099 0.142172 0.085446 0.131788 0.08834099 0.135048 0.08321499 0.142172 0.085446 0.1360999 0.09526598 0.131788 0.08834099 0.142172 0.085446 0.135048 0.08321499 0.1387439 0.07839095 0.149948 0.07690697 0.1387439 0.07839095 0.142846 0.07390797 0.149948 0.07690697 0.142172 0.085446 0.1387439 0.07839095 0.159165 0.06994199 0.142846 0.07390797 0.147325 0.06979995 0.159165 0.06994199 0.149948 0.07690697 0.142846 0.07390797 0.159165 0.06994199 0.147325 0.06979995 0.152145 0.06609797 0.169512 0.06478798 0.152145 0.06609797 0.157272 0.06282895 0.169512 0.06478798 0.159165 0.06994199 0.152145 0.06609797 0.180634 0.06162291 0.157272 0.06282895 0.162666 0.06001991 0.180634 0.06162291 0.169512 0.06478798 0.157272 0.06282895 0.221638 0.06001991 0.162666 0.06001991 0.168288 0.05768996 0.192152 0.06055498 0.162666 0.06001991 0.221638 0.06001991 0.180634 0.06162291 0.162666 0.06001991 0.192152 0.06055498 0.216017 0.05768996 0.168288 0.05768996 0.174093 0.05585998 0.221638 0.06001991 0.168288 0.05768996 0.216017 0.05768996 0.210212 0.05585998 0.174093 0.05585998 0.180036 0.054542 0.216017 0.05768996 0.174093 0.05585998 0.210212 0.05585998 0.204269 0.054542 0.180036 0.054542 0.186071 0.05374795 0.210212 0.05585998 0.180036 0.054542 0.204269 0.054542 0.198234 0.05374795 0.186071 0.05374795 0.192152 0.05348193 0.204269 0.054542 0.186071 0.05374795 0.198234 0.05374795 0.192152 0.06055498 0.221638 0.06001991 0.227032 0.06282895 0.214793 0.06478798 0.227032 0.06282895 0.232159 0.06609797 0.20367 0.06162291 0.192152 0.06055498 0.227032 0.06282895 0.214793 0.06478798 0.20367 0.06162291 0.227032 0.06282895 0.214793 0.06478798 0.232159 0.06609797 0.23698 0.06979995 0.225139 0.06994199 0.23698 0.06979995 0.2414579 0.07390797 0.225139 0.06994199 0.214793 0.06478798 0.23698 0.06979995 0.234356 0.07690697 0.2414579 0.07390797 0.245561 0.07839095 0.234356 0.07690697 0.225139 0.06994199 0.2414579 0.07390797 0.234356 0.07690697 0.245561 0.07839095 0.249256 0.08321499 0.242132 0.085446 0.249256 0.08321499 0.252516 0.08834099 0.242132 0.085446 0.234356 0.07690697 0.249256 0.08321499 0.242132 0.085446 0.252516 0.08834099 0.255317 0.09373098 0.2482039 0.09526598 0.255317 0.09373098 0.257637 0.09934395 0.2482039 0.09526598 0.242132 0.085446 0.255317 0.09373098 0.2482039 0.09526598 0.257637 0.09934395 0.259459 0.105136 0.252369 0.106034 0.259459 0.105136 0.260771 0.111066 0.252369 0.106034 0.2482039 0.09526598 0.259459 0.105136 0.252369 0.106034 0.260771 0.111066 0.261562 0.117087 0.254487 0.117383 0.252369 0.106034 0.261562 0.117087 0.192152 0.06325995 0.192152 0.06055498 0.20367 0.06162291 0.181133 0.06428098 0.180634 0.06162291 0.192152 0.06055498 0.181133 0.06428098 0.192152 0.06055498 0.192152 0.06325995 0.203172 0.06428098 0.20367 0.06162291 0.214793 0.06478798 0.203172 0.06428098 0.192152 0.06325995 0.20367 0.06162291 0.2138119 0.06730896 0.214793 0.06478798 0.225139 0.06994199 0.203172 0.06428098 0.214793 0.06478798 0.2138119 0.06730896 0.223711 0.07223999 0.225139 0.06994199 0.234356 0.07690697 0.2138119 0.06730896 0.225139 0.06994199 0.223711 0.07223999 0.2325299 0.07890397 0.234356 0.07690697 0.242132 0.085446 0.223711 0.07223999 0.234356 0.07690697 0.2325299 0.07890397 0.239971 0.08707398 0.242132 0.085446 0.2482039 0.09526598 0.2325299 0.07890397 0.242132 0.085446 0.239971 0.08707398 0.245782 0.09647095 0.2482039 0.09526598 0.252369 0.106034 0.239971 0.08707398 0.2482039 0.09526598 0.245782 0.09647095 0.249767 0.106775 0.252369 0.106034 0.254487 0.117383 0.245782 0.09647095 0.252369 0.106034 0.249767 0.106775 0.251793 0.117633 0.254487 0.117383 0.254487 0.128929 0.249767 0.106775 0.254487 0.117383 0.251793 0.117633 0.251793 0.128679 0.254487 0.128929 0.252369 0.140278 0.251793 0.117633 0.254487 0.128929 0.251793 0.128679 0.249767 0.139537 0.252369 0.140278 0.2482039 0.151046 0.251793 0.128679 0.252369 0.140278 0.249767 0.139537 0.245782 0.149841 0.2482039 0.151046 0.242132 0.160866 0.249767 0.139537 0.2482039 0.151046 0.245782 0.149841 0.239971 0.159238 0.242132 0.160866 0.234356 0.169405 0.245782 0.149841 0.242132 0.160866 0.239971 0.159238 0.2325299 0.167408 0.234356 0.169405 0.225139 0.17637 0.239971 0.159238 0.234356 0.169405 0.2325299 0.167408 0.223711 0.174072 0.225139 0.17637 0.214793 0.181524 0.2325299 0.167408 0.225139 0.17637 0.223711 0.174072 0.2138119 0.179003 0.214793 0.181524 0.20367 0.1846899 0.223711 0.174072 0.214793 0.181524 0.2138119 0.179003 0.203172 0.182031 0.20367 0.1846899 0.192152 0.185757 0.2138119 0.179003 0.20367 0.1846899 0.203172 0.182031 0.192152 0.183052 0.192152 0.185757 0.180634 0.1846899 0.203172 0.182031 0.192152 0.185757 0.192152 0.183052 0.181133 0.182031 0.180634 0.1846899 0.169512 0.181524 0.192152 0.183052 0.180634 0.1846899 0.181133 0.182031 0.1704919 0.179003 0.169512 0.181524 0.159165 0.17637 0.181133 0.182031 0.169512 0.181524 0.1704919 0.179003 0.160594 0.174072 0.159165 0.17637 0.149948 0.169405 0.1704919 0.179003 0.159165 0.17637 0.160594 0.174072 0.151775 0.167408 0.149948 0.169405 0.142172 0.160866 0.160594 0.174072 0.149948 0.169405 0.151775 0.167408 0.144334 0.159238 0.142172 0.160866 0.1360999 0.151046 0.151775 0.167408 0.142172 0.160866 0.144334 0.159238 0.138522 0.149841 0.1360999 0.151046 0.131935 0.140278 0.144334 0.159238 0.1360999 0.151046 0.138522 0.149841 0.134537 0.139537 0.131935 0.140278 0.129818 0.128929 0.138522 0.149841 0.131935 0.140278 0.134537 0.139537 0.132511 0.128679 0.129818 0.128929 0.129818 0.117383 0.134537 0.139537 0.129818 0.128929 0.132511 0.128679 0.132511 0.117633 0.129818 0.117383 0.131935 0.106034 0.132511 0.128679 0.129818 0.117383 0.132511 0.117633 0.134537 0.106775 0.131935 0.106034 0.1360999 0.09526598 0.132511 0.117633 0.131935 0.106034 0.134537 0.106775 0.138522 0.09647095 0.1360999 0.09526598 0.142172 0.085446 0.134537 0.106775 0.1360999 0.09526598 0.138522 0.09647095 0.144334 0.08707398 0.142172 0.085446 0.149948 0.07690697 0.138522 0.09647095 0.142172 0.085446 0.144334 0.08707398 0.151775 0.07890397 0.149948 0.07690697 0.159165 0.06994199 0.144334 0.08707398 0.149948 0.07690697 0.151775 0.07890397 0.160594 0.07223999 0.159165 0.06994199 0.169512 0.06478798 0.151775 0.07890397 0.159165 0.06994199 0.160594 0.07223999 0.1704919 0.06730896 0.169512 0.06478798 0.180634 0.06162291 0.160594 0.07223999 0.169512 0.06478798 0.1704919 0.06730896 0.1704919 0.06730896 0.180634 0.06162291 0.181133 0.06428098 0.175728 0.217263 0.208576 0.217263 0.209352 0.217715 0.174952 0.217715 0.175728 0.217263 0.209352 0.217715 0.208736 0.218174 0.174952 0.217715 0.209352 0.217715 0.177816 0.216853 0.206488 0.216853 0.208576 0.217263 0.175728 0.217263 0.177816 0.216853 0.208576 0.217263 0.181033 0.216516 0.203271 0.216516 0.206488 0.216853 0.177816 0.216853 0.181033 0.216516 0.206488 0.216853 0.185117 0.216278 0.199187 0.216278 0.203271 0.216516 0.181033 0.216516 0.185117 0.216278 0.203271 0.216516 0.189745 0.2161549 0.194559 0.2161549 0.199187 0.216278 0.185117 0.216278 0.189745 0.2161549 0.199187 0.216278 0.208736 0.218174 0.175568 0.218174 0.174952 0.217715 0.206758 0.218601 0.177547 0.218601 0.175568 0.218174 0.208736 0.218174 0.206758 0.218601 0.175568 0.218174 0.203564 0.218961 0.1807399 0.218961 0.177547 0.218601 0.206758 0.218601 0.203564 0.218961 0.177547 0.218601 0.199411 0.2192209 0.184893 0.2192209 0.1807399 0.218961 0.203564 0.218961 0.199411 0.2192209 0.1807399 0.218961 0.194642 0.219357 0.189662 0.219357 0.184893 0.2192209 0.199411 0.2192209 0.194642 0.219357 0.184893 0.2192209 0.287341 0.149321 0.291232 0.149296 0.293151 0.149314 0.285952 0.14936 0.287341 0.149321 0.293151 0.149314 0.287341 0.149321 0.289194 0.149298 0.291232 0.149296 0.227126 0.1506969 0.2379 0.1506749 0.238071 0.150734 0.22781 0.150641 0.236925 0.150623 0.2379 0.1506749 0.227126 0.1506969 0.22781 0.150641 0.2379 0.1506749 0.2292169 0.150597 0.235297 0.150584 0.236925 0.150623 0.22781 0.150641 0.2292169 0.150597 0.236925 0.150623 0.231131 0.15057 0.233264 0.150566 0.235297 0.150584 0.2292169 0.150597 0.231131 0.15057 0.235297 0.150584 0.1467649 0.150649 0.1572149 0.150725 0.156678 0.150782 0.1467649 0.150649 0.156912 0.1506659 0.1572149 0.150725 0.1467649 0.150649 0.155822 0.150615 0.156912 0.1506659 0.14807 0.1506029 0.154112 0.15058 0.155822 0.150615 0.1467649 0.150649 0.14807 0.1506029 0.155822 0.150615 0.149922 0.150573 0.152042 0.150565 0.154112 0.15058 0.14807 0.1506029 0.149922 0.150573 0.154112 0.15058 0.282347 0.145909 0.280583 0.145914 0.278873 0.145903 0.261998 0.144484 0.260341 0.144488 0.258748 0.144477 0.125485 0.144477 0.123893 0.144488 0.122236 0.144484 0.09754198 0.14586 0.08999496 0.145855 0.08937799 0.145817 0.098266 0.145824 0.09754198 0.14586 0.08937799 0.145817 0.09625101 0.145888 0.09120297 0.145884 0.08999496 0.145855 0.09754198 0.14586 0.09625101 0.145888 0.08999496 0.145855 0.09459096 0.145902 0.092817 0.145901 0.09120297 0.145884 0.09625101 0.145888 0.09459096 0.145902 0.09120297 0.145884 0.07204198 0.149621 0.08226799 0.14967 0.08190596 0.149724 0.07204198 0.149621 0.08182197 0.149617 0.08226799 0.14967 0.07317 0.1495749 0.08064198 0.149572 0.08182197 0.149617 0.07204198 0.149621 0.07317 0.1495749 0.08182197 0.149617 0.07486897 0.149544 0.07890796 0.149543 0.08064198 0.149572 0.07317 0.1495749 0.07486897 0.149544 0.08064198 0.149572 0.07486897 0.149544 0.076882 0.149533 0.07890796 0.149543 0.181133 0.182031 0.181133 0.06428098 0.192152 0.06325995 0.192152 0.183052 0.181133 0.182031 0.192152 0.06325995 0.203172 0.06428098 0.192152 0.183052 0.192152 0.06325995 0.1704919 0.179003 0.1704919 0.06730896 0.181133 0.06428098 0.181133 0.182031 0.1704919 0.179003 0.181133 0.06428098 0.160594 0.174072 0.160594 0.07223999 0.1704919 0.06730896 0.1704919 0.179003 0.160594 0.174072 0.1704919 0.06730896 0.151775 0.167408 0.151775 0.07890397 0.160594 0.07223999 0.160594 0.174072 0.151775 0.167408 0.160594 0.07223999 0.144334 0.159238 0.144334 0.08707398 0.151775 0.07890397 0.151775 0.167408 0.144334 0.159238 0.151775 0.07890397 0.138522 0.149841 0.138522 0.09647095 0.144334 0.08707398 0.144334 0.159238 0.138522 0.149841 0.144334 0.08707398 0.134537 0.139537 0.134537 0.106775 0.138522 0.09647095 0.138522 0.149841 0.134537 0.139537 0.138522 0.09647095 0.132511 0.128679 0.132511 0.117633 0.134537 0.106775 0.134537 0.139537 0.132511 0.128679 0.134537 0.106775 0.203172 0.06428098 0.203172 0.182031 0.192152 0.183052 0.2138119 0.06730896 0.2138119 0.179003 0.203172 0.182031 0.203172 0.06428098 0.2138119 0.06730896 0.203172 0.182031 0.223711 0.07223999 0.223711 0.174072 0.2138119 0.179003 0.2138119 0.06730896 0.223711 0.07223999 0.2138119 0.179003 0.2325299 0.07890397 0.2325299 0.167408 0.223711 0.174072 0.223711 0.07223999 0.2325299 0.07890397 0.223711 0.174072 0.239971 0.08707398 0.239971 0.159238 0.2325299 0.167408 0.2325299 0.07890397 0.239971 0.08707398 0.2325299 0.167408 0.245782 0.09647095 0.245782 0.149841 0.239971 0.159238 0.239971 0.08707398 0.245782 0.09647095 0.239971 0.159238 0.249767 0.106775 0.249767 0.139537 0.245782 0.149841 0.245782 0.09647095 0.249767 0.106775 0.245782 0.149841 0.251793 0.117633 0.251793 0.128679 0.249767 0.139537 0.249767 0.106775 0.251793 0.117633 0.249767 0.139537 2.54e-4 0.108819 0.02567398 0.1106989 0.02586597 0.123156 0 0.123156 2.54e-4 0.108819 0.02586597 0.123156 0.02567398 0.135613 0 0.123156 0.02586597 0.123156 0.001001954 0.09508597 0.02510493 0.098589 0.02567398 0.1106989 2.54e-4 0.108819 0.001001954 0.09508597 0.02567398 0.1106989 0.002208948 0.08251798 0.02416998 0.08716499 0.02510493 0.098589 0.001001954 0.09508597 0.002208948 0.08251798 0.02510493 0.098589 0.003816962 0.071603 0.02288889 0.07676297 0.02416998 0.08716499 0.002208948 0.08251798 0.003816962 0.071603 0.02416998 0.08716499 0.005752921 0.06272995 0.02129089 0.06770497 0.02288889 0.07676297 0.003816962 0.071603 0.005752921 0.06272995 0.02288889 0.07676297 0.007931947 0.05617499 0.01941496 0.06029593 0.02129089 0.06770497 0.005752921 0.06272995 0.007931947 0.05617499 0.02129089 0.06770497 0.01026499 0.05210191 0.01730996 0.05481588 0.01941496 0.06029593 0.007931947 0.05617499 0.01026499 0.05210191 0.01941496 0.06029593 0.01266098 0.05056095 0.01503592 0.05150789 0.01730996 0.05481588 0.01026499 0.05210191 0.01266098 0.05056095 0.01730996 0.05481588 0.02567398 0.135613 2.54e-4 0.137493 0 0.123156 0.02510493 0.147723 0.001001954 0.151226 2.54e-4 0.137493 0.02567398 0.135613 0.02510493 0.147723 2.54e-4 0.137493 0.02416998 0.159147 0.002208948 0.163794 0.001001954 0.151226 0.02510493 0.147723 0.02416998 0.159147 0.001001954 0.151226 0.02288889 0.169549 0.003816962 0.174709 0.002208948 0.163794 0.02416998 0.159147 0.02288889 0.169549 0.002208948 0.163794 0.02129089 0.178607 0.005752921 0.183582 0.003816962 0.174709 0.02288889 0.169549 0.02129089 0.178607 0.003816962 0.174709 0.01941496 0.186016 0.007931947 0.190137 0.005752921 0.183582 0.02129089 0.178607 0.01941496 0.186016 0.005752921 0.183582 0.01730996 0.191496 0.01026499 0.1942099 0.007931947 0.190137 0.01941496 0.186016 0.01730996 0.191496 0.007931947 0.190137 0.01503592 0.194804 0.01266098 0.195751 0.01026499 0.1942099 0.01730996 0.191496 0.01503592 0.194804 0.01026499 0.1942099 0.02444595 0.001239955 0.0245729 0.001059949 0.02439999 8.8e-4 0.02439999 0.007600963 0.02439999 8.8e-4 0.0245729 0.001059949 0.019939 1.74e-4 0.02444595 0.001239955 0.02439999 8.8e-4 0.019939 0.006844997 0.019939 1.74e-4 0.02439999 8.8e-4 0.019939 0.006844997 0.02439999 8.8e-4 0.02439999 0.007600963 0.0245729 0.007792949 0.0245729 0.001059949 0.02444595 0.001239955 0.0245729 0.007792949 0.02439999 0.007600963 0.0245729 0.001059949 0.019939 1.74e-4 0.020087 0.001970887 0.02444595 0.001239955 0.02444595 0.007985949 0.02444595 0.001239955 0.020087 0.001970887 0.0245729 0.007792949 0.02444595 0.001239955 0.02444595 0.007985949 0.01837396 7.6e-5 0.01850491 0.00207597 0.020087 0.001970887 0.020087 0.008767962 0.020087 0.001970887 0.01850491 0.00207597 0.019939 1.74e-4 0.01837396 7.6e-5 0.020087 0.001970887 0.02444595 0.007985949 0.020087 0.001970887 0.020087 0.008767962 0.01664799 0 0.01674896 0.0021559 0.01850491 0.00207597 0.01850491 0.008879959 0.01850491 0.00207597 0.01674896 0.0021559 0.01837396 7.6e-5 0.01664799 0 0.01850491 0.00207597 0.020087 0.008767962 0.01850491 0.00207597 0.01850491 0.008879959 0.007924973 0 0.007823944 0.0021559 0.01674896 0.0021559 0.01674896 0.008966982 0.01674896 0.0021559 0.007823944 0.0021559 0.01664799 0 0.007924973 0 0.01674896 0.0021559 0.01850491 0.008879959 0.01674896 0.0021559 0.01674896 0.008966982 0.006197929 7.6e-5 0.006067991 0.00207597 0.007823944 0.0021559 0.007823944 0.008966982 0.007823944 0.0021559 0.006067991 0.00207597 0.007924973 0 0.006197929 7.6e-5 0.007823944 0.0021559 0.01674896 0.008966982 0.007823944 0.0021559 0.007823944 0.008966982 0.004633963 1.74e-4 0.004485905 0.001970887 0.006067991 0.00207597 0.006067991 0.008879959 0.006067991 0.00207597 0.004485905 0.001970887 0.006197929 7.6e-5 0.004633963 1.74e-4 0.006067991 0.00207597 0.007823944 0.008966982 0.006067991 0.00207597 0.006067991 0.008879959 1.73e-4 8.8e-4 1.27e-4 0.001239955 0.004485905 0.001970887 0.004485905 0.008767962 0.004485905 0.001970887 1.27e-4 0.001239955 0.004633963 1.74e-4 1.73e-4 8.8e-4 0.004485905 0.001970887 0.006067991 0.008879959 0.004485905 0.001970887 0.004485905 0.008767962 1.73e-4 8.8e-4 0 0.001059949 1.27e-4 0.001239955 1.27e-4 0.007985949 1.27e-4 0.001239955 0 0.001059949 0.004485905 0.008767962 1.27e-4 0.001239955 1.27e-4 0.007985949 0 0.007792949 0 0.001059949 1.73e-4 8.8e-4 1.27e-4 0.007985949 0 0.001059949 0 0.007792949 1.73e-4 0.007600963 1.73e-4 8.8e-4 0.004633963 1.74e-4 0 0.007792949 1.73e-4 8.8e-4 1.73e-4 0.007600963 0.004633963 0.006844997 0.004633963 1.74e-4 0.006197929 7.6e-5 1.73e-4 0.007600963 0.004633963 1.74e-4 0.004633963 0.006844997 0.006197929 0.006739974 0.006197929 7.6e-5 0.007924973 0 0.004633963 0.006844997 0.006197929 7.6e-5 0.006197929 0.006739974 0.007924973 0.006658971 0.007924973 0 0.01664799 0 0.006197929 0.006739974 0.007924973 0 0.007924973 0.006658971 0.01664799 0.006658971 0.01664799 0 0.01837396 7.6e-5 0.007924973 0.006658971 0.01664799 0 0.01664799 0.006658971 0.01837396 0.006739974 0.01837396 7.6e-5 0.019939 1.74e-4 0.01664799 0.006658971 0.01837396 7.6e-5 0.01837396 0.006739974 0.01837396 0.006739974 0.019939 1.74e-4 0.019939 0.006844997 0.004633963 0.006844997 0.00346899 0.007369995 0.002456963 0.007795989 0.002456963 0.01322489 0.002456963 0.007795989 0.00346899 0.007369995 1.27e-4 0.007985949 0.002456963 0.007795989 0.003393948 0.00822699 0.003391981 0.01367795 0.003393948 0.00822699 0.002456963 0.007795989 1.27e-4 0.007985949 0.004633963 0.006844997 0.002456963 0.007795989 0.003391981 0.01367795 0.002456963 0.007795989 0.002456963 0.01322489 0.006197929 0.006739974 0.006207883 0.007030904 0.00346899 0.007369995 0.003466904 0.01277589 0.00346899 0.007369995 0.006207883 0.007030904 0.004633963 0.006844997 0.006197929 0.006739974 0.00346899 0.007369995 0.003466904 0.01277589 0.002456963 0.01322489 0.00346899 0.007369995 0.007924973 0.006658971 0.01011598 0.006845951 0.006207883 0.007030904 0.006207883 0.01241993 0.006207883 0.007030904 0.01011598 0.006845951 0.006197929 0.006739974 0.007924973 0.006658971 0.006207883 0.007030904 0.003466904 0.01277589 0.006207883 0.007030904 0.006207883 0.01241993 0.01664799 0.006658971 0.01445692 0.006845951 0.01011598 0.006845951 0.01012599 0.01222389 0.01011598 0.006845951 0.01445692 0.006845951 0.007924973 0.006658971 0.01664799 0.006658971 0.01011598 0.006845951 0.006207883 0.01241993 0.01011598 0.006845951 0.01012599 0.01222389 0.01664799 0.006658971 0.01836395 0.007030904 0.01445692 0.006845951 0.01444697 0.01222389 0.01445692 0.006845951 0.01836395 0.007030904 0.01012599 0.01222389 0.01445692 0.006845951 0.01444697 0.01222389 0.019939 0.006844997 0.02110391 0.007369995 0.01836395 0.007030904 0.01836395 0.01241993 0.01836395 0.007030904 0.02110391 0.007369995 0.01837396 0.006739974 0.019939 0.006844997 0.01836395 0.007030904 0.01664799 0.006658971 0.01837396 0.006739974 0.01836395 0.007030904 0.01444697 0.01222389 0.01836395 0.007030904 0.01836395 0.01241993 0.02439999 0.007600963 0.022116 0.007795989 0.02110391 0.007369995 0.02110499 0.01277589 0.02110391 0.007369995 0.022116 0.007795989 0.019939 0.006844997 0.02439999 0.007600963 0.02110391 0.007369995 0.01836395 0.01241993 0.02110391 0.007369995 0.02110499 0.01277589 0.020087 0.008767962 0.02117896 0.00822699 0.022116 0.007795989 0.022116 0.01322489 0.022116 0.007795989 0.02117896 0.00822699 0.020087 0.008767962 0.022116 0.007795989 0.02439999 0.007600963 0.02110499 0.01277589 0.022116 0.007795989 0.022116 0.01322489 0.01850491 0.008879959 0.01845896 0.008577942 0.02117896 0.00822699 0.02118092 0.01367795 0.02117896 0.00822699 0.01845896 0.008577942 0.020087 0.008767962 0.01850491 0.008879959 0.02117896 0.00822699 0.022116 0.01322489 0.02117896 0.00822699 0.02118092 0.01367795 0.01674896 0.008966982 0.01449888 0.008773982 0.01845896 0.008577942 0.01845788 0.01404798 0.01845896 0.008577942 0.01449888 0.008773982 0.01850491 0.008879959 0.01674896 0.008966982 0.01845896 0.008577942 0.02118092 0.01367795 0.01845896 0.008577942 0.01845788 0.01404798 0.007823944 0.008966982 0.0100739 0.008773982 0.01449888 0.008773982 0.01448899 0.01425397 0.01449888 0.008773982 0.0100739 0.008773982 0.01674896 0.008966982 0.007823944 0.008966982 0.01449888 0.008773982 0.01845788 0.01404798 0.01449888 0.008773982 0.01448899 0.01425397 0.007823944 0.008966982 0.006113946 0.008577942 0.0100739 0.008773982 0.01008397 0.01425397 0.0100739 0.008773982 0.006113946 0.008577942 0.01448899 0.01425397 0.0100739 0.008773982 0.01008397 0.01425397 0.004485905 0.008767962 0.003393948 0.00822699 0.006113946 0.008577942 0.006113946 0.01404798 0.006113946 0.008577942 0.003393948 0.00822699 0.006067991 0.008879959 0.004485905 0.008767962 0.006113946 0.008577942 0.007823944 0.008966982 0.006067991 0.008879959 0.006113946 0.008577942 0.01008397 0.01425397 0.006113946 0.008577942 0.006113946 0.01404798 0.004485905 0.008767962 1.27e-4 0.007985949 0.003393948 0.00822699 0.006113946 0.01404798 0.003393948 0.00822699 0.003391981 0.01367795 0.02444595 0.007985949 0.020087 0.008767962 0.02439999 0.007600963 0.0245729 0.007792949 0.02444595 0.007985949 0.02439999 0.007600963 1.27e-4 0.007985949 1.73e-4 0.007600963 0.004633963 0.006844997 1.27e-4 0.007985949 0 0.007792949 1.73e-4 0.007600963 0.005380988 0.01365 0.003391981 0.01367795 0.002456963 0.01322489 0.004340946 0.01322597 0.002456963 0.01322489 0.003466904 0.01277589 0.005380988 0.01365 0.002456963 0.01322489 0.004340946 0.01322597 0.008283972 0.01396197 0.006113946 0.01404798 0.003391981 0.01367795 0.005380988 0.01365 0.008283972 0.01396197 0.003391981 0.01367795 0.01448899 0.01425397 0.01008397 0.01425397 0.006113946 0.01404798 0.01228588 0.01407796 0.01448899 0.01425397 0.006113946 0.01404798 0.008283972 0.01396197 0.01228588 0.01407796 0.006113946 0.01404798 0.01228588 0.01407796 0.01845788 0.01404798 0.01448899 0.01425397 0.01628899 0.01396197 0.02118092 0.01367795 0.01845788 0.01404798 0.01228588 0.01407796 0.01628899 0.01396197 0.01845788 0.01404798 0.02023196 0.01322597 0.022116 0.01322489 0.02118092 0.01367795 0.01919198 0.01365 0.02023196 0.01322597 0.02118092 0.01367795 0.01628899 0.01396197 0.01919198 0.01365 0.02118092 0.01367795 0.01913696 0.0128079 0.02110499 0.01277589 0.022116 0.01322489 0.02023196 0.01322597 0.01913696 0.0128079 0.022116 0.01322489 0.01623398 0.01250499 0.01836395 0.01241993 0.02110499 0.01277589 0.01913696 0.0128079 0.01623398 0.01250499 0.02110499 0.01277589 0.01012599 0.01222389 0.01444697 0.01222389 0.01836395 0.01241993 0.01228588 0.01239496 0.01012599 0.01222389 0.01836395 0.01241993 0.01623398 0.01250499 0.01228588 0.01239496 0.01836395 0.01241993 0.01228588 0.01239496 0.006207883 0.01241993 0.01012599 0.01222389 0.008338987 0.01250499 0.003466904 0.01277589 0.006207883 0.01241993 0.01228588 0.01239496 0.008338987 0.01250499 0.006207883 0.01241993 0.00543493 0.0128079 0.004340946 0.01322597 0.003466904 0.01277589 0.008338987 0.01250499 0.00543493 0.0128079 0.003466904 0.01277589 0.004340946 0.01889199 0.004340946 0.01322597 0.00543493 0.0128079 0.005379915 0.01933693 0.005380988 0.01365 0.004340946 0.01322597 0.005379915 0.01933693 0.004340946 0.01322597 0.004340946 0.01889199 0.00543493 0.01845192 0.00543493 0.0128079 0.008338987 0.01250499 0.00543493 0.01845192 0.004340946 0.01889199 0.00543493 0.0128079 0.008340954 0.01813197 0.008338987 0.01250499 0.01228588 0.01239496 0.00543493 0.01845192 0.008338987 0.01250499 0.008340954 0.01813197 0.01228588 0.01801699 0.01228588 0.01239496 0.01623398 0.01250499 0.008340954 0.01813197 0.01228588 0.01239496 0.01228588 0.01801699 0.01623195 0.01813197 0.01623398 0.01250499 0.01913696 0.0128079 0.01228588 0.01801699 0.01623398 0.01250499 0.01623195 0.01813197 0.01913791 0.01845192 0.01913696 0.0128079 0.02023196 0.01322597 0.01623195 0.01813197 0.01913696 0.0128079 0.01913791 0.01845192 0.02023196 0.01889199 0.02023196 0.01322597 0.01919198 0.01365 0.01913791 0.01845192 0.02023196 0.01322597 0.02023196 0.01889199 0.01919198 0.01933693 0.01919198 0.01365 0.01628899 0.01396197 0.02023196 0.01889199 0.01919198 0.01365 0.01919198 0.01933693 0.0162869 0.01966595 0.01628899 0.01396197 0.01228588 0.01407796 0.01919198 0.01933693 0.01628899 0.01396197 0.0162869 0.01966595 0.01228588 0.01978695 0.01228588 0.01407796 0.008283972 0.01396197 0.0162869 0.01966595 0.01228588 0.01407796 0.01228588 0.01978695 0.008285999 0.01966595 0.008283972 0.01396197 0.005380988 0.01365 0.01228588 0.01978695 0.008283972 0.01396197 0.008285999 0.01966595 0.008285999 0.01966595 0.005380988 0.01365 0.005379915 0.01933693 0.01919198 0.01933693 0.005379915 0.01933693 0.004340946 0.01889199 0.02023196 0.01889199 0.01919198 0.01933693 0.004340946 0.01889199 0.00543493 0.01845192 0.02023196 0.01889199 0.004340946 0.01889199 0.0162869 0.01966595 0.008285999 0.01966595 0.005379915 0.01933693 0.01919198 0.01933693 0.0162869 0.01966595 0.005379915 0.01933693 0.0162869 0.01966595 0.01228588 0.01978695 0.008285999 0.01966595 0.00543493 0.01845192 0.01913791 0.01845192 0.02023196 0.01889199 0.008340954 0.01813197 0.01623195 0.01813197 0.01913791 0.01845192 0.00543493 0.01845192 0.008340954 0.01813197 0.01913791 0.01845192 0.008340954 0.01813197 0.01228588 0.01801699 0.01623195 0.01813197 - - - - - - - - - - - - - - -

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 6 6 10 2 2 11 8 8 12 9 9 13 10 10 14 11 11 15 12 12 16 4 4 17 3 3 18 11 11 19 4 4 20 13 13 21 14 14 22 1 1 23 15 15 24 5 5 25 16 16 26 17 17 27 13 13 28 1 1 29 0 0 30 17 17 31 1 1 32 15 15 33 3 3 34 5 5 35 18 18 36 19 19 37 14 14 38 20 20 39 16 16 40 21 21 41 13 13 42 18 18 43 14 14 44 22 22 45 15 15 46 16 16 47 20 20 48 22 22 49 16 16 50 23 23 51 24 24 52 19 19 53 25 25 54 21 21 55 26 26 56 27 27 57 19 19 58 18 18 59 28 28 60 23 23 61 19 19 62 29 29 63 28 28 64 19 19 65 30 30 66 29 29 67 19 19 68 31 31 69 30 30 70 19 19 71 32 32 72 31 31 73 19 19 74 33 33 75 32 32 76 19 19 77 34 34 78 33 33 79 19 19 80 27 35 81 34 35 82 19 35 83 35 36 84 20 20 85 21 21 86 36 37 87 35 36 88 21 21 89 37 38 90 36 37 91 21 21 92 38 39 93 37 38 94 21 21 95 39 40 96 38 39 97 21 21 98 40 41 99 39 40 100 21 21 101 25 25 102 40 41 103 21 21 104 41 42 105 42 43 106 24 24 107 43 44 108 26 26 109 44 45 110 45 46 111 41 42 112 24 24 113 23 23 114 45 46 115 24 24 116 46 47 117 25 25 118 26 26 119 47 48 120 46 47 121 26 26 122 43 44 123 47 48 124 26 26 125 48 49 126 49 50 127 42 43 128 50 51 129 44 45 130 51 52 131 52 53 132 48 49 133 42 43 134 41 42 135 52 53 136 42 43 137 50 51 138 53 54 139 44 45 140 43 44 141 44 45 142 53 54 143 54 55 144 55 56 145 49 50 146 56 57 147 51 52 148 57 58 149 58 59 150 54 55 151 49 50 152 48 49 153 58 59 154 49 50 155 56 57 156 50 51 157 51 52 158 59 60 159 60 61 160 61 62 161 59 60 162 62 63 163 60 61 164 63 64 165 64 65 166 65 66 167 66 67 168 56 57 169 57 58 170 67 68 171 68 68 172 69 68 173 70 68 174 71 68 175 68 68 176 70 68 177 68 68 178 67 68 179 72 68 180 69 68 181 73 68 182 72 68 183 67 68 184 69 68 185 72 68 186 73 68 187 74 68 188 75 69 189 76 70 190 52 53 191 77 68 192 74 68 193 78 68 194 79 71 195 52 53 196 41 42 197 79 71 198 75 69 199 52 53 200 77 68 201 72 68 202 74 68 203 80 72 204 81 73 205 76 70 206 77 74 207 78 74 208 82 74 209 83 75 210 80 72 211 76 70 212 75 69 213 83 75 214 76 70 215 84 76 216 85 77 217 81 73 218 86 68 219 82 68 220 87 68 221 88 78 222 84 76 223 81 73 224 89 79 225 88 78 226 81 73 227 90 80 228 89 79 229 81 73 230 80 72 231 90 80 232 81 73 233 86 68 234 77 68 235 82 68 236 27 27 237 18 18 238 85 77 239 86 81 240 87 81 241 91 81 242 92 82 243 27 27 244 85 77 245 93 83 246 92 82 247 85 77 248 94 84 249 93 83 250 85 77 251 84 76 252 94 84 253 85 77 254 95 68 255 91 68 256 96 68 257 95 85 258 86 85 259 91 85 260 95 68 261 96 68 262 97 68 263 98 68 264 97 68 265 99 68 266 98 68 267 95 68 268 97 68 269 100 86 270 99 86 271 101 86 272 100 87 273 98 87 274 99 87 275 7 7 276 102 88 277 6 6 278 103 89 279 101 89 280 104 89 281 103 90 282 100 90 283 101 90 284 105 91 285 106 92 286 102 88 287 107 68 288 104 68 289 108 68 290 7 7 291 105 91 292 102 88 293 107 93 294 103 93 295 104 93 296 109 68 297 108 68 298 110 68 299 111 94 300 112 95 301 106 92 302 113 68 303 108 68 304 109 68 305 105 91 306 111 94 307 106 92 308 113 68 309 107 68 310 108 68 311 114 68 312 110 68 313 115 68 314 116 96 315 117 97 316 112 95 317 109 68 318 110 68 319 114 68 320 111 94 321 116 96 322 112 95 323 118 68 324 115 68 325 119 68 326 120 98 327 121 99 328 117 97 329 114 68 330 115 68 331 118 68 332 116 96 333 120 98 334 117 97 335 122 68 336 119 68 337 123 68 338 124 100 339 125 101 340 121 99 341 118 68 342 119 68 343 122 68 344 120 98 345 124 100 346 121 99 347 126 68 348 123 68 349 127 68 350 128 102 351 129 103 352 125 101 353 122 68 354 123 68 355 126 68 356 124 100 357 128 102 358 125 101 359 130 104 360 131 105 361 129 103 362 128 102 363 130 104 364 129 103 365 132 106 366 133 107 367 131 105 368 134 108 369 132 106 370 131 105 371 130 104 372 134 108 373 131 105 374 135 109 375 136 110 376 133 107 377 132 106 378 135 109 379 133 107 380 137 111 381 138 112 382 136 110 383 135 109 384 137 111 385 136 110 386 139 113 387 140 114 388 138 112 389 137 111 390 139 113 391 138 112 392 141 115 393 142 116 394 140 114 395 113 68 396 109 68 397 143 68 398 139 113 399 141 115 400 140 114 401 144 117 402 145 118 403 142 116 404 146 119 405 143 119 406 147 119 407 141 115 408 144 117 409 142 116 410 146 68 411 113 68 412 143 68 413 148 120 414 149 121 415 145 118 416 150 122 417 147 122 418 151 122 419 144 117 420 148 120 421 145 118 422 150 68 423 146 68 424 147 68 425 152 123 426 153 124 427 149 121 428 154 68 429 151 68 430 155 68 431 148 120 432 152 123 433 149 121 434 154 125 435 150 125 436 151 125 437 156 126 438 157 127 439 153 124 440 154 128 441 155 128 442 158 128 443 159 129 444 156 126 445 153 124 446 152 123 447 159 129 448 153 124 449 160 130 450 161 131 451 157 127 452 162 68 453 158 68 454 163 68 455 156 126 456 160 130 457 157 127 458 162 132 459 154 132 460 158 132 461 164 133 462 165 134 463 161 131 464 162 68 465 163 68 466 166 68 467 160 130 468 167 135 469 161 131 470 168 136 471 161 131 472 167 135 473 169 137 474 164 133 475 161 131 476 170 138 477 169 137 478 161 131 479 168 136 480 170 138 481 161 131 482 171 139 483 172 140 484 165 134 485 173 68 486 166 68 487 174 68 488 175 141 489 171 139 490 165 134 491 176 142 492 175 141 493 165 134 494 177 143 495 176 142 496 165 134 497 164 133 498 177 143 499 165 134 500 173 68 501 162 68 502 166 68 503 178 144 504 179 145 505 172 140 506 173 68 507 174 68 508 180 68 509 181 146 510 178 144 511 172 140 512 171 139 513 181 146 514 172 140 515 182 147 516 183 148 517 179 145 518 184 68 519 180 68 520 185 68 521 178 144 522 182 147 523 179 145 524 184 68 525 173 68 526 180 68 527 186 149 528 187 150 529 183 148 530 184 68 531 185 68 532 188 68 533 189 151 534 186 149 535 183 148 536 190 152 537 183 148 538 182 147 539 190 152 540 189 151 541 183 148 542 191 153 543 192 154 544 187 150 545 193 68 546 188 68 547 194 68 548 186 149 549 191 153 550 187 150 551 193 68 552 184 68 553 188 68 554 195 155 555 196 156 556 192 154 557 193 68 558 194 68 559 197 68 560 198 157 561 195 155 562 192 154 563 191 153 564 198 157 565 192 154 566 199 158 567 200 159 568 201 160 569 202 161 570 200 159 571 199 158 572 203 68 573 197 68 574 204 68 575 203 68 576 193 68 577 197 68 578 205 162 579 206 163 580 207 164 581 208 165 582 209 166 583 210 167 584 208 165 585 210 167 586 211 168 587 212 169 588 207 164 589 213 170 590 205 162 591 207 164 592 212 169 593 212 169 594 213 170 595 214 171 596 189 151 597 215 172 598 186 149 599 216 173 600 214 171 601 217 174 602 212 169 603 214 171 604 216 173 605 218 175 606 219 176 607 215 172 608 216 173 609 217 174 610 220 177 611 189 151 612 218 175 613 215 172 614 221 178 615 222 179 616 219 176 617 223 180 618 220 177 619 224 181 620 225 182 621 221 178 622 219 176 623 218 175 624 225 182 625 219 176 626 216 173 627 220 177 628 223 180 629 226 183 630 167 135 631 222 179 632 223 180 633 224 181 634 227 184 635 228 185 636 226 183 637 222 179 638 229 186 639 228 185 640 222 179 641 230 187 642 229 186 643 222 179 644 231 188 645 230 187 646 222 179 647 221 178 648 231 188 649 222 179 650 232 189 651 227 184 652 233 190 653 234 191 654 168 191 655 167 191 656 226 183 657 234 192 658 167 135 659 223 180 660 227 184 661 232 189 662 232 189 663 233 190 664 235 193 665 236 194 666 235 193 667 237 195 668 232 189 669 235 193 670 236 194 671 238 196 672 237 195 673 239 197 674 236 194 675 237 195 676 238 196 677 238 196 678 239 197 679 240 198 680 241 199 681 240 198 682 242 200 683 238 196 684 240 198 685 241 199 686 241 199 687 242 200 688 243 201 689 244 202 690 243 201 691 245 203 692 241 199 693 243 201 694 244 202 695 244 202 696 245 203 697 246 204 698 247 205 699 246 204 700 248 206 701 244 202 702 246 204 703 247 205 704 247 205 705 248 206 706 249 207 707 250 208 708 249 207 709 251 209 710 247 205 711 249 207 712 250 208 713 252 210 714 251 209 715 253 211 716 250 208 717 251 209 718 252 210 719 252 210 720 253 211 721 254 212 722 255 213 723 254 212 724 256 214 725 252 210 726 254 212 727 255 213 728 255 213 729 256 214 730 257 215 731 258 216 732 257 215 733 259 217 734 255 213 735 257 215 736 258 216 737 258 216 738 259 217 739 260 218 740 261 219 741 260 218 742 262 220 743 258 216 744 260 218 745 261 219 746 261 219 747 262 220 748 9 9 749 261 219 750 9 9 751 263 221 752 8 8 753 263 221 754 9 9 755 264 222 756 265 222 757 266 222 758 267 223 759 268 223 760 269 223 761 264 224 762 266 224 763 270 224 764 271 225 765 272 226 766 273 227 767 271 225 768 273 227 769 274 228 770 275 229 771 274 228 772 276 230 773 271 225 774 274 228 775 275 229 776 275 229 777 276 230 778 277 231 779 278 232 780 277 231 781 279 233 782 275 229 783 277 231 784 278 232 785 278 232 786 279 233 787 280 234 788 281 235 789 280 234 790 282 236 791 278 232 792 280 234 793 281 235 794 281 235 795 282 236 796 283 237 797 284 238 798 283 237 799 285 239 800 281 235 801 283 237 802 284 238 803 286 240 804 285 239 805 287 241 806 284 238 807 285 239 808 286 240 809 286 240 810 287 241 811 288 242 812 289 243 813 288 242 814 290 244 815 286 240 816 288 242 817 289 243 818 289 243 819 290 244 820 291 245 821 292 246 822 291 245 823 293 247 824 289 243 825 291 245 826 292 246 827 292 246 828 293 247 829 294 248 830 292 246 831 294 248 832 295 249 833 296 250 834 297 250 835 298 250 836 299 251 837 297 251 838 296 251 839 292 246 840 295 249 841 300 252 842 267 223 843 301 223 844 268 223 845 302 223 846 303 223 847 301 223 848 267 223 849 302 223 850 301 223 851 304 253 852 305 253 853 306 253 854 307 223 855 308 223 856 309 223 857 309 223 858 310 223 859 307 223 860 311 223 861 309 223 862 308 223 863 304 254 864 306 254 865 312 254 866 313 255 867 314 256 868 315 257 869 313 255 870 315 257 871 316 258 872 317 259 873 316 258 874 318 260 875 313 255 876 316 258 877 317 259 878 317 259 879 318 260 880 319 261 881 320 262 882 319 261 883 321 263 884 317 259 885 319 261 886 320 262 887 320 262 888 321 263 889 322 264 890 323 265 891 322 264 892 324 266 893 320 262 894 322 264 895 323 265 896 323 265 897 324 266 898 325 267 899 326 268 900 325 267 901 327 269 902 323 265 903 325 267 904 326 268 905 328 270 906 327 269 907 329 271 908 326 268 909 327 269 910 328 270 911 328 270 912 329 271 913 330 272 914 331 273 915 330 272 916 332 274 917 328 270 918 330 272 919 331 273 920 331 273 921 332 274 922 333 275 923 334 276 924 333 275 925 335 277 926 331 273 927 333 275 928 334 276 929 334 276 930 335 277 931 336 278 932 334 276 933 336 278 934 337 279 935 338 280 936 339 280 937 340 280 938 341 281 939 339 281 940 338 281 941 334 276 942 337 279 943 342 282 944 343 283 945 344 284 946 62 63 947 345 285 948 65 66 949 346 286 950 347 287 951 343 283 952 62 63 953 59 60 954 347 287 955 62 63 956 348 288 957 63 64 958 65 66 959 345 285 960 348 288 961 65 66 962 349 289 963 350 290 964 344 284 965 351 291 966 346 286 967 352 292 968 343 283 969 349 289 970 344 284 971 351 291 972 345 285 973 346 286 974 353 293 975 354 294 976 350 290 977 355 295 978 352 292 979 356 296 980 357 297 981 353 293 982 350 290 983 349 289 984 357 297 985 350 290 986 358 298 987 351 291 988 352 292 989 355 295 990 358 298 991 352 292 992 359 299 993 360 300 994 354 294 995 361 301 996 356 296 997 362 302 998 353 293 999 359 299 1000 354 294 1001 361 301 1002 355 295 1003 356 296 1004 363 303 1005 364 304 1006 360 300 1007 365 305 1008 362 302 1009 366 306 1010 367 307 1011 363 303 1012 360 300 1013 359 299 1014 367 307 1015 360 300 1016 365 305 1017 361 301 1018 362 302 1019 368 308 1020 369 309 1021 364 304 1022 370 310 1023 366 306 1024 371 311 1025 372 312 1026 368 308 1027 364 304 1028 363 303 1029 372 312 1030 364 304 1031 373 313 1032 365 305 1033 366 306 1034 370 310 1035 373 313 1036 366 306 1037 374 314 1038 375 315 1039 369 309 1040 376 316 1041 377 317 1042 378 318 1043 368 308 1044 374 314 1045 369 309 1046 379 319 1047 371 311 1048 380 320 1049 379 319 1050 370 310 1051 371 311 1052 374 314 1053 381 321 1054 375 315 1055 382 322 1056 378 318 1057 383 323 1058 382 322 1059 376 316 1060 378 318 1061 384 324 1062 385 325 1063 381 321 1064 386 326 1065 383 323 1066 387 327 1067 374 314 1068 384 324 1069 381 321 1070 386 326 1071 382 322 1072 383 323 1073 388 328 1074 389 329 1075 385 325 1076 386 326 1077 387 327 1078 390 330 1079 384 324 1080 388 328 1081 385 325 1082 391 331 1083 392 332 1084 389 329 1085 393 333 1086 390 330 1087 394 334 1088 388 328 1089 391 331 1090 389 329 1091 393 333 1092 386 326 1093 390 330 1094 395 335 1095 396 336 1096 392 332 1097 393 333 1098 394 334 1099 397 337 1100 391 331 1101 395 335 1102 392 332 1103 398 338 1104 399 339 1105 396 336 1106 400 340 1107 397 337 1108 401 341 1109 395 335 1110 398 338 1111 396 336 1112 400 340 1113 393 333 1114 397 337 1115 402 342 1116 403 343 1117 399 339 1118 400 340 1119 401 341 1120 404 344 1121 398 338 1122 402 342 1123 399 339 1124 405 345 1125 406 346 1126 403 343 1127 407 347 1128 404 344 1129 408 348 1130 402 342 1131 405 345 1132 403 343 1133 407 347 1134 400 340 1135 404 344 1136 409 349 1137 410 350 1138 406 346 1139 411 351 1140 408 348 1141 412 352 1142 405 345 1143 409 349 1144 406 346 1145 411 351 1146 407 347 1147 408 348 1148 409 349 1149 413 353 1150 410 350 1151 411 351 1152 412 352 1153 414 354 1154 415 355 1155 416 356 1156 413 353 1157 417 357 1158 414 354 1159 418 358 1160 409 349 1161 415 355 1162 413 353 1163 417 357 1164 411 351 1165 414 354 1166 419 359 1167 420 360 1168 416 356 1169 417 357 1170 418 358 1171 421 361 1172 415 355 1173 419 359 1174 416 356 1175 422 362 1176 423 363 1177 420 360 1178 424 364 1179 421 361 1180 425 365 1181 419 359 1182 422 362 1183 420 360 1184 424 364 1185 417 357 1186 421 361 1187 426 366 1188 427 367 1189 423 363 1190 424 364 1191 425 365 1192 428 368 1193 422 362 1194 426 366 1195 423 363 1196 429 369 1197 430 370 1198 427 367 1199 431 371 1200 428 368 1201 432 372 1202 426 366 1203 429 369 1204 427 367 1205 431 371 1206 424 364 1207 428 368 1208 433 373 1209 434 374 1210 430 370 1211 431 371 1212 432 372 1213 435 375 1214 429 369 1215 433 373 1216 430 370 1217 436 376 1218 437 377 1219 434 374 1220 438 378 1221 435 375 1222 439 379 1223 433 373 1224 436 376 1225 434 374 1226 438 378 1227 431 371 1228 435 375 1229 440 380 1230 441 381 1231 437 377 1232 442 382 1233 439 379 1234 443 383 1235 436 376 1236 440 380 1237 437 377 1238 442 382 1239 438 378 1240 439 379 1241 440 380 1242 444 384 1243 441 381 1244 442 382 1245 443 383 1246 445 385 1247 446 386 1248 447 387 1249 444 384 1250 448 388 1251 445 385 1252 449 389 1253 440 380 1254 446 386 1255 444 384 1256 448 388 1257 442 382 1258 445 385 1259 450 390 1260 451 391 1261 447 387 1262 448 388 1263 449 389 1264 452 392 1265 446 386 1266 450 390 1267 447 387 1268 453 393 1269 454 394 1270 451 391 1271 455 395 1272 452 392 1273 456 396 1274 450 390 1275 453 393 1276 451 391 1277 455 395 1278 448 388 1279 452 392 1280 457 397 1281 458 398 1282 454 394 1283 455 395 1284 456 396 1285 459 399 1286 453 393 1287 457 397 1288 454 394 1289 460 400 1290 461 401 1291 458 398 1292 462 402 1293 459 399 1294 463 403 1295 457 397 1296 460 400 1297 458 398 1298 462 402 1299 455 395 1300 459 399 1301 464 404 1302 465 405 1303 461 401 1304 462 402 1305 463 403 1306 466 406 1307 460 400 1308 464 404 1309 461 401 1310 202 161 1311 199 158 1312 465 405 1313 208 165 1314 466 406 1315 209 166 1316 464 404 1317 202 161 1318 465 405 1319 208 165 1320 462 402 1321 466 406 1322 467 68 1323 204 68 1324 468 68 1325 467 68 1326 203 68 1327 204 68 1328 467 68 1329 468 68 1330 469 68 1331 470 68 1332 469 68 1333 471 68 1334 470 68 1335 467 68 1336 469 68 1337 470 407 1338 471 407 1339 472 407 1340 473 68 1341 472 68 1342 474 68 1343 473 68 1344 470 68 1345 472 68 1346 473 408 1347 474 408 1348 475 408 1349 476 68 1350 475 68 1351 477 68 1352 476 409 1353 473 409 1354 475 409 1355 476 68 1356 477 68 1357 478 68 1358 479 68 1359 478 68 1360 480 68 1361 479 68 1362 476 68 1363 478 68 1364 481 122 1365 480 122 1366 482 122 1367 481 125 1368 479 125 1369 480 125 1370 483 119 1371 482 119 1372 484 119 1373 483 410 1374 481 410 1375 482 410 1376 485 68 1377 484 68 1378 486 68 1379 485 411 1380 483 411 1381 484 411 1382 487 68 1383 486 68 1384 488 68 1385 489 68 1386 486 68 1387 487 68 1388 489 68 1389 485 68 1390 486 68 1391 490 68 1392 488 68 1393 491 68 1394 487 68 1395 488 68 1396 490 68 1397 492 68 1398 491 68 1399 493 68 1400 490 68 1401 491 68 1402 492 68 1403 494 68 1404 493 68 1405 495 68 1406 492 68 1407 493 68 1408 494 68 1409 496 68 1410 495 68 1411 497 68 1412 494 68 1413 495 68 1414 496 68 1415 489 68 1416 487 68 1417 498 68 1418 499 89 1419 498 89 1420 500 89 1421 499 68 1422 489 68 1423 498 68 1424 501 86 1425 500 86 1426 502 86 1427 501 68 1428 499 68 1429 500 68 1430 503 68 1431 502 68 1432 504 68 1433 503 87 1434 501 87 1435 502 87 1436 503 412 1437 504 412 1438 505 412 1439 506 68 1440 505 68 1441 507 68 1442 506 413 1443 503 413 1444 505 413 1445 506 68 1446 507 68 1447 508 68 1448 509 68 1449 508 68 1450 510 68 1451 509 68 1452 506 68 1453 508 68 1454 509 68 1455 510 68 1456 511 68 1457 512 68 1458 511 68 1459 513 68 1460 512 68 1461 509 68 1462 511 68 1463 512 68 1464 513 68 1465 514 68 1466 70 68 1467 514 68 1468 71 68 1469 70 68 1470 512 68 1471 514 68 1472 515 414 1473 516 414 1474 517 415 1475 518 416 1476 519 417 1477 520 418 1478 518 416 1479 520 418 1480 521 418 1481 522 419 1482 517 415 1483 523 420 1484 522 419 1485 515 414 1486 517 415 1487 524 420 1488 523 420 1489 525 421 1490 522 419 1491 523 420 1492 524 420 1493 526 421 1494 525 421 1495 527 422 1496 524 420 1497 525 421 1498 526 421 1499 528 423 1500 527 422 1501 529 424 1502 526 421 1503 527 422 1504 528 423 1505 530 424 1506 529 424 1507 531 425 1508 528 423 1509 529 424 1510 530 424 1511 532 425 1512 531 425 1513 533 426 1514 530 424 1515 531 425 1516 532 425 1517 534 427 1518 533 426 1519 535 428 1520 532 425 1521 533 426 1522 534 427 1523 536 428 1524 535 428 1525 537 429 1526 534 427 1527 535 428 1528 536 428 1529 538 429 1530 537 429 1531 539 430 1532 536 428 1533 537 429 1534 538 429 1535 540 431 1536 539 430 1537 541 432 1538 538 429 1539 539 430 1540 540 431 1541 542 433 1542 541 432 1543 543 434 1544 540 431 1545 541 432 1546 542 433 1547 544 434 1548 543 434 1549 545 435 1550 542 433 1551 543 434 1552 544 434 1553 546 435 1554 545 435 1555 547 436 1556 544 434 1557 545 435 1558 546 435 1559 548 437 1560 547 436 1561 549 438 1562 546 435 1563 547 436 1564 548 437 1565 550 438 1566 549 438 1567 551 439 1568 548 437 1569 549 438 1570 550 438 1571 552 440 1572 551 439 1573 553 441 1574 550 438 1575 551 439 1576 552 440 1577 554 442 1578 555 443 1579 556 444 1580 552 440 1581 553 441 1582 557 445 1583 558 444 1584 556 444 1585 559 446 1586 554 442 1587 556 444 1588 558 444 1589 560 446 1590 559 446 1591 561 447 1592 558 444 1593 559 446 1594 560 446 1595 562 447 1596 561 447 1597 563 448 1598 560 446 1599 561 447 1600 562 447 1601 564 448 1602 563 448 1603 565 449 1604 562 447 1605 563 448 1606 564 448 1607 566 450 1608 565 449 1609 567 451 1610 564 448 1611 565 449 1612 566 450 1613 568 451 1614 567 451 1615 569 452 1616 566 450 1617 567 451 1618 568 451 1619 570 453 1620 569 452 1621 571 454 1622 568 451 1623 569 452 1624 570 453 1625 572 454 1626 571 454 1627 573 455 1628 570 453 1629 571 454 1630 572 454 1631 574 455 1632 573 455 1633 575 456 1634 572 454 1635 573 455 1636 574 455 1637 576 457 1638 575 456 1639 577 458 1640 574 455 1641 575 456 1642 576 457 1643 578 459 1644 577 458 1645 579 460 1646 576 457 1647 577 458 1648 578 459 1649 580 460 1650 579 460 1651 581 461 1652 578 459 1653 579 460 1654 580 460 1655 582 461 1656 581 461 1657 583 462 1658 580 460 1659 581 461 1660 582 461 1661 584 463 1662 583 462 1663 585 464 1664 582 461 1665 583 462 1666 584 463 1667 586 464 1668 585 464 1669 519 417 1670 584 463 1671 585 464 1672 586 464 1673 586 464 1674 519 417 1675 518 416 1676 587 465 1677 588 466 1678 589 467 1679 590 468 1680 591 469 1681 592 470 1682 593 471 1683 594 472 1684 595 473 1685 596 474 1686 597 475 1687 591 469 1688 598 476 1689 596 474 1690 591 469 1691 590 468 1692 598 476 1693 591 469 1694 599 477 1695 600 478 1696 588 466 1697 590 468 1698 592 470 1699 601 479 1700 602 480 1701 599 477 1702 588 466 1703 587 465 1704 602 480 1705 588 466 1706 603 481 1707 600 478 1708 599 477 1709 604 482 1710 601 479 1711 605 483 1712 604 482 1713 590 468 1714 601 479 1715 602 480 1716 606 484 1717 599 477 1718 607 485 1719 599 477 1720 606 484 1721 608 486 1722 603 481 1723 599 477 1724 607 485 1725 608 486 1726 599 477 1727 609 487 1728 610 488 1729 606 484 1730 611 489 1731 606 484 1732 610 488 1733 602 480 1734 609 487 1735 606 484 1736 611 489 1737 607 485 1738 606 484 1739 609 487 1740 612 490 1741 610 488 1742 613 491 1743 614 492 1744 615 493 1745 616 494 1746 611 489 1747 610 488 1748 613 491 1749 617 495 1750 614 492 1751 609 487 1752 618 496 1753 612 490 1754 619 497 1755 615 493 1756 620 498 1757 613 491 1758 615 493 1759 619 497 1760 609 487 1761 621 499 1762 618 496 1763 622 500 1764 620 498 1765 623 501 1766 624 502 1767 620 498 1768 622 500 1769 619 497 1770 620 498 1771 624 502 1772 625 503 1773 626 504 1774 621 499 1775 627 505 1776 623 501 1777 628 506 1778 609 487 1779 625 503 1780 621 499 1781 622 500 1782 623 501 1783 627 505 1784 625 503 1785 629 507 1786 626 504 1787 627 505 1788 628 506 1789 630 508 1790 631 509 1791 632 510 1792 629 507 1793 633 511 1794 634 512 1795 635 513 1796 625 503 1797 631 509 1798 629 507 1799 627 505 1800 630 508 1801 636 514 1802 631 509 1803 637 515 1804 632 510 1805 638 516 1806 635 513 1807 639 517 1808 638 516 1809 633 511 1810 635 513 1811 631 509 1812 640 518 1813 637 515 1814 641 519 1815 639 517 1816 642 520 1817 638 516 1818 639 517 1819 641 519 1820 631 509 1821 643 521 1822 640 518 1823 644 522 1824 642 520 1825 645 523 1826 641 519 1827 642 520 1828 644 522 1829 646 524 1830 647 525 1831 643 521 1832 648 526 1833 645 523 1834 649 527 1835 631 509 1836 646 524 1837 643 521 1838 644 522 1839 645 523 1840 648 526 1841 646 524 1842 650 528 1843 647 525 1844 651 529 1845 647 525 1846 650 528 1847 652 530 1848 649 527 1849 653 531 1850 648 526 1851 649 527 1852 652 530 1853 654 532 1854 655 533 1855 650 528 1856 656 534 1857 650 528 1858 655 533 1859 646 524 1860 654 532 1861 650 528 1862 657 535 1863 650 528 1864 656 534 1865 651 529 1866 650 528 1867 657 535 1868 658 536 1869 659 537 1870 655 533 1871 660 538 1872 655 533 1873 659 537 1874 654 532 1875 658 536 1876 655 533 1877 656 534 1878 655 533 1879 660 538 1880 661 539 1881 662 540 1882 659 537 1883 663 541 1884 659 537 1885 662 540 1886 658 536 1887 661 539 1888 659 537 1889 660 538 1890 659 537 1891 663 541 1892 664 542 1893 665 543 1894 662 540 1895 666 544 1896 662 540 1897 665 543 1898 661 539 1899 664 542 1900 662 540 1901 663 541 1902 662 540 1903 666 544 1904 667 545 1905 668 546 1906 665 543 1907 669 547 1908 665 543 1909 668 546 1910 664 542 1911 667 545 1912 665 543 1913 666 544 1914 665 543 1915 669 547 1916 670 548 1917 671 549 1918 668 546 1919 672 550 1920 668 546 1921 671 549 1922 667 545 1923 670 548 1924 668 546 1925 669 547 1926 668 546 1927 672 550 1928 673 551 1929 674 552 1930 671 549 1931 675 553 1932 671 549 1933 674 552 1934 670 548 1935 673 551 1936 671 549 1937 672 550 1938 671 549 1939 675 553 1940 676 554 1941 677 555 1942 674 552 1943 678 556 1944 674 552 1945 677 555 1946 673 551 1947 676 554 1948 674 552 1949 675 553 1950 674 552 1951 678 556 1952 679 557 1953 680 558 1954 677 555 1955 681 559 1956 677 555 1957 680 558 1958 682 560 1959 679 557 1960 677 555 1961 676 554 1962 682 560 1963 677 555 1964 678 556 1965 677 555 1966 681 559 1967 683 561 1968 684 562 1969 685 563 1970 686 564 1971 681 559 1972 680 558 1973 687 565 1974 688 566 1975 684 562 1976 683 561 1977 687 565 1978 684 562 1979 683 561 1980 685 563 1981 689 567 1982 690 568 1983 682 560 1984 676 554 1985 691 569 1986 689 567 1987 692 570 1988 691 569 1989 683 561 1990 689 567 1991 693 571 1992 676 554 1993 673 551 1994 694 572 1995 690 568 1996 676 554 1997 693 571 1998 694 572 1999 676 554 2000 695 573 2001 673 551 2002 670 548 2003 695 573 2004 693 571 2005 673 551 2006 696 574 2007 670 548 2008 667 545 2009 697 575 2010 695 573 2011 670 548 2012 698 576 2013 697 575 2014 670 548 2015 696 574 2016 698 576 2017 670 548 2018 699 577 2019 667 545 2020 664 542 2021 700 578 2022 667 545 2023 699 577 2024 701 579 2025 667 545 2026 700 578 2027 702 580 2028 696 574 2029 667 545 2030 703 581 2031 702 580 2032 667 545 2033 704 582 2034 703 581 2035 667 545 2036 705 583 2037 704 582 2038 667 545 2039 706 584 2040 705 583 2041 667 545 2042 701 579 2043 706 584 2044 667 545 2045 707 585 2046 664 542 2047 661 539 2048 699 577 2049 664 542 2050 707 585 2051 708 586 2052 661 539 2053 658 536 2054 707 585 2055 661 539 2056 708 586 2057 709 587 2058 658 536 2059 654 532 2060 708 586 2061 658 536 2062 709 587 2063 710 588 2064 654 532 2065 646 524 2066 709 587 2067 654 532 2068 710 588 2069 711 589 2070 646 524 2071 631 509 2072 712 590 2073 646 524 2074 711 589 2075 710 588 2076 646 524 2077 712 590 2078 713 591 2079 631 509 2080 625 503 2081 711 589 2082 631 509 2083 713 591 2084 714 592 2085 625 503 2086 609 487 2087 713 591 2088 625 503 2089 714 592 2090 715 593 2091 609 487 2092 602 480 2093 714 592 2094 609 487 2095 715 593 2096 716 594 2097 602 480 2098 587 465 2099 715 593 2100 602 480 2101 717 595 2102 716 594 2103 717 595 2104 602 480 2105 593 471 2106 718 596 2107 594 472 2108 719 597 2109 605 483 2110 720 598 2111 719 597 2112 604 482 2113 605 483 2114 721 599 2115 608 486 2116 607 485 2117 722 600 2118 720 598 2119 723 601 2120 722 600 2121 719 597 2122 720 598 2123 724 602 2124 607 485 2125 611 489 2126 725 603 2127 721 599 2128 607 485 2129 724 602 2130 725 603 2131 607 485 2132 726 604 2133 727 605 2134 611 489 2135 728 606 2136 611 489 2137 727 605 2138 729 607 2139 726 604 2140 611 489 2141 730 608 2142 729 607 2143 611 489 2144 731 609 2145 730 608 2146 611 489 2147 616 494 2148 731 609 2149 611 489 2150 728 606 2151 724 602 2152 611 489 2153 732 610 2154 733 611 2155 734 612 2156 735 613 2157 728 606 2158 727 605 2159 736 614 2160 735 613 2161 727 605 2162 732 610 2163 737 615 2164 733 611 2165 738 616 2166 734 612 2167 739 617 2168 732 610 2169 734 612 2170 738 616 2171 740 618 2172 739 617 2173 741 619 2174 738 616 2175 739 617 2176 740 618 2177 742 620 2178 741 619 2179 743 621 2180 740 618 2181 741 619 2182 742 620 2183 744 622 2184 743 621 2185 617 495 2186 742 620 2187 743 621 2188 744 622 2189 744 622 2190 617 495 2191 613 491 2192 745 623 2193 723 601 2194 746 624 2195 745 623 2196 722 600 2197 723 601 2198 747 625 2199 725 603 2200 724 602 2201 747 625 2202 748 626 2203 725 603 2204 749 627 2205 746 624 2206 750 628 2207 749 627 2208 745 623 2209 746 624 2210 751 629 2211 724 602 2212 728 606 2213 751 629 2214 747 625 2215 724 602 2216 752 630 2217 728 606 2218 735 613 2219 752 630 2220 751 629 2221 728 606 2222 753 631 2223 754 632 2224 735 613 2225 755 633 2226 735 613 2227 754 632 2228 756 634 2229 753 631 2230 735 613 2231 757 635 2232 756 634 2233 735 613 2234 736 614 2235 757 635 2236 735 613 2237 755 633 2238 752 630 2239 735 613 2240 657 535 2241 758 636 2242 754 632 2243 759 637 2244 754 632 2245 758 636 2246 753 631 2247 657 535 2248 754 632 2249 759 637 2250 755 633 2251 754 632 2252 656 534 2253 760 638 2254 758 636 2255 761 639 2256 758 636 2257 760 638 2258 657 535 2259 656 534 2260 758 636 2261 761 639 2262 759 637 2263 758 636 2264 660 538 2265 762 640 2266 760 638 2267 763 641 2268 760 638 2269 762 640 2270 656 534 2271 660 538 2272 760 638 2273 763 641 2274 761 639 2275 760 638 2276 663 541 2277 764 642 2278 762 640 2279 765 643 2280 762 640 2281 764 642 2282 660 538 2283 663 541 2284 762 640 2285 765 643 2286 763 641 2287 762 640 2288 666 544 2289 766 644 2290 764 642 2291 765 643 2292 764 642 2293 766 644 2294 663 541 2295 666 544 2296 764 642 2297 669 547 2298 767 645 2299 766 644 2300 768 646 2301 766 644 2302 767 645 2303 666 544 2304 669 547 2305 766 644 2306 768 646 2307 765 643 2308 766 644 2309 672 550 2310 769 647 2311 767 645 2312 770 648 2313 767 645 2314 769 647 2315 669 547 2316 672 550 2317 767 645 2318 771 649 2319 768 646 2320 767 645 2321 772 650 2322 771 649 2323 767 645 2324 773 651 2325 772 650 2326 767 645 2327 770 648 2328 773 651 2329 767 645 2330 675 553 2331 774 652 2332 769 647 2333 775 653 2334 776 654 2335 777 655 2336 672 550 2337 675 553 2338 769 647 2339 775 653 2340 778 656 2341 776 654 2342 675 553 2343 779 657 2344 774 652 2345 780 658 2346 777 655 2347 781 659 2348 775 653 2349 777 655 2350 780 658 2351 675 553 2352 782 660 2353 779 657 2354 780 658 2355 781 659 2356 783 661 2357 678 556 2358 784 662 2359 782 660 2360 785 663 2361 783 661 2362 786 664 2363 675 553 2364 678 556 2365 782 660 2366 780 658 2367 783 661 2368 785 663 2369 678 556 2370 787 665 2371 784 662 2372 785 663 2373 786 664 2374 788 666 2375 678 556 2376 789 667 2377 787 665 2378 790 668 2379 791 668 2380 792 668 2381 793 669 2382 791 669 2383 790 669 2384 785 663 2385 788 666 2386 794 670 2387 678 556 2388 795 671 2389 789 667 2390 796 672 2391 789 667 2392 795 671 2393 790 673 2394 792 673 2395 797 673 2396 681 559 2397 798 674 2398 795 671 2399 799 675 2400 795 671 2401 798 674 2402 678 556 2403 681 559 2404 795 671 2405 799 675 2406 796 672 2407 795 671 2408 800 676 2409 801 677 2410 798 674 2411 802 678 2412 798 674 2413 801 677 2414 803 679 2415 800 676 2416 798 674 2417 681 559 2418 803 679 2419 798 674 2420 799 675 2421 798 674 2422 802 678 2423 804 680 2424 805 681 2425 806 682 2426 807 683 2427 802 678 2428 801 677 2429 808 684 2430 809 685 2431 805 681 2432 804 680 2433 808 684 2434 805 681 2435 804 680 2436 806 682 2437 810 686 2438 686 564 2439 803 679 2440 681 559 2441 687 565 2442 810 686 2443 688 566 2444 687 565 2445 804 680 2446 810 686 2447 811 687 2448 657 535 2449 753 631 2450 812 688 2451 651 529 2452 657 535 2453 813 689 2454 812 688 2455 657 535 2456 814 690 2457 813 689 2458 657 535 2459 811 687 2460 814 690 2461 657 535 2462 815 691 2463 816 692 2464 817 693 2465 818 694 2466 819 695 2467 816 692 2468 818 694 2469 816 692 2470 815 691 2471 815 691 2472 817 693 2473 820 696 2474 821 697 2475 822 698 2476 737 615 2477 815 691 2478 820 696 2479 823 699 2480 821 697 2481 737 615 2482 732 610 2483 747 625 2484 824 700 2485 748 626 2486 825 701 2487 750 628 2488 826 702 2489 825 701 2490 749 627 2491 750 628 2492 261 219 2493 824 700 2494 747 625 2495 261 219 2496 827 703 2497 824 700 2498 825 701 2499 826 702 2500 828 704 2501 258 216 2502 747 625 2503 751 629 2504 258 216 2505 261 219 2506 747 625 2507 255 213 2508 751 629 2509 752 630 2510 255 213 2511 258 216 2512 751 629 2513 252 210 2514 752 630 2515 755 633 2516 252 210 2517 255 213 2518 752 630 2519 250 208 2520 755 633 2521 759 637 2522 250 208 2523 252 210 2524 755 633 2525 247 205 2526 759 637 2527 761 639 2528 247 205 2529 250 208 2530 759 637 2531 244 202 2532 761 639 2533 763 641 2534 244 202 2535 247 205 2536 761 639 2537 241 199 2538 763 641 2539 765 643 2540 241 199 2541 244 202 2542 763 641 2543 238 196 2544 765 643 2545 768 646 2546 238 196 2547 241 199 2548 765 643 2549 236 194 2550 768 646 2551 771 649 2552 236 194 2553 238 196 2554 768 646 2555 829 705 2556 830 706 2557 771 649 2558 232 189 2559 771 649 2560 830 706 2561 831 707 2562 829 705 2563 771 649 2564 832 708 2565 831 707 2566 771 649 2567 833 709 2568 832 708 2569 771 649 2570 834 710 2571 833 709 2572 771 649 2573 772 650 2574 834 710 2575 771 649 2576 232 189 2577 236 194 2578 771 649 2579 835 711 2580 836 712 2581 830 706 2582 223 180 2583 830 706 2584 836 712 2585 837 713 2586 835 711 2587 830 706 2588 838 714 2589 837 713 2590 830 706 2591 839 715 2592 838 714 2593 830 706 2594 829 705 2595 839 715 2596 830 706 2597 223 180 2598 232 189 2599 830 706 2600 840 716 2601 802 678 2602 836 712 2603 216 173 2604 836 712 2605 802 678 2606 835 711 2607 840 716 2608 836 712 2609 216 173 2610 223 180 2611 836 712 2612 807 683 2613 841 717 2614 802 678 2615 212 169 2616 802 678 2617 841 717 2618 842 718 2619 799 675 2620 802 678 2621 840 716 2622 842 718 2623 802 678 2624 212 169 2625 216 173 2626 802 678 2627 808 684 2628 843 719 2629 809 685 2630 844 720 2631 212 169 2632 841 717 2633 845 721 2634 846 722 2635 843 719 2636 808 684 2637 845 721 2638 843 719 2639 847 223 2640 848 223 2641 849 223 2642 850 223 2643 848 223 2644 847 223 2645 851 723 2646 852 723 2647 853 723 2648 854 223 2649 850 223 2650 847 223 2651 851 724 2652 853 724 2653 855 724 2654 856 725 2655 857 726 2656 858 727 2657 859 728 2658 858 727 2659 860 729 2660 856 725 2661 858 727 2662 859 728 2663 859 728 2664 860 729 2665 861 730 2666 862 731 2667 861 730 2668 863 732 2669 859 728 2670 861 730 2671 862 731 2672 862 731 2673 863 732 2674 864 733 2675 865 734 2676 864 733 2677 866 735 2678 862 731 2679 864 733 2680 865 734 2681 865 734 2682 866 735 2683 867 736 2684 868 737 2685 867 736 2686 869 738 2687 865 734 2688 867 736 2689 868 737 2690 868 737 2691 869 738 2692 870 739 2693 775 653 2694 870 739 2695 778 656 2696 868 737 2697 870 739 2698 775 653 2699 261 219 2700 263 221 2701 827 703 2702 871 740 2703 828 704 2704 872 741 2705 871 740 2706 825 701 2707 828 704 2708 873 742 2709 872 741 2710 12 12 2711 873 742 2712 871 740 2713 872 741 2714 844 720 2715 205 162 2716 212 169 2717 845 721 2718 211 168 2719 846 722 2720 845 721 2721 208 165 2722 211 168 2723 11 11 2724 873 742 2725 12 12 2726 874 743 2727 875 223 2728 876 744 2729 877 745 2730 878 746 2731 879 747 2732 880 748 2733 874 743 2734 876 744 2735 881 749 2736 880 748 2737 876 744 2738 882 750 2739 881 749 2740 876 744 2741 883 751 2742 882 750 2743 876 744 2744 884 752 2745 883 751 2746 876 744 2747 885 753 2748 884 752 2749 876 744 2750 886 754 2751 885 753 2752 876 744 2753 887 755 2754 886 754 2755 876 744 2756 888 756 2757 887 755 2758 876 744 2759 889 757 2760 888 756 2761 876 744 2762 890 758 2763 889 757 2764 876 744 2765 891 759 2766 890 758 2767 876 744 2768 892 760 2769 891 759 2770 876 744 2771 893 761 2772 892 760 2773 876 744 2774 894 762 2775 893 761 2776 876 744 2777 895 763 2778 894 762 2779 876 744 2780 896 764 2781 895 763 2782 876 744 2783 897 765 2784 896 764 2785 876 744 2786 898 766 2787 897 765 2788 876 744 2789 899 767 2790 898 766 2791 876 744 2792 900 768 2793 899 767 2794 876 744 2795 901 769 2796 900 768 2797 876 744 2798 902 770 2799 903 771 2800 878 746 2801 904 772 2802 878 746 2803 877 745 2804 905 773 2805 878 746 2806 904 772 2807 906 774 2808 878 746 2809 905 773 2810 907 775 2811 878 746 2812 906 774 2813 908 776 2814 878 746 2815 907 775 2816 909 777 2817 878 746 2818 908 776 2819 910 778 2820 878 746 2821 909 777 2822 911 779 2823 878 746 2824 910 778 2825 912 780 2826 878 746 2827 911 779 2828 913 781 2829 878 746 2830 912 780 2831 914 782 2832 878 746 2833 913 781 2834 915 783 2835 878 746 2836 914 782 2837 916 784 2838 878 746 2839 915 783 2840 917 785 2841 878 746 2842 916 784 2843 918 786 2844 878 746 2845 917 785 2846 919 787 2847 878 746 2848 918 786 2849 920 788 2850 878 746 2851 919 787 2852 921 789 2853 878 746 2854 920 788 2855 922 790 2856 878 746 2857 921 789 2858 902 770 2859 878 746 2860 922 790 2861 877 745 2862 879 747 2863 923 791 2864 924 792 2865 874 743 2866 880 748 2867 925 793 2868 923 791 2869 926 794 2870 925 793 2871 877 745 2872 923 791 2873 927 795 2874 880 748 2875 881 749 2876 928 796 2877 924 792 2878 880 748 2879 927 795 2880 928 796 2881 880 748 2882 929 797 2883 881 749 2884 882 750 2885 930 798 2886 927 795 2887 881 749 2888 929 797 2889 930 798 2890 881 749 2891 931 799 2892 882 750 2893 883 751 2894 932 800 2895 929 797 2896 882 750 2897 931 799 2898 932 800 2899 882 750 2900 933 801 2901 883 751 2902 884 752 2903 933 801 2904 931 799 2905 883 751 2906 934 802 2907 884 752 2908 885 753 2909 934 802 2910 933 801 2911 884 752 2912 935 803 2913 885 753 2914 886 754 2915 935 803 2916 934 802 2917 885 753 2918 936 804 2919 886 754 2920 887 755 2921 937 805 2922 935 803 2923 886 754 2924 936 804 2925 937 805 2926 886 754 2927 938 806 2928 887 755 2929 888 756 2930 938 806 2931 936 804 2932 887 755 2933 939 807 2934 888 756 2935 889 757 2936 939 807 2937 938 806 2938 888 756 2939 940 808 2940 889 757 2941 890 758 2942 941 809 2943 939 807 2944 889 757 2945 940 808 2946 941 809 2947 889 757 2948 942 810 2949 890 758 2950 891 759 2951 942 810 2952 940 808 2953 890 758 2954 943 811 2955 891 759 2956 892 760 2957 944 812 2958 942 810 2959 891 759 2960 943 811 2961 944 812 2962 891 759 2963 945 813 2964 892 760 2965 893 761 2966 946 814 2967 943 811 2968 892 760 2969 945 813 2970 946 814 2971 892 760 2972 947 815 2973 893 761 2974 894 762 2975 947 815 2976 945 813 2977 893 761 2978 948 816 2979 894 762 2980 895 763 2981 948 816 2982 947 815 2983 894 762 2984 949 817 2985 895 763 2986 896 764 2987 949 817 2988 948 816 2989 895 763 2990 950 818 2991 896 764 2992 897 765 2993 950 818 2994 949 817 2995 896 764 2996 951 819 2997 897 765 2998 898 766 2999 951 819 3000 950 818 3001 897 765 3002 952 820 3003 898 766 3004 899 767 3005 952 820 3006 951 819 3007 898 766 3008 953 821 3009 899 767 3010 900 768 3011 953 821 3012 952 820 3013 899 767 3014 954 822 3015 900 768 3016 901 769 3017 954 822 3018 953 821 3019 900 768 3020 954 822 3021 901 769 3022 955 823 3023 902 770 3024 956 824 3025 903 771 3026 957 825 3027 954 822 3028 955 823 3029 957 825 3030 955 823 3031 958 826 3032 959 827 3033 960 828 3034 956 824 3035 959 827 3036 956 824 3037 902 770 3038 961 829 3039 962 830 3040 963 831 3041 964 832 3042 965 833 3043 962 830 3044 961 829 3045 964 832 3046 962 830 3047 961 829 3048 963 831 3049 966 834 3050 961 829 3051 966 834 3052 967 835 3053 961 829 3054 967 835 3055 968 836 3056 969 837 3057 968 836 3058 970 838 3059 969 837 3060 961 829 3061 968 836 3062 969 837 3063 970 838 3064 971 839 3065 969 837 3066 971 839 3067 972 840 3068 973 841 3069 972 840 3070 974 842 3071 973 841 3072 969 837 3073 972 840 3074 973 841 3075 974 842 3076 975 843 3077 976 844 3078 975 843 3079 977 845 3080 976 844 3081 973 841 3082 975 843 3083 978 846 3084 937 805 3085 936 804 3086 976 844 3087 977 845 3088 979 847 3089 980 848 3090 936 804 3091 938 806 3092 978 846 3093 936 804 3094 980 848 3095 981 849 3096 938 806 3097 939 807 3098 982 850 3099 938 806 3100 981 849 3101 980 848 3102 938 806 3103 982 850 3104 983 851 3105 984 852 3106 939 807 3107 985 853 3108 939 807 3109 984 852 3110 941 809 3111 983 851 3112 939 807 3113 981 849 3114 939 807 3115 985 853 3116 986 854 3117 987 854 3118 988 854 3119 989 855 3120 987 855 3121 986 855 3122 990 856 3123 985 853 3124 984 852 3125 991 223 3126 992 223 3127 993 223 3128 994 855 3129 989 855 3130 986 855 3131 995 223 3132 993 223 3133 996 223 3134 997 223 3135 991 223 3136 993 223 3137 998 223 3138 997 223 3139 993 223 3140 995 223 3141 998 223 3142 993 223 3143 999 223 3144 996 223 3145 1000 223 3146 999 223 3147 995 223 3148 996 223 3149 1001 223 3150 1000 223 3151 1002 223 3152 1003 223 3153 999 223 3154 1000 223 3155 1001 223 3156 1003 223 3157 1000 223 3158 946 814 3159 1004 855 3160 943 811 3161 1005 857 3162 1006 857 3163 1007 857 3164 1008 223 3165 1001 223 3166 1002 223 3167 1009 223 3168 1008 223 3169 1002 223 3170 1005 858 3171 1007 858 3172 1010 858 3173 1011 859 3174 946 814 3175 945 813 3176 1012 860 3177 1013 861 3178 946 814 3179 1005 857 3180 1010 857 3181 1014 857 3182 1011 859 3183 1012 860 3184 946 814 3185 1015 862 3186 945 813 3187 947 815 3188 1015 862 3189 1011 859 3190 945 813 3191 1016 863 3192 947 815 3193 948 816 3194 1016 863 3195 1015 862 3196 947 815 3197 1017 864 3198 948 816 3199 949 817 3200 1017 864 3201 1016 863 3202 948 816 3203 1018 865 3204 949 817 3205 950 818 3206 1018 865 3207 1017 864 3208 949 817 3209 1019 866 3210 950 818 3211 951 819 3212 1019 866 3213 1018 865 3214 950 818 3215 1020 867 3216 951 819 3217 952 820 3218 1020 867 3219 1019 866 3220 951 819 3221 1021 868 3222 952 820 3223 953 821 3224 1021 868 3225 1020 867 3226 952 820 3227 957 825 3228 953 821 3229 954 822 3230 957 825 3231 1021 868 3232 953 821 3233 1022 869 3234 957 825 3235 958 826 3236 1022 869 3237 958 826 3238 1023 870 3239 1024 871 3240 1025 872 3241 960 828 3242 1024 871 3243 960 828 3244 959 827 3245 1026 873 3246 1027 874 3247 1028 875 3248 1011 859 3249 1029 876 3250 1012 860 3251 1026 873 3252 1028 875 3253 1030 877 3254 1011 859 3255 1031 878 3256 1029 876 3257 1032 879 3258 1030 877 3259 1033 880 3260 1026 873 3261 1030 877 3262 1032 879 3263 1011 859 3264 1034 881 3265 1031 878 3266 1032 879 3267 1033 880 3268 1035 882 3269 1036 883 3270 1034 881 3271 1011 859 3272 1037 884 3273 1038 885 3274 1034 881 3275 1032 879 3276 1035 882 3277 1039 886 3278 1036 883 3279 1037 884 3280 1034 881 3281 1040 887 3282 1011 859 3283 1015 862 3284 1040 887 3285 1036 883 3286 1011 859 3287 1041 888 3288 1015 862 3289 1016 863 3290 1041 888 3291 1040 887 3292 1015 862 3293 1042 889 3294 1016 863 3295 1017 864 3296 1042 889 3297 1041 888 3298 1016 863 3299 1043 890 3300 1017 864 3301 1018 865 3302 1043 890 3303 1042 889 3304 1017 864 3305 1044 891 3306 1018 865 3307 1019 866 3308 1044 891 3309 1043 890 3310 1018 865 3311 1045 892 3312 1019 866 3313 1020 867 3314 1045 892 3315 1044 891 3316 1019 866 3317 1046 893 3318 1020 867 3319 1021 868 3320 1046 893 3321 1045 892 3322 1020 867 3323 1047 894 3324 1021 868 3325 957 825 3326 1047 894 3327 1046 893 3328 1021 868 3329 1022 869 3330 1047 894 3331 957 825 3332 1048 895 3333 1022 869 3334 1023 870 3335 1048 895 3336 1023 870 3337 1049 896 3338 1050 897 3339 1051 898 3340 1025 872 3341 1050 897 3342 1025 872 3343 1024 871 3344 1037 884 3345 1052 899 3346 1038 885 3347 1053 900 3348 1039 886 3349 1054 901 3350 1032 879 3351 1039 886 3352 1053 900 3353 1037 884 3354 1055 902 3355 1052 899 3356 1053 900 3357 1054 901 3358 1056 903 3359 1037 884 3360 1057 904 3361 1055 902 3362 1058 905 3363 1056 903 3364 1059 906 3365 1053 900 3366 1056 903 3367 1058 905 3368 1037 884 3369 1060 907 3370 1057 904 3371 1058 905 3372 1059 906 3373 1061 908 3374 1062 909 3375 1063 910 3376 1060 907 3377 1064 911 3378 1061 908 3379 1065 912 3380 1037 884 3381 1062 909 3382 1060 907 3383 1058 905 3384 1061 908 3385 1064 911 3386 1062 909 3387 1066 913 3388 1063 910 3389 1064 911 3390 1065 912 3391 1067 914 3392 1062 909 3393 1068 915 3394 1066 913 3395 1069 916 3396 1067 914 3397 1070 917 3398 1064 911 3399 1067 914 3400 1069 916 3401 1062 909 3402 1071 918 3403 1068 915 3404 1069 916 3405 1070 917 3406 1072 919 3407 1062 909 3408 1073 920 3409 1071 918 3410 1074 921 3411 1072 919 3412 1075 922 3413 1069 916 3414 1072 919 3415 1074 921 3416 1062 909 3417 1076 923 3418 1073 920 3419 1074 921 3420 1075 922 3421 1077 924 3422 1062 909 3423 985 853 3424 1076 923 3425 1078 925 3426 1076 923 3427 985 853 3428 1074 921 3429 1077 924 3430 1079 926 3431 1080 927 3432 981 849 3433 985 853 3434 1062 909 3435 1080 927 3436 985 853 3437 1081 928 3438 1078 925 3439 985 853 3440 1082 929 3441 1081 928 3442 985 853 3443 990 856 3444 1082 929 3445 985 853 3446 1083 930 3447 982 850 3448 981 849 3449 1084 931 3450 1083 930 3451 981 849 3452 1085 932 3453 1084 931 3454 981 849 3455 1080 927 3456 1085 932 3457 981 849 3458 1086 933 3459 1087 934 3460 1088 935 3461 1086 933 3462 1089 936 3463 1087 934 3464 1090 937 3465 1088 935 3466 1091 938 3467 1090 937 3468 1086 933 3469 1088 935 3470 1092 939 3471 1091 938 3472 1093 940 3473 1092 939 3474 1090 937 3475 1091 938 3476 1094 941 3477 1085 932 3478 1080 927 3479 1092 939 3480 1093 940 3481 1095 942 3482 1096 943 3483 1080 927 3484 1062 909 3485 1097 944 3486 1094 941 3487 1080 927 3488 1098 945 3489 1097 944 3490 1080 927 3491 1096 943 3492 1098 945 3493 1080 927 3494 1099 946 3495 1062 909 3496 1037 884 3497 1099 946 3498 1096 943 3499 1062 909 3500 1100 947 3501 1037 884 3502 1036 883 3503 1100 947 3504 1099 946 3505 1037 884 3506 1101 948 3507 1036 883 3508 1040 887 3509 1101 948 3510 1100 947 3511 1036 883 3512 1102 949 3513 1040 887 3514 1041 888 3515 1102 949 3516 1101 948 3517 1040 887 3518 1103 950 3519 1041 888 3520 1042 889 3521 1103 950 3522 1102 949 3523 1041 888 3524 1104 951 3525 1042 889 3526 1043 890 3527 1104 951 3528 1103 950 3529 1042 889 3530 1105 952 3531 1043 890 3532 1044 891 3533 1105 952 3534 1104 951 3535 1043 890 3536 1106 953 3537 1044 891 3538 1045 892 3539 1106 953 3540 1105 952 3541 1044 891 3542 1107 954 3543 1045 892 3544 1046 893 3545 1108 955 3546 1106 953 3547 1045 892 3548 1109 956 3549 1108 955 3550 1045 892 3551 1107 954 3552 1109 956 3553 1045 892 3554 1110 957 3555 1046 893 3556 1047 894 3557 1110 957 3558 1107 954 3559 1046 893 3560 1111 958 3561 1047 894 3562 1022 869 3563 1112 959 3564 1110 957 3565 1047 894 3566 1113 960 3567 1112 959 3568 1047 894 3569 1111 958 3570 1113 960 3571 1047 894 3572 1048 895 3573 1111 958 3574 1022 869 3575 1114 961 3576 1048 895 3577 1049 896 3578 1114 961 3579 1049 896 3580 1115 962 3581 1116 963 3582 1117 964 3583 1051 898 3584 1116 963 3585 1051 898 3586 1050 897 3587 1118 965 3588 1095 942 3589 1119 966 3590 1118 965 3591 1092 939 3592 1095 942 3593 1120 967 3594 1119 966 3595 1121 968 3596 1120 967 3597 1118 965 3598 1119 966 3599 1122 969 3600 1098 945 3601 1096 943 3602 1123 970 3603 1121 968 3604 1124 971 3605 1123 970 3606 1120 967 3607 1121 968 3608 1125 972 3609 1096 943 3610 1099 946 3611 1126 973 3612 1122 969 3613 1096 943 3614 1125 972 3615 1126 973 3616 1096 943 3617 1127 974 3618 1099 946 3619 1100 947 3620 1127 974 3621 1125 972 3622 1099 946 3623 1128 975 3624 1100 947 3625 1101 948 3626 1128 975 3627 1127 974 3628 1100 947 3629 1129 976 3630 1101 948 3631 1102 949 3632 1129 976 3633 1128 975 3634 1101 948 3635 1130 977 3636 1102 949 3637 1103 950 3638 1130 977 3639 1129 976 3640 1102 949 3641 1131 978 3642 1103 950 3643 1104 951 3644 1131 978 3645 1130 977 3646 1103 950 3647 1132 979 3648 1104 951 3649 1105 952 3650 1132 979 3651 1131 978 3652 1104 951 3653 1133 980 3654 1105 952 3655 1106 953 3656 1134 981 3657 1135 982 3658 1105 952 3659 1136 983 3660 1105 952 3661 1135 982 3662 1137 984 3663 1134 981 3664 1105 952 3665 1133 980 3666 1137 984 3667 1105 952 3668 1136 983 3669 1132 979 3670 1105 952 3671 1138 985 3672 1139 986 3673 1140 987 3674 1138 985 3675 1141 988 3676 1139 986 3677 1138 985 3678 1140 987 3679 1142 989 3680 1143 990 3681 1144 990 3682 1145 990 3683 1146 991 3684 1144 991 3685 1143 991 3686 1138 985 3687 1142 989 3688 1147 992 3689 1148 223 3690 1149 223 3691 1150 223 3692 1151 223 3693 1152 223 3694 1149 223 3695 1153 223 3696 1151 223 3697 1149 223 3698 1148 223 3699 1153 223 3700 1149 223 3701 1154 223 3702 1150 223 3703 1155 223 3704 1156 223 3705 1148 223 3706 1150 223 3707 1154 223 3708 1156 223 3709 1150 223 3710 1157 993 3711 1113 960 3712 1111 958 3713 1154 223 3714 1155 223 3715 1158 223 3716 1114 961 3717 1111 958 3718 1048 895 3719 1159 994 3720 1157 993 3721 1111 958 3722 1114 961 3723 1159 994 3724 1111 958 3725 1160 995 3726 1114 961 3727 1115 962 3728 1160 995 3729 1115 962 3730 1161 996 3731 1162 997 3732 1163 998 3733 1117 964 3734 1162 997 3735 1117 964 3736 1116 963 3737 1164 999 3738 1165 1000 3739 1157 993 3740 1166 1001 3741 1167 1001 3742 1168 1001 3743 1159 994 3744 1164 999 3745 1157 993 3746 1164 999 3747 1169 1002 3748 1165 1000 3749 1166 1003 3750 1168 1003 3751 1170 1003 3752 1171 1004 3753 1172 1005 3754 1169 1002 3755 1173 1006 3756 1174 1007 3757 1175 1008 3758 1164 999 3759 1171 1004 3760 1169 1002 3761 1171 1004 3762 1176 1009 3763 1172 1005 3764 1173 1006 3765 1175 1008 3766 1177 1010 3767 1171 1004 3768 1178 1011 3769 1176 1009 3770 1179 1012 3771 1177 1010 3772 1180 1013 3773 1173 1006 3774 1177 1010 3775 1179 1012 3776 1136 983 3777 1181 1014 3778 1178 1011 3779 1179 1012 3780 1180 1013 3781 1182 1015 3782 1171 1004 3783 1136 983 3784 1178 1011 3785 1136 983 3786 1183 1016 3787 1181 1014 3788 1184 1017 3789 1182 1015 3790 1185 1018 3791 1179 1012 3792 1182 1015 3793 1184 1017 3794 1136 983 3795 1186 1019 3796 1183 1016 3797 1184 1017 3798 1185 1018 3799 1187 1020 3800 1136 983 3801 1188 1021 3802 1186 1019 3803 1189 1022 3804 1187 1020 3805 1190 1023 3806 1184 1017 3807 1187 1020 3808 1189 1022 3809 1136 983 3810 1191 1024 3811 1188 1021 3812 1189 1022 3813 1190 1023 3814 1192 1025 3815 1136 983 3816 1193 1026 3817 1191 1024 3818 1194 1027 3819 1192 1025 3820 1195 1028 3821 1189 1022 3822 1192 1025 3823 1194 1027 3824 1136 983 3825 1196 1029 3826 1193 1026 3827 1194 1027 3828 1195 1028 3829 1197 1030 3830 1136 983 3831 1135 982 3832 1196 1029 3833 1198 1031 3834 1197 1030 3835 1199 1032 3836 1194 1027 3837 1197 1030 3838 1198 1031 3839 1200 1033 3840 1199 1032 3841 1201 1034 3842 1198 1031 3843 1199 1032 3844 1200 1033 3845 1200 1033 3846 1201 1034 3847 1202 1035 3848 1138 985 3849 1202 1035 3850 1141 988 3851 1200 1033 3852 1202 1035 3853 1138 985 3854 1203 1036 3855 1124 971 3856 1204 1037 3857 1203 1036 3858 1123 970 3859 1124 971 3860 1205 1038 3861 1126 973 3862 1125 972 3863 1205 1038 3864 1206 1039 3865 1126 973 3866 1207 1040 3867 1204 1037 3868 1208 1041 3869 1207 1040 3870 1203 1036 3871 1204 1037 3872 1209 1042 3873 1125 972 3874 1127 974 3875 1209 1042 3876 1205 1038 3877 1125 972 3878 1210 1043 3879 1127 974 3880 1128 975 3881 1210 1043 3882 1209 1042 3883 1127 974 3884 1211 1044 3885 1128 975 3886 1129 976 3887 1211 1044 3888 1210 1043 3889 1128 975 3890 1212 1045 3891 1129 976 3892 1130 977 3893 1212 1045 3894 1211 1044 3895 1129 976 3896 1213 1046 3897 1130 977 3898 1131 978 3899 1213 1046 3900 1212 1045 3901 1130 977 3902 1214 1047 3903 1131 978 3904 1132 979 3905 1214 1047 3906 1213 1046 3907 1131 978 3908 1215 1048 3909 1132 979 3910 1136 983 3911 1215 1048 3912 1214 1047 3913 1132 979 3914 1216 1049 3915 1136 983 3916 1171 1004 3917 1216 1049 3918 1215 1048 3919 1136 983 3920 1217 1050 3921 1171 1004 3922 1164 999 3923 1217 1050 3924 1216 1049 3925 1171 1004 3926 1218 1051 3927 1164 999 3928 1159 994 3929 1218 1051 3930 1217 1050 3931 1164 999 3932 1219 1052 3933 1159 994 3934 1114 961 3935 1219 1052 3936 1218 1051 3937 1159 994 3938 1160 995 3939 1219 1052 3940 1114 961 3941 1220 1053 3942 1160 995 3943 1161 996 3944 1220 1053 3945 1161 996 3946 1221 1054 3947 1222 1055 3948 1223 1056 3949 1163 998 3950 1222 1055 3951 1163 998 3952 1162 997 3953 1205 1038 3954 1224 1057 3955 1206 1039 3956 1225 1058 3957 1208 1041 3958 1226 1059 3959 1225 1058 3960 1207 1040 3961 1208 1041 3962 1227 1060 3963 1224 1057 3964 1205 1038 3965 1227 1060 3966 1228 1061 3967 1224 1057 3968 1229 1062 3969 1226 1059 3970 1230 1063 3971 1229 1062 3972 1225 1058 3973 1226 1059 3974 1231 1064 3975 1205 1038 3976 1209 1042 3977 1231 1064 3978 1227 1060 3979 1205 1038 3980 1232 1065 3981 1209 1042 3982 1210 1043 3983 1232 1065 3984 1231 1064 3985 1209 1042 3986 1233 1066 3987 1210 1043 3988 1211 1044 3989 1233 1066 3990 1232 1065 3991 1210 1043 3992 1234 1067 3993 1211 1044 3994 1212 1045 3995 1234 1067 3996 1233 1066 3997 1211 1044 3998 1235 1068 3999 1212 1045 4000 1213 1046 4001 1235 1068 4002 1234 1067 4003 1212 1045 4004 1236 1069 4005 1213 1046 4006 1214 1047 4007 1236 1069 4008 1235 1068 4009 1213 1046 4010 1237 1070 4011 1214 1047 4012 1215 1048 4013 1237 1070 4014 1236 1069 4015 1214 1047 4016 1238 1071 4017 1215 1048 4018 1216 1049 4019 1238 1071 4020 1237 1070 4021 1215 1048 4022 1239 1072 4023 1216 1049 4024 1217 1050 4025 1239 1072 4026 1238 1071 4027 1216 1049 4028 1240 1073 4029 1217 1050 4030 1218 1051 4031 1240 1073 4032 1239 1072 4033 1217 1050 4034 1241 1074 4035 1218 1051 4036 1219 1052 4037 1241 1074 4038 1240 1073 4039 1218 1051 4040 1220 1053 4041 1219 1052 4042 1160 995 4043 1220 1053 4044 1241 1074 4045 1219 1052 4046 694 572 4047 1220 1053 4048 1221 1054 4049 694 572 4050 1221 1054 4051 690 568 4052 1242 1075 4053 692 570 4054 1223 1056 4055 1242 1075 4056 1223 1056 4057 1222 1055 4058 1227 1060 4059 1243 1076 4060 1228 1061 4061 1244 1077 4062 1230 1063 4063 1245 1078 4064 1244 1077 4065 1229 1062 4066 1230 1063 4067 715 593 4068 1243 1076 4069 1227 1060 4070 715 593 4071 1246 1079 4072 1243 1076 4073 1247 1080 4074 1245 1078 4075 1248 1081 4076 1247 1080 4077 1244 1077 4078 1245 1078 4079 714 592 4080 1227 1060 4081 1231 1064 4082 714 592 4083 715 593 4084 1227 1060 4085 713 591 4086 1231 1064 4087 1232 1065 4088 713 591 4089 714 592 4090 1231 1064 4091 711 589 4092 1232 1065 4093 1233 1066 4094 711 589 4095 713 591 4096 1232 1065 4097 712 590 4098 1233 1066 4099 1234 1067 4100 712 590 4101 711 589 4102 1233 1066 4103 710 588 4104 1234 1067 4105 1235 1068 4106 710 588 4107 712 590 4108 1234 1067 4109 709 587 4110 1235 1068 4111 1236 1069 4112 709 587 4113 710 588 4114 1235 1068 4115 708 586 4116 1236 1069 4117 1237 1070 4118 708 586 4119 709 587 4120 1236 1069 4121 707 585 4122 1237 1070 4123 1238 1071 4124 707 585 4125 708 586 4126 1237 1070 4127 699 577 4128 1238 1071 4129 1239 1072 4130 699 577 4131 707 585 4132 1238 1071 4133 700 578 4134 1239 1072 4135 1240 1073 4136 700 578 4137 699 577 4138 1239 1072 4139 1249 1082 4140 1240 1073 4141 1241 1074 4142 1250 1083 4143 700 578 4144 1240 1073 4145 1251 1084 4146 1250 1083 4147 1240 1073 4148 1252 1085 4149 1251 1084 4150 1240 1073 4151 1253 1086 4152 1252 1085 4153 1240 1073 4154 1249 1082 4155 1253 1086 4156 1240 1073 4157 1254 1087 4158 1241 1074 4159 1220 1053 4160 1255 1088 4161 1249 1082 4162 1241 1074 4163 1256 1089 4164 1255 1088 4165 1241 1074 4166 1257 1090 4167 1256 1089 4168 1241 1074 4169 1254 1087 4170 1257 1090 4171 1241 1074 4172 1258 1091 4173 1254 1087 4174 1220 1053 4175 1259 1092 4176 1258 1091 4177 1220 1053 4178 694 572 4179 1259 1092 4180 1220 1053 4181 691 569 4182 692 570 4183 1242 1075 4184 715 593 4185 717 595 4186 1246 1079 4187 1260 1093 4188 1248 1081 4189 1261 1094 4190 1260 1093 4191 1247 1080 4192 1248 1081 4193 593 471 4194 1261 1094 4195 718 596 4196 593 471 4197 1260 1093 4198 1261 1094 4199 1262 1095 4200 1263 1096 4201 1264 1097 4202 1262 1095 4203 1265 1098 4204 1263 1096 4205 1266 1099 4206 1264 1097 4207 1267 1100 4208 1262 1095 4209 1264 1097 4210 1266 1099 4211 1268 1101 4212 1267 1100 4213 1269 1102 4214 1266 1099 4215 1267 1100 4216 1268 1101 4217 1268 1101 4218 1269 1102 4219 1270 1103 4220 1271 1104 4221 1270 1103 4222 1272 1105 4223 1268 1101 4224 1270 1103 4225 1271 1104 4226 1271 1104 4227 1272 1105 4228 1273 1106 4229 1274 1107 4230 1273 1106 4231 1275 1108 4232 1271 1104 4233 1273 1106 4234 1274 1107 4235 1274 1107 4236 1275 1108 4237 1276 1109 4238 1277 1110 4239 1278 1110 4240 1279 1110 4241 1280 1111 4242 1278 1111 4243 1277 1111 4244 1274 1107 4245 1276 1109 4246 1281 1112 4247 1282 223 4248 1283 223 4249 1284 223 4250 1282 223 4251 1285 223 4252 1283 223 4253 1286 1113 4254 1259 1092 4255 694 572 4256 1282 223 4257 1284 223 4258 1287 223 4259 693 571 4260 1286 1113 4261 694 572 4262 1282 223 4263 1287 223 4264 1288 223 4265 1289 1114 4266 1290 1114 4267 1291 1114 4268 1289 1115 4269 1291 1115 4270 1292 1115 4271 1293 1116 4272 1294 1117 4273 1295 1118 4274 1293 1116 4275 1295 1118 4276 1296 1119 4277 1297 1120 4278 1296 1119 4279 1298 1121 4280 1293 1116 4281 1296 1119 4282 1297 1120 4283 1297 1120 4284 1298 1121 4285 1299 1122 4286 1297 1120 4287 1299 1122 4288 1300 1123 4289 1301 1124 4290 1300 1123 4291 1302 1125 4292 1297 1120 4293 1300 1123 4294 1301 1124 4295 1301 1124 4296 1302 1125 4297 1303 1126 4298 1262 1095 4299 1303 1126 4300 1265 1098 4301 1301 1124 4302 1303 1126 4303 1262 1095 4304 1304 1127 4305 653 531 4306 1305 1128 4307 652 530 4308 653 531 4309 1304 1127 4310 1306 1129 4311 1305 1128 4312 1307 1130 4313 1304 1127 4314 1305 1128 4315 1306 1129 4316 1308 1131 4317 1307 1130 4318 1309 1132 4319 1306 1129 4320 1307 1130 4321 1308 1131 4322 818 694 4323 1309 1132 4324 819 695 4325 1308 1131 4326 1309 1132 4327 818 694 4328 1310 1133 4329 979 847 4330 1089 936 4331 1086 933 4332 1310 1133 4333 1089 936 4334 1311 1134 4335 1079 926 4336 1312 1135 4337 1074 921 4338 1079 926 4339 1311 1134 4340 1311 1134 4341 1312 1135 4342 1313 1136 4343 1311 1134 4344 1313 1136 4345 1314 1137 4346 1311 1134 4347 1314 1137 4348 1315 1138 4349 1310 1133 4350 976 844 4351 979 847 4352 379 319 4353 380 320 4354 1316 1139 4355 1317 1140 4356 382 322 4357 386 326 4358 1318 1141 4359 1316 1139 4360 1319 1142 4361 1318 1141 4362 379 319 4363 1316 1139 4364 1320 1143 4365 386 326 4366 393 333 4367 1321 1144 4368 1317 1140 4369 386 326 4370 1320 1143 4371 1321 1144 4372 386 326 4373 1322 1145 4374 393 333 4375 400 340 4376 1322 1145 4377 1320 1143 4378 393 333 4379 1323 1146 4380 400 340 4381 407 347 4382 1323 1146 4383 1322 1145 4384 400 340 4385 1324 1147 4386 407 347 4387 411 351 4388 1324 1147 4389 1323 1146 4390 407 347 4391 1325 1148 4392 411 351 4393 417 357 4394 1325 1148 4395 1324 1147 4396 411 351 4397 1326 1149 4398 417 357 4399 424 364 4400 1326 1149 4401 1325 1148 4402 417 357 4403 1327 1150 4404 424 364 4405 431 371 4406 1327 1150 4407 1326 1149 4408 424 364 4409 1328 1151 4410 431 371 4411 438 378 4412 1328 1151 4413 1327 1150 4414 431 371 4415 1329 1152 4416 438 378 4417 442 382 4418 1329 1152 4419 1328 1151 4420 438 378 4421 1330 1153 4422 442 382 4423 448 388 4424 1330 1153 4425 1329 1152 4426 442 382 4427 1331 1154 4428 448 388 4429 455 395 4430 1331 1154 4431 1330 1153 4432 448 388 4433 1332 1155 4434 455 395 4435 462 402 4436 1332 1155 4437 1331 1154 4438 455 395 4439 845 721 4440 462 402 4441 208 165 4442 845 721 4443 1332 1155 4444 462 402 4445 1333 1156 4446 1319 1142 4447 1334 1157 4448 1333 1156 4449 1318 1141 4450 1319 1142 4451 1335 1158 4452 1321 1144 4453 1320 1143 4454 1336 1159 4455 1334 1157 4456 1337 1160 4457 1336 1159 4458 1333 1156 4459 1334 1157 4460 1338 1161 4461 1320 1143 4462 1322 1145 4463 1339 1162 4464 1335 1158 4465 1320 1143 4466 1338 1161 4467 1339 1162 4468 1320 1143 4469 1340 1163 4470 1322 1145 4471 1323 1146 4472 1340 1163 4473 1338 1161 4474 1322 1145 4475 1341 1164 4476 1323 1146 4477 1324 1147 4478 1341 1164 4479 1340 1163 4480 1323 1146 4481 1342 1165 4482 1324 1147 4483 1325 1148 4484 1342 1165 4485 1341 1164 4486 1324 1147 4487 1343 1166 4488 1325 1148 4489 1326 1149 4490 1343 1166 4491 1342 1165 4492 1325 1148 4493 1344 1167 4494 1326 1149 4495 1327 1150 4496 1344 1167 4497 1343 1166 4498 1326 1149 4499 1345 1168 4500 1327 1150 4501 1328 1151 4502 1345 1168 4503 1344 1167 4504 1327 1150 4505 1346 1169 4506 1328 1151 4507 1329 1152 4508 1346 1169 4509 1345 1168 4510 1328 1151 4511 1347 1170 4512 1329 1152 4513 1330 1153 4514 1347 1170 4515 1346 1169 4516 1329 1152 4517 1348 1171 4518 1330 1153 4519 1331 1154 4520 1348 1171 4521 1347 1170 4522 1330 1153 4523 1349 1172 4524 1331 1154 4525 1332 1155 4526 1349 1172 4527 1348 1171 4528 1331 1154 4529 1350 1173 4530 1332 1155 4531 845 721 4532 1350 1173 4533 1349 1172 4534 1332 1155 4535 808 684 4536 1350 1173 4537 845 721 4538 1351 1174 4539 1337 1160 4540 1352 1175 4541 1351 1174 4542 1336 1159 4543 1337 1160 4544 1353 1176 4545 1339 1162 4546 1338 1161 4547 1354 1177 4548 1352 1175 4549 1355 1178 4550 1354 1177 4551 1351 1174 4552 1352 1175 4553 1356 1179 4554 1338 1161 4555 1340 1163 4556 1357 1180 4557 1353 1176 4558 1338 1161 4559 1356 1179 4560 1357 1180 4561 1338 1161 4562 1358 1181 4563 1340 1163 4564 1341 1164 4565 1358 1181 4566 1356 1179 4567 1340 1163 4568 1359 1182 4569 1341 1164 4570 1342 1165 4571 1359 1182 4572 1358 1181 4573 1341 1164 4574 1360 1183 4575 1342 1165 4576 1343 1166 4577 1360 1183 4578 1359 1182 4579 1342 1165 4580 1361 1184 4581 1343 1166 4582 1344 1167 4583 1361 1184 4584 1360 1183 4585 1343 1166 4586 1362 1185 4587 1344 1167 4588 1345 1168 4589 1362 1185 4590 1361 1184 4591 1344 1167 4592 1363 1186 4593 1345 1168 4594 1346 1169 4595 1363 1186 4596 1362 1185 4597 1345 1168 4598 1364 1187 4599 1346 1169 4600 1347 1170 4601 1364 1187 4602 1363 1186 4603 1346 1169 4604 1365 1188 4605 1347 1170 4606 1348 1171 4607 1365 1188 4608 1364 1187 4609 1347 1170 4610 1366 1189 4611 1348 1171 4612 1349 1172 4613 1366 1189 4614 1365 1188 4615 1348 1171 4616 1367 1190 4617 1349 1172 4618 1350 1173 4619 1367 1190 4620 1366 1189 4621 1349 1172 4622 1368 1191 4623 1350 1173 4624 808 684 4625 1368 1191 4626 1367 1190 4627 1350 1173 4628 804 680 4629 1368 1191 4630 808 684 4631 1369 1192 4632 1355 1178 4633 1370 1193 4634 1369 1192 4635 1354 1177 4636 1355 1178 4637 1371 1194 4638 1357 1180 4639 1356 1179 4640 1369 1192 4641 1370 1193 4642 1372 1195 4643 1373 1196 4644 1356 1179 4645 1358 1181 4646 1374 1197 4647 1371 1194 4648 1356 1179 4649 1373 1196 4650 1374 1197 4651 1356 1179 4652 1375 1198 4653 1358 1181 4654 1359 1182 4655 1375 1198 4656 1373 1196 4657 1358 1181 4658 1376 1199 4659 1359 1182 4660 1360 1183 4661 1376 1199 4662 1375 1198 4663 1359 1182 4664 1377 1200 4665 1360 1183 4666 1361 1184 4667 1377 1200 4668 1376 1199 4669 1360 1183 4670 1378 1201 4671 1361 1184 4672 1362 1185 4673 1378 1201 4674 1377 1200 4675 1361 1184 4676 1379 1202 4677 1362 1185 4678 1363 1186 4679 1379 1202 4680 1378 1201 4681 1362 1185 4682 1380 1203 4683 1363 1186 4684 1364 1187 4685 1380 1203 4686 1379 1202 4687 1363 1186 4688 1381 1204 4689 1364 1187 4690 1365 1188 4691 1381 1204 4692 1380 1203 4693 1364 1187 4694 1382 1205 4695 1365 1188 4696 1366 1189 4697 1382 1205 4698 1381 1204 4699 1365 1188 4700 1383 1206 4701 1366 1189 4702 1367 1190 4703 1383 1206 4704 1382 1205 4705 1366 1189 4706 1384 1207 4707 1367 1190 4708 1368 1191 4709 1384 1207 4710 1383 1206 4711 1367 1190 4712 1385 1208 4713 1368 1191 4714 804 680 4715 1385 1208 4716 1384 1207 4717 1368 1191 4718 687 565 4719 1385 1208 4720 804 680 4721 1386 1209 4722 1372 1195 4723 1387 1210 4724 1386 1209 4725 1369 1192 4726 1372 1195 4727 1388 1211 4728 1374 1197 4729 1373 1196 4730 1389 1212 4731 1387 1210 4732 1390 1213 4733 1389 1212 4734 1386 1209 4735 1387 1210 4736 1391 1214 4737 1373 1196 4738 1375 1198 4739 1392 1215 4740 1388 1211 4741 1373 1196 4742 1391 1214 4743 1392 1215 4744 1373 1196 4745 1393 1216 4746 1375 1198 4747 1376 1199 4748 1393 1216 4749 1391 1214 4750 1375 1198 4751 1394 1217 4752 1376 1199 4753 1377 1200 4754 1394 1217 4755 1393 1216 4756 1376 1199 4757 1395 1218 4758 1377 1200 4759 1378 1201 4760 1395 1218 4761 1394 1217 4762 1377 1200 4763 1396 1219 4764 1378 1201 4765 1379 1202 4766 1396 1219 4767 1395 1218 4768 1378 1201 4769 1397 1220 4770 1379 1202 4771 1380 1203 4772 1397 1220 4773 1396 1219 4774 1379 1202 4775 1398 1221 4776 1380 1203 4777 1381 1204 4778 1398 1221 4779 1397 1220 4780 1380 1203 4781 1399 1222 4782 1381 1204 4783 1382 1205 4784 1399 1222 4785 1398 1221 4786 1381 1204 4787 1400 1223 4788 1382 1205 4789 1383 1206 4790 1400 1223 4791 1399 1222 4792 1382 1205 4793 1401 1224 4794 1383 1206 4795 1384 1207 4796 1401 1224 4797 1400 1223 4798 1383 1206 4799 1402 1225 4800 1384 1207 4801 1385 1208 4802 1402 1225 4803 1401 1224 4804 1384 1207 4805 683 561 4806 1385 1208 4807 687 565 4808 683 561 4809 1402 1225 4810 1385 1208 4811 1403 1226 4812 1404 1227 4813 1388 1211 4814 1405 1228 4815 1390 1213 4816 1406 1229 4817 1392 1215 4818 1403 1226 4819 1388 1211 4820 1405 1228 4821 1389 1212 4822 1390 1213 4823 1407 1230 4824 1408 1231 4825 1409 1232 4826 1410 1233 4827 1406 1229 4828 1411 1234 4829 1410 1233 4830 1405 1228 4831 1406 1229 4832 1412 1235 4833 1403 1226 4834 1392 1215 4835 1407 1230 4836 1409 1232 4837 1413 1236 4838 1414 1237 4839 1392 1215 4840 1391 1214 4841 1415 1238 4842 1392 1215 4843 1414 1237 4844 1412 1235 4845 1392 1215 4846 1415 1238 4847 1416 1239 4848 1391 1214 4849 1393 1216 4850 1414 1237 4851 1391 1214 4852 1416 1239 4853 1417 1240 4854 1393 1216 4855 1394 1217 4856 1416 1239 4857 1393 1216 4858 1417 1240 4859 1418 1241 4860 1394 1217 4861 1395 1218 4862 1417 1240 4863 1394 1217 4864 1418 1241 4865 1419 1242 4866 1395 1218 4867 1396 1219 4868 1418 1241 4869 1395 1218 4870 1419 1242 4871 1420 1243 4872 1396 1219 4873 1397 1220 4874 1419 1242 4875 1396 1219 4876 1420 1243 4877 1421 1244 4878 1397 1220 4879 1398 1221 4880 1420 1243 4881 1397 1220 4882 1421 1244 4883 1422 1245 4884 1398 1221 4885 1399 1222 4886 1421 1244 4887 1398 1221 4888 1422 1245 4889 1423 1246 4890 1399 1222 4891 1400 1223 4892 1422 1245 4893 1399 1222 4894 1423 1246 4895 1424 1247 4896 1400 1223 4897 1401 1224 4898 1423 1246 4899 1400 1223 4900 1424 1247 4901 1425 1248 4902 1401 1224 4903 1402 1225 4904 1424 1247 4905 1401 1224 4906 1425 1248 4907 1426 1249 4908 1402 1225 4909 683 561 4910 1425 1248 4911 1402 1225 4912 1426 1249 4913 1426 1249 4914 683 561 4915 691 569 4916 1427 1250 4917 904 772 4918 877 745 4919 1428 1251 4920 1427 1250 4921 877 745 4922 925 793 4923 1428 1251 4924 877 745 4925 1429 1252 4926 905 773 4927 904 772 4928 1427 1250 4929 1429 1252 4930 904 772 4931 1430 1253 4932 906 774 4933 905 773 4934 1431 1254 4935 1430 1253 4936 905 773 4937 1429 1252 4938 1431 1254 4939 905 773 4940 1432 1255 4941 907 775 4942 906 774 4943 1430 1253 4944 1432 1255 4945 906 774 4946 1433 1256 4947 908 776 4948 907 775 4949 1432 1255 4950 1433 1256 4951 907 775 4952 1434 1257 4953 909 777 4954 908 776 4955 1435 1258 4956 1434 1257 4957 908 776 4958 1433 1256 4959 1435 1258 4960 908 776 4961 1436 1259 4962 910 778 4963 909 777 4964 1434 1257 4965 1436 1259 4966 909 777 4967 1437 1260 4968 911 779 4969 910 778 4970 1436 1259 4971 1437 1260 4972 910 778 4973 1438 1261 4974 912 780 4975 911 779 4976 1437 1260 4977 1438 1261 4978 911 779 4979 1439 1262 4980 913 781 4981 912 780 4982 1438 1261 4983 1439 1262 4984 912 780 4985 1440 1263 4986 914 782 4987 913 781 4988 1439 1262 4989 1440 1263 4990 913 781 4991 1441 1264 4992 915 783 4993 914 782 4994 1440 1263 4995 1441 1264 4996 914 782 4997 1442 1265 4998 916 784 4999 915 783 5000 1441 1264 5001 1442 1265 5002 915 783 5003 1443 1266 5004 917 785 5005 916 784 5006 1442 1265 5007 1443 1266 5008 916 784 5009 1444 1267 5010 918 786 5011 917 785 5012 1443 1266 5013 1444 1267 5014 917 785 5015 1445 1268 5016 919 787 5017 918 786 5018 1444 1267 5019 1445 1268 5020 918 786 5021 1446 1269 5022 920 788 5023 919 787 5024 1445 1268 5025 1446 1269 5026 919 787 5027 1447 1270 5028 921 789 5029 920 788 5030 1446 1269 5031 1447 1270 5032 920 788 5033 1448 1271 5034 922 790 5035 921 789 5036 1447 1270 5037 1448 1271 5038 921 789 5039 959 827 5040 902 770 5041 922 790 5042 1448 1271 5043 959 827 5044 922 790 5045 1449 1272 5046 959 827 5047 1448 1271 5048 1449 1272 5049 1024 871 5050 959 827 5051 1450 1273 5052 1448 1271 5053 1447 1270 5054 1450 1273 5055 1449 1272 5056 1448 1271 5057 1451 1274 5058 1447 1270 5059 1446 1269 5060 1451 1274 5061 1450 1273 5062 1447 1270 5063 1452 1275 5064 1446 1269 5065 1445 1268 5066 1452 1275 5067 1451 1274 5068 1446 1269 5069 1453 1276 5070 1445 1268 5071 1444 1267 5072 1453 1276 5073 1452 1275 5074 1445 1268 5075 1454 1277 5076 1444 1267 5077 1443 1266 5078 1454 1277 5079 1453 1276 5080 1444 1267 5081 1455 1278 5082 1443 1266 5083 1442 1265 5084 1455 1278 5085 1454 1277 5086 1443 1266 5087 1456 1279 5088 1442 1265 5089 1441 1264 5090 1456 1279 5091 1455 1278 5092 1442 1265 5093 1457 1280 5094 1441 1264 5095 1440 1263 5096 1457 1280 5097 1456 1279 5098 1441 1264 5099 1458 1281 5100 1440 1263 5101 1439 1262 5102 1458 1281 5103 1457 1280 5104 1440 1263 5105 1459 1282 5106 1439 1262 5107 1438 1261 5108 1459 1282 5109 1458 1281 5110 1439 1262 5111 1460 1283 5112 1438 1261 5113 1437 1260 5114 1460 1283 5115 1459 1282 5116 1438 1261 5117 1461 1284 5118 1437 1260 5119 1436 1259 5120 1461 1284 5121 1460 1283 5122 1437 1260 5123 1462 1285 5124 1436 1259 5125 1434 1257 5126 1463 1286 5127 1436 1259 5128 1462 1285 5129 1463 1286 5130 1461 1284 5131 1436 1259 5132 1464 1287 5133 1465 1288 5134 1466 1289 5135 1467 1290 5136 1468 1291 5137 1465 1288 5138 1464 1287 5139 1467 1290 5140 1465 1288 5141 1464 1287 5142 1466 1289 5143 1469 1292 5144 1470 1293 5145 1469 1292 5146 1471 1294 5147 1470 1293 5148 1464 1287 5149 1469 1292 5150 1470 1293 5151 1471 1294 5152 1472 1295 5153 1470 1293 5154 1472 1295 5155 1473 1296 5156 964 832 5157 1473 1296 5158 1474 1297 5159 964 832 5160 1470 1293 5161 1473 1296 5162 964 832 5163 1474 1297 5164 1475 1298 5165 964 832 5166 1475 1298 5167 1476 1299 5168 964 832 5169 1476 1299 5170 965 833 5171 1467 1290 5172 1477 1300 5173 1468 1291 5174 1478 1301 5175 1024 871 5176 1449 1272 5177 1478 1301 5178 1050 897 5179 1024 871 5180 1479 1302 5181 1449 1272 5182 1450 1273 5183 1479 1302 5184 1478 1301 5185 1449 1272 5186 1480 1303 5187 1450 1273 5188 1451 1274 5189 1480 1303 5190 1479 1302 5191 1450 1273 5192 1481 1304 5193 1451 1274 5194 1452 1275 5195 1481 1304 5196 1480 1303 5197 1451 1274 5198 1482 1305 5199 1452 1275 5200 1453 1276 5201 1482 1305 5202 1481 1304 5203 1452 1275 5204 1483 1306 5205 1453 1276 5206 1454 1277 5207 1483 1306 5208 1482 1305 5209 1453 1276 5210 1484 1307 5211 1454 1277 5212 1455 1278 5213 1484 1307 5214 1483 1306 5215 1454 1277 5216 1485 1308 5217 1455 1278 5218 1456 1279 5219 1485 1308 5220 1484 1307 5221 1455 1278 5222 1486 1309 5223 1456 1279 5224 1457 1280 5225 1486 1309 5226 1485 1308 5227 1456 1279 5228 1487 1310 5229 1457 1280 5230 1458 1281 5231 1487 1310 5232 1486 1309 5233 1457 1280 5234 1488 1311 5235 1458 1281 5236 1459 1282 5237 1488 1311 5238 1487 1310 5239 1458 1281 5240 1489 1312 5241 1459 1282 5242 1460 1283 5243 1489 1312 5244 1488 1311 5245 1459 1282 5246 1490 1313 5247 1460 1283 5248 1461 1284 5249 1491 1314 5250 1460 1283 5251 1490 1313 5252 1492 1315 5253 1489 1312 5254 1460 1283 5255 1491 1314 5256 1492 1315 5257 1460 1283 5258 1493 1316 5259 1494 1317 5260 1477 1300 5261 1495 1318 5262 1496 1319 5263 1494 1317 5264 1493 1316 5265 1495 1318 5266 1494 1317 5267 1467 1290 5268 1493 1316 5269 1477 1300 5270 1495 1318 5271 1497 1320 5272 1496 1319 5273 1498 1321 5274 1050 897 5275 1478 1301 5276 1498 1321 5277 1116 963 5278 1050 897 5279 1499 1322 5280 1478 1301 5281 1479 1302 5282 1499 1322 5283 1498 1321 5284 1478 1301 5285 1500 1323 5286 1479 1302 5287 1480 1303 5288 1500 1323 5289 1499 1322 5290 1479 1302 5291 1501 1324 5292 1480 1303 5293 1481 1304 5294 1501 1324 5295 1500 1323 5296 1480 1303 5297 1502 1325 5298 1481 1304 5299 1482 1305 5300 1502 1325 5301 1501 1324 5302 1481 1304 5303 1503 1326 5304 1482 1305 5305 1483 1306 5306 1503 1326 5307 1502 1325 5308 1482 1305 5309 1504 1327 5310 1483 1306 5311 1484 1307 5312 1504 1327 5313 1503 1326 5314 1483 1306 5315 1505 1328 5316 1484 1307 5317 1485 1308 5318 1505 1328 5319 1504 1327 5320 1484 1307 5321 1506 1329 5322 1485 1308 5323 1486 1309 5324 1506 1329 5325 1505 1328 5326 1485 1308 5327 1507 1330 5328 1486 1309 5329 1487 1310 5330 1507 1330 5331 1506 1329 5332 1486 1309 5333 1508 1331 5334 1487 1310 5335 1488 1311 5336 1508 1331 5337 1507 1330 5338 1487 1310 5339 1509 1332 5340 1488 1311 5341 1489 1312 5342 1509 1332 5343 1508 1331 5344 1488 1311 5345 1510 1333 5346 1489 1312 5347 1492 1315 5348 1511 1334 5349 1489 1312 5350 1510 1333 5351 1512 1335 5352 1509 1332 5353 1489 1312 5354 1511 1334 5355 1512 1335 5356 1489 1312 5357 1513 1336 5358 1514 1337 5359 1497 1320 5360 1515 1338 5361 1516 1339 5362 1514 1337 5363 1513 1336 5364 1515 1338 5365 1514 1337 5366 1495 1318 5367 1513 1336 5368 1497 1320 5369 1515 1338 5370 1517 1340 5371 1516 1339 5372 1162 997 5373 1116 963 5374 1498 1321 5375 1518 1341 5376 1498 1321 5377 1499 1322 5378 1518 1341 5379 1162 997 5380 1498 1321 5381 1519 1342 5382 1499 1322 5383 1500 1323 5384 1519 1342 5385 1518 1341 5386 1499 1322 5387 1520 1343 5388 1500 1323 5389 1501 1324 5390 1520 1343 5391 1519 1342 5392 1500 1323 5393 1521 1344 5394 1501 1324 5395 1502 1325 5396 1521 1344 5397 1520 1343 5398 1501 1324 5399 1522 1345 5400 1502 1325 5401 1503 1326 5402 1522 1345 5403 1521 1344 5404 1502 1325 5405 1523 1346 5406 1503 1326 5407 1504 1327 5408 1523 1346 5409 1522 1345 5410 1503 1326 5411 1524 1347 5412 1504 1327 5413 1505 1328 5414 1524 1347 5415 1523 1346 5416 1504 1327 5417 1525 1348 5418 1505 1328 5419 1506 1329 5420 1525 1348 5421 1524 1347 5422 1505 1328 5423 1526 1349 5424 1506 1329 5425 1507 1330 5426 1526 1349 5427 1525 1348 5428 1506 1329 5429 1527 1350 5430 1507 1330 5431 1508 1331 5432 1527 1350 5433 1526 1349 5434 1507 1330 5435 1528 1351 5436 1508 1331 5437 1509 1332 5438 1528 1351 5439 1527 1350 5440 1508 1331 5441 1529 1352 5442 1509 1332 5443 1512 1335 5444 1528 1351 5445 1509 1332 5446 1529 1352 5447 1530 1353 5448 1531 1354 5449 1517 1340 5450 1532 1355 5451 1533 1356 5452 1531 1354 5453 1530 1353 5454 1532 1355 5455 1531 1354 5456 1515 1338 5457 1530 1353 5458 1517 1340 5459 1534 1357 5460 1528 1351 5461 1529 1352 5462 1535 1358 5463 1536 1359 5464 1533 1356 5465 1532 1355 5466 1535 1358 5467 1533 1356 5468 1537 1360 5469 1162 997 5470 1518 1341 5471 1537 1360 5472 1222 1055 5473 1162 997 5474 1538 1361 5475 1518 1341 5476 1519 1342 5477 1538 1361 5478 1537 1360 5479 1518 1341 5480 1539 1362 5481 1519 1342 5482 1520 1343 5483 1539 1362 5484 1538 1361 5485 1519 1342 5486 1540 1363 5487 1520 1343 5488 1521 1344 5489 1540 1363 5490 1539 1362 5491 1520 1343 5492 1541 1364 5493 1521 1344 5494 1522 1345 5495 1541 1364 5496 1540 1363 5497 1521 1344 5498 1542 1365 5499 1522 1345 5500 1523 1346 5501 1542 1365 5502 1541 1364 5503 1522 1345 5504 1543 1366 5505 1523 1346 5506 1524 1347 5507 1543 1366 5508 1542 1365 5509 1523 1346 5510 1544 1367 5511 1524 1347 5512 1525 1348 5513 1544 1367 5514 1543 1366 5515 1524 1347 5516 1545 1368 5517 1525 1348 5518 1526 1349 5519 1545 1368 5520 1544 1367 5521 1525 1348 5522 1546 1369 5523 1526 1349 5524 1527 1350 5525 1546 1369 5526 1545 1368 5527 1526 1349 5528 1547 1370 5529 1527 1350 5530 1528 1351 5531 1547 1370 5532 1546 1369 5533 1527 1350 5534 1548 1371 5535 1528 1351 5536 1534 1357 5537 1548 1371 5538 1547 1370 5539 1528 1351 5540 1548 1371 5541 1534 1357 5542 1549 1372 5543 1550 1373 5544 1551 1374 5545 1536 1359 5546 1535 1358 5547 1550 1373 5548 1536 1359 5549 1552 1375 5550 1548 1371 5551 1549 1372 5552 1553 1376 5553 1554 1377 5554 1551 1374 5555 1550 1373 5556 1553 1376 5557 1551 1374 5558 1242 1075 5559 1222 1055 5560 1537 1360 5561 1555 1378 5562 1537 1360 5563 1538 1361 5564 1555 1378 5565 1242 1075 5566 1537 1360 5567 1556 1379 5568 1538 1361 5569 1539 1362 5570 1556 1379 5571 1555 1378 5572 1538 1361 5573 1557 1380 5574 1539 1362 5575 1540 1363 5576 1557 1380 5577 1556 1379 5578 1539 1362 5579 1558 1381 5580 1540 1363 5581 1541 1364 5582 1558 1381 5583 1557 1380 5584 1540 1363 5585 1559 1382 5586 1541 1364 5587 1542 1365 5588 1559 1382 5589 1558 1381 5590 1541 1364 5591 1560 1383 5592 1542 1365 5593 1543 1366 5594 1560 1383 5595 1559 1382 5596 1542 1365 5597 1561 1384 5598 1543 1366 5599 1544 1367 5600 1561 1384 5601 1560 1383 5602 1543 1366 5603 1562 1385 5604 1544 1367 5605 1545 1368 5606 1562 1385 5607 1561 1384 5608 1544 1367 5609 1563 1386 5610 1545 1368 5611 1546 1369 5612 1563 1386 5613 1562 1385 5614 1545 1368 5615 1564 1387 5616 1546 1369 5617 1547 1370 5618 1564 1387 5619 1563 1386 5620 1546 1369 5621 1565 1388 5622 1547 1370 5623 1548 1371 5624 1565 1388 5625 1564 1387 5626 1547 1370 5627 1566 1389 5628 1548 1371 5629 1552 1375 5630 1566 1389 5631 1565 1388 5632 1548 1371 5633 1566 1389 5634 1552 1375 5635 1567 1390 5636 1568 1391 5637 1569 1392 5638 1554 1377 5639 1553 1376 5640 1568 1391 5641 1554 1377 5642 1570 1393 5643 1566 1389 5644 1567 1390 5645 1571 1394 5646 1572 1395 5647 1569 1392 5648 1568 1391 5649 1571 1394 5650 1569 1392 5651 691 569 5652 1242 1075 5653 1555 1378 5654 1426 1249 5655 1555 1378 5656 1556 1379 5657 1426 1249 5658 691 569 5659 1555 1378 5660 1425 1248 5661 1556 1379 5662 1557 1380 5663 1425 1248 5664 1426 1249 5665 1556 1379 5666 1424 1247 5667 1557 1380 5668 1558 1381 5669 1424 1247 5670 1425 1248 5671 1557 1380 5672 1423 1246 5673 1558 1381 5674 1559 1382 5675 1423 1246 5676 1424 1247 5677 1558 1381 5678 1422 1245 5679 1559 1382 5680 1560 1383 5681 1422 1245 5682 1423 1246 5683 1559 1382 5684 1421 1244 5685 1560 1383 5686 1561 1384 5687 1421 1244 5688 1422 1245 5689 1560 1383 5690 1420 1243 5691 1561 1384 5692 1562 1385 5693 1420 1243 5694 1421 1244 5695 1561 1384 5696 1419 1242 5697 1562 1385 5698 1563 1386 5699 1419 1242 5700 1420 1243 5701 1562 1385 5702 1418 1241 5703 1563 1386 5704 1564 1387 5705 1418 1241 5706 1419 1242 5707 1563 1386 5708 1417 1240 5709 1564 1387 5710 1565 1388 5711 1417 1240 5712 1418 1241 5713 1564 1387 5714 1416 1239 5715 1565 1388 5716 1566 1389 5717 1416 1239 5718 1417 1240 5719 1565 1388 5720 1414 1237 5721 1566 1389 5722 1570 1393 5723 1414 1237 5724 1416 1239 5725 1566 1389 5726 1414 1237 5727 1570 1393 5728 1573 1396 5729 1574 1397 5730 1575 1398 5731 1572 1395 5732 1571 1394 5733 1574 1397 5734 1572 1395 5735 1415 1238 5736 1414 1237 5737 1573 1396 5738 1576 1399 5739 1577 1400 5740 1575 1398 5741 1574 1397 5742 1576 1399 5743 1575 1398 5744 1407 1230 5745 1413 1236 5746 1577 1400 5747 1576 1399 5748 1407 1230 5749 1577 1400 5750 1578 1401 5751 1411 1234 5752 1579 1402 5753 1580 1403 5754 1410 1233 5755 1411 1234 5756 1578 1401 5757 1580 1403 5758 1411 1234 5759 1581 1404 5760 1579 1402 5761 1582 1405 5762 1581 1404 5763 1578 1401 5764 1579 1402 5765 1583 1406 5766 1582 1405 5767 1584 1407 5768 1583 1406 5769 1581 1404 5770 1582 1405 5771 1583 1406 5772 1584 1407 5773 1585 1408 5774 1586 1409 5775 1585 1408 5776 1587 1410 5777 1586 1409 5778 1583 1406 5779 1585 1408 5780 1588 1411 5781 1587 1410 5782 1589 1412 5783 1588 1411 5784 1586 1409 5785 1587 1410 5786 1590 1413 5787 1589 1412 5788 1591 1414 5789 1590 1413 5790 1588 1411 5791 1589 1412 5792 1592 1415 5793 1591 1414 5794 1593 1416 5795 1592 1415 5796 1590 1413 5797 1591 1414 5798 1592 1415 5799 1593 1416 5800 1594 1417 5801 1595 1418 5802 1594 1417 5803 1596 1419 5804 1595 1418 5805 1592 1415 5806 1594 1417 5807 1597 1420 5808 1596 1419 5809 1598 1421 5810 1597 1420 5811 1595 1418 5812 1596 1419 5813 1599 1422 5814 1598 1421 5815 1600 1423 5816 1599 1422 5817 1597 1420 5818 1598 1421 5819 1601 1424 5820 1600 1423 5821 1602 1425 5822 1601 1424 5823 1599 1422 5824 1600 1423 5825 1601 1424 5826 1602 1425 5827 1603 1426 5828 1604 1427 5829 1603 1426 5830 1605 1428 5831 1604 1427 5832 1601 1424 5833 1603 1426 5834 1606 1429 5835 1605 1428 5836 1607 1430 5837 1606 1429 5838 1604 1427 5839 1605 1428 5840 1608 1431 5841 1607 1430 5842 1609 1432 5843 1608 1431 5844 1606 1429 5845 1607 1430 5846 1608 1431 5847 1609 1432 5848 1610 1433 5849 1611 1434 5850 1612 1435 5851 1613 1436 5852 1608 1431 5853 1610 1433 5854 1614 1437 5855 1615 1438 5856 1613 1436 5857 1616 1439 5858 1615 1438 5859 1611 1434 5860 1613 1436 5861 1617 1440 5862 1616 1439 5863 1618 1441 5864 1617 1440 5865 1615 1438 5866 1616 1439 5867 1619 1442 5868 1618 1441 5869 1620 1443 5870 1619 1442 5871 1617 1440 5872 1618 1441 5873 1621 1444 5874 1620 1443 5875 1622 1445 5876 1621 1444 5877 1619 1442 5878 1620 1443 5879 1623 1446 5880 1622 1445 5881 1624 1447 5882 1623 1446 5883 1621 1444 5884 1622 1445 5885 1625 1448 5886 1624 1447 5887 1626 1449 5888 1625 1448 5889 1623 1446 5890 1624 1447 5891 1627 1450 5892 1626 1449 5893 1628 1451 5894 1629 1452 5895 1625 1448 5896 1626 1449 5897 1630 1453 5898 1629 1452 5899 1626 1449 5900 1631 1454 5901 1630 1453 5902 1626 1449 5903 1627 1450 5904 1631 1454 5905 1626 1449 5906 1632 1455 5907 1628 1451 5908 1633 1456 5909 1634 1457 5910 1627 1450 5911 1628 1451 5912 1635 1458 5913 1634 1457 5914 1628 1451 5915 1636 1459 5916 1635 1458 5917 1628 1451 5918 1637 1460 5919 1636 1459 5920 1628 1451 5921 1638 1461 5922 1637 1460 5923 1628 1451 5924 1639 1462 5925 1638 1461 5926 1628 1451 5927 1640 1463 5928 1639 1462 5929 1628 1451 5930 1632 1464 5931 1640 1464 5932 1628 1464 5933 1641 1465 5934 1633 1456 5935 1642 1466 5936 1632 1455 5937 1633 1456 5938 1641 1465 5939 1643 1467 5940 1642 1466 5941 1644 1468 5942 1643 1467 5943 1641 1465 5944 1642 1466 5945 1645 1469 5946 1644 1468 5947 1646 1470 5948 1645 1469 5949 1643 1467 5950 1644 1468 5951 1647 1471 5952 1646 1470 5953 1648 1472 5954 1647 1471 5955 1645 1469 5956 1646 1470 5957 1649 1473 5958 1648 1472 5959 1650 1474 5960 1649 1473 5961 1647 1471 5962 1648 1472 5963 1649 1473 5964 1650 1474 5965 1651 1475 5966 1652 1476 5967 1651 1475 5968 1653 1477 5969 1652 1476 5970 1649 1473 5971 1651 1475 5972 1654 1478 5973 1653 1477 5974 1655 1479 5975 1654 1478 5976 1652 1476 5977 1653 1477 5978 1656 1480 5979 1655 1479 5980 597 475 5981 1656 1480 5982 1654 1478 5983 1655 1479 5984 596 474 5985 1656 1480 5986 597 475 5987 1657 1481 5988 1658 1481 5989 1659 1481 5990 1660 1482 5991 1661 1482 5992 1658 1482 5993 1657 857 5994 1660 857 5995 1658 857 5996 1657 1483 5997 1659 1483 5998 1662 1483 5999 1663 1484 6000 1664 1485 6001 1617 1440 6002 1665 1486 6003 1662 1486 6004 1666 1486 6005 1667 1487 6006 1617 1440 6007 1619 1442 6008 1667 1487 6009 1663 1484 6010 1617 1440 6011 1665 1488 6012 1657 1488 6013 1662 1488 6014 1668 1489 6015 1669 1490 6016 1664 1485 6017 1665 1491 6018 1666 1491 6019 1670 1491 6020 1663 1484 6021 1671 1492 6022 1664 1485 6023 1672 1493 6024 1664 1485 6025 1671 1492 6026 1673 1494 6027 1664 1485 6028 1672 1493 6029 1673 1494 6030 1668 1489 6031 1664 1485 6032 1674 1495 6033 1675 1496 6034 1669 1490 6035 1676 1497 6036 1670 1497 6037 1677 1497 6038 1678 1498 6039 1674 1495 6040 1669 1490 6041 1668 1489 6042 1678 1498 6043 1669 1490 6044 1676 1499 6045 1665 1499 6046 1670 1499 6047 1679 1500 6048 1680 1501 6049 1675 1496 6050 1676 1502 6051 1677 1502 6052 1681 1502 6053 1682 1503 6054 1679 1500 6055 1675 1496 6056 1683 1504 6057 1682 1503 6058 1675 1496 6059 1684 1505 6060 1683 1504 6061 1675 1496 6062 1674 1495 6063 1684 1505 6064 1675 1496 6065 1632 1455 6066 1641 1465 6067 1680 1501 6068 1685 1506 6069 1681 1506 6070 1686 1506 6071 1687 1507 6072 1632 1455 6073 1680 1501 6074 1688 1508 6075 1687 1507 6076 1680 1501 6077 1689 1509 6078 1688 1508 6079 1680 1501 6080 1679 1500 6081 1689 1509 6082 1680 1501 6083 1685 857 6084 1676 857 6085 1681 857 6086 1685 857 6087 1686 857 6088 1690 857 6089 1691 857 6090 1690 857 6091 1692 857 6092 1691 1510 6093 1685 1510 6094 1690 1510 6095 1693 1511 6096 1692 1511 6097 1694 1511 6098 1693 857 6099 1691 857 6100 1692 857 6101 1693 1512 6102 1694 1512 6103 1695 1512 6104 1696 1513 6105 1695 1513 6106 1697 1513 6107 1696 1514 6108 1693 1514 6109 1695 1514 6110 1698 1515 6111 1697 1515 6112 1699 1515 6113 1698 1516 6114 1696 1516 6115 1697 1516 6116 1700 1517 6117 1699 1517 6118 1701 1517 6119 1702 857 6120 1699 857 6121 1700 857 6122 1702 1518 6123 1698 1518 6124 1699 1518 6125 1703 1519 6126 1701 1519 6127 1704 1519 6128 1700 857 6129 1701 857 6130 1703 857 6131 1705 1520 6132 1704 1520 6133 1706 1520 6134 1703 1521 6135 1704 1521 6136 1705 1521 6137 1707 1522 6138 1706 1522 6139 1708 1522 6140 1705 857 6141 1706 857 6142 1707 857 6143 1709 857 6144 1708 857 6145 1710 857 6146 1707 1523 6147 1708 1523 6148 1709 1523 6149 1702 1524 6150 1700 1524 6151 1711 1524 6152 1712 1513 6153 1711 1513 6154 1713 1513 6155 1714 857 6156 1702 857 6157 1711 857 6158 1712 1516 6159 1714 1516 6160 1711 1516 6161 1712 1525 6162 1713 1525 6163 1715 1525 6164 1716 1511 6165 1715 1511 6166 1717 1511 6167 1716 857 6168 1712 857 6169 1715 857 6170 1718 857 6171 1717 857 6172 1719 857 6173 1718 857 6174 1716 857 6175 1717 857 6176 1718 1526 6177 1719 1526 6178 1720 1526 6179 1721 1527 6180 1722 1528 6181 22 22 6182 1723 1506 6183 1720 1506 6184 1724 1506 6185 1725 1529 6186 1721 1527 6187 22 22 6188 1726 1530 6189 1725 1529 6190 22 22 6191 20 20 6192 1726 1530 6193 22 22 6194 1723 857 6195 1718 857 6196 1720 857 6197 1727 1531 6198 1728 1532 6199 1722 1528 6200 1723 1533 6201 1724 1533 6202 1729 1533 6203 1730 1534 6204 1727 1531 6205 1722 1528 6206 1731 1535 6207 1730 1534 6208 1722 1528 6209 1732 1536 6210 1731 1535 6211 1722 1528 6212 1721 1527 6213 1732 1536 6214 1722 1528 6215 1733 1537 6216 1734 1538 6217 1728 1532 6218 1735 1497 6219 1729 1497 6220 1736 1497 6221 1737 1539 6222 1733 1537 6223 1728 1532 6224 1727 1531 6225 1737 1539 6226 1728 1532 6227 1735 857 6228 1723 857 6229 1729 857 6230 1738 1540 6231 53 54 6232 1734 1538 6233 1735 1541 6234 1736 1541 6235 1739 1541 6236 1733 1537 6237 1738 1540 6238 1734 1538 6239 1740 1486 6240 1739 1486 6241 1741 1486 6242 1742 1542 6243 53 54 6244 1738 1540 6245 1742 1542 6246 43 44 6247 53 54 6248 1740 857 6249 1735 857 6250 1739 857 6251 1740 1543 6252 1741 1543 6253 1743 1543 6254 1744 1481 6255 1743 1481 6256 1745 1481 6257 1744 857 6258 1740 857 6259 1743 857 6260 1746 1482 6261 1745 1482 6262 1747 1482 6263 1746 857 6264 1744 857 6265 1745 857 6266 1748 1544 6267 1749 1544 6268 1750 1544 6269 1751 223 6270 1752 223 6271 1753 223 6272 1754 223 6273 1751 223 6274 1753 223 6275 1755 223 6276 1754 223 6277 1753 223 6278 1756 223 6279 1755 223 6280 1753 223 6281 1757 223 6282 1756 223 6283 1753 223 6284 1748 1545 6285 1750 1545 6286 1758 1545 6287 1759 1546 6288 1760 1547 6289 1761 1548 6290 1759 1546 6291 1761 1548 6292 1762 1549 6293 1763 1550 6294 1762 1549 6295 1764 1551 6296 1759 1546 6297 1762 1549 6298 1763 1550 6299 1763 1550 6300 1764 1551 6301 1765 1552 6302 1766 1553 6303 1765 1552 6304 1767 1554 6305 1763 1550 6306 1765 1552 6307 1766 1553 6308 1766 1553 6309 1767 1554 6310 1768 1555 6311 1769 1556 6312 1768 1555 6313 1770 1557 6314 1766 1553 6315 1768 1555 6316 1769 1556 6317 1769 1556 6318 1770 1557 6319 1771 1558 6320 1772 1559 6321 1773 1560 6322 1636 1459 6323 1774 1561 6324 1771 1558 6325 1775 1562 6326 1637 1460 6327 1772 1559 6328 1636 1459 6329 1769 1556 6330 1771 1558 6331 1774 1561 6332 1772 1559 6333 1776 1563 6334 1773 1560 6335 1777 1564 6336 1775 1562 6337 1778 1565 6338 1774 1561 6339 1775 1562 6340 1777 1564 6341 1772 1559 6342 1779 1566 6343 1776 1563 6344 1777 1564 6345 1778 1565 6346 1780 1567 6347 1781 1568 6348 1782 1569 6349 1779 1566 6350 1783 1570 6351 1780 1567 6352 1784 1571 6353 1772 1559 6354 1781 1568 6355 1779 1566 6356 1777 1564 6357 1780 1567 6358 1783 1570 6359 1785 1572 6360 1786 1573 6361 1782 1569 6362 1783 1570 6363 1784 1571 6364 1787 1574 6365 1781 1568 6366 1785 1572 6367 1782 1569 6368 1785 1572 6369 1788 1575 6370 1786 1573 6371 1789 1576 6372 1787 1574 6373 1790 1577 6374 1783 1570 6375 1787 1574 6376 1789 1576 6377 1791 1578 6378 1792 1579 6379 1788 1575 6380 1789 1576 6381 1790 1577 6382 1793 1580 6383 1785 1572 6384 1791 1578 6385 1788 1575 6386 1794 1581 6387 1795 1581 6388 1796 1581 6389 1797 1582 6390 1671 1492 6391 1792 1579 6392 1798 1583 6393 1795 1583 6394 1794 1583 6395 1791 1578 6396 1797 1582 6397 1792 1579 6398 1789 1576 6399 1793 1580 6400 1799 1584 6401 1797 1582 6402 1672 1493 6403 1671 1492 6404 1800 223 6405 1801 223 6406 1752 223 6407 1802 223 6408 1800 223 6409 1752 223 6410 1803 223 6411 1802 223 6412 1752 223 6413 1751 223 6414 1803 223 6415 1752 223 6416 1804 1585 6417 1805 1585 6418 1806 1585 6419 1807 223 6420 1808 223 6421 1809 223 6422 1810 223 6423 1807 223 6424 1809 223 6425 1811 223 6426 1810 223 6427 1809 223 6428 1812 223 6429 1811 223 6430 1809 223 6431 1813 223 6432 1812 223 6433 1809 223 6434 1804 1586 6435 1806 1586 6436 1814 1586 6437 1815 1587 6438 1816 1588 6439 1817 1589 6440 1815 1587 6441 1817 1589 6442 1818 1590 6443 1819 1591 6444 1818 1590 6445 1820 1592 6446 1815 1587 6447 1818 1590 6448 1819 1591 6449 1819 1591 6450 1820 1592 6451 1821 1593 6452 1822 1594 6453 1821 1593 6454 1823 1595 6455 1819 1591 6456 1821 1593 6457 1822 1594 6458 1822 1594 6459 1823 1595 6460 1824 1596 6461 1825 1597 6462 1824 1596 6463 1826 1598 6464 1822 1594 6465 1824 1596 6466 1825 1597 6467 1825 1597 6468 1826 1598 6469 1827 1599 6470 1828 1600 6471 1827 1599 6472 1829 1601 6473 1825 1597 6474 1827 1599 6475 1828 1600 6476 1830 1602 6477 1829 1601 6478 1831 1603 6479 1828 1600 6480 1829 1601 6481 1830 1602 6482 1830 1602 6483 1831 1603 6484 1832 1604 6485 1833 1605 6486 1832 1604 6487 1834 1606 6488 1830 1602 6489 1832 1604 6490 1833 1605 6491 1833 1605 6492 1834 1606 6493 1835 1607 6494 1836 1608 6495 1835 1607 6496 1837 1609 6497 1833 1605 6498 1835 1607 6499 1836 1608 6500 1836 1608 6501 1837 1609 6502 1838 1610 6503 1836 1608 6504 1838 1610 6505 1839 1611 6506 1840 1612 6507 1841 1612 6508 1842 1612 6509 1843 1613 6510 1841 1613 6511 1840 1613 6512 1836 1608 6513 1839 1611 6514 1844 1584 6515 1845 223 6516 1846 223 6517 1808 223 6518 1847 223 6519 1845 223 6520 1808 223 6521 1848 223 6522 1847 223 6523 1808 223 6524 1807 223 6525 1848 223 6526 1808 223 6527 1849 1614 6528 1850 1614 6529 1851 1614 6530 1852 223 6531 1853 223 6532 1854 223 6533 1855 223 6534 1852 223 6535 1854 223 6536 1856 223 6537 1855 223 6538 1854 223 6539 1849 1615 6540 1851 1615 6541 1857 1615 6542 1858 1616 6543 1859 1617 6544 1860 1618 6545 1858 1616 6546 1860 1618 6547 1861 1619 6548 1862 1620 6549 1861 1619 6550 1863 1621 6551 1858 1616 6552 1861 1619 6553 1862 1620 6554 1862 1620 6555 1863 1621 6556 1864 1622 6557 1865 1623 6558 1864 1622 6559 1866 1624 6560 1862 1620 6561 1864 1622 6562 1865 1623 6563 1865 1623 6564 1866 1624 6565 1867 1625 6566 1868 1626 6567 1867 1625 6568 1869 1627 6569 1865 1623 6570 1867 1625 6571 1868 1626 6572 1868 1626 6573 1869 1627 6574 1870 1628 6575 1871 1629 6576 1870 1628 6577 1872 1630 6578 1868 1626 6579 1870 1628 6580 1871 1629 6581 1873 1631 6582 1872 1630 6583 1874 1632 6584 1871 1629 6585 1872 1630 6586 1873 1631 6587 1873 1631 6588 1874 1632 6589 1875 1633 6590 1876 1634 6591 1875 1633 6592 1877 1635 6593 1873 1631 6594 1875 1633 6595 1876 1634 6596 1876 1634 6597 1877 1635 6598 1878 1636 6599 1879 1637 6600 1878 1636 6601 1880 1638 6602 1876 1634 6603 1878 1636 6604 1879 1637 6605 1879 1637 6606 1880 1638 6607 1881 1639 6608 1879 1637 6609 1881 1639 6610 1882 1640 6611 1883 1641 6612 1884 1641 6613 1885 1641 6614 1886 1642 6615 1884 1642 6616 1883 1642 6617 1879 1637 6618 1882 1640 6619 1887 1643 6620 1888 223 6621 1889 223 6622 1853 223 6623 1890 223 6624 1891 223 6625 1889 223 6626 1888 223 6627 1890 223 6628 1889 223 6629 1892 223 6630 1888 223 6631 1853 223 6632 1893 223 6633 1892 223 6634 1853 223 6635 1852 223 6636 1893 223 6637 1853 223 6638 1746 1644 6639 1747 1644 6640 1894 1644 6641 1895 1645 6642 1894 1645 6643 1896 1645 6644 1895 1646 6645 1746 1646 6646 1894 1646 6647 1895 1647 6648 1896 1647 6649 1897 1647 6650 1898 1648 6651 1897 1648 6652 1899 1648 6653 1898 1649 6654 1895 1649 6655 1897 1649 6656 1898 1650 6657 1899 1650 6658 1900 1650 6659 1901 1651 6660 1900 1651 6661 1902 1651 6662 1901 857 6663 1898 857 6664 1900 857 6665 1901 857 6666 1902 857 6667 1903 857 6668 1904 857 6669 1903 857 6670 1905 857 6671 1904 1652 6672 1901 1652 6673 1903 1652 6674 1906 1653 6675 1905 1653 6676 1907 1653 6677 1906 857 6678 1904 857 6679 1905 857 6680 1906 1654 6681 1907 1654 6682 1908 1654 6683 1909 1655 6684 1908 1655 6685 1910 1655 6686 1909 1656 6687 1906 1656 6688 1908 1656 6689 1911 1657 6690 1910 1657 6691 1912 1657 6692 1911 1658 6693 1909 1658 6694 1910 1658 6695 1913 1659 6696 1912 1659 6697 1914 1659 6698 1915 857 6699 1912 857 6700 1913 857 6701 1911 1660 6702 1912 1660 6703 1915 1660 6704 1916 1661 6705 1914 1661 6706 1917 1661 6707 1913 857 6708 1914 857 6709 1916 857 6710 1918 1662 6711 1917 1662 6712 1919 1662 6713 1916 1663 6714 1917 1663 6715 1918 1663 6716 1920 1664 6717 1919 1664 6718 1921 1664 6719 1918 857 6720 1919 857 6721 1920 857 6722 1922 857 6723 1921 857 6724 1923 857 6725 1920 1665 6726 1921 1665 6727 1922 1665 6728 1915 1666 6729 1913 1666 6730 1924 1666 6731 1925 1655 6732 1924 1655 6733 1926 1655 6734 1927 857 6735 1915 857 6736 1924 857 6737 1925 1658 6738 1927 1658 6739 1924 1658 6740 1925 1667 6741 1926 1667 6742 1928 1667 6743 1929 1653 6744 1928 1653 6745 1930 1653 6746 1929 857 6747 1925 857 6748 1928 857 6749 1931 857 6750 1930 857 6751 1932 857 6752 1931 857 6753 1929 857 6754 1930 857 6755 1931 1668 6756 1932 1668 6757 1933 1668 6758 1934 1651 6759 1933 1651 6760 1935 1651 6761 1934 857 6762 1931 857 6763 1933 857 6764 1934 1669 6765 1935 1669 6766 1936 1669 6767 1937 1648 6768 1936 1648 6769 1938 1648 6770 1937 857 6771 1934 857 6772 1936 857 6773 1937 1670 6774 1938 1670 6775 1939 1670 6776 1940 1645 6777 1939 1645 6778 1941 1645 6779 1940 857 6780 1937 857 6781 1939 857 6782 1940 1671 6783 1941 1671 6784 1661 1671 6785 1660 857 6786 1940 857 6787 1661 857 6788 1942 1672 6789 1943 1672 6790 1944 1673 6791 1945 1674 6792 1946 1675 6793 1947 1676 6794 1945 1674 6795 1947 1676 6796 1948 1676 6797 1949 1677 6798 1944 1673 6799 1950 1678 6800 1949 1677 6801 1942 1672 6802 1944 1673 6803 1951 1678 6804 1950 1678 6805 1952 1679 6806 1949 1677 6807 1950 1678 6808 1951 1678 6809 1953 1680 6810 1952 1679 6811 1954 1681 6812 1951 1678 6813 1952 1679 6814 1953 1680 6815 1955 1682 6816 1954 1681 6817 1956 1683 6818 1953 1680 6819 1954 1681 6820 1955 1682 6821 1957 1683 6822 1956 1683 6823 1958 1684 6824 1955 1682 6825 1956 1683 6826 1957 1683 6827 1959 1684 6828 1958 1684 6829 1960 1685 6830 1957 1683 6831 1958 1684 6832 1959 1684 6833 1961 1686 6834 1960 1685 6835 1962 1687 6836 1959 1684 6837 1960 1685 6838 1961 1686 6839 1963 1687 6840 1962 1687 6841 1964 1688 6842 1961 1686 6843 1962 1687 6844 1963 1687 6845 1965 1688 6846 1964 1688 6847 1966 1689 6848 1963 1687 6849 1964 1688 6850 1965 1688 6851 1967 1690 6852 1966 1689 6853 1968 1691 6854 1965 1688 6855 1966 1689 6856 1967 1690 6857 1969 1691 6858 1968 1691 6859 1970 1692 6860 1967 1690 6861 1968 1691 6862 1969 1691 6863 1971 1692 6864 1970 1692 6865 1972 1693 6866 1969 1691 6867 1970 1692 6868 1971 1692 6869 1973 1694 6870 1972 1693 6871 1974 1695 6872 1971 1692 6873 1972 1693 6874 1973 1694 6875 1975 1696 6876 1974 1695 6877 1976 1697 6878 1973 1694 6879 1974 1695 6880 1975 1696 6881 1977 1697 6882 1976 1697 6883 1978 1698 6884 1975 1696 6885 1976 1697 6886 1977 1697 6887 1979 1699 6888 1978 1698 6889 1980 1700 6890 1977 1697 6891 1978 1698 6892 1979 1699 6893 1981 1701 6894 1982 1701 6895 1983 1702 6896 1979 1699 6897 1980 1700 6898 1984 1700 6899 1985 1703 6900 1983 1702 6901 1986 1704 6902 1981 1701 6903 1983 1702 6904 1985 1703 6905 1987 1704 6906 1986 1704 6907 1988 1705 6908 1985 1703 6909 1986 1704 6910 1987 1704 6911 1989 1706 6912 1988 1705 6913 1990 1707 6914 1987 1704 6915 1988 1705 6916 1989 1706 6917 1991 1708 6918 1990 1707 6919 1992 1709 6920 1989 1706 6921 1990 1707 6922 1991 1708 6923 1993 1709 6924 1992 1709 6925 1994 1710 6926 1991 1708 6927 1992 1709 6928 1993 1709 6929 1995 1710 6930 1994 1710 6931 1996 1711 6932 1993 1709 6933 1994 1710 6934 1995 1710 6935 1997 1712 6936 1996 1711 6937 1998 1713 6938 1995 1710 6939 1996 1711 6940 1997 1712 6941 1999 1713 6942 1998 1713 6943 2000 1714 6944 1997 1712 6945 1998 1713 6946 1999 1713 6947 2001 1714 6948 2000 1714 6949 2002 1715 6950 1999 1713 6951 2000 1714 6952 2001 1714 6953 2003 1716 6954 2002 1715 6955 2004 1717 6956 2001 1714 6957 2002 1715 6958 2003 1716 6959 2005 1717 6960 2004 1717 6961 2006 1718 6962 2003 1716 6963 2004 1717 6964 2005 1717 6965 2007 1718 6966 2006 1718 6967 2008 1719 6968 2005 1717 6969 2006 1718 6970 2007 1718 6971 2009 1720 6972 2008 1719 6973 2010 1721 6974 2007 1718 6975 2008 1719 6976 2009 1720 6977 2011 1722 6978 2010 1721 6979 2012 1723 6980 2009 1720 6981 2010 1721 6982 2011 1722 6983 2013 1723 6984 2012 1723 6985 1946 1675 6986 2011 1722 6987 2012 1723 6988 2013 1723 6989 2013 1723 6990 1946 1675 6991 1945 1674 6992 2014 223 6993 2015 223 6994 2016 223 6995 2017 223 6996 2014 223 6997 2016 223 6998 2018 223 6999 2017 223 7000 2016 223 7001 2019 223 7002 2020 223 7003 2015 223 7004 2014 223 7005 2019 223 7006 2015 223 7007 2021 223 7008 2022 223 7009 2020 223 7010 2019 223 7011 2021 223 7012 2020 223 7013 2023 223 7014 2024 223 7015 2022 223 7016 2021 223 7017 2023 223 7018 2022 223 7019 2025 223 7020 2026 223 7021 2024 223 7022 2023 223 7023 2025 223 7024 2024 223 7025 2018 223 7026 2027 223 7027 2017 223 7028 2028 223 7029 2029 223 7030 2027 223 7031 2018 223 7032 2028 223 7033 2027 223 7034 2030 223 7035 2031 223 7036 2029 223 7037 2028 223 7038 2030 223 7039 2029 223 7040 2032 223 7041 2033 223 7042 2031 223 7043 2030 223 7044 2032 223 7045 2031 223 7046 2034 223 7047 2035 223 7048 2033 223 7049 2032 223 7050 2034 223 7051 2033 223 7052 2036 223 7053 2037 223 7054 1152 223 7055 1151 223 7056 2036 223 7057 1152 223 7058 2036 223 7059 2038 223 7060 2037 223 7061 1282 223 7062 2039 223 7063 1285 223 7064 2040 223 7065 2041 223 7066 2039 223 7067 1282 223 7068 2040 223 7069 2039 223 7070 2042 223 7071 2043 223 7072 2041 223 7073 2040 223 7074 2042 223 7075 2041 223 7076 2044 223 7077 2045 223 7078 2043 223 7079 2042 223 7080 2044 223 7081 2043 223 7082 854 223 7083 2046 223 7084 850 223 7085 854 223 7086 2047 223 7087 2046 223 7088 854 223 7089 2048 223 7090 2047 223 7091 2049 223 7092 2050 223 7093 2048 223 7094 854 223 7095 2049 223 7096 2048 223 7097 2051 223 7098 2052 223 7099 2050 223 7100 2049 223 7101 2051 223 7102 2050 223 7103 1757 223 7104 2053 223 7105 1756 223 7106 1813 223 7107 2054 223 7108 1812 223 7109 1890 223 7110 2055 223 7111 1891 223 7112 2056 223 7113 2057 223 7114 303 223 7115 302 223 7116 2056 223 7117 303 223 7118 2058 223 7119 2059 223 7120 2057 223 7121 2056 223 7122 2058 223 7123 2057 223 7124 2060 223 7125 2061 223 7126 2059 223 7127 2058 223 7128 2060 223 7129 2059 223 7130 311 223 7131 2062 223 7132 309 223 7133 311 223 7134 2063 223 7135 2062 223 7136 2064 223 7137 2065 223 7138 2063 223 7139 311 223 7140 2064 223 7141 2063 223 7142 2066 223 7143 2067 223 7144 2065 223 7145 2064 223 7146 2066 223 7147 2065 223 7148 2066 223 7149 2068 223 7150 2067 223 7151 2069 857 7152 2070 857 7153 2071 857 7154 2072 857 7155 2069 857 7156 2071 857 7157 2073 857 7158 2072 857 7159 2071 857 7160 2074 857 7161 2075 857 7162 2070 857 7163 2069 857 7164 2074 857 7165 2070 857 7166 2076 857 7167 2077 857 7168 2075 857 7169 2074 857 7170 2076 857 7171 2075 857 7172 2078 857 7173 2079 857 7174 2077 857 7175 2076 857 7176 2078 857 7177 2077 857 7178 2080 857 7179 2081 857 7180 2079 857 7181 2078 857 7182 2080 857 7183 2079 857 7184 2082 857 7185 2083 857 7186 2081 857 7187 2080 857 7188 2082 857 7189 2081 857 7190 2084 857 7191 2085 857 7192 2083 857 7193 2082 857 7194 2084 857 7195 2083 857 7196 2086 857 7197 2087 857 7198 2085 857 7199 2084 857 7200 2086 857 7201 2085 857 7202 2073 857 7203 2088 857 7204 2072 857 7205 2089 857 7206 2090 857 7207 2088 857 7208 2073 857 7209 2089 857 7210 2088 857 7211 2091 857 7212 2092 857 7213 2090 857 7214 2089 857 7215 2091 857 7216 2090 857 7217 2093 857 7218 2094 857 7219 2092 857 7220 2091 857 7221 2093 857 7222 2092 857 7223 2095 857 7224 2096 857 7225 2094 857 7226 2093 857 7227 2095 857 7228 2094 857 7229 2097 857 7230 2098 857 7231 2096 857 7232 2095 857 7233 2097 857 7234 2096 857 7235 2099 857 7236 2100 857 7237 2098 857 7238 2097 857 7239 2099 857 7240 2098 857 7241 2101 857 7242 2102 857 7243 2100 857 7244 2099 857 7245 2101 857 7246 2100 857 7247 2103 68 7248 2104 68 7249 2105 68 7250 2106 68 7251 2103 68 7252 2105 68 7253 2107 68 7254 2106 68 7255 2105 68 7256 2108 68 7257 2109 68 7258 2104 68 7259 2103 68 7260 2108 68 7261 2104 68 7262 2110 68 7263 2111 68 7264 2109 68 7265 2108 68 7266 2110 68 7267 2109 68 7268 2112 68 7269 2113 68 7270 2111 68 7271 2110 68 7272 2112 68 7273 2111 68 7274 2114 68 7275 2115 68 7276 2113 68 7277 2112 68 7278 2114 68 7279 2113 68 7280 2116 68 7281 2117 68 7282 2115 68 7283 2114 68 7284 2116 68 7285 2115 68 7286 2118 68 7287 2119 68 7288 2117 68 7289 2116 68 7290 2118 68 7291 2117 68 7292 2120 68 7293 2121 68 7294 2119 68 7295 2118 68 7296 2120 68 7297 2119 68 7298 2107 68 7299 2122 68 7300 2106 68 7301 2123 68 7302 2124 68 7303 2122 68 7304 2107 68 7305 2123 68 7306 2122 68 7307 2125 68 7308 2126 68 7309 2124 68 7310 2123 68 7311 2125 68 7312 2124 68 7313 2127 68 7314 2128 68 7315 2126 68 7316 2125 68 7317 2127 68 7318 2126 68 7319 2129 68 7320 2130 68 7321 2128 68 7322 2127 68 7323 2129 68 7324 2128 68 7325 2131 68 7326 2132 68 7327 2130 68 7328 2129 68 7329 2131 68 7330 2130 68 7331 2133 68 7332 2134 68 7333 2132 68 7334 2131 68 7335 2133 68 7336 2132 68 7337 2135 68 7338 2136 68 7339 2134 68 7340 2133 68 7341 2135 68 7342 2134 68 7343 2137 1724 7344 2138 1724 7345 2139 1724 7346 2140 1725 7347 2141 1725 7348 2142 1726 7349 2143 1727 7350 2137 1727 7351 2139 1727 7352 2144 1728 7353 2145 1728 7354 2146 1728 7355 2144 1729 7356 2146 1729 7357 2147 1729 7358 2148 1726 7359 2142 1726 7360 2149 1730 7361 2148 1726 7362 2140 1725 7363 2142 1726 7364 2143 1731 7365 2150 1731 7366 2137 1731 7367 2151 1732 7368 2152 1732 7369 2153 1732 7370 2148 1726 7371 2149 1730 7372 2154 1730 7373 2155 1733 7374 2156 1733 7375 2150 1733 7376 2157 1734 7377 2158 1734 7378 2159 1735 7379 2143 1724 7380 2155 1724 7381 2150 1724 7382 2151 1736 7383 2153 1736 7384 2160 1736 7385 2161 1737 7386 2162 1737 7387 2156 1737 7388 2163 1735 7389 2159 1735 7390 2164 1738 7391 2155 1739 7392 2161 1739 7393 2156 1739 7394 2157 1734 7395 2159 1735 7396 2163 1735 7397 2165 1724 7398 2166 1724 7399 2162 1724 7400 2167 855 7401 2168 855 7402 2169 855 7403 2161 1724 7404 2165 1724 7405 2162 1724 7406 2163 1735 7407 2164 1738 7408 2170 1738 7409 2171 1740 7410 2172 1740 7411 2166 1740 7412 2173 1741 7413 2174 1741 7414 2175 1742 7415 2165 1743 7416 2171 1743 7417 2166 1743 7418 2167 855 7419 2169 855 7420 2176 855 7421 2177 1744 7422 2178 1744 7423 2172 1744 7424 2179 1742 7425 2175 1742 7426 2180 1745 7427 2171 1724 7428 2177 1724 7429 2172 1724 7430 2173 1741 7431 2175 1742 7432 2179 1742 7433 2181 1724 7434 2182 1724 7435 2178 1724 7436 2183 1746 7437 2184 1746 7438 2185 1746 7439 2177 1747 7440 2181 1747 7441 2178 1747 7442 2179 1742 7443 2180 1745 7444 2186 1745 7445 2181 1724 7446 2187 1724 7447 2182 1724 7448 2188 1748 7449 2189 1748 7450 2190 68 7451 2183 1749 7452 2185 1749 7453 2191 1749 7454 2192 68 7455 2190 68 7456 2193 1750 7457 2188 1748 7458 2190 68 7459 2192 68 7460 2194 1751 7461 2195 1751 7462 2196 1751 7463 2192 68 7464 2193 1750 7465 2197 1750 7466 2198 1752 7467 2199 1752 7468 2200 1753 7469 2194 1754 7470 2196 1754 7471 2201 1754 7472 2202 1753 7473 2200 1753 7474 2203 1755 7475 2198 1752 7476 2200 1753 7477 2202 1753 7478 2204 857 7479 2205 857 7480 2206 857 7481 2202 1753 7482 2203 1755 7483 2207 1755 7484 2208 1756 7485 2209 1756 7486 2210 1757 7487 2204 857 7488 2206 857 7489 2211 857 7490 2212 1757 7491 2210 1757 7492 2213 1758 7493 2208 1756 7494 2210 1757 7495 2212 1757 7496 2212 1757 7497 2213 1758 7498 2214 1758 7499 2215 1759 7500 2216 1759 7501 2217 1759 7502 2218 1760 7503 2219 1761 7504 2220 1762 7505 2221 223 7506 2217 223 7507 2222 223 7508 2223 1763 7509 2224 1764 7510 2225 1765 7511 2221 223 7512 2215 223 7513 2217 223 7514 2223 1763 7515 2225 1765 7516 2226 1766 7517 2227 223 7518 2228 223 7519 2216 223 7520 2229 1767 7521 2220 1762 7522 2230 1768 7523 2215 223 7524 2227 223 7525 2216 223 7526 2229 1767 7527 2218 1760 7528 2220 1762 7529 2231 1769 7530 2232 1769 7531 2228 1769 7532 2233 1770 7533 2230 1768 7534 2234 1771 7535 2227 1772 7536 2231 1772 7537 2228 1772 7538 2229 1767 7539 2230 1768 7540 2233 1770 7541 2235 223 7542 2236 223 7543 2232 223 7544 2237 1773 7545 2234 1771 7546 2238 1774 7547 2231 223 7548 2235 223 7549 2232 223 7550 2233 1770 7551 2234 1771 7552 2237 1773 7553 2235 1775 7554 2239 1775 7555 2236 1775 7556 2240 1776 7557 2238 1774 7558 2241 1777 7559 2237 1773 7560 2238 1774 7561 2240 1776 7562 2242 223 7563 2243 223 7564 2239 223 7565 2244 1778 7566 2241 1777 7567 2245 1779 7568 2246 1780 7569 2242 1780 7570 2239 1780 7571 2235 1781 7572 2246 1781 7573 2239 1781 7574 2240 1776 7575 2241 1777 7576 2244 1778 7577 2247 223 7578 2248 223 7579 2243 223 7580 2249 1782 7581 2245 1779 7582 2250 1783 7583 2242 1784 7584 2247 1784 7585 2243 1784 7586 2244 1778 7587 2245 1779 7588 2249 1782 7589 2251 1785 7590 2252 1785 7591 2248 1785 7592 2253 1786 7593 2254 1787 7594 2255 1788 7595 2251 1789 7596 2248 1789 7597 2247 1789 7598 2249 1782 7599 2250 1783 7600 2256 1790 7601 2257 1791 7602 2258 1791 7603 2252 1791 7604 2259 1792 7605 2255 1788 7606 2260 1793 7607 2251 223 7608 2257 223 7609 2252 223 7610 2253 1786 7611 2255 1788 7612 2259 1792 7613 2261 223 7614 2262 223 7615 2258 223 7616 2263 1794 7617 2260 1793 7618 2264 1795 7619 2257 223 7620 2261 223 7621 2258 223 7622 2259 1792 7623 2260 1793 7624 2263 1794 7625 2265 223 7626 2266 223 7627 2262 223 7628 2267 1796 7629 2264 1795 7630 2268 1797 7631 2261 223 7632 2265 223 7633 2262 223 7634 2263 1794 7635 2264 1795 7636 2267 1796 7637 2265 223 7638 2269 223 7639 2266 223 7640 2270 1798 7641 2268 1797 7642 2271 1799 7643 2267 1796 7644 2268 1797 7645 2270 1798 7646 2272 1800 7647 2222 1800 7648 2269 1800 7649 2273 1801 7650 2271 1799 7651 2224 1764 7652 2274 223 7653 2272 223 7654 2269 223 7655 2265 1802 7656 2274 1802 7657 2269 1802 7658 2270 1798 7659 2271 1799 7660 2273 1801 7661 2272 1803 7662 2221 1803 7663 2222 1803 7664 2273 1801 7665 2224 1764 7666 2223 1763 7667 2275 1804 7668 2251 1804 7669 2247 1804 7670 2276 223 7671 2275 223 7672 2247 223 7673 2221 1805 7674 2277 1805 7675 2215 1805 7676 2221 223 7677 2278 223 7678 2277 223 7679 2279 1806 7680 2280 1806 7681 2281 1806 7682 2282 223 7683 2281 223 7684 2283 223 7685 2279 223 7686 2281 223 7687 2282 223 7688 2284 223 7689 2285 223 7690 2280 223 7691 2279 223 7692 2284 223 7693 2280 223 7694 2286 223 7695 2287 223 7696 2285 223 7697 2288 223 7698 2286 223 7699 2285 223 7700 2284 223 7701 2288 223 7702 2285 223 7703 2288 223 7704 2289 223 7705 2286 223 7706 2290 223 7707 2291 223 7708 2289 223 7709 2288 223 7710 2290 223 7711 2289 223 7712 2292 223 7713 2293 223 7714 2291 223 7715 2294 1807 7716 2292 1807 7717 2291 1807 7718 2290 1808 7719 2294 1808 7720 2291 1808 7721 2295 223 7722 2296 223 7723 2293 223 7724 2292 223 7725 2295 223 7726 2293 223 7727 2297 223 7728 2298 223 7729 2296 223 7730 2295 223 7731 2297 223 7732 2296 223 7733 2299 223 7734 2300 223 7735 2298 223 7736 2301 223 7737 2299 223 7738 2298 223 7739 2297 223 7740 2301 223 7741 2298 223 7742 2301 223 7743 2302 223 7744 2299 223 7745 2303 223 7746 2283 223 7747 2302 223 7748 2301 223 7749 2303 223 7750 2302 223 7751 2304 223 7752 2282 223 7753 2283 223 7754 2303 1809 7755 2304 1809 7756 2283 1809 7757 2305 1810 7758 2306 1811 7759 2307 1812 7760 2308 1813 7761 2309 1814 7762 2310 1815 7763 2308 1813 7764 2310 1815 7765 2311 1816 7766 2312 1817 7767 2307 1812 7768 2313 1818 7769 2312 1817 7770 2305 1810 7771 2307 1812 7772 2314 1819 7773 2313 1818 7774 2315 1820 7775 2312 1817 7776 2313 1818 7777 2314 1819 7778 2316 1821 7779 2315 1820 7780 2317 1822 7781 2314 1819 7782 2315 1820 7783 2316 1821 7784 2318 1823 7785 2317 1822 7786 2319 1824 7787 2316 1821 7788 2317 1822 7789 2318 1823 7790 2320 1825 7791 2319 1824 7792 2321 1826 7793 2318 1823 7794 2319 1824 7795 2320 1825 7796 2322 1827 7797 2323 1828 7798 2324 1829 7799 2320 1825 7800 2321 1826 7801 2325 1830 7802 2326 1831 7803 2324 1829 7804 2327 1832 7805 2322 1827 7806 2324 1829 7807 2326 1831 7808 2328 1833 7809 2327 1832 7810 2329 1834 7811 2326 1831 7812 2327 1832 7813 2328 1833 7814 2330 1834 7815 2329 1834 7816 2331 1835 7817 2328 1833 7818 2329 1834 7819 2330 1834 7820 2332 1836 7821 2331 1835 7822 2309 1814 7823 2330 1834 7824 2331 1835 7825 2332 1836 7826 2332 1836 7827 2309 1814 7828 2308 1813 7829 2333 223 7830 2334 223 7831 2335 223 7832 2336 223 7833 2333 223 7834 2335 223 7835 2337 223 7836 2336 223 7837 2335 223 7838 2338 223 7839 2339 223 7840 2334 223 7841 2333 223 7842 2338 223 7843 2334 223 7844 2338 223 7845 2340 223 7846 2339 223 7847 2337 223 7848 2341 223 7849 2336 223 7850 2342 223 7851 2343 223 7852 2341 223 7853 2337 223 7854 2342 223 7855 2341 223 7856 2342 223 7857 2344 223 7858 2343 223 7859

-
-
-
-
- - - - - 7.54969e-11 1.19208e-10 9.99987e-4 0 0 9.99987e-4 -1.19208e-10 -0.6104 -9.99987e-4 0 7.54969e-11 0 0 0 0 1 - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl deleted file mode 100644 index 0c4575ec6b0447a9f5383bcb978c3d4841bfdaef..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18184 zcmb81dz??z`p1_`NbWOkxg-veOfF-D?_Qf6CYM1?2<6VWEBE+Sa>*gNN2-&{Nyjy* zkTLta-Es>xQRg5EA(}Zw7ef3#&)$2@eD?SF{qdXEt7bLNdOy#z?$26luUd|OcErfh z{rgoJFmlAODvu8BKfGW6k#*`PG-_O>=BP1!s?@Ee{$D?X^C&gm*=G&i{i1EaJ=I28 zarZ5C3MZKtF|Toh$rkJ+f(X)KvW2bN!P1c?~SZ)JvL~J zW9WCz4$n#ZC4U=49uU7hdp41E-HG;z{K&lol=KRtS0pAaHa_<(UDb*Qum5&IP zm^9PAjWEn)8%7)(}`0Zque9D?x<#?pR zwq(a>dcS5%c=b;Z8$nzzpO$DOY(w<2CZ*qHaL2#H2;9p?w>}Fk(kz9EuGYr9E#hsV5R9Oxm|0V|+wF?5**v zb^4PlO*d3+?+D!sbnD}7y|mG!)CdqWGxk}t#{Rtl>x!jw3Gr&0vkxUwYA;IoR)&?~ zdBq-*J*9+bY6y6B>XR$m#4AJBNBx+zU-ID~vNHBLM<{(xTVUzKsGHQH#^6x>Al{+&Lm)!lZp0g+O3F@rcsp|7sl=U(9LKse>7{&aK6* za?-wyYiC>9{|pG$btl><;E@f_{>v-lq1cdF0ot6`>b6437ZJe{lNP;(_HF!#5sR_z z*+45rP%mD|nJ{VJMp=y5SphNRr$dnvPj+|y@l%Rp=#xX+<)nQZ$6(_f5Or_oO=Mkn zqJ2VEHT13j@``ON@K;XfKh;uD@~R-Ps(A!UB#r*$mC4Y)jR!Ge(c?X0arO5;M347! zF~OQJmk@Dvf8)rSxx<|oQ&Jp5pBd6JC+*wNpY5}n!Nx1+-rmBx?nL`U7mQfUC;#OY z+sMG!$E@Mhy^@TQw+Df-?h!08Y0+zF-$rwczq^CF>Wz`<1Z~cQN&7Y$6Y<3S*E6EE z2RH?y9UMcuTUzI&eH*Po6bfvxt~=2_aTO!>^`KuFy&^Gbv5^^H&^dtK{zaUuI5$De z4+xf+G}FEftg|jwPp_^xmr0A>0@<~lYgx6OA_ZhFSqb9$S)X8uNsC@X`!+B$xC?`E z{uO-P0iQ*}gh~50?g23;Ai5N)=iL6Nx^rz$ieu=kTWxdFzKvQSh6V)dx)bda|3E$M z2p%xi_~Py&^Gbv2g%BeF%DdnKjbphyYx(;;_V|nf7g9t#x0-swQ(g z=Q3&0D`P)CVQhoSQ`#e+5GwyfU<$2T0odOma;w-@0#4(q+g$QC)uhx}XM+8fF?__o|zE`VG#x*iFSR!?1_BG*1-;^7> zL6;?Gua}PW`OmR!qBlr4^=+g~&Hl*Ph_Bv%+mQ}+y?t$5pT-&TcgbbuV4tY-XZMc{ z!Cu|LUSPw|E&rb6vJKW7o<*5p8|*u4!hF^EjZHo^$>sLonr2P87Q`#=CEWh3Nh$6n zW(-Q5n4T|b)}++(lM8bC70-!gUJ-&dg?kCtiCHs*U`;q9+ga_7?ZNfKnv|N{dTpYV z|Mu;dLM7+Y{@-=Q*4g)P$v<7UFQ;FzF7|{q<+g`-6(VQ_2;2B(-cBp=$BFvapT^o9 z*Hnwt+;xm?it zV!%9W9!~L^?Y=FGKNlTuqw&vp)HCdQ+m&t=k@=n9`<*|S4IvGy&3uQ*ICvQoZ@Be&x{=J@;8e$VLmT0 zRc~rDO^>ZR+-6-&hl#r`-Ox7@$LlwWbq;yOHYVeIZrR~zq}8A?sH;~J7t?Y|wXe8u*1#&(OqB6+t@IZ1&4klQWQtv00vhy5$O&|H9Wr*Nh(`$CN=I;6} zGNO1JcvWI?Z+qI=DSFW51Nu^t=d8R|0qe6iwJfQZCvM$}yo`Ec+c-)6roNq)I9;bV zdeCNFOoxe8Gy2;D|Cp@rDZEv)gl$N>Pygfd$YS&Zr8ed5Zcp4gUeBy@NwXvyeM@Sg zIrsxuoWJP8m9%4;ORhT};K0bJ=9CeD-`WIwiHlJ5V=swhj?22Sj)TfM%DEJRd@{m1lS_UR=Pbju2JqbxCPkT`8w zj8|oT=w_b-Q6&GRsOb$A3t!A&f;B1CWk-^oI`?J$ON|HIuewdJhAqx(eV%@=lZ@W} z!&8@~w>zv!srbWbcC8nu>0gGg4SB_Mm^k^2ZO8YSth0+$a?MDspAsL^%l4F#TZZAg zSARSg(Kt)^^jt=;IaODx`oEjmnekKfccm+Y2+qZ}aaVMsqFtcj6rK8*?N$wDwWsw-5syG?=>Cu>)8hjXz#rG7aVXE*tEogVdw_M#Wes`Tdcl2SGbxF)%=rB>E=c{_)zc%XRt^M5=!Ro9(N^v+B+f!=X z6-Pg`AgU)F?CP4xTkf{_mW(wimACpieY?yK?JnrxvM#2>#IB=Tt)lPj(22)}xF_H5 z|Dntb=h7c{I2YSfs;-q!*Q>r)_n0*(XK&!&1Lp2tSd&uO4La+j^n-f(sD3W%GLfaw zVWPxmpEyHr?A1%B4|aQDo)WK`qOQWZa_uRVp4BmW;pv@vVxF{|7*2LVyz^pBN~N95 z8?BbPOV4RB*p;Zr?7U1&C3KkhbkU4x3Dnik`}(+#VWttUen7wCTx?INFSEXlW@T;E z8#+Ddny6Uzmb^=4O-ij;oDuE1Zn3 zY)`2kv+s8s?R-oBxh}~y5v%OOc}LHhlxnxClw0SS<+|L5&0W^TbeMQ(<-P8CjKT3E zBJLxY*~F`d@SAh7J*A4AYU)-h_^N&`?Y{k9|ik|geNtbmo9VTQhERH!*->B&JM6F6WilLS{7u!?n``~QX#Z1i- zKEIk)v$Hc1@zuEEZ5*YFF7EBlLVPvg@`31uBF{N@A-+1)rk0a}bD1WHuf}1;VcXbk z!^Wd~A8d3Y#s=$UO-lXce4_h7r|J5g0yRTkajvk9)ie6LLlBXv!ds&(VXsc&jAkq% zvKPG7d0XD@?hA;>Mpd~KWyxiX5vjLo7&EL1V=nJt_ZA|uPqJ4=ITzCoPF((mh^!+b z4yF1g40F39zDhnfC(07U51x(Em@QZnc6F=9dc>PucRJ@Wvxz6E7sfSUf;A~sZ{%pV z6C$!%+e<|kR>mBHh^)zyo03UZ~vj2dk93s{Fn6O!H8;sXoCsXq*VDGNp5RIWQ`tpz(!2vjP@fk zt1-sMene!iWBbE2KLP0_p3huT+H`w_rjv2)>EY)`2N z50{A^{rg1Sy5$&qe({wV_wT8%>Egik!erv`>tpT1`^OH8CMzs-(C>mD6V?+3V9=C9#CpK3?H+ZAgkGyyApsYGXrwvxH~r@C;{& zQ78vXc!uM7#m{g06-#)W^C$=tEa9HdeL9zTWKp|@EHOPs{>D8tmyi@oxK|oF+!KXh z3HLGXJ(5p;CfSLL+9k1sdkpslKfkFfmT>!X%jOc*7PZ^N5^hayr(8l(EaA4{S`QN} z;hN?;%q99Ho=;>6*BjSJE+HwFa4m58!URjWOzdqg(PWeUm?i8X+x7{WOC-e-w#S;3 z`f6RK^9I@+PG_br7|KR0h+4{16hdQbmaZt~|N ztm91*oL))s4u9hnoQeeBsvQF{5yX8l1m`l}s`+2geG6hJhzcP1%RC2X?&9J0rU?$) zR_Z*6F(Be%Y_MK)|0Q4SDRmV@QxL^s2+qZ}mD+{eMFu5DH^T(_19-NEs*pzyDeVRQ2b{?v^I?8pzbye$)zgsIZ4+iVgw5S@O;zvBU6jLg5L?KAH+!L2l88~#9e*el20y=)&p_0;X?1P z_kc(%)z2yXadl@e2-t9PZG1K^#on7-+8y$)3VFqzlsWjQwGH-s8*l#pc60^2azL2r zlky`{Q>sDx%h8umjxr!nyH3#CE!0&;P*>K9UyC@yP`eV_;e@4IWBb>E$@;r~wQP8W zzu>F7qC-KfS!nc6}pe&TQboiKcY#gJ|L=r*bRbp@oko$-w?$|-_S=s*sP<&+hSzp`p#vN zbJ*P5rC&zf&}}zv*6U*k&c%0AN_BvZM?owA!8c> zO12jz58Bp?+r#bbm))tW^9JrXj9TeeoQwNd*xuoF zna*f`rZzUb9vAMf?A3?mnnf=hjB_{SdgT$^cf<6d%u3ev4YpejUU4oSD`6svUXl-U z;wPvpmW11Yy~>C7us3dwu7g)h@E8o!!T5-Ni}As^cua(e#=H93KVuecT64ALT*2() z%?5log;^BDHy~blAWU$s@GY4Q;u?tJu)%kNJkHrRcH1DDJ-J*rit&o|^39)8Ngzst zs1AZ9Y%gqMF={pMp*UNWZ>G7leE-E|QtFxYY3_4q#hS3e=P*2Tau3Ch9z=f-l|ZnB z&oaX2C0Ev^xmP1I^ux7QYd*PQd#ni&D{Q<38?|C=uwK@LyNS^gy)pQ;UvgQCymk)C z;jMjP8(2A|nbOj;NBM|4vb52_h985@vaKhF4sc1uHcm$copULfZm)agK3ZsLE3RGS%Bh8LU7-ba(1PBoK&_S&EisL6SdJC4 zrI(C^S7@o6Tqtc$v>YZ7$$0BHA{jGky*3Ei!|TUf(_U})2=sQTtDN>gfAwMpiIACA zsw?8ez8Fz0;1%cMJK^xXGiC;RCWtr?d;^YAn{)dfw$TT~;~?&jvB7#-lQ;WF^s1}H z5S%M)L-qzEK~zNC&c1V*_>B?nogZyrmk05Ezc9hM%=b+GYbV*U3)!>s}ve*wYwb$r{08P1EAWoPN{IpaYz0l^aXFlMSDt=P}O9qPKG{9uwg^ zmbD<}fJgzsw>=zRVbtdAEO5gMLUwqiL9m4Fg>9S$F&>0O`Yd64tO<8s80RlwoL9ko z#j6^>aO0P6-riZi=osrt--} zOoxfzx;1vEU`M|jvnbEIJlC2pjQv+B{{rzC_UA`Hm~VFFeT?~LTi)Y@d;8ZQHo*q= zQ7(@=wimV`#E&4p0l^Zs7q)@Z5BE5T(=i0+V%s>=?VTBY9cMBMEyyt(zw_evUx*n% zJPSf1046w>d9UWbqU!+SWe_Dn@LM~6smC#+Qu9F!1yMZ42J2-_O7#RGXG_@8hitH3 z_SQQoaxV@{mVK?u^}{V_-eCDJ!}gn`R74+6Y%nT(qf78JK3*H+9@9X5-d{euU=5ts>%kN1ppXssM zmo+K%9=$O!^&`4W8%UZpDYcmh)B7Zs>FttcP4cE8F6ZTod6z1=On;R$YYLY`<|~xa zkzD+ymNhBWHh7OCZvo8gEQFciB+Z(_Hq6Pt - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-15T14:40:02 - 2019-01-15T14:40:02 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.973 0.71 0 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - - - - 96.63961 822.28 -45.4537 99.58848 824.0162 -44.73399 100.3009 822.5781 -44.22518 102.2305 825.6064 -44.10003 100.3009 822.5781 -44.22518 99.58848 824.0162 -44.73399 98.81455 821.7077 -44.59094 98.81455 821.7077 -44.59094 100.3009 822.5781 -44.22518 97.35289 820.8485 -44.94186 103.0888 823.0031 -43.06891 102.4791 823.9492 -43.70977 102.4791 823.9492 -43.70977 95.78633 823.7277 -45.41882 98.732 825.4668 -44.69404 101.3344 826.9566 -44.10634 98.732 825.4668 -44.69404 94.89007 825.0267 -44.84073 97.82931 826.764 -44.1095 100.4032 828.1838 -43.60338 97.82931 826.764 -44.1095 94.05198 826.0305 -43.7847 96.98281 827.7606 -43.04671 99.53475 829.1593 -42.64395 96.98281 827.7606 -43.04671 94.8309 827.4833 -42.00791 96.29096 828.3419 -41.63231 99.08172 829.932 -41.3139 96.29096 828.3419 -41.63231 93.36914 826.6239 -42.376 66.87915 815.8128 -36.57975 96.29096 828.3419 -41.63231 94.8309 827.4833 -42.00791 91.03065 827.1286 -38.24599 94.5586 829.5798 -37.15718 96.29096 828.3419 -41.63231 91.03065 827.1286 -38.24599 99.08172 829.932 -41.3139 93.36914 826.6239 -42.376 82.38558 819.1723 -46.42704 93.36914 826.6239 -42.376 94.05198 826.0305 -43.7847 83.20429 820.6342 -44.76264 83.20429 820.6342 -44.76264 83.16931 818.204 -47.44021 94.89007 825.0267 -44.84073 84.01802 816.9689 -48.01707 95.78633 823.7277 -45.41882 84.84444 815.5946 -48.09809 96.63961 822.28 -45.4537 97.35289 820.8485 -44.94186 89.78161 816.5842 -46.73441 97.35289 820.8485 -44.94186 86.53163 814.7584 -47.4607 97.22507 816.6182 -43.4109 97.35289 820.8485 -44.94186 103.0888 823.0031 -43.06891 89.78161 816.5842 -46.73441 126.3658 848.138 -39.59248 122.9972 853.8332 -40.77885 122.9813 854.0506 -40.77388 122.5459 853.6271 -40.85788 122.9813 854.0506 -40.77388 122.9972 853.8332 -40.77885 126.6314 856.4227 -39.94916 122.9076 859.4448 -40.58209 126.6314 856.4227 -39.94916 122.9813 854.0506 -40.77388 121.8066 854.0563 -40.87001 122.9076 859.4448 -40.58209 122.9813 854.0506 -40.77388 121.8396 853.6424 -40.88691 121.8066 854.0563 -40.87001 122.0749 853.6376 -40.88835 123.0112 853.615 -40.78322 123.0112 853.615 -40.78322 122.9759 851.9521 -40.81676 122.5459 853.6271 -40.85788 123.0112 853.615 -40.78322 122.9759 851.9521 -40.81676 122.7545 850.2697 -40.8462 122.2552 850.7108 -40.95146 122.7545 850.2697 -40.8462 122.3393 848.5747 -40.88467 122.3393 848.5747 -40.88467 121.7676 846.8433 -40.92945 121.434 847.9445 -41.0604 121.7676 846.8433 -40.92945 120.9755 844.9235 -40.9898 120.288 845.3042 -41.18836 120.9755 844.9235 -40.9898 123.7472 839.2442 -38.72842 120.1634 843.2412 -41.05213 120.1634 843.2412 -41.05213 131.6624 851.4304 -38.2397 132.5773 847.8466 -37.14473 133.4368 844.9106 -35.84304 131.2948 853.0414 -38.58212 133.6607 848.7818 -36.68614 131.6624 851.4304 -38.2397 131.2948 853.0414 -38.58212 132.5773 847.8466 -37.14473 130.7148 855.85 -38.9846 132.57 853.7291 -38.01493 130.7148 855.85 -38.9846 130.1761 858.7857 -39.16753 130.1761 858.7857 -39.16753 130.1761 858.7857 -39.16753 129.7046 862.9567 -39.2102 130.0502 867.2322 -39.03238 130.1761 858.7857 -39.16753 129.7046 862.9567 -39.2102 130.8236 867.3078 -38.67462 131.71 858.9349 -38.56543 131.71 858.9349 -38.56543 119.1268 841.3548 -41.13626 118.908 842.7618 -41.33905 119.1268 841.3548 -41.13626 117.9432 839.4354 -41.2396 117.3367 840.3011 -41.5174 117.9432 839.4354 -41.2396 116.5804 837.4562 -41.37215 116.5804 837.4562 -41.37215 115.0098 835.3923 -41.54201 115.596 837.9152 -41.72971 115.0098 835.3923 -41.54201 113.7895 833.9255 -41.68958 113.7059 835.614 -41.9822 113.7895 833.9255 -41.68958 121.7037 831.6785 -36.78449 115.2597 828.4114 -38.98679 112.5321 832.514 -41.85503 112.5321 832.514 -41.85503 128.4031 835.3474 -34.48127 134.947 844.2312 -34.54032 133.4368 844.9106 -35.84304 133.9633 843.2614 -34.92213 133.9633 843.2614 -34.92213 109.059 825.5263 -41.08322 111.1721 831.0858 -42.04923 111.6669 833.3928 -42.28318 111.1721 831.0858 -42.04923 108.9007 828.9141 -42.41382 109.4939 831.2684 -42.63869 108.9007 828.9141 -42.41382 106.3776 826.7628 -42.87363 107.1902 829.2504 -43.05638 106.3776 826.7628 -42.87363 104.5042 825.3461 -43.25953 104.7672 827.3576 -43.54169 104.5042 825.3461 -43.25953 109.059 825.5263 -41.08322 104.3088 816.6144 -39.68877 115.2597 828.4114 -38.98679 121.7037 831.6785 -36.78449 110.9404 816.6098 -35.59943 128.4031 835.3474 -34.48127 135.3475 839.4111 -32.08028 135.3475 839.4111 -32.08028 136.3576 840.2106 -31.58448 135.3475 839.4111 -32.08028 116.9984 816.6045 -31.17918 136.4499 836.6348 -29.44046 137.9292 836.2534 -27.66033 136.4499 836.6348 -29.44046 135.3475 839.4111 -32.08028 136.3576 840.2106 -31.58448 122.8234 864.872 -40.40821 122.8234 864.872 -40.40821 129.2301 867.1531 -39.25193 122.5049 876.5244 -40.10868 129.2301 867.1531 -39.25193 122.8234 864.872 -40.40821 121.9715 864.8721 -40.47755 122.5049 876.5244 -40.10868 122.8234 864.872 -40.40821 121.9715 864.8721 -40.47755 129.2301 867.1531 -39.25193 122.4838 877.0347 -40.09796 127.8447 879.516 -39.34615 124.9302 918.7655 -39.21965 129.2301 867.1531 -39.25193 127.8447 879.516 -39.34615 130.0502 867.2322 -39.03238 120.2931 864.858 -40.18024 120.0931 859.3576 -40.29303 119.517 864.8444 -39.82251 115.9878 861.3115 -37.80797 119.517 864.8444 -39.82251 120.0931 859.3576 -40.29303 119.3378 876.4132 -39.4775 120.2931 864.858 -40.18024 119.517 864.8444 -39.82251 118.9433 870.7209 -39.2923 116.0766 867.6079 -37.09818 118.9433 870.7209 -39.2923 120.642 854.0506 -40.68865 115.7227 855.0606 -38.52877 120.642 854.0506 -40.68865 121.1195 864.8674 -40.40108 120.6603 853.855 -40.70168 120.642 854.0506 -40.68865 120.6603 853.855 -40.70168 121.1348 853.6541 -40.81576 120.6761 853.66 -40.71397 121.6031 853.6467 -40.87426 121.4128 876.4819 -40.13354 121.1195 864.8674 -40.40108 120.3389 876.4493 -39.92034 118.7332 888.2786 -39.19315 117.9535 882.6265 -38.41393 117.5169 888.1918 -38.14724 115.1068 887.1198 -35.03 117.5169 888.1918 -38.14724 117.9535 882.6265 -38.41393 118.2263 891.7055 -39.14393 118.7332 888.2786 -39.19315 117.5169 888.1918 -38.14724 117.047 891.4428 -38.09558 115.1068 887.1198 -35.03 117.047 891.4428 -38.09558 117.5169 888.1918 -38.14724 118.4155 876.9236 -38.79073 115.6424 880.3112 -35.71014 118.4155 876.9236 -38.79073 118.458 876.399 -38.82933 118.458 876.399 -38.82933 115.9681 873.9399 -36.39908 120.2227 888.3742 -39.79951 122.4838 877.0347 -40.09796 121.8234 888.4683 -39.90036 121.8234 888.4683 -39.90036 121.2369 892.3251 -39.87262 121.8234 888.4683 -39.90036 120.2227 888.3742 -39.79951 126.4223 892.2186 -39.412 121.2369 892.3251 -39.87262 119.6688 892.0253 -39.75721 -40.95819 756.9003 21.16058 -40.87191 756.9262 21.29193 -40.86539 756.9 21.30298 117.1597 894.9561 -39.10882 116.0405 894.5249 -38.02728 114.4759 890.0855 -34.55942 116.0405 894.5249 -38.02728 114.4647 900.7906 -38.99804 117.1597 894.9561 -39.10882 116.0405 894.5249 -38.02728 114.7937 897.3363 -37.92744 116.0405 894.5249 -38.02728 113.3762 900.2973 -37.78983 113.5036 896.4718 -35.86352 114.7937 897.3363 -37.92744 114.5365 893.679 -35.84715 114.5365 893.679 -35.84715 118.5446 895.4949 -39.75284 120.043 896.0821 -39.88854 120.043 896.0821 -39.88854 -42.78251 756.9 17.60024 -42.94599 757.1629 17.25689 -43.60866 757.0657 15.8037 118.8036 899.0205 -39.90953 120.043 896.0821 -39.88854 118.5446 895.4949 -39.75284 118.8036 899.0205 -39.90953 115.8607 901.424 -39.73756 117.4005 902.1232 -39.92086 113.3762 900.2973 -37.78983 112.5642 902.5535 -38.21789 114.4647 900.7906 -38.99804 113.3762 900.2973 -37.78983 112.6046 900.2908 -36.984 112.5642 902.5535 -38.21789 113.3762 900.2973 -37.78983 113.5036 896.4718 -35.86352 117.4005 902.1232 -39.92086 113.7839 905.6068 -39.82262 117.4005 902.1232 -39.92086 115.8607 901.424 -39.73756 116.1417 904.4844 -39.92755 116.1417 904.4844 -39.92755 112.7351 904.8718 -39.34645 112.0375 903.7823 -38.45359 107.9124 911.9072 -39.79281 106.4995 912.6536 -39.67431 104.8784 914.7015 -39.79062 104.4634 914.4802 -39.71433 104.8784 914.7015 -39.79062 106.4995 912.6536 -39.67431 105.1641 915.0373 -39.86838 104.127 915.6387 -39.82101 105.1641 915.0373 -39.86838 104.8784 914.7015 -39.79062 102.3078 917.065 -39.8171 104.127 915.6387 -39.82101 104.8784 914.7015 -39.79062 104.4634 914.4802 -39.71433 106.8844 912.1488 -39.63413 108.2143 909.1361 -39.0623 106.8844 912.1488 -39.63413 105.3821 912.0302 -39.44074 104.0454 914.2536 -39.68529 108.6624 909.6759 -39.3782 108.6624 909.6759 -39.3782 110.4807 908.5613 -39.61805 109.9506 907.6937 -39.11391 109.9506 907.6937 -39.11391 110.2177 907.2536 -39.04916 110.9919 904.2917 -38.04355 110.2177 907.2536 -39.04916 109.5879 905.4799 -38.07789 111.5216 904.8729 -38.6565 111.5216 904.8729 -38.6565 112.0375 903.7823 -38.45359 111.6362 900.7736 -36.6109 111.22 909.2433 -39.88789 108.3988 912.4432 -39.91779 105.3088 915.2073 -39.89245 105.3088 915.2073 -39.89245 105.4539 915.3775 -39.90648 105.4539 915.3775 -39.90648 114.6334 906.759 -39.93593 110.7272 911.238 -39.94303 112.8562 908.9759 -39.94253 108.3496 913.488 -39.93131 105.7449 915.7183 -39.90445 105.7449 915.7183 -39.90445 124.964 905.2604 -39.45148 108.3496 913.488 -39.93131 105.7449 915.7183 -39.90445 104.1876 917.0498 -39.87772 104.1876 917.0498 -39.87772 114.6334 906.759 -39.93593 112.8562 908.9759 -39.94253 110.7272 911.238 -39.94303 102.1898 918.042 -39.83635 102.0809 918.7595 -39.83027 102.3539 918.6521 -39.83146 105.3215 918.6506 -39.78065 102.3539 918.6521 -39.83146 102.0809 918.7595 -39.83027 103.304 917.8117 -39.85877 103.304 917.8117 -39.85877 102.3539 918.6521 -39.83146 105.3215 918.6506 -39.78065 101.0211 919.5717 -39.80072 101.7747 918.9539 -39.82463 123.4706 918.6409 -39.46994 101.7747 918.9539 -39.82463 101.4227 919.2172 -39.81539 101.4227 919.2172 -39.81539 101.0211 919.5717 -39.80072 100.5076 920.0678 -39.77748 101.0211 919.5717 -39.80072 102.1898 918.042 -39.83635 123.4211 919.5814 -39.4158 100.5076 920.0678 -39.77748 103.2362 916.7457 -39.83912 103.2362 916.7457 -39.83912 99.99839 920.5518 -39.75283 126.4223 892.2186 -39.412 124.964 905.2604 -39.45148 123.4706 918.6409 -39.46994 123.4706 918.6409 -39.46994 124.7983 920.6039 -39.10908 124.9302 918.7655 -39.21965 123.4706 918.6409 -39.46994 124.5188 920.5902 -39.19145 123.4211 919.5814 -39.4158 132.6344 867.4899 -36.89392 127.3099 918.9406 -37.54774 128.0462 918.9772 -36.27764 127.9836 919.7941 -36.23212 128.0462 918.9772 -36.27764 127.3099 918.9406 -37.54774 128.917 910.0979 -36.27208 127.9836 919.7941 -36.23212 128.917 910.0979 -36.27208 128.0462 918.9772 -36.27764 132.1367 867.4387 -37.58807 126.2435 918.8682 -38.56114 126.5789 920.6547 -38.08487 126.2435 918.8682 -38.56114 127.9252 920.6104 -36.17528 127.3605 920.6456 -37.20397 127.1848 920.6505 -37.44117 130.8236 867.3078 -38.67462 125.6137 920.6359 -38.75999 131.5267 867.3773 -38.1882 126.1147 920.6488 -38.45192 131.5267 867.3773 -38.1882 132.1367 867.4387 -37.58807 132.9647 859.0614 -37.49254 132.6344 867.4899 -36.89392 132.9238 868.4552 -36.13468 133.0059 867.5297 -36.12742 133.0059 867.5297 -36.12742 130.5536 893.2473 -36.23859 136.3429 868.772 -25.48204 133.0059 867.5297 -36.12742 132.9238 868.4552 -36.13468 133.4032 863.3398 -36.09855 133.4032 863.3398 -36.09855 130.1468 902.922 -34.83712 130.5536 893.2473 -36.23859 134.582 883.9559 -26.72184 133.9329 885.6323 -28.46388 133.2871 887.4611 -30.01383 132.6661 889.4246 -31.3619 131.5576 893.6783 -33.41914 130.6988 898.244 -34.58691 129.5595 910.1627 -34.51994 129.5904 909.7661 -34.53731 127.9252 920.6104 -36.17528 127.7267 926.5746 -35.14918 139.5671 868.9575 3.388088 143.1579 827.939 5.734078 143.3643 827.4586 -3e-6 143.3012 826.0701 0 143.3643 827.4586 -3e-6 143.1579 827.939 5.734078 139.6239 868.7347 2.039108 139.6233 868.737 -2.057874 143.1485 827.9603 -5.863436 143.0552 826.6248 -6.282001 143.1485 827.9603 -5.863436 143.3643 827.4586 -3e-6 143.3012 826.0701 0 138.5625 868.9774 14.51246 142.8816 828.5879 8.756622 143.0547 826.6259 6.283241 142.8816 828.5879 8.756622 142.4804 829.5326 11.83533 142.361 828.2103 12.24535 142.4804 829.5326 11.83533 141.9534 830.7908 14.92265 141.9534 830.7908 14.92265 136.3432 868.772 25.48079 141.297 832.3806 18.01872 141.3204 830.6381 17.70509 141.297 832.3806 18.01872 140.503 834.3419 21.1327 140.503 834.3419 21.1327 139.5903 836.6267 24.19011 140.0413 833.7045 22.60368 139.5903 836.6267 24.19011 138.5869 839.1967 27.11442 138.612 837.2388 26.96593 138.5869 839.1967 27.11442 132.9238 868.4552 36.13486 137.4944 842.0653 29.93016 137.4944 842.0653 29.93016 136.3567 845.4484 32.47555 137.0927 841.1191 30.84845 137.4944 842.0653 29.93016 136.3567 845.4484 32.47555 137.0927 841.1191 30.84845 135.3003 849.5056 34.42562 135.779 844.9494 33.68421 135.3003 849.5056 34.42562 134.8411 851.7266 35.12348 134.6131 849.3018 35.734 134.8411 851.7266 35.12348 134.4357 854.075 35.63267 134.4357 854.075 35.63267 134.0899 856.5495 35.94763 133.6641 854.0498 36.99082 134.0899 856.5495 35.94763 133.4032 863.3399 36.09856 133.8004 859.1506 36.06969 133.8004 859.1506 36.06969 132.6345 867.49 36.89372 133.8004 859.1506 36.06969 133.4032 863.3399 36.09856 132.9646 859.0614 37.49256 132.9646 859.0614 37.49256 133.0059 867.5297 36.12741 133.0059 867.5297 36.12741 127.3146 918.9409 37.53897 133.0059 867.5297 36.12741 132.9238 868.4552 36.13486 132.6345 867.49 36.89372 131.5577 893.6779 33.41898 128.9165 910.0979 36.27341 130.5527 893.2471 36.24093 130.5527 893.2471 36.24093 130.1468 902.922 34.83712 130.6988 898.2439 34.58691 135.2394 882.4541 24.8023 132.6669 889.4222 31.36039 133.2879 887.4588 30.01202 133.9335 885.6305 28.46219 134.5824 883.9549 26.72071 139.371 869.7337 6.015368 137.3591 877.1428 17.28558 138.9048 871.6922 9.639678 129.5947 867.9478 2.053213 139.5671 868.9575 3.388088 139.6239 868.7347 2.039108 129.5146 868.9653 6.033399 139.371 869.7337 6.015368 129.5947 867.9478 -2.0535 139.6233 868.737 -2.057874 139.5669 868.9584 -3.392788 139.5669 868.9584 -3.392788 142.453 829.5972 -12.01607 138.5621 868.9774 -14.51512 139.3699 869.7383 -6.027314 142.8634 828.6302 -8.920443 139.3699 869.7383 -6.027314 139.5584 836.708 -24.28902 137.3591 877.1428 -17.28544 140.4641 834.4384 -21.27277 141.2572 832.478 -18.18894 141.9182 830.8756 -15.10584 138.9051 871.6923 -9.639678 133.8004 859.1506 -36.06969 134.0903 856.5468 -35.94738 134.4364 854.0704 -35.63197 134.8421 851.721 -35.12205 135.3016 849.4999 -34.42351 136.3579 845.4445 -32.47325 137.4944 842.0653 -29.93017 138.5677 839.2455 -27.1672 135.2398 882.4542 -24.8023 133.8004 859.1506 -36.06969 132.9647 859.0614 -37.49254 133.8004 859.1506 -36.06969 134.0903 856.5468 -35.94738 133.6641 854.0498 -36.99079 134.4364 854.0704 -35.63197 134.8421 851.721 -35.12205 134.6132 849.3018 -35.73392 135.3016 849.4999 -34.42351 135.779 844.9495 -33.68419 136.3579 845.4445 -32.47325 137.4944 842.0653 -29.93017 137.0927 841.1191 -30.84844 137.4944 842.0653 -29.93017 138.5677 839.2455 -27.1672 137.0927 841.1191 -30.84844 138.6115 837.2401 -26.96671 139.5584 836.708 -24.28902 140.041 833.7053 -22.60442 140.4641 834.4384 -21.27277 141.2572 832.478 -18.18894 141.3205 830.6378 -17.70416 141.9182 830.8756 -15.10584 142.453 829.5972 -12.01607 142.3613 828.2095 -12.24408 142.8634 828.6302 -8.920443 128.9165 910.0979 36.27341 129.5904 909.7661 34.53731 129.5595 910.1627 34.51994 127.9836 919.794 36.23212 128.0463 918.9772 36.27764 128.0463 918.9772 36.27764 125.7858 916.3447 34.23794 129.5595 910.1627 34.51994 129.5904 909.7661 34.53731 127.9252 920.6104 36.17529 127.7266 926.5471 35.1567 129.0347 916.6004 34.23794 129.0347 916.6004 34.23794 130.1468 902.922 34.83712 126.8625 902.6635 34.83712 130.1468 902.922 34.83712 130.6988 898.2439 34.58691 126.8625 902.6635 34.83712 127.2389 897.8814 34.57314 131.5577 893.6779 33.41898 127.6039 893.2432 33.37425 132.6669 889.4222 31.36039 127.9435 888.9289 31.28688 133.2879 887.4588 30.01202 133.9335 885.6305 28.46219 128.2443 885.1062 28.39206 134.5824 883.9549 26.72071 135.2394 882.4541 24.8023 128.4948 881.9233 24.8023 135.2394 882.4541 24.8023 137.3591 877.1428 17.28558 128.4948 881.9233 24.8023 138.9048 871.6922 9.639678 129.3591 870.941 9.639678 138.9048 871.6922 9.639678 129.3591 870.941 9.639678 127.3605 920.6456 37.20409 128.0463 918.9772 36.27764 127.9836 919.794 36.23212 127.3146 918.9409 37.53897 127.9252 920.6104 36.17529 127.3605 920.6456 37.20409 127.9252 920.6104 36.17529 127.7266 926.5471 35.1567 128.7303 923.3433 33.26499 127.9364 932.3805 32.97206 127.1629 926.9227 36.12649 127.9364 932.3805 32.97206 128.8782 930.0548 30.85227 128.4863 937.8391 29.64143 127.3887 932.8817 33.91877 128.4863 937.8391 29.64143 128.7515 926.7415 32.23795 129.4002 936.1706 27.10119 129.2494 942.6716 25.25912 128.6865 943.1541 26.49909 129.2494 942.6716 25.25912 129.1083 933.2332 29.11908 127.9387 938.3433 30.67211 129.7447 938.8656 24.81575 129.6655 944.8053 22.69896 129.6655 944.8053 22.69896 130.1156 941.334 22.24767 130.0774 946.708 19.92429 129.4962 947.1883 21.52464 130.0774 946.708 19.92429 130.8404 945.372 16.50157 130.4675 948.3737 16.93998 130.4675 948.3737 16.93998 130.8156 949.7644 13.79026 130.2363 950.3331 15.88587 130.8156 949.7644 13.79026 131.4074 948.0896 10.25294 131.1057 950.8742 10.49296 131.1057 950.8742 10.49296 131.3222 951.6738 7.119486 130.8015 952.4959 9.745577 131.3222 951.6738 7.119486 131.7261 949.5084 3.510437 131.4582 952.1645 3.678002 131.4582 952.1645 3.678002 131.5077 952.3397 0.1952069 131.1072 953.5996 3.285838 131.5077 952.3397 0.1952069 131.7282 949.5183 -3.415012 131.468 952.1997 -3.291884 131.1071 953.5995 -3.286304 131.468 952.1997 -3.291884 131.3411 951.7426 -6.746467 131.3411 951.7426 -6.746467 131.6024 948.9771 -6.892071 131.1321 950.9731 -10.14081 130.8015 952.4959 -9.746229 131.1321 950.9731 -10.14081 131.4045 948.0778 -10.28975 130.8474 949.8888 -13.46649 130.8474 949.8888 -13.46649 131.1363 946.838 -13.55845 130.5023 948.5167 -16.65008 130.2365 950.3331 -15.88685 130.5023 948.5167 -16.65008 130.8147 945.2409 -16.7336 130.1124 946.8617 -19.67341 130.1124 946.8617 -19.67341 130.448 943.2946 -19.76618 129.6983 944.9621 -22.48851 129.4958 947.1877 -21.52445 129.6983 944.9621 -22.48851 130.0682 941.0363 -22.5865 129.278 942.8237 -25.09 129.278 942.8237 -25.09 129.3599 935.8105 -27.37289 128.8736 940.4887 -27.44325 128.6855 943.1534 -26.49745 128.8736 940.4887 -27.44325 129.696 938.5127 -25.1426 128.8637 929.7872 -30.97928 128.5027 937.9624 -29.5483 128.5027 937.9624 -29.5483 127.9419 932.4565 -32.93466 127.9387 938.3439 -30.67176 127.9419 932.4565 -32.93466 129.0347 916.6004 -34.23794 127.3891 932.8815 -33.91855 127.7267 926.5746 -35.14918 128.7312 923.2493 -33.28806 127.1628 926.9234 -36.12641 127.9252 920.6104 -36.17528 127.3605 920.6456 -37.20397 126.8625 902.6635 -34.83712 129.5595 910.1627 -34.51994 129.0347 916.6004 -34.23794 129.5904 909.7661 -34.53731 125.7858 916.3447 -34.23794 129.0347 916.6004 -34.23794 128.7312 923.2493 -33.28806 125.7858 916.3447 -34.23794 125.243 923.2413 -33.22167 128.8637 929.7872 -30.97928 124.7276 929.7897 -30.82175 129.3599 935.8105 -27.37289 124.2632 935.6913 -27.15947 129.696 938.5127 -25.1426 130.0682 941.0363 -22.5865 123.8676 940.718 -22.3899 130.448 943.2946 -19.76618 130.8147 945.2409 -16.7336 123.5545 944.6964 -16.68411 131.1363 946.838 -13.55845 123.3385 947.4402 -10.29736 131.4045 948.0778 -10.28975 131.6024 948.9771 -6.892071 123.2282 948.8416 -3.490015 131.7282 949.5183 -3.415012 123.228 948.8441 3.464874 131.7261 949.5084 3.510437 131.4074 948.0896 10.25294 123.3384 947.4419 10.29131 130.8404 945.372 16.50157 123.5555 944.6834 16.70721 130.1156 941.334 22.24767 123.8705 940.6809 22.4328 129.7447 938.8656 24.81575 129.4002 936.1706 27.10119 124.2675 935.6369 27.20138 129.1083 933.2332 29.11908 124.7319 929.7355 30.84803 128.8782 930.0548 30.85227 128.7515 926.7415 32.23795 125.2457 923.207 33.23033 128.7303 923.3433 33.26499 129.0347 916.6004 34.23794 125.7858 916.3447 34.23794 129.5146 868.9654 -6.033578 138.9051 871.6923 -9.639678 129.3591 870.941 -9.639678 138.9051 871.6923 -9.639678 137.3591 877.1428 -17.28544 129.3591 870.941 -9.639678 135.2398 882.4542 -24.8023 128.4948 881.9233 -24.8023 135.2398 882.4542 -24.8023 134.582 883.9559 -26.72184 128.4948 881.9233 -24.8023 128.2443 885.1062 -28.39206 133.9329 885.6323 -28.46388 133.2871 887.4611 -30.01383 127.9435 888.9289 -31.28688 132.6661 889.4246 -31.3619 127.6039 893.2432 -33.37425 131.5576 893.6783 -33.41914 127.2389 897.8814 -34.57314 130.6988 898.244 -34.58691 130.1468 902.922 -34.83712 130.1468 902.922 -34.83712 126.8625 902.6635 -34.83712 142.848 824.7522 0 142.5868 825.3287 -6.487818 142.848 824.7522 0 142.5863 825.3298 6.488985 141.852 826.9725 12.631 140.756 829.4799 18.23106 139.417 832.6331 23.22996 137.9297 836.2521 27.65963 136.3575 840.2105 31.58454 134.9469 844.231 34.54037 136.3575 840.2105 31.58454 136.6261 836.195 28.99015 135.3474 839.4114 32.08058 133.9639 843.2587 34.92061 135.3474 839.4114 32.08058 142.0496 823.6112 0 141.9178 823.898 -4.608072 142.0496 823.6112 0 141.5431 824.7125 9.011344 141.842 824.0759 5.837203 140.5285 826.9774 15.57968 141.113 825.6724 12.26144 139.7832 828.6753 18.96641 137.8111 833.3204 25.75347 138.8802 830.7847 22.3666 117.0195 816.6045 31.16236 136.6261 836.195 28.99015 135.3474 839.4114 32.08058 123.7471 839.2442 38.72842 135.3474 839.4114 32.08058 133.9639 843.2587 34.92061 128.4038 835.3477 34.481 128.4038 835.3477 34.481 135.4948 816.5819 10e-7 142.0496 823.6112 0 141.842 824.0759 5.837203 134.9391 816.5828 -5.532523 142.0496 823.6112 0 135.4948 816.5819 10e-7 141.9178 823.898 -4.608072 134.9398 816.5828 5.529152 141.5431 824.7125 9.011344 133.2979 816.5854 10.98375 141.113 825.6724 12.26144 140.5285 826.9774 15.57968 130.6096 816.5892 16.3187 139.7832 828.6753 18.96641 126.9437 816.5939 21.48931 138.8802 830.7847 22.3666 137.8111 833.3204 25.75347 122.3805 816.5991 26.45132 133.6605 848.7817 36.68626 132.5699 853.7291 38.01499 131.7098 858.9349 38.56552 131.5267 867.3773 38.18819 131.7098 858.9349 38.56552 132.1369 867.4387 37.58791 130.715 855.8483 38.98445 130.176 858.7857 39.16754 130.05 867.2322 39.03246 130.176 858.7857 39.16754 130.8235 867.3077 38.67472 133.4366 844.9102 35.84298 131.9201 850.3676 37.96505 132.5781 847.8427 37.14339 131.6607 851.4362 38.24123 131.2952 853.0383 38.58163 126.6314 856.4227 39.94916 130.715 855.8483 38.98445 130.176 858.7857 39.16754 129.7046 862.9567 39.2102 122.9071 859.4451 40.58218 130.176 858.7857 39.16754 129.7046 862.9567 39.2102 122.9814 854.0507 40.77393 126.6314 856.4227 39.94916 133.4366 844.9102 35.84298 126.3457 848.1257 39.59766 132.5781 847.8427 37.14339 120.976 844.9239 40.9897 131.9201 850.3676 37.96505 131.6607 851.4362 38.24123 131.2952 853.0383 38.58163 122.9814 854.0507 40.77393 122.9972 853.8332 40.77884 123.0112 853.615 40.78322 129.2301 867.1531 39.25193 129.2301 867.1531 39.25193 127.8451 879.4953 39.34627 129.2301 867.1531 39.25193 130.05 867.2322 39.03246 122.8234 864.872 40.40821 129.2301 867.1531 39.25193 127.8451 879.4953 39.34627 122.8234 864.872 40.40821 124.9208 918.7646 39.2209 130.8235 867.3077 38.67472 123.4904 918.6412 39.46746 124.9644 905.2396 39.45153 126.4229 892.191 39.41211 131.5267 867.3773 38.18819 126.2437 918.8684 38.56097 132.1369 867.4387 37.58791 123.4199 919.581 39.41373 123.4904 918.6412 39.46746 124.9208 918.7646 39.2209 114.6004 906.7994 39.93623 124.9644 905.2396 39.45153 123.4904 918.6412 39.46746 102.0805 918.7595 39.83206 123.4904 918.6412 39.46746 123.4199 919.581 39.41373 102.3536 918.6522 39.8332 105.3215 918.6506 39.78185 103.2511 917.8596 39.85745 105.3215 918.6506 39.78185 104.1147 917.1116 39.87629 104.9456 916.4006 39.89176 105.745 915.7183 39.90445 108.3745 913.4779 39.93101 112.7982 909.0377 39.94281 110.7237 911.25 39.94271 124.7988 920.6039 39.10903 126.2437 918.8684 38.56097 123.3564 920.5201 39.35204 124.5189 920.5902 39.19149 126.579 920.6547 38.08509 125.6138 920.6359 38.76018 126.1148 920.6488 38.45215 127.1846 920.6505 37.44161 121.8234 888.4683 39.90036 126.4229 892.191 39.41211 122.5049 876.5245 40.10868 122.4837 877.0357 40.09794 121.2369 892.3253 39.87262 -44.39982 756.9 13.93945 120.0429 896.0822 39.88854 118.8021 899.0239 39.90954 117.4006 902.1232 39.92086 116.1325 904.4937 39.92776 100.5079 920.0677 39.77952 123.3564 920.5201 39.35204 101.7749 918.9538 39.82648 101.423 919.2171 39.81728 101.0208 919.5722 39.80266 124.3138 927.4183 38.05457 123.3564 920.5201 39.35204 124.5189 920.5902 39.19149 99.99843 920.552 39.75493 123.1448 927.5365 38.18885 99.99843 920.552 39.75493 123.3564 920.5201 39.35204 123.1448 927.5365 38.18885 125.413 927.312 37.63742 124.7988 920.6039 39.10903 125.6138 920.6359 38.76018 126.3807 927.1437 36.98257 126.1148 920.6488 38.45215 126.579 920.6547 38.08509 127.1846 920.6505 37.44161 102.0961 918.1702 39.83518 102.3536 918.6522 39.8332 102.0805 918.7595 39.83206 102.3536 918.6522 39.8332 103.2511 917.8596 39.85745 101.7749 918.9538 39.82648 101.423 919.2171 39.81728 101.0208 919.5722 39.80266 102.0085 917.5321 39.82312 101.0208 919.5722 39.80266 100.5079 920.0677 39.77952 102.0961 918.1702 39.83518 99.99843 920.552 39.75493 88 920.566 39.95563 88 917.4 40.05699 99.99843 920.552 39.75493 88 920.566 39.95563 102.0085 917.5321 39.82312 103.1013 916.9078 39.83985 104.1147 917.1116 39.87629 104.032 915.7561 39.82368 104.9456 916.4006 39.89176 105.454 915.3775 39.90653 105.745 915.7183 39.90445 105.3088 915.2073 39.89252 105.164 915.0373 39.86842 104.8785 914.7015 39.79062 107.8173 913.044 39.91899 105.745 915.7183 39.90445 105.454 915.3775 39.90653 108.3745 913.4779 39.93101 107.3747 912.5442 39.81581 105.3088 915.2073 39.89252 105.164 915.0373 39.86842 106.4988 912.6548 39.67447 104.8785 914.7015 39.79062 106.8839 912.1497 39.63427 104.4605 914.4786 39.71438 104.8785 914.7015 39.79062 104.032 915.7561 39.82368 104.4605 914.4786 39.71438 105.3521 912.084 39.44811 104.8785 914.7015 39.79062 106.4988 912.6548 39.67447 104.0454 914.2536 39.68529 103.1013 916.9078 39.83985 121.4128 876.482 40.13354 122.8234 864.872 40.40821 122.5049 876.5245 40.10868 121.9715 864.8721 40.47755 122.9071 859.4451 40.58218 122.8234 864.872 40.40821 121.9715 864.8721 40.47755 120.2235 888.3743 39.79911 122.4837 877.0357 40.09794 121.8234 888.4683 39.90036 120.2235 888.3743 39.79911 121.8234 888.4683 39.90036 121.2369 892.3253 39.87262 -43.60866 757.0657 15.8037 -42.94599 757.1629 17.25689 -44.39982 756.9 13.93945 119.6687 892.0253 39.75721 118.5446 895.4949 39.75284 120.0429 896.0822 39.88854 115.8605 901.4239 39.73825 120.0429 896.0822 39.88854 118.8021 899.0239 39.90954 118.5446 895.4949 39.75284 117.4006 902.1232 39.92086 115.8605 901.4239 39.73825 117.4006 902.1232 39.92086 116.1325 904.4937 39.92776 114.2468 904.8197 39.80636 114.6004 906.7994 39.93623 112.2884 907.8459 39.86549 112.7982 909.0377 39.94281 110.1178 910.5621 39.90443 110.7237 911.25 39.94271 122.9814 854.0507 40.77393 121.8066 854.0562 40.87001 122.9972 853.8332 40.77884 122.9814 854.0507 40.77393 121.8066 854.0562 40.87001 123.0112 853.615 40.78322 122.9749 851.9451 40.81702 122.2956 850.9064 40.94459 122.9749 851.9451 40.81702 123.0112 853.615 40.78322 122.5459 853.627 40.85791 122.5459 853.627 40.85791 121.7646 846.8342 40.92959 122.3363 848.5637 40.88488 122.7524 850.259 40.84643 120.5506 845.8501 41.1597 120.976 844.9239 40.9897 121.7646 846.8342 40.92959 120.1625 843.2394 41.05216 119.317 843.4682 41.29409 120.1625 843.2394 41.05216 121.5706 848.3198 41.04421 122.3363 848.5637 40.88488 122.7524 850.259 40.84643 115.017 835.4008 41.54104 113.7935 833.9299 41.68902 121.7049 831.679 36.78407 116.5805 837.4561 41.37209 117.9428 839.4351 41.23969 119.1273 841.3557 41.13624 112.8496 834.6514 42.10485 113.7935 833.9299 41.68902 115.017 835.4008 41.54104 115.2609 828.4119 38.98633 112.5386 832.5211 41.85418 112.5386 832.5211 41.85418 114.6703 836.7551 41.8503 116.5805 837.4561 41.37209 116.3521 838.9153 41.63529 117.9428 839.4351 41.23969 117.9103 841.1591 41.45104 119.1273 841.3557 41.13624 110.9677 816.6097 35.58115 121.7049 831.679 36.78407 115.2609 828.4119 38.98633 108.1023 828.2022 42.55206 109.0601 825.5267 41.08283 104.3425 816.6144 39.66959 109.0601 825.5267 41.08283 109.6882 829.6423 42.28274 111.1799 831.0939 42.04812 104.5137 825.3532 43.25754 103.0894 823.0034 43.06869 103.0894 823.0034 43.06869 106.3885 826.7714 42.87145 98.81452 821.7077 44.59096 97.35247 820.8483 44.94198 97.26519 816.6182 43.39142 97.35247 820.8483 44.94198 100.3009 822.5781 44.2252 102.485 823.9533 43.70849 99.5885 824.0161 44.73398 97.35247 820.8483 44.94198 98.81452 821.7077 44.59096 96.63951 822.2802 45.4537 84.86185 815.6048 48.09411 97.35247 820.8483 44.94198 96.63951 822.2802 45.4537 89.85622 816.6152 46.71382 89.85622 816.6152 46.71382 100.3009 822.5781 44.2252 99.5885 824.0161 44.73398 100.3009 822.5781 44.2252 102.485 823.9533 43.70849 102.0457 825.4873 44.14255 104.5137 825.3532 43.25754 104.4147 827.1004 43.61626 106.3885 826.7714 42.87145 106.6865 828.8381 43.15335 108.1023 828.2022 42.55206 109.6882 829.6423 42.28274 108.8465 830.6784 42.75177 111.1799 831.0939 42.04812 110.9056 832.6222 42.40356 120.642 854.0506 40.68863 120.6603 853.855 40.70168 120.676 853.6598 40.71396 115.312 848.8668 39.26469 120.676 853.6598 40.71396 120.6603 853.855 40.70168 121.1348 853.6541 40.81579 120.085 851.4066 40.72256 121.1348 853.6541 40.81579 120.676 853.6598 40.71396 115.312 848.8668 39.26469 120.085 851.4066 40.72256 120.676 853.6598 40.71396 120.642 854.0506 40.68863 121.6031 853.6467 40.87428 120.093 859.3574 40.29296 120.642 854.0506 40.68863 115.7233 855.0706 38.52759 120.093 859.3574 40.29296 122.075 853.6376 40.88836 121.8396 853.6424 40.88692 120.293 864.858 40.18021 119.517 864.8443 39.8225 121.1195 864.8674 40.40108 121.7408 851.0461 40.98669 122.075 853.6376 40.88836 121.1843 851.1834 40.96302 121.8396 853.6424 40.88692 121.6031 853.6467 40.87428 120.6335 851.3166 40.87392 99.35521 829.0547 42.67078 98.21279 829.4124 41.41084 96.2909 828.3418 41.63232 94.55615 829.579 37.15581 96.2909 828.3418 41.63232 98.21279 829.4124 41.41084 96.98281 827.7604 43.04682 94.05181 826.0307 43.7844 96.98281 827.7604 43.04682 96.2909 828.3418 41.63232 94.83088 827.4833 42.00795 68.69729 812.0592 47.6857 94.83088 827.4833 42.00795 96.2909 828.3418 41.63232 91.04274 827.1311 38.25501 91.04274 827.1311 38.25501 100.0135 830.512 41.21683 100.0135 830.512 41.21683 101.6677 830.4695 42.34325 101.6144 831.5631 41.06837 101.6144 831.5631 41.06837 103.9106 831.9912 42.06219 101.6966 831.6187 41.06171 100.0268 833.3928 37.25405 101.6966 831.6187 41.06171 104.0257 833.2709 40.89819 104.0257 833.2709 40.89819 106.0683 833.6017 41.82527 106.1351 834.9028 40.78632 106.1351 834.9028 40.78632 108.1514 835.3029 41.62664 107.816 836.3023 40.72071 107.816 836.3023 40.72071 110.1448 837.0797 41.46234 108.0766 836.5268 40.7131 108.2744 839.8704 38.4513 108.0766 836.5268 40.7131 100.847 836.3925 35.19604 109.8533 838.1243 40.67061 109.8533 838.1243 40.67061 112.0389 838.9229 41.3274 111.4277 839.6414 40.64946 111.4277 839.6414 40.64946 113.8182 840.817 41.21794 112.846 841.1002 40.6436 112.846 841.1002 40.6436 114.1254 842.502 40.64823 114.1254 842.502 40.64823 115.5004 842.786 41.12781 115.2119 843.7706 40.65759 115.2119 843.7706 40.65759 117.0563 844.8134 41.05279 115.2864 843.8604 40.65848 114.5769 848.2745 39.03366 115.2864 843.8604 40.65848 109.3784 844.4636 37.18497 116.3603 845.2092 40.67144 116.3603 845.2092 40.67144 118.4639 846.9035 40.98808 117.3447 846.5452 40.6861 117.3447 846.5452 40.6861 118.2025 847.8196 40.69953 118.2025 847.8196 40.69953 119.6829 849.0655 40.92969 118.9446 849.0504 40.71001 118.9446 849.0504 40.71001 119.573 850.242 40.71794 119.573 850.242 40.71794 120.3069 848.8236 41.06026 119.1514 846.5637 41.16828 117.7982 844.3827 41.28962 116.288 842.27 41.42749 114.6426 840.2206 41.58603 112.8914 838.2517 41.76824 111.0176 836.3389 41.98121 109.0372 834.4989 42.22831 106.9596 832.7414 42.51381 104.8005 831.0829 42.84066 102.5494 829.5218 43.21485 100.2224 828.0773 43.63751 97.82933 826.7639 44.10958 94.8899 825.027 44.84055 97.82933 826.7639 44.10958 101.1519 826.8448 44.146 98.73204 825.4667 44.69408 95.78619 823.728 45.41874 98.73204 825.4667 44.69408 120.9401 848.5735 41.09867 119.8527 846.2096 41.22596 118.5598 843.9295 41.37091 117.1019 841.7206 41.53665 115.5006 839.5767 41.72735 113.7849 837.5157 41.94579 111.9386 835.5121 42.19999 109.9777 833.5834 42.49362 107.9112 831.7402 42.83114 105.754 829.9998 43.21549 103.4958 828.3611 43.65342 93.36917 826.6239 42.37608 93.36917 826.6239 42.37608 83.27864 820.6784 44.74552 94.05181 826.0307 43.7844 93.36917 826.6239 42.37608 83.27864 820.6784 44.74552 84.03742 816.9805 48.01265 95.78619 823.728 45.41874 83.19112 818.2172 47.43517 94.8899 825.027 44.84055 82.41016 819.1872 46.42119 38.85072 794.8016 51.40095 23.89223 786.7396 51.57627 31.15691 790.5802 51.67125 35.85374 792.3453 52.64204 31.15691 790.5802 51.67125 23.89223 786.7396 51.57627 19.00859 784.2606 51.27798 24.15266 786.1592 52.57764 19.00859 784.2606 51.27798 24.15266 786.1592 52.57764 23.89223 786.7396 51.57627 38.85072 794.8016 51.40095 47.52556 798.851 51.89384 41.0798 796.0496 51.25895 41.0798 796.0496 51.25895 55.55648 804.3496 49.75762 47.00964 799.4151 50.75516 47.00964 799.4151 50.75516 64.3999 809.5261 48.4304 39.40974 799.3629 42.5282 14.08579 781.8502 50.77355 55.55648 804.3496 49.75762 59.1632 805.5448 50.53491 64.3999 809.5261 48.4304 70.78514 812.345 48.68265 68.69729 812.0592 47.6857 73.62217 814.9689 46.76115 73.62217 814.9689 46.76115 66.87905 815.813 36.579 71.50614 811.4096 49.65756 59.81768 804.6455 51.47333 48.1024 797.9901 52.79718 36.33682 791.5256 53.50995 24.23593 785.9807 52.80495 24.23593 785.9807 52.80495 24.5204 785.3845 53.40709 16.84811 782.3249 52.22959 24.5204 785.3845 53.40709 72.29828 810.2336 50.23626 60.54825 803.5299 52.05586 48.75956 796.9358 53.38592 36.90369 790.5349 54.10634 24.73831 784.9375 53.73996 24.73831 784.9375 53.73996 24.97445 784.4603 54.00923 17.25212 781.3226 53.1433 24.97445 784.4603 54.00923 73.08731 808.9273 50.3645 61.29306 802.2923 52.23317 49.44739 795.7678 53.61556 37.51676 789.4389 54.39167 25.35625 783.7005 54.29008 25.35625 783.7005 54.29008 25.48905 783.439 54.34984 17.77774 780.1406 53.71718 25.48905 783.439 54.34984 81.32271 811.8273 48.56457 89.23085 816.2634 46.85568 73.6519 807.5382 50.05944 59.03035 799.4121 52.40525 66.24102 803.393 51.33299 48.38925 793.655 53.63646 51.99261 795.5892 53.27133 32.18207 785.348 54.49921 45.16223 791.9449 53.91514 38.5587 788.5338 54.32919 26.0331 782.3823 54.41256 26.0331 782.3823 54.41256 26.7635 770.7086 53.2744 32.18207 785.348 54.49921 26.0331 782.3823 54.41256 19.18492 779.2378 53.98412 20.73796 770.6902 53.51503 26.0331 782.3823 54.41256 19.18492 779.2378 53.98412 20.73796 770.6902 53.51503 77.32096 793.6918 44.12339 89.23085 816.2634 46.85568 70.24884 793.6939 47.26134 81.32271 811.8273 48.56457 73.6519 807.5382 50.05944 62.99538 793.6934 49.90782 66.24102 803.393 51.33299 59.03035 799.4121 52.40525 55.6737 793.6894 52.04004 51.99261 795.5892 53.27133 48.38925 793.655 53.63646 39.17115 770.7317 51.32629 45.16223 791.9449 53.91514 32.92752 770.7223 52.54581 38.5587 788.5338 54.32919 9.369278 779.621 50.09883 9.449625 778.8548 51.20565 12.86346 781.2648 50.61743 14.08579 781.8502 50.77355 4.793039 777.5397 49.24356 2.096187 775.5989 49.70719 9.758913 777.887 52.09827 -3.933196 773.7857 47.03597 -5.139601 772.5883 47.70478 2.312551 774.6586 50.57894 0.287192 775.5648 48.20545 -11.89241 770.6198 44.24214 -12.17881 769.8516 45.16756 -5.016316 771.6679 48.55542 -8.134219 772.0848 45.66157 -16.56712 768.8731 42.1929 -18.92153 767.4064 42.07899 -12.15068 768.9427 45.99603 -15.39932 769.3005 42.73904 -23.73027 766.3764 38.27744 -25.25899 765.2653 38.42862 -18.99211 766.5005 42.8818 -19.28725 767.9067 40.80994 -27.82905 765.0387 35.52417 -31.08151 763.4387 34.21219 -25.43312 764.3538 39.19918 -34.65762 762.9643 29.73189 -36.27386 761.9216 29.46411 -31.36484 762.5129 34.94046 -31.36289 763.9411 32.75059 -39.59837 761.5718 24.11051 -40.71865 760.703 24.23377 -36.66963 760.9743 30.13438 -37.3636 762.1868 26.87069 -41.67632 761.0189 21.1053 -44.30499 759.7718 18.57973 -41.2265 759.7295 24.82384 -45.34208 760.0789 13.97997 -46.94388 759.1163 12.59107 -44.91918 758.77 19.06197 -43.69307 760.4937 17.60755 -46.45667 759.7993 10.83478 -48.55935 758.7263 6.364321 -47.64735 758.089 12.93613 -48.07806 759.4079 -6e-6 -49.10628 758.5971 -10e-7 -49.32313 757.6811 6.544657 -47.75965 759.482 4.866301 -47.91673 759.4463 -3.438587 -49.10628 758.5971 -10e-7 -48.07806 759.4079 -6e-6 -49.89212 757.5452 -10e-7 -48.47212 758.7462 -6.880445 -49.89212 757.5452 -10e-7 -43.7532 761.9663 -10e-7 -48.07806 759.4079 -6e-6 -47.75965 759.482 4.866301 -43.09181 762.087 -7.459362 -47.91673 759.4463 -3.438587 -43.11808 762.0819 7.310119 -46.45667 759.7993 10.83478 -45.34208 760.0789 13.97997 -41.19666 762.4481 14.52244 -43.69307 760.4937 17.60755 -41.67632 761.0189 21.1053 -38.03592 763.1048 21.35387 -39.59837 761.5718 24.11051 -37.3636 762.1868 26.87069 -33.79207 764.0991 27.51586 -34.65762 762.9643 29.73189 -31.36289 763.9411 32.75059 -28.61921 765.4989 32.85301 -27.82905 765.0387 35.52417 -22.67718 767.3845 37.22455 -23.73027 766.3764 38.27744 -17.06942 769.4624 40.1074 -19.28725 767.9067 40.80994 -16.56712 768.8731 42.1929 -9.856452 772.6096 42.35595 -15.39932 769.3005 42.73904 -16.31 769.7685 40.41832 -11.89241 770.6198 44.24214 1.646165 778.0004 44.71033 -8.134219 772.0848 45.66157 12.09747 782.76 46.83872 -3.933196 773.7857 47.03597 0.287192 775.5648 48.20545 4.793039 777.5397 49.24356 9.369278 779.621 50.09883 12.86346 781.2648 50.61743 22.10997 788.0576 47.13203 13.16653 783.2395 47.05585 17.69994 785.472 47.54053 10.19475 776.7512 52.68895 2.660353 773.5595 51.1803 -4.755814 770.5952 49.16175 -11.97784 767.8861 46.60159 -18.90794 765.449 43.47949 -25.43913 763.2966 39.77998 -31.46263 761.4393 35.4932 -36.85876 759.8757 30.64443 -41.50357 758.6 25.27258 -45.27685 757.6074 19.42767 -48.07094 756.8965 13.19679 -49.79044 756.4678 6.680483 -50.37518 756.3242 -10e-7 -49.23342 757.7017 -7.071477 -50.37518 756.3242 -10e-7 12.66647 776.3655 53.23078 6.539922 773.7766 52.19754 0.802283 771.4539 50.92126 -4.613345 769.3491 49.41516 -14.50433 765.7459 45.78041 -9.681407 767.4671 47.708 -19.07221 764.1859 43.63946 -27.02206 761.6102 39.00819 -21.93635 763.2337 42.11726 -23.25105 762.8033 41.36663 -33.48423 759.6559 34.09585 -30.43435 760.5633 36.57149 -38.79347 758.1422 28.88532 -43.11706 756.9575 23.3362 -46.40786 756.0834 17.61451 -48.70777 755.4863 11.80585 -50.07782 755.1347 5.889109 -50.52575 755.0203 -10e-7 -49.699 756.4893 -7.214983 -50.52575 755.0203 -10e-7 10.82011 763.2304 52.6397 12.66647 776.3655 53.23078 17.34372 763.1956 52.93972 4.163714 763.2432 51.72873 6.539922 773.7766 52.19754 0.802283 771.4539 50.92126 -2.534927 763.2515 50.20745 -4.613345 769.3491 49.41516 -9.181291 763.2556 48.08655 -9.681407 767.4671 47.708 -14.50433 765.7459 45.78041 -15.67527 763.2565 45.38491 -19.07221 764.1859 43.63946 -21.93635 763.2337 42.11726 -23.60488 744.0228 42.52841 -23.25105 762.8033 41.36663 -29.30298 744.0132 38.72866 -27.02206 761.6102 39.00819 -30.43435 760.5633 36.57149 -34.50137 744.0023 34.35669 -33.48423 759.6559 34.09585 -39.10133 743.9904 29.47379 -38.79347 758.1422 28.88532 -43.01125 743.9783 24.14875 -43.11706 756.9575 23.3362 -46.15095 743.9664 18.45722 -46.40786 756.0834 17.61451 -48.45123 743.9551 12.47914 -48.70777 755.4863 11.80585 -49.8576 743.945 6.298303 -50.07782 755.1347 5.889109 -50.52575 755.0203 -10e-7 -50.33228 743.9365 10e-7 -50.11894 755.1223 -5.625079 -50.33228 743.9365 10e-7 -50.52575 755.0203 -10e-7 -50.11894 755.1223 -5.625079 -49.81027 724.9 4.351593 -50 724.9 -2e-6 -49.85733 743.9365 -6.31117 -50 724.9 -2e-6 -49.24263 718.9 8.66892 -49.81027 724.9 4.351593 -50 724.9 -2e-6 -49.81027 724.9 -4.351606 -50 718.9 0 -49.81027 724.9 -4.351606 -49.24202 724.9 8.673124 -46.98724 724.9 17.09384 -48.2987 724.9 12.93193 -45.31734 724.9 21.12673 -43.30224 724.9 24.99831 -38.30188 724.9 32.13978 -40.95749 724.9 28.67898 -35.35535 724.9 35.35532 -28.67901 724.9 40.95746 -32.13982 724.9 38.30185 -24.99835 724.9 43.30222 -17.51157 744.0307 45.70288 -21.12676 724.9 45.31732 -11.13082 744.0361 48.21011 -12.93196 724.9 48.2987 -4.570854 744.0388 50.01796 -17.09387 724.9 46.98723 -8.673139 724.9 49.24202 2.061697 744.0381 51.10652 0 724.9 50 8.657423 744.0159 51.46741 -4.351603 724.9 49.81027 4.351607 724.9 49.81027 8.657423 744.0159 51.46741 0 724.9 50 10.35503 747.7643 51.75515 10.35503 747.7643 51.75515 0.08961498 718.9 49.9991 0 724.9 50 -4.351603 724.9 49.81027 4.351607 724.9 49.81027 -8.579459 718.9 49.25764 -8.673139 724.9 49.24202 -12.93196 724.9 48.2987 -17.00655 718.9 47.0181 -17.09387 724.9 46.98723 -21.12676 724.9 45.31732 -24.93545 718.9 43.33771 -24.99835 724.9 43.30222 -28.62909 718.9 40.99165 -28.67901 724.9 40.95746 -32.11779 718.9 38.31937 -32.13982 724.9 38.30185 -35.34941 718.9 35.35975 -35.35535 724.9 35.35532 -38.30188 724.9 32.13978 -38.31934 718.9 32.11657 -40.95749 724.9 28.67898 -43.30387 718.9 24.99637 -43.30224 724.9 24.99831 -45.31734 724.9 21.12673 -46.98614 718.9 17.0963 -46.98724 724.9 17.09384 -48.2987 724.9 12.93193 -49.24202 724.9 8.673124 15.81375 747.7763 51.51704 17.34372 763.1956 52.93972 -49.24202 724.9 -8.673145 -49.24202 724.9 -8.673145 -48.45064 743.9365 -12.52634 -48.2987 724.9 -12.93196 -49.23646 718.9 -8.704545 -48.2987 724.9 -12.93196 -46.1503 743.9365 -18.55373 -46.98723 724.9 -17.09387 -46.98723 724.9 -17.09387 -45.31732 724.9 -21.12677 -46.97477 718.9 -17.12734 -45.31732 724.9 -21.12677 -43.01107 743.9365 -24.30312 -43.30222 724.9 -24.99835 -43.30222 724.9 -24.99835 -39.10234 743.9365 -29.68809 -40.95746 724.9 -28.67902 -43.28997 718.9 -25.01854 -40.95746 724.9 -28.67902 -34.50446 743.9365 -34.62654 -38.30185 724.9 -32.13982 -38.30185 724.9 -32.13982 -35.35532 724.9 -35.35536 -38.29654 718.9 -32.14511 -35.35532 724.9 -35.35536 -29.30913 743.9365 -39.0432 -32.13978 724.9 -38.30188 -32.14511 718.9 -38.29654 -32.13978 724.9 -38.30188 -23.61512 743.9365 -42.87034 -28.67897 724.9 -40.9575 -28.67897 724.9 -40.9575 -24.99831 724.9 -43.30224 -25.01854 718.9 -43.28997 -24.99831 724.9 -43.30224 -17.52689 743.9365 -46.04841 -21.12673 724.9 -45.31734 -21.12673 724.9 -45.31734 -11.15216 743.9365 -48.52899 -17.09384 724.9 -46.98724 -17.12734 718.9 -46.97477 -17.09384 724.9 -46.98724 -4.599072 743.9365 -50.27346 -12.93193 724.9 -48.29871 -12.93193 724.9 -48.29871 -8.673118 724.9 -49.24202 -8.704545 718.9 -49.23646 -8.673118 724.9 -49.24202 2.025853 743.9365 -51.25542 -4.351621 724.9 -49.81027 -4.351621 724.9 -49.81027 8.621268 743.9365 -51.46132 -8.6e-5 724.9 -50 -8.6e-5 724.9 -50 16.18021 747.777 -51.48316 -8.6e-5 724.9 -50 8.621268 743.9365 -51.46132 0 718.9 -50 4.378001 724.9 -49.80796 0 718.9 -50 -8.6e-5 724.9 -50 4.378001 724.9 -49.80796 10.36351 747.7835 -51.75663 10.36351 747.7835 -51.75663 4.125842 763.018 -52.12049 17.26307 763.018 -52.92609 10.75716 763.018 -52.86061 -2.548381 763.018 -50.71304 -9.171617 763.018 -48.65679 -15.6445 763.018 -45.97836 -21.86335 763.0171 -42.71271 -25.85827 761.7617 -40.28337 -32.70063 759.7453 -35.17599 -29.44219 760.6896 -37.77818 -38.25954 758.1998 -29.78472 -42.98539 756.9506 -23.73622 -46.49929 756.0407 -17.54045 -48.82169 755.4506 -11.48663 27.1714 770.7097 -53.24008 17.26307 763.018 -52.92609 20.74262 770.7009 -53.51587 20.74262 770.7009 -53.51587 13.48523 776.3973 -53.69128 25.90084 782.0905 -54.39017 19.58057 779.1296 -54.20767 7.660595 773.8989 -52.87249 -3.156252 769.5614 -50.43632 2.137165 771.6353 -51.78485 -8.204087 767.6766 -48.84355 -17.58868 764.405 -44.95866 -13.00404 765.9657 -47.01968 -22.06598 764.1458 -42.35543 -21.86335 763.0171 -42.71271 -25.85827 761.7617 -40.28337 -14.77454 766.5861 -46.03746 -17.58868 764.405 -44.95866 -28.83006 762.0545 -37.97055 -29.44219 760.6896 -37.77818 -32.70063 759.7453 -35.17599 -34.92123 760.303 -32.90315 -38.25954 758.1998 -29.78472 -40.19388 758.8798 -27.20555 -42.98539 756.9506 -23.73622 -44.50394 757.7738 -20.95789 -46.49929 756.0407 -17.54045 -47.71144 756.9758 -14.24977 -48.82169 755.4506 -11.48663 32.98033 785.725 -54.48884 25.90084 782.0905 -54.39017 25.30277 783.5043 -54.3176 25.90084 782.0905 -54.39017 19.58057 779.1296 -54.20767 25.93846 782.2175 -54.39987 25.93846 782.2175 -54.39987 17.13969 779.5921 -53.92319 13.48523 776.3973 -53.69128 8.966308 775.9068 -52.92917 7.660595 773.8989 -52.87249 2.137165 771.6353 -51.78485 0.859374 772.4877 -51.30401 -3.156252 769.5614 -50.43632 -7.091088 769.3717 -49.01591 -8.204087 767.6766 -48.84355 -13.00404 765.9657 -47.01968 -47 718.9 0 -50 718.9 0 -49.23646 718.9 -8.704545 -46.27937 718.9 8.198644 -49.24263 718.9 8.66892 -46.81725 718.9 4.129784 -44.16648 718.9 -16.07183 -46.97477 718.9 -17.12734 -46.28787 718.9 -8.149951 -40.70402 718.9 -23.49939 -43.28997 718.9 -25.01854 -36.0195 718.9 -30.1906 -38.29654 718.9 -32.14511 -33.23096 718.9 -33.23587 -32.14511 718.9 -38.29654 -26.91589 718.9 -38.52895 -25.01854 718.9 -43.28997 -30.19496 718.9 -36.01652 -15.9915 718.9 -44.19508 -17.12734 718.9 -46.97477 -23.44416 718.9 -40.73464 0.07673799 718.9 -46.99917 -8.704545 718.9 -49.23646 -8.070898 718.9 -46.30111 8.704545 718.9 -49.23646 0 718.9 -50 17.12734 718.9 -46.97477 8.704545 718.9 -49.23646 8.744272 718.9 49.22862 8.673146 724.9 49.24202 8.673146 724.9 49.24202 12.93196 724.9 48.2987 21.32088 747.7852 50.79938 12.93196 724.9 48.2987 17.13034 718.9 46.9732 17.09386 724.9 46.98723 26.82196 747.7913 49.60231 17.09386 724.9 46.98723 21.12675 724.9 45.31733 32.25825 747.7949 47.93365 21.12675 724.9 45.31733 25.00269 718.9 43.29909 24.99833 724.9 43.30223 37.56957 747.7965 45.80488 24.99833 724.9 43.30223 28.679 724.9 40.95748 42.69428 747.7962 43.23431 28.679 724.9 40.95748 32.13113 718.9 38.30842 32.1398 724.9 38.30186 47.57067 747.7944 40.24349 32.1398 724.9 38.30186 38.29721 718.9 32.14329 35.35534 724.9 35.35533 35.35534 724.9 35.35533 38.30187 724.9 32.1398 52.13829 747.7915 36.86001 38.30187 724.9 32.1398 43.2706 718.9 25.05428 40.95748 724.9 28.67899 56.33791 747.7877 33.1142 40.95748 724.9 28.67899 43.30224 724.9 24.99833 60.11408 747.7835 29.0412 43.30224 724.9 24.99833 46.96085 718.9 17.16614 45.31733 724.9 21.12674 63.41386 747.7789 24.67829 45.31733 724.9 21.12674 46.98723 724.9 17.09385 66.19059 747.7745 20.06634 46.98723 724.9 17.09385 49.23353 718.9 8.721057 48.2987 724.9 12.93194 68.40129 747.7705 15.24771 48.2987 724.9 12.93194 49.24202 724.9 8.67313 70.01139 747.7673 10.26688 49.24202 724.9 8.67313 49.80558 718.9 4.393081 49.81027 724.9 4.351598 70.99109 747.7651 5.169038 49.81027 724.9 4.351598 50 718.9 0 50 724.9 0 50 724.9 0 49.23646 718.9 -8.704545 50 724.9 0 50 718.9 0 49.81054 724.9 -4.348595 71.32131 747.7643 10e-7 50 724.9 0 49.81054 724.9 -4.348595 71.32131 747.7643 10e-7 47 718.9 0 50 718.9 0 49.80558 718.9 4.393081 46.27937 718.9 -8.198644 49.23646 718.9 -8.704545 46.81725 718.9 -4.129784 46.28787 718.9 8.149951 49.23353 718.9 8.721057 44.16648 718.9 16.07183 46.96085 718.9 17.16614 40.70402 718.9 23.49939 43.2706 718.9 25.05428 36.0195 718.9 30.1906 38.29721 718.9 32.14329 33.23096 718.9 33.23587 32.13113 718.9 38.30842 26.91589 718.9 38.52895 25.00269 718.9 43.29909 30.19496 718.9 36.01652 15.9915 718.9 44.19508 17.13034 718.9 46.9732 23.44416 718.9 40.73464 -0.07673799 718.9 46.99917 8.744272 718.9 49.22862 8.070898 718.9 46.30111 -8.579459 718.9 49.25764 0.08961498 718.9 49.9991 -17.00655 718.9 47.0181 -8.211176 718.9 46.27641 -24.93545 718.9 43.33771 -16.09428 718.9 44.15781 -28.62909 718.9 40.99165 -23.49571 718.9 40.70508 -32.11779 718.9 38.31937 -30.19856 718.9 36.01375 -35.34941 718.9 35.35975 -38.31934 718.9 32.11657 -35.99309 718.9 30.22239 -43.30387 718.9 24.99637 -40.6702 718.9 23.5582 -46.98614 718.9 17.0963 -44.1421 718.9 16.13909 44.1421 718.9 -16.13909 46.97477 718.9 -17.12734 48.30121 724.9 -12.92259 46.97477 718.9 -17.12734 49.2431 724.9 -8.666996 40.6702 718.9 -23.5582 43.28997 718.9 -25.01854 45.32436 724.9 -21.11166 43.28997 718.9 -25.01854 46.99174 724.9 -17.08147 35.99309 718.9 -30.22239 38.29654 718.9 -32.14511 40.97064 724.9 -28.66019 38.29654 718.9 -32.14511 43.31218 724.9 -24.98109 30.19856 718.9 -36.01375 32.14511 718.9 -38.29654 35.37553 724.9 -35.33514 32.14511 718.9 -38.29654 38.31836 724.9 -32.12013 23.49571 718.9 -40.70508 25.01854 718.9 -43.28997 28.70945 724.9 -40.93614 25.01854 718.9 -43.28997 32.16456 724.9 -38.28108 8.211176 718.9 -46.27641 21.17142 724.9 -45.29648 17.12734 718.9 -46.97477 16.09428 718.9 -44.15781 25.03631 724.9 -43.28028 12.98158 724.9 -48.28538 17.14361 724.9 -46.9691 8.716361 724.9 -49.23439 47 750.4 0 47 718.9 0 46.28787 718.9 8.149951 46.28787 750.4 -8.149951 46.81725 718.9 -4.129784 47 718.9 0 47 750.4 0 46.27937 750.4 8.198644 44.16648 718.9 16.07183 46.81725 750.4 4.129784 44.1421 750.4 16.13909 40.70402 718.9 23.49939 40.6702 750.4 23.5582 36.0195 718.9 30.1906 35.99309 750.4 30.22239 33.23096 718.9 33.23587 30.19856 750.4 36.01375 30.19496 718.9 36.01652 26.91589 718.9 38.52895 23.49571 750.4 40.70508 23.44416 718.9 40.73464 16.09428 750.4 44.15781 15.9915 718.9 44.19508 8.211176 750.4 46.27641 8.070898 718.9 46.30111 0.07673799 750.4 46.99917 -0.07673799 718.9 46.99917 -8.070898 750.4 46.30111 -8.211176 718.9 46.27641 -15.9915 750.4 44.19508 -16.09428 718.9 44.15781 -23.44416 750.4 40.73464 -23.49571 718.9 40.70508 -26.91589 750.4 38.52895 -30.19856 718.9 36.01375 -33.23096 750.4 33.23587 -35.99309 718.9 30.22239 -30.19496 750.4 36.01652 -36.0195 750.4 30.1906 -40.6702 718.9 23.5582 -40.70402 750.4 23.49939 -44.1421 718.9 16.13909 -44.16648 750.4 16.07183 -46.27937 718.9 8.198644 -46.28787 750.4 8.149951 -46.81725 718.9 4.129784 -47 718.9 0 -47 750.4 0 -47 718.9 0 -46.28787 718.9 -8.149951 -47 750.4 0 -46.27937 750.4 -8.198644 -44.16648 718.9 -16.07183 -46.81725 750.4 -4.129784 -44.1421 750.4 -16.13909 -40.70402 718.9 -23.49939 -40.6702 750.4 -23.5582 -36.0195 718.9 -30.1906 -35.99309 750.4 -30.22239 -33.23096 718.9 -33.23587 -30.19856 750.4 -36.01375 -30.19496 718.9 -36.01652 -26.91589 718.9 -38.52895 -23.49571 750.4 -40.70508 -23.44416 718.9 -40.73464 -16.09428 750.4 -44.15781 -15.9915 718.9 -44.19508 -8.211176 750.4 -46.27641 -8.070898 718.9 -46.30111 -0.07673799 750.4 -46.99917 0.07673799 718.9 -46.99917 8.070898 750.4 -46.30111 8.211176 718.9 -46.27641 15.9915 750.4 -44.19508 16.09428 718.9 -44.15781 23.44416 750.4 -40.73464 23.49571 718.9 -40.70508 26.91589 750.4 -38.52895 30.19856 718.9 -36.01375 33.23096 750.4 -33.23587 35.99309 718.9 -30.22239 30.19496 750.4 -36.01652 36.0195 750.4 -30.1906 40.6702 718.9 -23.5582 40.70402 750.4 -23.49939 44.1421 718.9 -16.13909 44.16648 750.4 -16.07183 46.27937 718.9 -8.198644 70.9458 747.7652 -5.511627 49.2431 724.9 -8.666996 69.83258 747.7677 -10.93876 48.30121 724.9 -12.92259 68.00615 747.7713 -16.22589 46.99174 724.9 -17.08147 65.50381 747.7757 -21.31822 45.32436 724.9 -21.11166 43.31218 724.9 -24.98109 62.3698 747.7805 -26.16238 40.97064 724.9 -28.66019 58.65788 747.7852 -30.70739 38.31836 724.9 -32.12013 54.42741 747.7896 -34.90523 35.37553 724.9 -35.33514 49.74423 747.7932 -38.7117 32.16456 724.9 -38.28108 44.67794 747.7957 -42.08703 28.70945 724.9 -40.93614 25.03631 724.9 -43.28028 39.30151 747.7966 -44.99612 21.17142 724.9 -45.29648 33.68923 747.7955 -47.41031 17.14361 724.9 -46.9691 27.91608 747.7922 -49.30627 12.98158 724.9 -48.28538 22.05575 747.7861 -50.66751 8.716361 724.9 -49.23439 40.57278 789.5609 -54.22637 33.75657 770.7238 -52.41167 48.42269 793.6744 -53.63383 40.42299 770.7331 -51.02418 55.709 793.6895 -52.03111 47.0841 770.7383 -49.08604 63.02792 793.6934 -49.89712 53.64741 770.7399 -46.61193 70.27787 793.6939 -47.24962 60.01427 770.7385 -43.62418 77.34616 793.6917 -44.11115 66.0841 770.7347 -40.15092 84.1151 793.6874 -40.51096 71.75473 770.7291 -36.22726 90.46425 793.6814 -36.48309 76.9266 770.7224 -31.89321 96.27542 793.6743 -32.06681 81.50342 770.715 -27.19349 101.433 793.6668 -27.30467 85.39672 770.7077 -22.17675 105.8312 793.6594 -22.24315 88.52507 770.7009 -16.89457 109.3713 793.6526 -16.93081 90.82044 770.6954 -11.40088 111.9722 793.647 -11.41839 92.22492 770.6916 -5.750843 114.1029 793.642 10e-7 92.70006 770.6902 10e-7 113.5641 793.6433 -5.757491 113.5637 793.6433 5.759802 92.70006 770.6902 10e-7 114.1029 793.642 10e-7 92.28218 770.6914 5.393782 133.2952 816.5854 -10.99037 130.6037 816.5892 -16.32837 126.9335 816.5939 -21.50175 122.3653 816.5991 -26.46617 76.27854 809.0079 -49.56719 86.53163 814.7584 -47.4607 66.60717 803.5972 -51.27408 48.72329 793.8344 -53.60536 57.4072 798.526 -52.62214 49.38068 795.7319 -53.62133 48.42269 793.6744 -53.63383 40.57278 789.5609 -54.22637 48.72329 793.8344 -53.60536 37.43463 789.3961 -54.39488 32.98033 785.725 -54.48884 25.91914 782.3287 -54.40845 25.91914 782.3287 -54.40845 25.36768 783.3798 -54.34405 25.91914 782.3287 -54.40845 25.36768 783.3798 -54.34405 141.4557 824.9111 -9.773571 140.5921 826.8347 -15.25531 139.9914 828.2009 -18.09158 138.434 831.8461 -23.85544 139.2711 829.859 -20.9606 137.4781 834.117 -26.706 76.27854 809.0079 -49.56719 73.05382 808.9076 -50.37134 66.60717 803.5972 -51.27408 61.24377 802.2661 -52.23765 57.4072 798.526 -52.62214 141.4557 824.9111 -9.773571 141.8523 826.9717 -12.6298 140.5921 826.8347 -15.25531 139.9914 828.2009 -18.09158 140.7561 829.4797 -18.22994 139.2711 829.859 -20.9606 139.4167 832.6339 -23.23061 138.434 831.8461 -23.85544 137.4781 834.117 -26.706 36.81172 790.486 -54.10951 25.30277 783.5043 -54.3176 16.5924 780.8023 -53.35862 25.23647 783.6316 -54.2863 25.23647 783.6316 -54.2863 8.530138 777.0588 -52.34431 0.529525 773.5957 -50.70874 -7.317887 770.4495 -48.41851 -14.90059 767.6479 -45.44591 -22.09284 765.2053 -41.77856 -28.75876 763.1247 -37.41912 -34.75297 761.3953 -32.39136 -39.93235 760.0027 -26.75135 -44.15762 758.9306 -20.58307 -47.29426 758.1647 -13.97909 24.84152 784.3945 -54.00286 24.84152 784.3945 -54.00286 24.63983 784.7872 -53.78479 36.23294 791.4694 -53.5135 24.63983 784.7872 -53.78479 16.1691 781.83 -52.4373 24.59791 784.8691 -53.7321 24.59791 784.8691 -53.7321 8.224061 778.0432 -51.45127 0.335249 774.5472 -49.84376 -7.40264 771.3785 -47.58174 -14.87587 768.5652 -44.63884 -21.95693 766.1216 -41.00521 -28.5086 764.0502 -36.68748 -34.3849 762.3393 -31.71536 -39.44607 760.972 -26.15149 -43.55991 759.9282 -20.08682 -46.60021 759.1894 -13.61959 24.37296 785.3109 -53.39895 24.37296 785.3109 -53.39895 24.0927 785.8679 -52.8353 35.73635 792.281 -52.64646 24.0927 785.8679 -52.8353 17.9446 783.6255 -51.38454 24.07334 785.9067 -52.78847 24.07334 785.9067 -52.78847 12.94546 781.1237 -50.96657 6.987076 778.2829 -50.14714 12.15401 780.7365 -50.88008 -3.557575 773.6436 -47.75153 1.84848 775.9602 -49.13809 -8.86096 771.4994 -46.03133 -16.54346 768.6159 -42.81383 -13.32412 769.7924 -44.27602 -22.30826 766.6275 -39.70695 -17.65035 768.2241 -42.26446 -30.15029 764.1542 -34.21226 -26.71074 765.207 -36.83364 -38.37897 761.8331 -25.94769 -33.35501 763.2183 -31.39007 -42.27048 760.8248 -20.33949 -44.06414 760.3768 -17.00394 -46.64092 759.7507 -10.24394 -45.53955 760.0163 -13.57654 -47.43456 759.561 -6.865048 23.989 786.0762 -52.56891 23.989 786.0762 -52.56891 23.71171 786.6465 -51.56863 30.95543 790.4709 -51.67483 23.71171 786.6465 -51.56863 38.63786 794.6826 -51.4137 23.71171 786.6465 -51.56863 17.9446 783.6255 -51.38454 30.95543 790.4709 -51.67483 41.07627 796.0476 -51.25925 12.94546 781.1237 -50.96657 6.987076 778.2829 -50.14714 12.15401 780.7365 -50.88008 1.84848 775.9602 -49.13809 -3.557575 773.6436 -47.75153 12.09774 782.7601 -46.83877 17.58523 785.4104 -47.53919 13.16656 783.2394 -47.05585 -8.86096 771.4994 -46.03133 1.646352 778.0005 -44.71037 -13.32412 769.7924 -44.27602 -16.54346 768.6159 -42.81383 -17.07181 769.4619 -40.10647 -17.65035 768.2241 -42.26446 -16.23861 769.797 -40.44654 -9.856426 772.6095 -42.35595 -22.30826 766.6275 -39.70695 -22.54685 767.4286 -37.30389 -26.71074 765.207 -36.83364 -30.15029 764.1542 -34.21226 -28.46178 765.5436 -32.98941 -33.35501 763.2183 -31.39007 -33.62357 764.1412 -27.71999 -38.37897 761.8331 -25.94769 -37.8954 763.1363 -21.59856 -42.27048 760.8248 -20.33949 -44.06414 760.3768 -17.00394 -41.11388 762.4648 -14.74979 -45.53955 760.0163 -13.57654 -46.64092 759.7507 -10.24394 -47.43456 759.561 -6.865048 72.26081 810.2113 -50.24373 60.4931 803.4998 -52.06107 48.685 796.8949 -53.39217 71.46382 811.3841 -49.66598 59.75539 804.6108 -51.47968 48.01832 797.9431 -52.80437 70.73727 812.3161 -48.69233 59.09275 805.5049 -50.54279 47.43062 798.7973 -51.90244 73.48892 814.8897 -46.78807 68.69527 812.0579 -47.68629 55.34984 804.2307 -49.78272 64.22206 809.422 -48.45883 46.79332 799.292 -50.77524 41.07627 796.0476 -51.25925 38.63786 794.6826 -51.4137 73.48892 814.8897 -46.78807 68.69527 812.0579 -47.68629 39.40956 799.3632 -42.52716 64.22206 809.422 -48.45883 55.34984 804.2307 -49.78272 46.79332 799.292 -50.77524 30.03554 793.9196 -43.6488 26.13886 790.8208 -45.88045 22.00404 787.9903 -47.15288 -18.46122 764.19 -38.56038 -17.07181 769.4619 -40.10647 -22.54685 767.4286 -37.30389 -15.13636 765.7333 -40.17865 -16.23861 769.797 -40.44654 -21.62717 762.7204 -36.61668 -28.46178 765.5436 -32.98941 -27.39353 760.0438 -31.81053 -33.62357 764.1412 -27.71999 -32.23561 757.7962 -25.94529 -37.8954 763.1363 -21.59856 -36.03159 756.0341 -19.17983 -41.11388 762.4648 -14.74979 -38.63088 754.8276 -11.77211 -43.09181 762.087 -7.459362 -39.95194 754.2144 -3.969198 -43.7532 761.9663 -10e-7 -39.95166 754.2145 3.972513 -43.11808 762.0819 7.310119 -38.62562 754.83 11.79207 -41.19666 762.4481 14.52244 -36.01155 756.0434 19.2237 -38.03592 763.1048 21.35387 -32.19611 757.8145 26.00253 -33.79207 764.0991 27.51586 -27.34307 760.0672 31.8611 -28.61921 765.4989 32.85301 -21.58094 762.7419 36.64815 -22.67718 767.3845 37.22455 -17.06942 769.4624 40.1074 -15.10909 765.746 40.19025 -16.31 769.7685 40.41832 14.83479 779.6455 -47.05585 12.09774 782.7601 -46.83877 1.646352 778.0005 -44.71037 13.16656 783.2394 -47.05585 -9.856426 772.6095 -42.35595 -8.166404 768.9687 -42.35595 -9.856426 772.6095 -42.35595 -8.166404 768.9687 -42.35595 36.10726 799.898 -36.79175 38.00378 802.0112 -33.56867 33.34222 796.9572 -40.62983 57.38745 799.3978 -13.21573 38.00378 802.0112 -33.56867 36.10726 799.898 -36.79175 65.51174 818.5321 -25.16099 43.16478 807.1087 -25.13748 43.16478 807.1087 -25.13748 40.07063 791.3596 -36.79175 36.10726 799.898 -36.79175 33.34222 796.9572 -40.62983 40.07063 791.3596 -36.79175 36.07163 789.5033 -41.17658 30.03554 793.9196 -43.6488 31.32197 787.2986 -44.51765 26.13886 790.8208 -45.88045 26.0382 784.846 -46.66667 22.00404 787.9903 -47.15288 20.45846 782.2559 -47.52681 17.58523 785.4104 -47.53919 13.16656 783.2394 -47.05585 14.83479 779.6455 -47.05585 85.81986 825.9322 -34.4591 64.5676 820.1878 -13.51989 66.07361 820.6832 -15.4402 80.65918 824.7162 -30.24904 75.61484 823.4539 -25.65611 70.75191 822.1224 -20.72462 50.93492 813.2986 -13.21573 63.31803 819.7802 -11.64482 67.42974 822.5675 -10.46173 64.5676 820.1878 -13.51989 63.31803 819.7802 -11.64482 67.73902 821.89 -13.9669 66.07361 820.6832 -15.4402 69.2611 823.3291 -12.54675 53.06249 814.8139 -9.178676 62.21976 819.4243 -9.661641 65.83658 821.91 -8.149031 62.21976 819.4243 -9.661641 61.32498 819.1346 -7.663414 61.32498 819.1346 -7.663414 54.36064 815.7691 -4.699023 60.65583 818.9195 -5.691586 64.57337 821.3919 -5.605688 60.65583 818.9195 -5.691586 60.19192 818.7705 -3.748839 60.19192 818.7705 -3.748839 54.79643 816.0949 -10e-7 59.83893 818.6575 -10e-7 63.74985 821.0556 -2.862322 59.83893 818.6575 -10e-7 54.36068 815.7691 4.698818 60.18076 818.7669 3.690529 63.46183 820.9382 4.72e-4 60.18076 818.7669 3.690529 60.63559 818.913 5.620534 63.74975 821.0555 2.86306 60.63559 818.913 5.620534 53.06254 814.8139 9.178548 61.29675 819.1256 7.589931 64.57326 821.3918 5.604653 61.29675 819.1256 7.589931 62.18728 819.4139 9.596158 62.18728 819.4139 9.596158 50.93521 813.2979 13.21573 63.28733 819.77 11.59542 65.83665 821.91 8.148368 63.28733 819.77 11.59542 64.56336 820.1865 13.51319 67.42871 822.567 10.46172 64.56336 820.1865 13.51319 43.16464 807.1086 25.13764 65.51155 818.5325 25.15887 66.0736 820.6831 15.44022 66.0736 820.6831 15.44022 38.00347 802.0104 33.56941 75.62987 823.4579 25.67016 70.76074 822.1251 20.73339 80.6781 824.7209 30.26508 85.83842 825.9365 34.47356 36.10755 799.8973 36.79175 26.18297 790.8534 45.86138 30.0183 793.9048 43.66143 33.30578 796.9213 40.67073 40.07063 791.3596 36.79175 38.00347 802.0104 33.56941 43.16464 807.1086 25.13764 36.10755 799.8973 36.79175 50.93521 813.2979 13.21573 57.38745 799.3978 13.21573 50.93521 813.2979 13.21573 53.06254 814.8139 9.178548 57.38745 799.3978 13.21573 61.14601 801.1425 4.713194 54.36068 815.7691 4.698818 59.70998 800.4758 9.193468 54.79643 816.0949 -10e-7 61.6318 801.3679 0 54.36064 815.7691 -4.699023 61.14601 801.1425 -4.713194 53.06249 814.8139 -9.178676 59.70998 800.4758 -9.193468 50.93492 813.2986 -13.21573 50.93492 813.2986 -13.21573 57.38745 799.3978 -13.21573 87.49483 827.6888 -32.40904 85.81986 825.9322 -34.4591 80.65918 824.7162 -30.24904 80.59275 825.8308 -26.89463 75.61484 823.4539 -25.65611 73.98327 823.9259 -20.71995 70.75191 822.1224 -20.72462 66.07361 820.6832 -15.4402 67.73902 821.89 -13.9669 67.73899 821.89 13.96695 66.0736 820.6831 15.44022 70.76074 822.1251 20.73339 67.73899 821.89 13.96695 73.97792 823.9241 20.71463 75.62987 823.4579 25.67016 80.58841 825.8295 26.89146 80.6781 824.7209 30.26508 85.83842 825.9365 34.47356 87.49193 827.688 32.40707 -8.166404 768.9687 42.35595 12.09747 782.76 46.83872 13.16653 783.2395 47.05585 1.646165 778.0004 44.71033 14.83479 779.6455 47.05585 13.16653 783.2395 47.05585 17.69994 785.472 47.54053 14.83479 779.6455 47.05585 20.45866 782.256 47.5268 22.10997 788.0576 47.13203 26.03849 784.8461 46.66659 26.18297 790.8534 45.86138 31.32223 787.2987 44.51751 30.0183 793.9048 43.66143 36.07178 789.5034 41.17645 33.30578 796.9213 40.67073 36.10755 799.8973 36.79175 40.07063 791.3596 36.79175 -9.856452 772.6096 42.35595 -9.856452 772.6096 42.35595 -8.166404 768.9687 42.35595 101.6193 831.5657 -41.0689 102.0141 830.6948 -42.29737 101.6193 831.5657 -41.0689 100.0996 833.4182 -37.29118 103.9626 833.2241 -40.9021 104.4114 832.3521 -42.00422 103.9626 833.2241 -40.9021 92.09827 830.7786 -32.65124 84.13774 828.3091 -26.87197 76.4802 825.875 -20.12901 69.2611 823.3291 -12.54675 106.0813 834.8596 -40.78866 106.7203 834.1181 -41.75991 106.0813 834.8596 -40.78866 107.929 836.4 -40.71681 107.929 836.4 -40.71681 108.2696 839.868 -38.44953 109.7853 838.061 -40.67174 108.9287 835.9775 -41.55963 109.7853 838.061 -40.67174 100.847 836.3924 -35.19598 93.09534 833.2975 -30.7703 85.30567 830.4746 -25.18763 77.7676 827.761 -18.62415 70.62313 824.9868 -11.19487 70.62313 824.9868 -11.19487 111.3603 839.5775 -40.64797 111.0321 837.9229 -41.39665 111.3603 839.5775 -40.64797 112.7879 841.0394 -40.64314 113.0142 839.9398 -41.26535 112.7879 841.0394 -40.64314 114.0583 842.4263 -40.64778 114.0583 842.4263 -40.64778 115.2108 843.7691 -40.65768 114.8768 842.0329 -41.15988 115.2108 843.7691 -40.65768 111.7129 846.0933 -38.06155 115.3054 848.8642 -39.26224 116.2978 845.128 -40.67052 116.5995 844.1932 -41.07419 116.2978 845.128 -40.67052 114.9427 848.5682 -39.14949 108.2357 843.7103 -36.7276 109.3787 844.4639 -37.18505 100.7015 839.3574 -33.21243 104.5687 841.469 -35.12798 102.6978 840.4185 -34.23185 93.18474 835.7913 -28.75852 94.81628 836.5195 -29.81083 86.03099 832.7854 -23.53708 86.38545 832.9296 -23.81959 78.85509 829.8578 -17.26306 77.17443 829.1606 -15.62349 71.80097 826.8314 -9.935744 71.80097 826.8314 -9.935744 117.8847 851.0693 -40.01062 117.2993 846.4812 -40.68528 117.2993 846.4812 -40.68528 118.1663 847.7633 -40.69887 118.1597 846.4248 -41.00202 118.1663 847.7633 -40.69887 118.918 849.0035 -40.7096 119.5149 848.7375 -40.93814 118.918 849.0035 -40.7096 120.6761 853.66 -40.71397 120.0759 851.3817 -40.72269 120.5755 851.1471 -40.87802 120.0759 851.3817 -40.72269 120.6761 853.66 -40.71397 120.6761 853.66 -40.71397 117.8847 851.0693 -40.01062 121.1348 853.6541 -40.81576 115.3054 848.8642 -39.26224 110.4905 850.2702 -36.19815 114.9427 848.5682 -39.14949 111.7129 846.0933 -38.06155 109.3787 844.4639 -37.18505 104.6943 846.5588 -32.99619 108.2357 843.7103 -36.7276 104.5687 841.469 -35.12798 102.6978 840.4185 -34.23185 98.01207 842.9514 -28.64151 100.7015 839.3574 -33.21243 94.81628 836.5195 -29.81083 90.45103 839.4813 -22.6402 93.18474 835.7913 -28.75852 86.38545 832.9296 -23.81959 82.47856 836.0665 -14.81699 86.03099 832.7854 -23.53708 78.85509 829.8578 -17.26306 77.17443 829.1606 -15.62349 77.2143 833.2915 -9.398168 71.80097 826.8314 -9.935744 74.52854 832.0998 -4.864228 77.2143 833.2915 -9.398168 71.80097 826.8314 -9.935744 70.49073 826.0778 -8.636091 70.49073 826.0778 -8.636091 102.8974 829.7525 -43.15467 105.3022 831.4541 -42.76187 107.6107 833.2744 -42.42128 109.8104 835.197 -42.12897 111.8964 837.2136 -41.87889 113.8525 839.3085 -41.6663 115.6793 841.4859 -41.48489 117.3562 843.7362 -41.32944 118.8603 846.0638 -41.19447 120.149 848.4804 -41.07565 121.132 851.0054 -40.96987 121.6031 853.6467 -40.87426 121.6945 850.8593 -40.99446 121.8396 853.6424 -40.88691 103.8455 828.6033 -43.58316 106.2561 830.3893 -43.12305 108.5598 832.2992 -42.72199 110.7444 834.3153 -42.37579 112.8057 836.4284 -42.07801 114.7279 838.622 -41.82374 116.5109 840.9005 -41.60575 118.1344 843.2536 -41.41873 119.576 845.687 -41.25713 120.7929 848.2144 -41.11667 122.0749 853.6376 -40.88835 80.53759 837.3906 -9.061828 87.32508 842.7849 -13.97991 88.21717 847.6184 -7.972946 91.67277 849.2988 -13.14507 94.13928 845.8997 -21.46435 84.30211 842.2455 -8.59624 91.42646 852.3741 -7.299854 95.44178 855.5661 -12.31241 97.38691 852.1566 -20.29222 96.03496 860.1156 -5.898525 98.55286 861.551 -11.48188 100.1256 858.2161 -19.12374 93.9878 856.5017 -6.603752 98.92422 866.0561 -4.4443 100.9263 867.2121 -10.65343 102.2877 864.0497 -17.95883 102.3887 872.5633 -9.489856 102.492 872.6718 -9.812292 103.8041 869.6124 -16.79735 102.2562 872.4262 -9.067708 100.8417 871.0832 -3.450073 102.3292 873.6525 -8.780432 102.492 872.6718 -9.812292 102.3887 872.5633 -9.489856 104.1053 874.5335 -14.30589 104.1053 874.5335 -14.30589 102.2562 872.4262 -9.067708 101.0593 872.6113 -3.271138 100.8417 871.0832 -3.450073 100.6052 870.8923 -1.74866 100.8417 871.0832 -3.450073 98.92422 866.0561 -4.4443 101.0593 872.6113 -3.271138 100.8417 871.0832 -3.450073 100.6052 870.8923 -1.74866 98.27259 865.3334 -2.358345 96.03496 860.1156 -5.898525 95.08197 859.455 -3.071128 93.9878 856.5017 -6.603752 91.04655 853.1495 -3.663745 91.42646 852.3741 -7.299854 88.21717 847.6184 -7.972946 86.22846 846.4586 -4.152169 84.30211 842.2455 -8.59624 80.69532 839.4254 -4.545564 80.53759 837.3906 -9.061828 100.636 849.1614 -27.33614 102.8789 855.254 -26.03603 104.6841 861.2001 -24.74106 105.9958 866.9776 -23.45112 104.6395 875.2005 -15.63908 106.7564 872.5474 -22.16598 104.0461 875.6522 -13.9724 104.6395 875.2005 -15.63908 106.1451 877.202 -19.12842 106.1451 877.202 -19.12842 106.3985 852.6306 -31.76168 107.7869 858.6328 -30.53399 108.8152 864.5436 -29.31297 109.4393 870.3441 -28.09843 106.9483 878.3591 -20.86245 109.6175 876.0408 -26.89006 105.9782 878.2154 -18.76292 106.9483 878.3591 -20.86245 107.3776 879.0051 -21.75894 107.3776 879.0051 -21.75894 111.3965 856.0602 -35.2181 112.0779 861.8353 -34.24591 112.5062 867.5823 -33.28142 112.6529 873.2865 -32.32437 108.269 880.4045 -23.56097 109.3526 882.1942 -25.65165 112.4946 878.9895 -31.37441 108.0234 881.2661 -23.18125 109.3526 882.1942 -25.65165 108.269 880.4045 -23.56097 112.045 885.3143 -30.41329 110.4696 884.1159 -27.70077 110.4696 884.1159 -27.70077 111.4323 886.291 -29.45036 112.045 885.3143 -30.41329 110.4696 884.1159 -27.70077 113.8016 886.4208 -33.15812 112.1883 888.4014 -30.955 113.8016 886.4208 -33.15812 112.1449 888.2636 -30.86196 110.1839 884.7295 -27.29811 111.4323 886.291 -29.45036 110.4696 884.1159 -27.70077 110.1839 884.7295 -27.29811 112.2044 888.4533 -30.98984 113.078 892.5701 -33.51186 111.5526 888.9963 -30.32037 112.1883 888.4014 -30.955 112.1449 888.2636 -30.86196 112.2044 888.4533 -30.98984 113.078 892.5701 -33.51186 113.078 892.5701 -33.51186 112.6942 896.6884 -35.13051 113.078 892.5701 -33.51186 112.2792 893.158 -32.93191 112.2792 893.158 -32.93191 111.7566 897.1758 -34.76956 111.9757 893.3336 -32.77871 110.7934 889.6719 -29.93601 111.9757 893.3336 -32.77871 110.4871 901.7097 -36.66869 110.7328 897.8379 -34.76167 111.3171 893.6512 -32.53575 111.3171 893.6512 -32.53575 110.6107 893.9127 -32.38658 109.9019 890.256 -29.72426 110.6107 893.9127 -32.38658 107.5741 907.6395 -38.57983 106.5568 909.8268 -39.07302 108.4068 905.507 -37.97211 109.4356 901.5075 -36.47487 110.2431 894.0213 -32.34754 109.6397 897.7233 -34.58345 108.9202 890.7208 -29.69511 110.2431 894.0213 -32.34754 109.12 894.2491 -32.37482 107.9171 891.0914 -29.88982 109.12 894.2491 -32.37482 107.8945 891.0466 -29.85086 104.0454 914.2536 -39.68529 88 914.234 -39.95563 104.0454 914.2536 -39.68529 105.3821 912.0302 -39.44074 88 917.4 -40.05699 102.3078 917.065 -39.8171 104.0454 914.2536 -39.68529 88 914.234 -39.95563 106.5568 909.8268 -39.07302 107.5741 907.6395 -38.57983 88 907.0598 -38.80419 108.4068 905.507 -37.97211 109.4356 901.5075 -36.47487 88 900.1444 -36.30818 109.6397 897.7233 -34.58345 109.12 894.2491 -32.37482 88 893.7796 -32.53591 107.9171 891.0914 -29.88982 123.3564 920.5202 -39.35414 99.99839 920.5518 -39.75283 99.99839 920.5518 -39.75283 88 927.7753 -38.79496 123.3564 920.5202 -39.35414 99.99839 920.5518 -39.75283 88 920.566 -39.95563 88 920.566 -39.95563 123.3564 920.5202 -39.35414 123.1448 927.5142 -38.19469 124.5188 920.5902 -39.19145 123.3564 920.5202 -39.35414 123.1448 927.5142 -38.19469 126.3806 927.1442 -36.98249 127.1848 920.6505 -37.44117 126.5789 920.6547 -38.08487 125.413 927.3125 -37.63735 126.1147 920.6488 -38.45192 125.6137 920.6359 -38.75999 124.3138 927.4187 -38.0545 124.7983 920.6039 -39.10908 126.6079 933.3074 34.73292 127.1617 938.9638 31.42482 127.9158 943.9548 27.16798 128.7338 948.1489 22.0847 129.483 951.4255 16.31074 130.0561 953.6834 10.01193 130.3664 954.8373 3.376805 130.3663 954.8372 -3.377282 130.0561 953.6834 -10.01261 129.4832 951.4253 -16.31177 128.7335 948.1484 -22.08446 127.915 943.9544 -27.16615 127.1617 938.9644 -31.42447 126.6082 933.3074 -34.73271 125.6304 933.6533 35.3484 126.1693 939.473 31.9827 126.9056 944.609 27.65158 127.7051 948.9259 22.47903 128.4378 952.2993 16.60282 128.9983 954.6245 10.19164 129.3018 955.8129 3.4375 129.3017 955.8129 -3.437985 128.9983 954.6244 -10.19233 128.4379 952.2991 -16.60387 127.7048 948.9254 -22.47878 126.9047 944.6086 -27.64971 126.1693 939.4736 -31.98235 125.6308 933.6533 -35.34819 124.5132 933.8991 35.72942 125.0232 939.8392 32.31107 125.7237 945.0728 27.91734 126.4848 949.463 22.67896 127.1817 952.8868 16.73946 127.7142 955.2425 10.27007 128.0023 956.445 3.462848 128.0022 956.445 -3.46334 127.7142 955.2424 -10.27075 127.1819 952.8867 -16.74048 126.4844 949.4623 -22.67877 125.7227 945.0719 -27.91563 125.0233 939.8399 -32.31071 124.5135 933.8992 -35.72917 123.3376 934.3372 35.7102 123.8546 940.616 31.97614 124.5683 946.1221 27.11155 125.3324 950.6657 21.24789 124.9585 948.5332 24.28488 125.9952 954.0308 14.64854 125.6865 952.5026 18.02704 126.4471 956.1097 7.532721 126.255 955.2361 11.14106 126.6112 956.8305 0.141691 126.5692 956.6429 3.855474 126.5751 956.6691 -3.576383 126.2706 955.307 -10.89528 126.4585 956.1602 -7.266433 125.7054 952.597 -17.84074 126.0134 954.1166 -14.43042 124.9733 948.6238 -24.16752 125.3499 950.7614 -21.09611 124.2067 943.5357 -29.62595 124.579 946.2009 -27.02729 123.3379 934.337 -35.7103 123.859 940.6572 -31.94607 88 927.7403 38.80418 123.3376 934.3372 35.7102 88 934.6558 36.30812 123.8546 940.616 31.97614 88 941.0206 32.53579 124.5683 946.1221 27.11155 88 946.5869 27.63153 124.9585 948.5332 24.28488 88 951.1737 21.73178 125.3324 950.6657 21.24789 88 953.0635 18.43839 125.6865 952.5026 18.02704 88 954.6275 14.99287 125.9952 954.0308 14.64854 88 955.8662 11.40541 126.255 955.2361 11.14106 88 956.7595 7.729559 126.4471 956.1097 7.532721 88 957.3077 3.984749 126.5692 956.6429 3.855474 88 957.5037 0.218952 126.6112 956.8305 0.141691 88 957.3482 -3.551093 126.5751 956.6691 -3.576383 88 956.839 -7.308726 126.4585 956.1602 -7.266433 88 955.981 -11.00572 126.2706 955.307 -10.89528 88 954.773 -14.62296 126.0134 954.1166 -14.43042 88 953.2324 -18.10463 125.7054 952.597 -17.84074 88 951.3579 -21.44032 125.3499 950.7614 -21.09611 88 949.2025 -24.55331 124.9733 948.6238 -24.16752 88 946.7727 -27.43265 124.579 946.2009 -27.02729 124.2067 943.5357 -29.62595 88 941.1729 -32.4244 123.859 940.6572 -31.94607 88 934.7509 -36.26299 123.3379 934.337 -35.7103 88 924.6329 36.28598 88 920.566 39.95563 88 927.7403 38.80418 88 917.4362 36.99993 88 917.4 40.05699 88 931.5532 34.18553 88 934.6558 36.30812 88 937.9393 30.77456 88 941.0206 32.53579 88 943.5462 26.17773 88 946.5869 27.63153 88 948.135 20.60119 88 951.1737 21.73178 88 951.5598 14.21501 88 953.0635 18.43839 88 953.6827 7.249401 88 954.6275 14.99287 88 954.773 -14.62296 88 955.8662 11.40541 88 954.4 0 88 954.2182 3.655726 88 955.981 -11.00572 88 956.7595 7.729559 88 956.839 -7.308726 88 957.3077 3.984749 88 957.3482 -3.551093 88 957.5037 0.218952 88 953.2324 -18.10463 88 951.5842 -14.15581 88 951.3579 -21.44032 88 953.6906 -7.209047 88 949.2025 -24.55331 88 948.1718 -20.54592 88 946.7727 -27.43265 88 943.5797 -26.14408 88 941.1729 -32.4244 88 937.9476 -30.76877 88 934.7509 -36.26299 88 931.5239 -34.19749 88 927.7753 -38.79496 88 924.5722 -36.29792 88 920.566 -39.95563 88 917.4 -40.05699 88 910.2279 36.29792 88 914.234 39.95563 104.0454 914.2536 39.68529 88 914.234 39.95563 88 907.0247 38.79496 104.0454 914.2536 39.68529 88 914.234 39.95563 88 907.0247 38.79496 88 903.2761 34.19749 88 900.0492 36.26301 108.3545 905.6569 38.01901 88 900.0492 36.26301 105.3521 912.084 39.44811 106.5077 909.9235 39.09187 107.5186 907.7692 38.61272 88 896.8524 30.76877 88 893.6273 32.4245 109.6442 897.8207 34.63853 88 893.6273 32.4245 109.4121 901.6524 36.53771 88 891.2203 26.14408 88 888.0274 27.43276 107.9203 891.098 29.89556 88 888.0274 27.43276 109.1199 894.2499 32.37365 88 886.6282 20.54592 88 885.5976 24.55344 105.9922 887.8729 26.75869 88 885.5976 24.55344 107.8944 891.0465 29.85075 88 883.2158 14.15581 88 883.4422 21.44041 103.654 884.7097 22.83897 88 883.4422 21.44041 88 881.5676 18.10463 102.6456 883.4823 20.99572 88 881.5676 18.10463 88 880.4 0 88 880.027 14.62284 99.77521 880.4518 15.12369 88 880.027 14.62284 88 881.1094 7.209047 101.4003 882.0893 18.58894 88 878.934 -11.40598 88 878.8189 11.00547 99.30154 880.0165 14.02792 88 878.8189 11.00547 88 880.1727 -14.99338 88 878.0407 -7.730095 88 877.9609 7.308418 97.5194 878.5509 9.303995 88 877.9609 7.308418 88 877.4924 -3.985209 88 877.4517 3.550745 96.03976 877.6006 3.638149 88 877.4517 3.550745 97.43226 878.4871 9.037449 88 877.2964 -0.219355 95.70199 877.4297 -4.89e-4 88 877.2964 -0.219355 96.03975 877.6006 -3.638136 88 877.4924 -3.985209 88 878.0407 -7.730095 97.43238 878.4873 -9.038298 88 878.934 -11.40598 99.30181 880.0167 -14.02849 88 880.1727 -14.99338 97.51562 878.5482 -9.292932 88 881.1173 -7.249401 88 881.7367 -18.43882 99.76918 880.4461 -15.11001 88 881.7367 -18.43882 88 880.5818 -3.655726 88 883.2402 -14.21501 88 883.6265 -21.73214 101.3999 882.0889 -18.58828 88 883.6265 -21.73214 88 886.6651 -20.60119 88 888.2135 -27.63179 103.6535 884.7092 -22.8383 88 888.2135 -27.63179 102.6405 883.4763 -20.98622 88 891.2538 -26.17773 88 893.7796 -32.53591 107.8945 891.0466 -29.85086 105.9922 887.8729 -26.75868 88 896.8607 -30.77456 88 900.1444 -36.30818 88 903.2468 -34.18553 88 907.0598 -38.80419 88 910.1671 -36.28598 88 914.234 -39.95563 88 917.3638 -36.99993 113.5 954.4 0 88 954.4 0 88 953.6906 -7.209047 113.5 953.6906 7.209047 88 954.2182 3.655726 88 954.4 0 113.5 954.4 0 113.5 953.6827 -7.249401 88 951.5842 -14.15581 113.5 954.2182 -3.655726 113.5 951.5598 -14.21501 88 948.1718 -20.54592 113.5 948.135 -20.60119 88 943.5797 -26.14408 113.5 943.5462 -26.17773 88 937.9476 -30.76877 113.5 937.9393 -30.77456 88 931.5239 -34.19749 113.5 924.6329 -36.28598 88 924.5722 -36.29792 113.5 931.5532 -34.18553 113.5 917.4362 -36.99993 88 917.3638 -36.99993 113.5 910.2279 -36.29792 88 910.1671 -36.28598 113.5 903.2761 -34.19749 88 903.2468 -34.18553 88 896.8607 -30.77456 113.5 896.8524 -30.76877 88 891.2538 -26.17773 113.5 891.2203 -26.14408 88 886.6651 -20.60119 113.5 886.6282 -20.54592 88 883.2402 -14.21501 113.5 883.2158 -14.15581 88 881.1173 -7.249401 113.5 881.1094 -7.209047 88 880.5818 -3.655726 88 880.4 0 113.5 880.4 0 88 880.4 0 88 881.1094 7.209047 113.5 880.4 0 113.5 881.1173 7.249401 88 883.2158 14.15581 113.5 880.5818 3.655726 113.5 883.2402 14.21501 88 886.6282 20.54592 113.5 886.6651 20.60119 88 891.2203 26.14408 113.5 891.2538 26.17773 88 896.8524 30.76877 113.5 896.8607 30.77456 88 903.2761 34.19749 113.5 910.1671 36.28598 88 910.2279 36.29792 113.5 903.2468 34.18553 113.5 917.3638 36.99993 88 917.4362 36.99993 113.5 924.5722 36.29792 88 924.6329 36.28598 113.5 931.5239 34.19749 88 931.5532 34.18553 88 937.9393 30.77456 113.5 937.9476 30.76877 88 943.5462 26.17773 113.5 943.5797 26.14408 88 948.135 20.60119 113.5 948.1718 20.54592 88 951.5598 14.21501 113.5 951.5842 14.15581 88 953.6827 7.249401 104.0454 914.2536 39.68529 106.5077 909.9235 39.09187 108.2138 909.1374 39.0626 107.5186 907.7692 38.61272 108.3545 905.6569 38.01901 109.5875 905.4813 38.07835 109.4121 901.6524 36.53771 110.4867 901.7111 36.66928 109.6442 897.8207 34.63853 110.7325 897.8375 34.76134 109.1199 894.2499 32.37365 108.92 890.7199 29.69451 109.1199 894.2499 32.37365 107.9203 891.098 29.89556 110.2434 894.0215 32.34703 110.2434 894.0215 32.34703 107.8944 891.0465 29.85075 106.7197 887.6365 26.56901 105.9922 887.8729 26.75869 104.5927 884.4688 22.63325 105.9922 887.8729 26.75869 103.654 884.7097 22.83897 106.7197 887.6365 26.56901 102.4367 881.8693 18.37834 102.6456 883.4823 20.99572 101.4003 882.0893 18.58894 100.4164 879.7918 13.75799 99.77521 880.4518 15.12369 99.30154 880.0165 14.02792 98.6483 878.2791 8.754967 97.5194 878.5509 9.303995 97.43226 878.4871 9.037449 97.55833 877.3627 3.408288 96.03976 877.6006 3.638149 97.27339 877.2043 -4.86e-4 96.03976 877.6006 3.638149 95.70199 877.4297 -4.89e-4 97.55833 877.3627 3.408288 97.55834 877.3627 -3.408287 96.03975 877.6006 -3.638136 98.64846 878.2792 -8.755381 96.03975 877.6006 -3.638136 97.43238 878.4873 -9.038298 97.55834 877.3627 -3.408287 100.4167 879.7919 -13.75876 97.51562 878.5482 -9.292932 99.30181 880.0167 -14.02849 102.4371 881.8697 -18.37843 99.76918 880.4461 -15.11001 101.3999 882.0889 -18.58828 104.5925 884.4688 -22.63338 102.6405 883.4763 -20.98622 103.6535 884.7092 -22.8383 106.7192 887.6366 -26.56913 105.9922 887.8729 -26.75868 105.9922 887.8729 -26.75868 106.7192 887.6366 -26.56913 106.8839 912.1497 39.63427 109.9508 907.6934 39.11383 108.6615 909.6772 39.3784 110.9923 904.2905 38.04304 111.6361 900.7733 36.61067 111.7561 897.1754 34.76902 110.6113 893.9127 32.38625 109.9017 890.2551 29.72365 110.6113 893.9127 32.38625 108.6615 909.6772 39.3784 109.4861 909.9299 39.69956 109.9508 907.6934 39.11383 110.2154 907.2576 39.04971 110.2154 907.2576 39.04971 112.0246 903.8109 38.45888 111.519 904.8784 38.65748 112.5987 900.3513 37.01211 111.317 893.6512 32.53569 112.695 896.7192 35.14743 111.317 893.6512 32.53569 111.9755 893.334 32.77811 110.7932 889.671 29.93539 111.9755 893.334 32.77811 111.4314 907.1287 39.52038 111.519 904.8784 38.65748 112.0246 903.8109 38.45888 113.3759 900.298 37.79 113.1306 904.0905 39.28195 113.3759 900.298 37.79 113.5037 896.4784 35.86691 112.2793 893.1583 32.9313 111.5524 888.9952 30.31974 112.2793 893.1583 32.9313 113.0778 892.5703 33.51158 112.2025 888.447 30.9856 113.0778 892.5703 33.51158 112.1883 888.4014 30.95501 112.1458 888.2664 30.86387 114.7938 897.336 37.92744 113.3759 900.298 37.79 113.5037 896.4784 35.86691 114.4642 900.7904 38.99851 117.1597 894.9561 39.10882 114.4642 900.7904 38.99851 113.3759 900.298 37.79 114.7938 897.336 37.92744 114.5383 893.6802 35.84999 113.0778 892.5703 33.51158 116.0405 894.5249 38.02727 114.4817 890.0892 34.56788 113.0778 892.5703 33.51158 112.2025 888.447 30.9856 114.5383 893.6802 35.84999 116.0405 894.5249 38.02727 118.2263 891.7055 39.14393 117.1597 894.9561 39.10882 116.0405 894.5249 38.02727 117.047 891.4428 38.09558 117.047 891.4428 38.09558 116.0405 894.5249 38.02727 118.733 888.2786 39.19237 117.5169 888.1917 38.14723 115.1117 887.1223 35.03686 117.5169 888.1917 38.14723 119.3378 876.4132 39.4775 118.733 888.2786 39.19237 117.5169 888.1917 38.14723 117.9536 882.6248 38.41403 115.6422 880.3132 35.70993 117.9536 882.6248 38.41403 117.5169 888.1917 38.14723 115.1117 887.1223 35.03686 120.3389 876.4494 39.92034 120.293 864.858 40.18021 118.9434 870.7203 39.29234 119.517 864.8443 39.8225 116.0766 867.6139 37.0975 119.517 864.8443 39.8225 118.9434 870.7203 39.29234 115.9881 861.3197 37.80705 118.458 876.3988 38.82935 115.968 873.9439 36.39864 118.458 876.3988 38.82935 118.4157 876.9213 38.7909 118.4157 876.9213 38.7909 121.1195 864.8674 40.40108 110.4945 850.2931 36.19426 109.3784 844.4636 37.18497 114.5769 848.2745 39.03366 111.3991 856.0792 35.21489 112.0794 861.8504 34.24337 112.5068 867.5935 33.27953 112.6529 873.2938 32.32313 112.4944 878.9932 31.3738 113.8022 886.4208 33.15901 113.8022 886.4208 33.15901 104.7039 846.5903 32.9898 102.5874 840.3643 34.1744 107.571 843.283 36.45324 107.571 843.283 36.45324 106.4052 852.6566 31.75639 107.7911 858.6533 30.52978 108.8173 864.5587 29.30983 109.44 870.354 28.09634 109.6175 876.0458 26.88902 112.0408 885.3116 30.40624 109.3525 882.194 25.65145 112.1458 888.2664 30.86387 112.0408 885.3116 30.40624 110.4696 884.1159 27.70077 110.4696 884.1159 27.70077 112.1883 888.4014 30.95501 102.5874 840.3643 34.1744 98.01316 842.9539 28.641 94.91403 836.5607 29.87435 99.68231 838.837 32.66625 99.68231 838.837 32.66625 100.6368 849.1633 27.33573 102.8794 855.2555 26.0357 104.6844 861.2012 24.74083 105.996 866.9783 23.45096 106.7564 872.5477 22.16591 107.3771 879.0043 21.75802 106.9483 878.359 20.8624 110.1837 884.7299 27.29786 109.3525 882.194 25.65145 110.4696 884.1159 27.70077 108.2686 880.4038 23.56022 108.2686 880.4038 23.56022 110.1837 884.7299 27.29786 110.4696 884.1159 27.70077 94.91403 836.5607 29.87435 90.45492 839.4878 22.63902 86.36159 832.9214 23.79931 92.4546 835.4714 28.27164 93.09426 833.2969 30.76972 92.4546 835.4714 28.27164 94.14219 845.905 21.46337 97.38893 852.1607 20.29144 100.1268 858.219 19.12316 102.2883 864.0516 17.95844 103.8043 869.6134 16.79716 104.6395 875.2005 15.63907 108.0235 881.2662 23.18103 106.9483 878.359 20.8624 107.3771 879.0043 21.75802 106.1449 877.2017 19.12797 106.1449 877.2017 19.12797 86.36159 832.9214 23.79931 82.47654 836.0637 14.81732 77.17958 829.16 15.63231 85.41413 832.5347 23.03966 85.30255 830.4732 25.18547 85.41413 832.5347 23.03966 87.32357 842.7827 13.98019 91.6717 849.2971 13.14529 95.4411 855.5649 12.31257 98.55252 861.5502 11.48199 100.9262 867.2117 10.65348 102.492 872.6718 9.812276 105.9774 878.2146 18.76206 104.6395 875.2005 15.63907 104.1054 874.5336 14.30616 104.1054 874.5336 14.30616 78.489 829.7063 16.91217 77.76358 827.7597 18.61957 78.489 829.7063 16.91217 77.17958 829.16 15.63231 77.21061 833.2871 9.398514 71.80095 826.8313 9.935777 71.80095 826.8313 9.935777 80.52293 837.3721 9.063443 84.27124 842.2046 8.600518 91.41178 852.3514 7.303383 88.19352 847.5847 7.977268 93.97883 856.4866 6.606506 98.9223 866.0517 4.445541 96.02964 860.1058 5.900594 102.3887 872.5633 9.489767 100.8417 871.0832 3.450076 102.2562 872.4262 9.06752 104.0461 875.6523 13.97244 102.492 872.6718 9.812276 102.3887 872.5633 9.489767 74.53226 832.1068 4.85441 71.80095 826.8313 9.935777 77.21061 833.2871 9.398514 70.6231 824.9868 11.19491 70.28833 825.9641 8.409552 70.6231 824.9868 11.19491 71.80095 826.8313 9.935777 70.28833 825.9641 8.409552 68.00643 824.6503 5.248205 80.52293 837.3721 9.063443 80.69789 839.431 4.536361 84.27124 842.2046 8.600518 86.23005 846.4628 4.143736 88.19352 847.5847 7.977268 91.41178 852.3514 7.303383 91.04735 853.1524 3.656289 93.97883 856.4866 6.606506 95.08218 859.4567 3.064887 96.02964 860.1058 5.900594 98.27246 865.3341 2.353588 98.9223 866.0517 4.445541 100.6049 870.892 1.745184 100.8417 871.0832 3.450076 102.3291 873.6525 8.780452 100.8417 871.0832 3.450076 102.2562 872.4262 9.06752 101.0593 872.6114 3.271139 100.6049 870.892 1.745184 100.8417 871.0832 3.450076 101.0593 872.6114 3.271139 92.04181 830.7607 32.61454 84.09829 828.2968 26.84037 76.4592 825.8682 20.10792 69.2611 823.3291 12.54675 69.2611 823.3291 12.54675 69.10845 825.2784 6.984041 67.63621 824.4355 4.525741 68.00643 824.6503 5.248205 68.26712 824.7983 5.710631 66.83929 823.9902 2.145108 66.62866 823.8676 0.756924 66.62174 823.8656 -0.606883 66.60063 823.8524 -0.005285978 67.08998 824.1286 -3.109051 68.61457 824.9974 -6.266973 68.01292 824.6517 -5.267594 67.97708 824.631 -5.20226 69.42745 825.462 -7.402983 69.42745 825.462 -7.402983 68.61457 824.9974 -6.266973 68.01292 824.6517 -5.267594 73.30205 831.3743 -0.004397988 67.97708 824.631 -5.20226 67.08998 824.1286 -3.109051 66.60063 823.8524 -0.005285978 66.62174 823.8656 -0.606883 66.83929 823.9902 2.145108 66.62866 823.8676 0.756924 67.63621 824.4355 4.525741 69.10845 825.2784 6.984041 68.26712 824.7983 5.710631 100.5243 870.8299 -4.62e-4 100.5243 870.8299 -4.62e-4 98.05286 865.127 -8.82e-4 94.69636 859.1605 -0.001473963 90.4718 852.7641 -0.002147853 85.44482 845.9691 -0.00287497 79.69321 838.8229 -0.003627896 100.7872 872.395 -4.67e-4 98.95037 876.6594 3.242929 99.78448 877.7719 8.545634 98.95037 876.6594 3.242929 99.82497 875.3803 -4.52e-4 100.0697 875.5527 3.160537 100.777 876.9995 8.44043 100.0697 875.5527 3.160537 98.69551 876.4974 -4.63e-4 100.546 873.9647 -4.53e-4 100.7964 874.1541 3.170622 101.5625 876.0121 8.445867 100.7964 874.1541 3.170622 102.0914 874.8721 8.561601 100.7964 874.1541 -3.17062 100.0697 875.5527 -3.160535 98.95037 876.6595 -3.242928 102.0915 874.8722 -8.561612 100.7964 874.1541 -3.17062 101.5625 876.0122 -8.44594 100.0697 875.5527 -3.160535 100.777 876.9995 -8.440592 98.95037 876.6595 -3.242928 99.78457 877.7719 -8.54591 107.4335 887.3129 26.46688 107.4335 887.3129 26.46688 105.468 884.044 22.49522 108.1155 886.9091 26.456 108.1155 886.9091 26.456 106.2781 883.4877 22.48302 108.7472 886.4359 26.5368 108.7472 886.4359 26.5368 106.9916 882.8217 22.59695 109.3118 885.9053 26.70771 109.3118 885.9053 26.70771 107.5811 882.0715 22.83261 109.7949 885.3314 26.96374 109.7949 885.3314 26.96374 105.5788 879.1519 18.43754 104.995 880.0233 18.23044 104.2533 880.7889 18.15005 103.3873 881.4139 18.20005 103.7155 876.7313 13.68568 103.151 877.7355 13.5151 102.3839 878.6103 13.46978 101.4556 879.3086 13.55216 103.7155 876.7312 -13.68572 103.1511 877.7354 -13.51526 102.384 878.6103 -13.47011 101.4558 879.3087 -13.5527 105.5795 879.1527 -18.43838 104.9957 880.0241 -18.23118 104.2539 880.7896 -18.15064 103.3878 881.4144 -18.20041 107.581 882.0714 -22.83279 106.9915 882.8216 -22.5971 106.2779 883.4877 -22.48316 105.4679 884.044 -22.49535 109.7952 885.3309 -26.9641 109.3119 885.9049 -26.70808 108.747 886.4357 -26.53711 108.1149 886.9092 -26.45622 107.4329 887.3131 -26.46705 109.7952 885.3309 -26.9641 109.3119 885.9049 -26.70808 108.747 886.4357 -26.53711 108.1149 886.9092 -26.45622 107.4329 887.3131 -26.46705 113.5 953.6906 7.209047 113.5 954.4 0 113.5 954.2182 -3.655726 113.5 953.6827 -7.249401 113.5 951.5842 14.15581 113.5 951.5598 -14.21501 113.5 948.1718 20.54592 113.5 948.135 -20.60119 113.5 943.5797 26.14408 113.5 943.5462 -26.17773 113.5 937.9476 30.76877 113.5 937.9393 -30.77456 113.5 931.5532 -34.18553 113.5 931.5239 34.19749 113.5 924.6329 -36.28598 113.5 924.5722 36.29792 113.5 917.4362 -36.99993 113.5 917.3638 36.99993 113.5 910.2279 -36.29792 113.5 910.1671 36.28598 113.5 903.2761 -34.19749 113.5 903.2468 34.18553 113.5 896.8524 -30.76877 113.5 891.2538 26.17773 113.5 891.2203 -26.14408 113.5 896.8607 30.77456 113.5 886.6651 20.60119 113.5 886.6282 -20.54592 113.5 883.2402 14.21501 113.5 883.2158 -14.15581 113.5 881.1173 7.249401 113.5 881.1094 -7.209047 113.5 880.5818 3.655726 113.5 880.4 0 57.38745 799.3978 13.21573 57.38745 799.3978 -13.21573 40.07063 791.3596 -36.79175 59.70998 800.4758 9.193468 59.70998 800.4758 -9.193468 40.07063 791.3596 36.79175 36.07163 789.5033 -41.17658 31.32223 787.2987 44.51751 31.32197 787.2986 -44.51765 36.07178 789.5034 41.17645 26.03849 784.8461 46.66659 26.0382 784.846 -46.66667 20.45866 782.256 47.5268 20.45846 782.2559 -47.52681 14.83479 779.6455 -47.05585 14.83479 779.6455 47.05585 -8.166404 768.9687 -42.35595 61.14601 801.1425 4.713194 61.14601 801.1425 -4.713194 61.6318 801.3679 0 -8.166404 768.9687 42.35595 -15.13636 765.7333 -40.17865 -15.10909 765.746 40.19025 -18.46122 764.19 -38.56038 -21.58094 762.7419 36.64815 -21.62717 762.7204 -36.61668 -27.34307 760.0672 31.8611 -27.39353 760.0438 -31.81053 -32.19611 757.8145 26.00253 -32.23561 757.7962 -25.94529 -36.01155 756.0434 19.2237 -36.03159 756.0341 -19.17983 -38.62562 754.83 11.79207 -38.63088 754.8276 -11.77211 -39.95166 754.2145 3.972513 -39.95194 754.2144 -3.969198 45.42438 770.7373 49.62154 51.61288 770.7397 47.44138 57.65616 770.7393 44.80319 63.47176 770.7366 41.72792 84.09385 793.6874 40.5233 68.97576 770.7321 38.24304 90.44699 793.6814 36.49505 74.08457 770.7263 34.37895 96.26206 793.6743 32.07794 78.71775 770.7197 30.17115 101.4233 793.6668 27.3146 82.79743 770.7127 25.65736 105.8247 793.6594 22.25154 86.25354 770.7059 20.879 109.3676 793.6526 16.93737 89.02076 770.6998 15.87892 111.9705 793.647 11.42291 91.04574 770.6948 10.70202 -47 750.4 0 47 750.4 0 46.81725 750.4 4.129784 -46.81725 750.4 -4.129784 46.28787 750.4 -8.149951 -46.28787 750.4 8.149951 46.27937 750.4 8.198644 -44.16648 750.4 16.07183 44.1421 750.4 16.13909 -40.70402 750.4 23.49939 40.6702 750.4 23.5582 -36.0195 750.4 30.1906 35.99309 750.4 30.22239 -33.23096 750.4 33.23587 30.19856 750.4 36.01375 -30.19496 750.4 36.01652 23.49571 750.4 40.70508 -23.44416 750.4 40.73464 16.09428 750.4 44.15781 -26.91589 750.4 38.52895 -15.9915 750.4 44.19508 8.211176 750.4 46.27641 -8.070898 750.4 46.30111 0.07673799 750.4 46.99917 -46.27937 750.4 -8.198644 44.16648 750.4 -16.07183 -44.1421 750.4 -16.13909 40.70402 750.4 -23.49939 -40.6702 750.4 -23.5582 36.0195 750.4 -30.1906 -35.99309 750.4 -30.22239 33.23096 750.4 -33.23587 -30.19856 750.4 -36.01375 30.19496 750.4 -36.01652 -23.49571 750.4 -40.70508 23.44416 750.4 -40.73464 -16.09428 750.4 -44.15781 26.91589 750.4 -38.52895 15.9915 750.4 -44.19508 -8.211176 750.4 -46.27641 8.070898 750.4 -46.30111 -0.07673799 750.4 -46.99917 129.3591 870.941 9.639678 129.3591 870.941 -9.639678 128.4948 881.9233 -24.8023 129.5146 868.9653 6.033399 129.5146 868.9654 -6.033578 128.4948 881.9233 24.8023 128.2443 885.1062 -28.39206 128.2443 885.1062 28.39206 127.9435 888.9289 -31.28688 127.9435 888.9289 31.28688 127.6039 893.2432 -33.37425 127.6039 893.2432 33.37425 127.2389 897.8814 -34.57314 127.2389 897.8814 34.57314 126.8625 902.6635 -34.83712 126.8625 902.6635 34.83712 125.7858 916.3447 -34.23794 129.5947 867.9478 2.053213 129.5947 867.9478 -2.0535 125.7858 916.3447 34.23794 125.243 923.2413 -33.22167 125.2457 923.207 33.23033 124.7319 929.7355 30.84803 124.7276 929.7897 -30.82175 124.2675 935.6369 27.20138 124.2632 935.6913 -27.15947 123.8705 940.6809 22.4328 123.8676 940.718 -22.3899 123.5555 944.6834 16.70721 123.3385 947.4402 -10.29736 123.3384 947.4419 10.29131 123.5545 944.6964 -16.68411 123.2282 948.8416 -3.490015 123.228 948.8441 3.464874 -42.89738 756.9 17.64657 -40.97083 756.9224 21.14017 -41.0405 756.9 21.01015 -41.0405 756.9 21.01015 -40.97083 756.9224 21.14017 -41.28938 757.1459 20.53412 -41.0405 756.9 21.01015 -41.06112 757.0635 20.95128 -40.95819 756.9003 21.16058 -41.58155 757.197 19.9889 -41.94689 757.2196 19.28848 -42.39703 757.2106 18.3952 -42.78251 756.9 17.60024 -42.89738 756.9 17.64657 -41.0405 756.9 21.01015 -40.8898 756.9448 21.26379 -40.8898 756.9448 21.26379 -41.06112 757.0635 20.95128 -40.8898 756.9448 21.26379 -40.87191 756.9262 21.29193 -40.86539 756.9 21.30298 -41.28938 757.1459 20.53412 -41.58155 757.197 19.9889 -41.94689 757.2196 19.28848 -42.79073 757.1798 17.58454 -42.39703 757.2106 18.3952 -42.79073 757.1798 17.58454 -44.39982 756.9 13.93945 31.48102 799.5927 -29.08545 44.53815 808.09 -22.45329 37.78889 801.6061 -33.3843 41.03539 794.5636 -33.19347 37.78889 801.6061 -33.3843 44.53815 808.09 -22.45329 36.85235 800.5808 -34.9665 39.38906 791.815 -36.44732 36.85235 800.5808 -34.9665 37.78889 801.6061 -33.3843 41.03539 794.5636 -33.19347 30.40827 801.6179 -17.5638 50.77352 812.9079 -12.96402 51.14352 797.2712 -20.31834 50.77352 812.9079 -12.96402 42.88395 795.4217 -30.65461 44.72676 796.2774 -28.12517 45.46254 794.6342 -28.10537 29.86931 802.6354 -5.872993 52.85843 814.386 -9.014695 56.63496 799.8202 -12.80564 50.77352 812.9079 -12.96402 52.85843 814.386 -9.014695 56.63496 799.8202 -12.80564 54.13798 815.3225 -4.606662 59.22314 801.0216 -8.073531 54.13798 815.3225 -4.606662 29.86935 802.6354 5.874382 54.56629 815.6407 0 60.56382 801.6439 -2.759381 54.56629 815.6407 0 54.138 815.3225 4.606548 60.56385 801.6439 2.759177 54.138 815.3225 4.606548 60.73397 801.7229 -1.07e-4 52.85852 814.3861 9.01449 59.22319 801.0216 8.073405 52.85852 814.3861 9.01449 30.40836 801.6177 17.56518 50.77356 812.9078 12.96405 50.77356 812.9078 12.96405 46.0414 809.3446 20.11712 56.63496 799.8202 12.80564 50.77356 812.9078 12.96405 46.0414 809.3446 20.11712 56.63496 799.8202 12.80564 31.48118 799.5924 29.0868 40.99219 804.8685 28.10014 51.14158 797.2703 20.32099 40.99219 804.8685 28.10014 38.40623 802.2627 32.35152 44.72673 796.2774 28.12514 40.99219 804.8685 28.10014 38.40623 802.2627 32.35152 44.72673 796.2774 28.12514 33.13495 796.5799 40.40057 35.93107 799.5392 36.54001 41.03554 794.5634 33.19351 35.93107 799.5392 36.54001 42.87622 795.4181 30.66521 39.38906 791.815 36.44732 35.93107 799.5392 36.54001 33.13495 796.5799 40.40057 41.77116 792.9207 33.17374 39.38906 791.815 36.44732 7.704969 784.9572 34.83233 9.617717 781.4716 45.91453 32.57117 796.0337 41.00528 35.47215 789.9968 40.78309 32.57117 796.0337 41.00528 37.53174 790.9528 38.7372 6.323956 787.4714 23.41057 5.489964 788.9897 11.7622 5.211067 789.4974 -4.00001e-6 5.489965 788.9897 -11.76221 6.323956 787.4714 -23.41057 35.93106 799.5392 -36.54003 33.13368 796.5786 -40.4023 7.704971 784.9572 -34.83234 37.53174 790.9528 -38.7372 33.13368 796.5786 -40.4023 35.93106 799.5392 -36.54003 32.56385 796.0266 -41.01319 35.47215 789.9968 -40.78309 32.56385 796.0266 -41.01319 35.93106 799.5392 -36.54003 39.38906 791.815 -36.44732 30.59902 794.2283 42.79674 33.22443 788.9534 42.5735 30.59902 794.2283 42.79674 28.43647 792.4105 44.29981 30.81453 787.8348 44.08666 28.43647 792.4105 44.29981 23.702 788.919 46.35472 25.63339 785.4298 46.21215 23.702 788.919 46.35472 13.29794 783.1301 46.66258 18.57328 785.774 47.13228 20.1499 782.8844 47.06884 18.57328 785.774 47.13228 13.29794 783.1301 46.66258 14.6151 780.3153 46.60961 13.29794 783.1301 46.66258 9.617717 781.4716 45.91453 14.6151 780.3153 46.60961 1.752901 777.8725 44.3115 3.141953 774.9896 44.26323 1.752901 777.8725 44.3115 -17.41696 772.7709 28.95494 -15.28066 770.0112 40.3613 -9.7199 772.4884 41.96263 -15.75463 769.8154 40.18149 -18.54039 774.7445 17.48425 -19.1048 775.7361 5.846706 -19.1048 775.7361 -5.846629 -18.54039 774.7446 -17.48417 -17.41696 772.7709 -28.95486 28.44293 792.4157 -44.29595 9.617804 781.4716 -45.91455 -15.75464 769.8154 -40.18149 30.59641 794.226 -42.7989 23.73148 788.9389 -46.34629 13.29764 783.13 -46.66255 3.141956 774.9896 -44.26323 9.617804 781.4716 -45.91455 13.29764 783.13 -46.66255 -15.27973 770.0116 -40.36164 1.752893 777.8725 -44.31147 1.752893 777.8725 -44.31147 18.61113 785.7949 -47.13139 14.6151 780.3153 -46.60961 13.29764 783.13 -46.66255 18.61113 785.7949 -47.13139 14.6151 780.3153 -46.60961 20.1499 782.8844 -47.06884 23.73148 788.9389 -46.34629 25.63339 785.4298 -46.21215 28.44293 792.4157 -44.29595 30.81453 787.8348 -44.08667 30.59641 794.226 -42.7989 33.22443 788.9534 -42.5735 -8.38594 769.6385 41.90864 -9.7199 772.4884 41.96263 -15.28066 770.0112 40.3613 -9.7199 772.4884 41.96263 -8.38594 769.6385 41.90864 -13.90236 767.0779 40.30782 -15.75463 769.8154 40.18149 -20.74854 767.8887 37.85063 -19.91469 766.2717 37.85287 -20.74854 767.8887 37.85063 -36.69028 763.2447 22.71041 -25.99024 766.1235 34.43253 -29.02804 765.2124 31.89563 -31.84337 764.436 29.08086 -40.30181 762.4692 15.57123 -43.28004 761.8969 0 -42.53479 762.0349 7.876314 -42.53423 762.035 -7.879176 -36.68834 763.2451 -22.71351 -40.30046 762.4695 -15.57466 -31.84158 764.4365 -29.08282 -13.90236 767.0779 -40.30782 -15.75464 769.8154 -40.18149 -15.27973 770.0116 -40.36164 -25.99024 766.1235 -34.43252 -20.74764 767.889 -37.85113 -19.91469 766.2717 -37.85287 -20.74764 767.889 -37.85113 -19.14559 764.6441 -37.82394 -9.719532 772.4885 -41.96273 -9.719532 772.4885 -41.96273 -8.385946 769.6385 -41.90866 -9.719532 772.4885 -41.96273 -8.385946 769.6385 -41.90866 -22.67596 764.9895 36.10401 -25.99024 766.1235 34.43253 -24.15538 762.3186 34.38758 -25.99024 766.1235 34.43253 -29.02804 765.2124 31.89563 -25.45957 765.0406 34.42577 -24.92052 763.9479 34.41909 -25.45957 765.0406 34.42577 -29.54388 759.8173 29.10018 -31.84337 764.436 29.08086 -33.96741 757.764 22.76786 -36.69028 763.2447 22.71041 -35.7573 756.9332 19.28325 -40.30181 762.4692 15.57123 -39.24954 755.3121 7.967524 -42.53479 762.0349 7.876314 -37.24722 756.2416 15.61862 -39.75849 755.0759 4.009252 -43.28004 761.8969 0 -39.76028 755.075 -3.985903 -42.53423 762.035 -7.879176 -39.92901 754.9967 0.01457285 -39.25046 755.3117 -7.962072 -40.30046 762.4695 -15.57466 -37.23548 756.247 -15.65263 -36.68834 763.2451 -22.71351 -38.40585 755.7037 -11.86088 -33.96634 757.7645 -22.76986 -31.84158 764.4365 -29.08282 -29.55285 759.8132 -29.08981 -25.99024 766.1235 -34.43252 -25.45889 765.0408 -34.42483 -25.99024 766.1235 -34.43252 -25.45889 765.0408 -34.42483 -24.92052 763.9479 -34.41909 -23.89927 764.4634 -35.23015 -22.01105 765.2838 -36.55213 41.77116 792.9207 -33.17374 42.88395 795.4217 -30.65461 41.77116 792.9207 -33.17374 41.03539 794.5636 -33.19347 39.38906 791.815 36.44732 39.38906 791.815 -36.44732 41.77116 792.9207 -33.17374 37.53174 790.9528 38.7372 37.53174 790.9528 -38.7372 44.72676 796.2774 -28.12517 45.46254 794.6342 -28.10537 41.77116 792.9207 33.17374 45.46254 794.6342 -28.10537 45.46254 794.6342 28.10537 51.14352 797.2712 -20.31834 51.14158 797.2703 20.32099 56.63496 799.8202 -12.80564 56.63496 799.8202 12.80564 59.22314 801.0216 -8.073531 -21.70319 763.4569 36.2155 -21.70319 763.4569 -36.2155 -19.14559 764.6441 -37.82394 -22.01105 765.2838 -36.55213 -19.14559 764.6441 -37.82394 -21.70319 763.4569 -36.2155 -19.14558 764.6441 37.82392 -13.90236 767.0779 -40.30782 -19.91469 766.2717 -37.85287 -24.15538 762.3186 34.38758 -24.15538 762.3186 -34.38758 -23.89927 764.4634 -35.23015 -24.15538 762.3186 -34.38758 -29.54388 759.8173 29.10018 -29.55285 759.8132 -29.08981 -24.92052 763.9479 -34.41909 -24.15538 762.3186 -34.38758 -24.92052 763.9479 -34.41909 -33.96741 757.764 22.76786 -33.96634 757.7645 -22.76986 -35.7573 756.9332 19.28325 -37.23548 756.247 -15.65263 -37.24722 756.2416 15.61862 -38.40585 755.7037 -11.86088 -39.24954 755.3121 7.967524 -39.25046 755.3117 -7.962072 -39.75849 755.0759 4.009252 -39.76028 755.075 -3.985903 -39.92901 754.9967 0.01457285 -22.67596 764.9895 36.10401 -24.15538 762.3186 34.38758 -21.70319 763.4569 36.2155 -24.92052 763.9479 34.41909 -24.92052 763.9479 34.41909 -19.14558 764.6441 37.82392 -13.90236 767.0779 40.30782 -19.14558 764.6441 37.82392 -19.91469 766.2717 37.85287 -8.385946 769.6385 -41.90866 -8.38594 769.6385 41.90864 3.141956 774.9896 -44.26323 3.141953 774.9896 44.26323 14.6151 780.3153 -46.60961 14.6151 780.3153 46.60961 20.1499 782.8844 -47.06884 20.1499 782.8844 47.06884 25.63339 785.4298 -46.21215 25.63339 785.4298 46.21215 30.81453 787.8348 -44.08667 30.81453 787.8348 44.08666 33.22443 788.9534 -42.5735 33.22443 788.9534 42.5735 35.47215 789.9968 -40.78309 35.47215 789.9968 40.78309 41.03554 794.5634 33.19351 41.77116 792.9207 33.17374 45.46254 794.6342 28.10537 45.46254 794.6342 28.10537 42.87622 795.4181 30.66521 44.72673 796.2774 28.12514 59.22319 801.0216 8.073405 60.56382 801.6439 -2.759381 60.56385 801.6439 2.759177 60.73397 801.7229 -1.07e-4 129.5225 908.555 34.19205 133.2455 887.0908 29.22579 134.8339 883.0313 24.9576 130.9351 882.7795 24.91705 134.8339 883.0313 24.9576 133.2455 887.0908 29.22579 132.4382 908.8385 24.6671 137.0248 877.561 17.21489 130.9607 882.455 24.46547 137.0248 877.561 17.21489 134.8339 883.0313 24.9576 130.9479 882.6173 24.69136 130.9351 882.7795 24.91705 131.8178 891.8647 32.23703 128.464 891.237 31.99841 131.8178 891.8647 32.23703 129.0062 884.3472 26.89677 128.8368 886.4996 28.92773 130.6748 897.2774 34.01597 128.2532 893.9151 33.11112 130.6748 897.2774 34.01597 129.9804 902.8915 34.43898 127.7966 899.7173 34.33748 129.9804 902.8915 34.43898 128.0279 896.7782 33.90766 127.5619 902.6992 34.39526 129.9804 902.8915 34.43898 129.5225 908.555 34.19205 127.5619 902.6992 34.39526 129.427 909.7293 34.14068 129.427 909.7293 34.14068 134.3982 909.0289 14.89846 129.8298 940.5786 22.47744 128.5646 922.5021 33.05109 128.8677 916.5698 33.84029 128.5497 925.3995 32.26696 128.6178 928.2351 31.22531 128.9633 933.5783 28.422 129.511 938.3998 24.689 138.8933 870.6928 7.24944 135.383 909.1245 4.982569 130.8626 946.2828 13.77843 138.5967 871.9926 9.404567 130.1594 942.5803 20.04078 130.533 944.6217 16.96953 139.1229 869.7482 -4.925337 135.383 909.1245 -4.982569 131.5155 949.2716 -0.001697957 139.2664 869.1759 -2.491409 139.3153 868.9838 0.001924932 139.2662 869.1765 2.495124 139.1226 869.7492 4.928397 131.344 948.5177 7.030491 138.597 871.9926 -9.404582 134.3982 909.0289 -14.89846 131.3437 948.5166 -7.035818 138.8934 870.6921 -7.248075 137.0242 877.5613 -17.21537 132.4382 908.8385 -24.6671 130.5319 944.6163 -16.97867 130.8618 946.2789 -13.78698 130.6754 897.2741 -34.0153 129.5225 908.555 -34.19205 129.5098 938.3914 -24.69671 131.8188 891.8608 -32.23521 133.2462 887.0888 -29.22415 134.8339 883.0325 -24.95916 130.1581 942.5731 -20.05053 129.8285 940.5707 -22.48623 129.9804 902.8915 -34.43898 126.4852 916.3804 -33.79704 129.5225 908.555 -34.19205 129.9804 902.8915 -34.43898 128.9626 933.57 -28.42729 128.6176 928.2281 -31.22821 128.5496 925.3937 -32.26878 128.5647 922.498 -33.05202 129.427 909.7293 -34.14068 128.8677 916.5698 -33.84029 129.427 909.7293 -34.14068 127.5619 902.6992 -34.39526 129.9804 902.8915 -34.43898 130.6754 897.2741 -34.0153 127.5619 902.6992 -34.39526 128.0281 896.776 -33.90715 131.8188 891.8608 -32.23521 127.7967 899.7162 -34.33739 128.4641 891.2354 -31.99762 133.2462 887.0888 -29.22415 128.2534 893.9126 -33.1103 128.8368 886.4993 -28.92748 134.8339 883.0325 -24.95916 130.9351 882.7806 -24.91856 134.8339 883.0325 -24.95916 137.0242 877.5613 -17.21537 129.0062 884.3471 -26.89663 130.9351 882.7806 -24.91856 129.5896 876.9345 -16.93554 138.597 871.9926 -9.404582 129.1644 882.3372 -24.44795 130.9608 882.4547 -24.465 130.9479 882.6176 -24.69167 130.1239 870.1461 -7.192123 138.597 871.9926 -9.404582 138.8934 870.6921 -7.248075 130.0221 871.4396 -9.316603 130.0221 871.4396 -9.316603 130.1983 869.2001 -4.893514 139.1229 869.7482 -4.925337 130.2437 868.6237 -2.476687 139.2664 869.1759 -2.491409 130.2589 868.4301 -6.6e-5 139.3153 868.9838 0.001924932 139.2662 869.1765 2.495124 130.2437 868.6237 2.476565 139.1226 869.7492 4.928397 130.1983 869.2001 4.89342 138.8933 870.6928 7.24944 130.1239 870.1461 7.192072 138.5967 871.9926 9.404567 130.0221 871.4396 9.316603 138.5967 871.9926 9.404567 130.0221 871.4396 9.316603 129.5896 876.9346 16.93576 126.4852 916.3804 33.79696 128.8677 916.5698 33.84029 128.5646 922.5021 33.05109 128.8677 916.5698 33.84029 126.4852 916.3804 33.79696 126.0141 922.3656 32.98859 128.5497 925.3995 32.26696 126.2481 919.3926 33.52805 125.7847 925.281 32.18224 128.6178 928.2351 31.22531 125.5616 928.1154 31.11446 128.9633 933.5783 28.422 125.1424 933.4423 28.23228 129.511 938.3998 24.689 125.3469 930.8438 29.79392 126.5639 938.3319 24.4605 129.8298 940.5786 22.47744 124.9497 935.8904 26.44224 126.426 940.0753 22.65181 130.1594 942.5803 20.04078 126.2572 942.218 19.99868 130.1594 942.5803 20.04078 130.533 944.6217 16.96953 126.2572 942.218 19.99868 124.4387 942.383 19.51665 130.8626 946.2828 13.77843 126.2307 942.5535 19.52923 126.2441 942.3865 19.76503 124.174 945.7467 13.50592 131.344 948.5177 7.030491 124.0096 947.8353 6.904347 131.5155 949.2716 -0.001697957 124.0096 947.8348 -6.906694 131.3437 948.5166 -7.035818 123.9539 948.5432 -0.001346886 124.174 945.7461 -13.50729 130.8618 946.2789 -13.78698 130.5319 944.6163 -16.97867 126.2307 942.5535 -19.52923 130.1581 942.5731 -20.05053 126.3847 940.9583 -21.62769 130.1581 942.5731 -20.05053 129.8285 940.5707 -22.48623 126.2577 942.2113 -20.00864 126.2436 942.3893 -19.7612 126.2577 942.2113 -20.00864 126.421 939.7194 -23.03985 129.5098 938.3914 -24.69671 124.9497 935.8904 -26.44225 128.9626 933.57 -28.42729 124.7701 938.1724 -24.43412 126.5639 938.3319 -24.4605 126.4641 938.8951 -23.89959 125.3469 930.8437 -29.79393 128.6176 928.2281 -31.22821 125.1424 933.4422 -28.23229 125.7847 925.281 -32.18225 128.5496 925.3937 -32.26878 125.5616 928.1154 -31.11447 126.0141 922.3656 -32.9886 128.5647 922.498 -33.05202 126.2481 919.3926 -33.52807 128.8677 916.5698 -33.84029 128.8677 916.5698 -33.84029 126.4852 916.3804 -33.79704 130.9479 882.6173 24.69136 129.1644 882.3375 24.44831 130.9607 882.455 24.46547 129.1644 882.3375 24.44831 129.1644 882.3372 -24.44795 129.5896 876.9346 16.93576 129.1644 882.3375 24.44831 129.0062 884.3471 -26.89663 129.0062 884.3472 26.89677 130.0221 871.4396 -9.316603 130.0221 871.4396 9.316603 130.1239 870.1461 -7.192123 130.1239 870.1461 7.192072 129.5896 876.9345 -16.93554 128.8368 886.4993 -28.92748 128.8368 886.4996 28.92773 128.4641 891.2354 -31.99762 128.464 891.237 31.99841 128.2534 893.9126 -33.1103 128.2532 893.9151 33.11112 128.0281 896.776 -33.90715 128.0279 896.7782 33.90766 127.7967 899.7162 -34.33739 127.7966 899.7173 34.33748 127.5619 902.6992 34.39526 127.5619 902.6992 -34.39526 126.4852 916.3804 33.79696 124.6007 940.3251 22.159 124.6002 940.3315 -22.1516 124.7701 938.1724 -24.43412 125.6737 938.2549 -24.44556 124.7701 938.1724 -24.43412 124.6002 940.3315 -22.1516 124.7701 938.1724 24.43411 124.9497 935.8904 -26.44225 125.6737 938.2549 -24.44556 124.4947 941.6719 20.49196 124.4945 941.6737 -20.48963 126.3847 940.9583 -21.62769 124.4945 941.6737 -20.48963 126.421 939.7194 -23.03985 126.4641 938.8951 -23.89959 124.4387 942.383 19.51665 124.4387 942.383 -19.51665 126.2577 942.2113 -20.00864 124.4387 942.383 -19.51665 124.174 945.7467 13.50592 124.174 945.7461 -13.50729 124.4387 942.383 -19.51665 126.2436 942.3893 -19.7612 125.3432 942.4669 -19.52603 125.3432 942.4669 -19.52603 124.0096 947.8348 -6.906694 124.0096 947.8353 6.904347 123.9539 948.5432 -0.001346886 125.3433 942.4669 19.52602 124.4387 942.383 19.51665 124.4947 941.6719 20.49196 125.3433 942.4669 19.52602 126.2572 942.218 19.99868 124.6007 940.3251 22.159 126.2441 942.3865 19.76503 126.426 940.0753 22.65181 124.7701 938.1724 24.43411 124.9497 935.8904 26.44224 124.7701 938.1724 24.43411 125.6736 938.2549 24.44556 125.6736 938.2549 24.44556 125.1424 933.4422 -28.23229 125.1424 933.4423 28.23228 125.3469 930.8437 -29.79393 125.3469 930.8438 29.79392 125.5616 928.1154 -31.11447 125.5616 928.1154 31.11446 125.7847 925.281 -32.18225 125.7847 925.281 32.18224 126.0141 922.3656 -32.9886 126.0141 922.3656 32.98859 126.2481 919.3926 -33.52807 126.2481 919.3926 33.52805 126.4852 916.3804 -33.79704 130.1983 869.2001 -4.893514 130.1983 869.2001 4.89342 130.2437 868.6237 -2.476687 130.2437 868.6237 2.476565 130.2589 868.4301 -6.6e-5 130.9479 882.6176 -24.69167 129.1644 882.3372 -24.44795 130.9608 882.4547 -24.465 126.5639 938.3319 -24.4605 126.2307 942.5535 19.52923 126.2307 942.5535 -19.52923 126.5639 938.3319 24.4605 - - - - - - - - - - 0.2495893 -0.02411049 -0.9680516 0.2496176 -0.02157717 -0.9681041 0.3258497 -0.1670296 -0.9305499 0.2470508 -0.03909474 -0.9682136 0.3253685 -0.1688644 -0.9303871 0.2459835 -0.02841323 -0.9688576 0.3253955 -0.1666653 -0.9307742 0.5357152 -0.7905971 -0.2965897 0.4091377 -0.3202969 -0.8544099 0.4074681 -0.3440177 -0.8459442 0.4042566 -0.3344593 -0.8513011 0.4062696 -0.3183137 -0.8565171 0.3259488 -0.1700854 -0.9299615 0.07944035 0.2648724 -0.9610057 0.07855635 0.2683857 -0.9601031 0.06814879 0.2308757 -0.9705937 0.06451731 0.2563298 -0.9644339 -0.1002259 0.5241718 -0.8456943 -0.101293 0.5279504 -0.843213 -0.1184152 0.4772013 -0.8707795 -0.1247321 0.511716 -0.8500522 -0.2685385 0.7241903 -0.6351658 -0.2692403 0.7275774 -0.6309842 -0.2870646 0.6773456 -0.6773456 -0.3011058 0.7069243 -0.6399949 -0.3427556 0.7970572 -0.4972108 -0.3420938 0.7984529 -0.4954241 -0.3657124 0.7446703 -0.5583196 -0.3829913 0.7733684 -0.5051921 -0.3429453 0.7952108 -0.5000282 -0.4298971 0.8501806 -0.3039433 -0.4173819 0.844713 -0.3350408 -0.4173219 0.849934 -0.3216437 -0.4180555 0.842154 -0.3405972 -0.4753346 0.7652353 -0.4341338 -0.427511 0.8151031 -0.3909492 -0.4498228 0.8151378 -0.3649793 -0.4475904 0.7893718 -0.4201844 -0.4175039 0.8481922 -0.3259766 -0.2826987 0.7109738 -0.6438927 -0.3497748 0.7896409 -0.5041079 -0.2779417 0.718522 -0.6375536 -0.3430939 0.7829328 -0.518944 -0.4188745 0.8422046 -0.3394638 -0.1261657 0.5169622 -0.8466595 -0.111946 0.5173079 -0.848446 0.04266601 0.269913 -0.961939 0.06674623 0.257768 -0.9638987 0.2074667 -0.006744623 -0.9782189 0.2389006 -0.02877914 -0.9706175 0.3239934 -0.171183 -0.9304433 0.2871533 -0.1324524 -0.948683 0.318739 -0.1742932 -0.9316799 0.2871251 -0.141945 -0.9473177 0.4126224 -0.3371479 -0.8462116 0.3955903 -0.3230766 -0.8597267 0.4204008 -0.3410511 -0.8408017 0.3845741 -0.3097102 -0.8695874 0.3289639 -0.1298276 -0.9353756 0.4052633 0.04953247 -0.9128572 0.2881303 -0.0263074 -0.9572298 0.08996891 0.1035802 -0.9905436 0.1146589 0.06857562 -0.9910352 0.1579048 0.03247207 -0.9869204 0.2430253 -0.05536198 -0.9684389 0.1897671 0.0310378 -0.9813385 0.1950796 0.03509724 -0.9801594 0.1969699 0.03750789 -0.9796919 -0.03527998 0.03497475 -0.9987654 0.09576952 0.03357118 -0.9948374 0.08166909 0.03650081 -0.9959909 0.009186267 0.06891226 -0.9975804 -0.02298057 0.0620141 -0.9978108 0.009277641 0.2483301 -0.968631 0.3884207 0.03772199 -0.9207098 0.1591858 0.02996939 -0.9867937 0.3412035 0.001525938 -0.9399883 0.1142021 0.0207529 -0.9932408 0.1588211 0.01651078 -0.9871693 0.1626383 0.01275712 -0.9866034 0.3089134 -0.03561568 -0.9504231 0.1394715 0.004089534 -0.9902178 0.1904091 -0.01867771 -0.9815272 0.298658 -0.06387603 -0.9522202 0.2074702 -0.02807772 -0.9778383 0.3009752 -0.08838206 -0.9495276 0.1578739 -0.01687687 -0.9873151 0.2240068 -0.0512408 -0.9732397 0.3579913 -0.1633087 -0.9193326 0.1712104 -0.03369271 -0.9846583 0.238719 -0.07388627 -0.9682738 0.4163691 -0.269146 -0.8684453 0.3987065 -0.1667584 -0.9017897 0.2503215 -0.08331841 -0.9645711 0.2899014 -0.1303473 -0.9481387 0.3437936 -0.2573951 -0.9030802 0.3967508 -0.2933209 -0.8697998 0.1746 -0.1524431 -0.9727672 0.6203113 -0.1247336 -0.7743743 0.5673437 -0.05386555 -0.8217176 0.4588214 -0.08420169 -0.8845299 0.5248077 -0.1875403 -0.8303046 0.2207447 -0.06500571 -0.973163 0.5667414 -0.04193335 -0.8228279 0.4838186 0.02325552 -0.8748593 0.2273036 -0.01895213 -0.9736396 0.3945517 -0.02258414 -0.9185962 0.1926351 0.0187996 -0.9810904 0.1825962 0.01629722 -0.9830529 0.342945 0.02017319 -0.9391389 0.3600034 0.02548342 -0.932603 0.258099 0.019288 -0.9659259 0.4894967 0.0352801 -0.8712912 0.5116615 0.04092681 -0.8582119 0.5089345 -0.01162773 -0.8607268 0.3877176 -0.1820783 -0.9036164 0.1832677 -0.04602289 -0.9819852 0.2624967 -0.1008358 -0.9596498 0.3836831 -0.1984336 -0.9018933 0.1929739 -0.05643028 -0.9795799 0.2688409 -0.1183827 -0.955882 0.3848506 -0.2156811 -0.8974251 0.2822431 -0.1290969 -0.9506172 0.3894544 -0.2324946 -0.8912191 0.2034122 -0.06274801 -0.9770805 0.2927727 -0.1419762 -0.9455828 0.4320939 -0.2971675 -0.8514613 0.2113155 -0.06695926 -0.9751216 0.2922784 -0.1492368 -0.9446173 0.4421973 -0.3252465 -0.8358685 0.4364593 -0.3016546 -0.8476484 0.4400613 -0.3023266 -0.845544 0.3028769 -0.1568404 -0.9400355 0.4626785 -0.3538148 -0.8128615 0.6767133 -0.2085105 -0.7061038 0.5898196 -0.1926084 -0.7842288 0.4428004 -0.3569199 -0.8225181 0.5861237 -0.2965258 -0.7540104 0.4261719 -0.3142271 -0.8483153 0.4486662 -0.3157846 -0.8360494 0.2200414 -0.06787407 -0.9731264 0.3094014 -0.1630934 -0.9368411 0.4302256 -0.312514 -0.8469008 0.2264183 -0.06576782 -0.9718073 0.3157531 -0.1696264 -0.9335561 0.4200055 -0.3192005 -0.8495331 0.2334374 -0.06039649 -0.9704944 0.3210594 -0.1729509 -0.9311332 0.4167993 -0.3209694 -0.8504452 0.2405824 -0.05157732 -0.9692574 0.3236519 -0.1722481 -0.9303656 0.442281 -0.3629927 -0.8201366 0.4581863 -0.3797212 -0.8036649 0.4647102 -0.3838964 -0.7979148 0.4863595 -0.4072833 -0.7730296 0.5040518 -0.4261368 -0.7512252 0.5069258 -0.4277587 -0.7483641 0.4971828 -0.3924115 -0.7738363 0.5307635 -0.4537324 -0.7158332 0.7022508 -0.2439413 -0.6688321 0.6084998 -0.3178921 -0.7270989 0.5498984 -0.4749428 -0.6870526 0.5479471 -0.4743646 -0.6890082 0.7573693 -0.3180121 -0.5703159 0.6800622 -0.3553671 -0.6412721 0.6464925 -0.3895801 -0.6559535 0.731037 -0.3141997 -0.6056928 0.1785969 0.02652096 -0.9835649 0.08215659 0.0347914 -0.996012 0.174172 0.009888112 -0.9846656 0.1645871 0.02795505 -0.9859665 0.158485 0.02377426 -0.9870752 0.1671854 0.02987849 -0.9854727 -0.0032655 0.03628677 -0.9993361 0.02310317 0.02618569 -0.9993901 0.0810886 0.02780264 -0.9963191 -0.00350964 0.02670377 -0.9996373 0.2567896 0.01941025 -0.9662725 0.1376087 0.0175482 -0.9903313 0.1266235 0.01495432 -0.9918382 0.3093147 0.02963435 -0.9504979 0.2569125 0.02200448 -0.9661841 0.2749476 0.02349978 -0.9611721 0.3379094 0.03015303 -0.9406956 -0.3401331 0.03549343 -0.9397073 -0.3633012 0.03228932 -0.9311121 -0.4188456 0.03381526 -0.9074276 -0.5779337 0.1055033 -0.8092353 -0.5639443 0.05032706 -0.8242779 -0.4630987 0.05878001 -0.8843556 -0.5013043 0.006988823 -0.8652428 -0.3398582 0.0217294 -0.9402257 -0.4297399 0.02026468 -0.9027254 -0.5924319 0.01483213 -0.805484 -0.663978 0.07779371 -0.7436945 -0.6539111 0.034487 -0.7557852 -0.1683402 0.03323465 -0.9851686 -0.4834212 0.1265623 -0.8661906 -0.397448 0.02526962 -0.9172768 -0.1742933 0.03723299 -0.9839897 -0.1537528 0.05047774 -0.9868193 -0.1539089 0.05133348 -0.9867507 -0.3976023 0.02490353 -0.9172198 -0.1938252 0.1940693 -0.9616491 -0.1657196 0.0860033 -0.9824157 -0.09744632 0.05871802 -0.9935072 -0.08578866 0.02172946 -0.9960764 -0.1742013 0.02414035 -0.9844142 -0.3016809 0.01486277 -0.9532932 -0.5216319 -0.004181087 -0.8531605 -0.6788474 -0.007568836 -0.7342404 -0.6513212 -0.014741 -0.758659 -0.7976511 -0.01202458 -0.6029993 -0.785364 -0.03198462 -0.6182075 -0.764137 -0.01101738 -0.6449599 -0.5085991 -0.1102041 -0.8539217 -0.511466 -0.06491363 -0.8568482 -0.647741 -0.08401954 -0.7572137 -0.642275 -0.1401743 -0.7535477 -0.794415 -0.08069276 -0.6019914 -0.7618553 -0.1662696 -0.626044 -0.7699083 -0.1012628 -0.6300692 -0.7059971 -0.005340814 -0.7081946 -0.7771928 0.01211595 -0.6291459 -0.7504676 -0.01339793 -0.6607716 -0.5988171 0.001434385 -0.8008846 -0.718424 0.01355051 -0.6954736 -0.7317272 0.04623651 -0.6800277 -0.2226067 0.01367253 -0.9748125 0.02295053 0.01980704 -0.9995405 -0.05899298 0.02142423 -0.9980286 0.1013856 0.01382529 -0.9947511 -0.07126182 -0.01153618 -0.997391 -0.0627163 -0.002349913 -0.9980287 -0.2137865 -0.02288931 -0.9766122 0.08734637 0.01532071 -0.9960603 0.08890271 0.02261477 -0.9957836 -0.217847 -0.04443615 -0.9749708 0.83737 -0.02167779 -0.5462065 -0.5130823 -0.1559206 -0.8440589 -0.6422852 -0.1933112 -0.7416876 -0.7921566 -0.138252 -0.5944531 -0.7526359 -0.2196167 -0.6207316 -0.5344482 -0.2267559 -0.8142156 -0.4929435 -0.2168682 -0.8426001 -0.6235476 -0.2704654 -0.73351 -0.2959464 -0.09744834 -0.9502208 -0.7380449 -0.2945709 -0.6070566 -0.7377691 -0.3159949 -0.5965266 -0.7441114 -0.3009467 -0.5964305 -0.673382 -0.2766286 -0.6855898 -0.7727072 -0.2025232 -0.6015879 -0.7436577 -0.2785779 -0.6077563 -0.2245 -0.07095736 -0.9718874 -0.07876861 -0.02923685 -0.9964641 0.09290075 0.03064137 -0.9952039 -0.9016965 -0.01626682 0.4320635 -0.9079789 -0.01791477 0.4186329 -0.901228 -0.1693503 0.3988842 -0.07693803 -0.03860634 -0.9962881 -0.07501673 -0.03875964 -0.9964287 -0.2195219 -0.1000102 -0.9704681 0.1020852 0.04162758 -0.9939044 -0.2505594 -0.1062054 -0.9622581 -0.09558498 -0.04168874 -0.994548 -0.6535068 -0.2801659 -0.7031615 -0.6358583 -0.3910063 -0.665431 -0.499041 -0.2975263 -0.8139019 -0.6176534 -0.3553689 -0.701582 -0.5918017 -0.3826827 -0.7094539 -0.6108152 -0.3874437 -0.6905014 -0.6731324 -0.3573803 -0.6474351 -0.6796416 -0.3372113 -0.6514415 0.1248224 0.06283849 -0.9901872 -0.1682801 -0.1220443 -0.978155 -0.08325487 -0.05838215 -0.9948167 -0.2242254 -0.1436544 -0.9638913 -0.0623508 -0.03778284 -0.9973389 0.05685633 0.02441495 -0.9980839 -0.3868935 -0.2729954 -0.8807877 -0.5307614 -0.3344001 -0.7787613 -0.1658722 -0.1817117 -0.9692612 -0.1899199 -0.2071326 -0.9597013 -0.1246381 -0.1345567 -0.9830361 -0.06344836 -0.09250217 -0.993689 -0.1062681 -0.1400223 -0.9844292 -0.1080692 -0.1936762 -0.9750952 -0.09744805 -0.102148 -0.9899847 -0.05621677 -0.04287976 -0.9974974 -0.09991836 -0.09430295 -0.9905168 -0.1185965 -0.1270198 -0.9847847 -0.04278802 -0.0350666 -0.9984686 -0.07132267 -0.08823019 -0.9935435 -0.106817 -0.1272343 -0.9861043 -0.07687717 -0.1035202 -0.9916519 -0.2015819 -0.2327424 -0.9514178 -0.1933976 -0.2856865 -0.9386057 -0.3072048 -0.306625 -0.900892 -0.09628766 -0.1916293 -0.9767328 -0.05758941 -0.09518891 -0.993792 -0.2822407 -0.2738785 -0.9194187 -0.2813833 -0.2998777 -0.9115355 -0.2638988 -0.2411621 -0.9339156 -0.3598777 -0.3129702 -0.8789414 -0.3254912 -0.3564381 -0.8757896 -0.4715833 -0.4003209 -0.7857179 -0.4041926 -0.3937856 -0.8255674 -0.4509213 -0.3903407 -0.8026857 -0.1999304 -0.3586296 -0.9118184 -0.458063 -0.3767598 -0.8051276 -0.4838576 -0.3868663 -0.7849945 -0.5071015 -0.3960434 -0.7655048 -0.4081018 -0.4189971 -0.8111069 -0.1116078 -0.1031236 -0.9883872 -0.06732398 -0.06689673 -0.995486 -0.06103801 -0.05908483 -0.9963852 -0.07513886 -0.0408045 -0.9963379 -0.02456754 -0.01727354 -0.9995489 -0.0590232 0.02661234 -0.9979019 -0.05881023 -0.05157721 -0.9969359 -0.0295729 -0.03323519 -0.99901 -0.03903329 -0.0348522 -0.99863 -0.01702958 -0.01281797 -0.9997729 -0.002990841 0.008514821 -0.9999594 -0.05191284 0.008728444 -0.9986135 0.04385524 0.01193279 -0.9989666 0.08032584 0.1044053 -0.9912857 0.09283816 0.1278737 -0.9874358 -0.03665381 -0.03125184 -0.9988393 0.0994001 0.139563 -0.9852116 0.05212599 0.03677505 -0.9979633 0.05594158 0.05057024 -0.9971526 0.0644859 0.07174938 -0.9953359 -0.01773154 0.004303157 -0.9998336 -0.0183112 0.004119992 -0.9998239 -0.007599174 0.0100407 -0.9999207 0.01710534 0.05452305 -0.9983661 -0.02603274 -0.01181083 -0.9995914 0.1067242 0.1523192 -0.9825522 0.04110914 0.04110914 -0.9983087 0.01709043 5.18818e-4 -0.9998539 -0.04306185 -0.01980662 -0.9988762 -0.02710115 -0.07156789 0.9970675 0.01712858 0.05593562 -0.9982875 0.01712691 0.05459004 -0.998362 -0.03082442 -0.07632863 0.9966062 0.01715767 0.05796909 -0.998171 0.01712107 0.05832159 -0.9981511 0.01718229 0.06021428 -0.9980376 0.01712131 0.06357181 -0.9978304 -0.09753996 -0.05215764 -0.9938639 -0.0863986 -0.04284828 -0.9953389 -0.06387621 -0.02768069 -0.9975739 0.01712453 0.05835479 -0.998149 0.01712149 0.06447225 -0.9977726 -0.02978616 -0.02505582 -0.9992423 -0.03891217 -0.0443446 -0.9982582 -0.08166891 -0.03817927 -0.995928 0.2168353 0.01925724 -0.9760183 0.181098 0.01730406 -0.9833129 0.1675507 0.01733493 -0.985711 0.312123 0.05218833 -0.9486072 0.295977 0.0686686 -0.9527237 0.1638275 0.06274765 -0.9844914 0.2369477 0.01242113 -0.971443 0.1401752 0.06711196 -0.9878497 0.8533784 0.07809865 -0.5154086 0.7796835 0.07434564 -0.6217447 0.8607022 0.08270698 -0.5023459 0.8594574 0.09555631 -0.5021971 0.8601272 0.09384703 -0.5013722 0.7831511 0.08066201 -0.6165778 0.8126292 0.07931882 -0.5773583 0.9307554 0.09105503 -0.3541234 0.7545086 0.07144665 -0.6523897 0.5699346 0.05356007 -0.8199428 0.6730518 0.08676761 -0.734488 0.5676533 0.06778264 -0.8204726 0.8683258 0.08206552 -0.489158 0.8439093 0.08185172 -0.5302053 0.7641159 0.09564799 -0.6379485 0.4921875 0.04516881 -0.8693166 0.4555551 0.07968473 -0.8866341 0.633156 0.05936026 -0.7717447 0.5691863 0.09128344 -0.8171256 0.6376317 0.04818934 -0.7688326 0.7527239 0.06082463 -0.6555205 0.762282 0.06692892 -0.6437754 0.8580464 0.0697363 -0.5088155 0.8923636 0.08160948 -0.4438775 0.895735 0.07602298 -0.4380404 0.8920537 0.06766164 -0.4468356 0.8566178 0.08215814 -0.5093683 0.963121 0.08716249 -0.2545596 0.9479116 0.08487254 -0.3070183 0.9476786 0.08267617 -0.3083343 0.9475743 0.08771061 -0.307262 0.8575194 0.07779258 -0.5085361 0.9283996 0.09106981 -0.3602508 0.9371922 0.08829283 -0.3374539 0.9556124 0.07925796 -0.2837661 0.9520332 0.07638847 -0.2963068 0.9470306 0.08188205 -0.3105294 0.9419164 0.0854845 -0.3247861 0.9357443 0.08746755 -0.3416607 0.9227061 0.088413 -0.3752289 0.9341899 0.09048914 -0.3451101 0.9338923 0.09052038 -0.3459064 0.9453217 0.08746701 -0.3141917 0.9324205 0.09116059 -0.3496882 0.9369788 0.09210777 -0.3370267 0.9317816 0.09114164 -0.3513922 0.9950357 0.07800608 0.06180059 0.9945302 0.09189337 0.04965478 0.9960432 0.08887082 -3.05188e-4 0.9793164 -0.1949233 0.05426234 0.9981818 -0.04535108 0.03970503 0.99654 -0.0490747 0.06708097 0.995878 0.08951336 0.01464927 0.9958855 0.0893892 -0.01489311 0.9947223 0.0899077 -0.04944008 0.9751703 -0.1941612 -0.1065109 0.9964912 -0.04815971 -0.06845515 0.9979813 -0.0468471 -0.04287958 0.9793483 -0.1942521 -0.05606299 0.9849391 0.08710116 0.1493599 0.9921855 0.09448802 0.08148676 0.975108 -0.194222 0.1069686 0.988329 -0.07443594 0.1329104 0.9895269 0.09064227 0.1123415 0.9606755 -0.1817708 0.2099093 0.9859921 -0.03869867 0.1622414 0.9851268 0.09244239 0.1448438 0.9750515 -0.05996978 0.2137246 0.9635523 0.08789527 0.2526685 0.9812554 0.09973692 0.1648955 0.9409747 -0.1625464 0.2968929 0.9666169 -0.03271597 0.2541287 0.9756811 0.09277957 0.198591 0.9582333 -0.03558504 0.283765 0.9688341 0.08856689 0.231336 0.9177376 -0.1427375 0.3706535 0.9423698 -0.03183144 0.3330553 0.9608128 0.08978813 0.2622535 0.8940168 -0.1241198 0.4304977 0.9304481 -0.01583957 0.3660814 0.9465707 0.08703953 0.3105286 0.9571295 0.1020242 0.2710982 0.9241126 -0.02035611 0.3815779 0.9487065 0.09350949 0.3020137 0.8556409 -0.08472174 0.510589 0.9147743 0.003692746 0.4039486 0.9023787 0.006531 0.4308944 0.8746702 -0.1225026 0.4689831 0.9410418 0.08853739 0.3264988 0.8372054 -0.07141512 0.5422058 0.8848695 0.02493405 0.4651714 0.9362936 0.08670455 0.3403483 0.8076517 -0.02624619 0.5890755 0.8711116 0.04129254 0.489346 0.9340399 0.08609461 0.346637 0.8680106 0.04956221 0.4940659 0.932787 0.08585029 0.3500545 0.78083 0.02011203 0.6244198 0.8556081 0.06836318 0.5130902 0.8952252 0.08078879 0.4382294 0.8574263 0.06915563 0.509939 0.9212977 0.08473634 0.3795133 0.8548482 0.07727509 0.513092 0.8607676 0.07053017 0.504088 0.8951924 0.08182227 0.4381047 0.7596551 0.04657238 0.6486565 0.762695 0.06024408 0.6439465 -0.1872885 -0.02449858 0.9819995 0.8951902 0.08185255 0.4381036 0.7799443 0.07501578 0.6213369 0.8916059 0.08649015 0.4444754 0.6629397 0.05282884 0.7468067 0.8546006 0.0819137 0.5127847 0.9360169 0.08584982 0.3413242 0.9338887 0.09079474 0.345844 0.8468216 0.08319586 -0.5253303 0.8336287 0.07742691 0.5468714 0.9304888 0.08856564 0.3554529 0.9227166 0.08841401 0.3752027 0.9661436 0.08774244 0.2426269 0.9244311 0.05719321 0.377036 0.9441396 0.07663351 0.3205118 0.9524474 0.08432489 0.2928025 0.9592126 0.08932912 0.2682011 0.9951934 -0.03466951 0.09158742 0.9754525 0.07321536 0.2076827 0.9916197 0.06994926 0.1086167 -0.072483 0.9899194 -0.1216799 -0.07486408 0.971311 -0.2257216 -0.0781297 0.9935597 -0.08206671 -0.06818026 0.9260191 -0.3712683 -0.0724225 0.921075 -0.382591 -0.07629817 0.9892216 0.1249765 -0.07812851 0.9934839 0.08298105 0.9950336 0.07812798 -0.0616784 -0.06732511 0.9706292 0.2309685 0.9893652 0.09250307 -0.1122489 0.9852494 0.08639967 -0.1477126 0.9952042 -0.03427314 -0.09161895 0.9919677 0.09283959 -0.08591169 -0.06595236 0.9234857 0.3779214 0.9695792 0.09323459 -0.2263267 0.9778224 0.08716166 -0.1904373 0.9748162 0.09329742 -0.2025564 0.9805099 0.08996957 -0.1746594 0.9854325 0.0890243 -0.1449049 0.9916174 0.06988805 -0.1086775 0.9467765 0.08994102 -0.3090711 0.9459059 0.0920453 -0.3111107 0.9447773 0.09418165 -0.3138881 0.9439716 0.09549582 -0.3159085 0.944353 0.09506702 -0.3148962 0.9476474 0.09222859 -0.3057094 0.9537365 0.088934 -0.2871891 0.9611055 0.08734548 -0.2620059 0.9655856 0.08996951 -0.2440286 0.7570871 0.04126179 -0.6520098 0.8580862 0.07162922 -0.5084854 0.858472 0.06689786 -0.5084788 0.7785165 0.01941025 -0.6273239 0.867994 0.04947143 -0.4941044 0.8711451 0.04129266 -0.4892866 0.8058046 -0.02716225 -0.5915582 0.8848701 0.02490353 -0.4651718 0.836714 -0.07092654 -0.5430279 0.9021388 5.18821e-4 -0.4314457 0.9111378 0.005554378 -0.4120644 0.8748813 -0.126195 -0.4676085 0.9240962 -0.02206546 -0.3815227 0.9291607 -0.01702976 -0.3692837 0.8557955 -0.08066284 -0.510987 0.8931984 -0.1256465 -0.4317517 0.9420929 -0.032045 -0.3338175 0.9171782 -0.1446328 -0.3713027 0.9580358 -0.03647071 -0.2843191 0.9644238 -0.03656148 -0.2618206 0.9406538 -0.1637949 -0.2972236 0.9720194 -0.09482145 -0.2149124 0.9834585 -0.04126226 -0.1763718 0.9604331 -0.1802452 -0.2123207 0.9881917 -0.07455915 -0.1338586 0.8565899 0.08224993 0.5094004 0.9342032 0.08791309 0.3457396 0.9338473 0.09132277 0.3458173 0.9341595 0.08963459 0.3454153 0.9315609 0.09110999 0.351985 0.8608862 0.08411097 0.5017971 0.00341022 -0.04349273 -0.9990479 0.9332854 0.0909565 0.347427 0.9358485 0.09271806 0.3399867 0.9331882 0.09088641 0.3477062 0.9340218 0.08963602 0.3457871 0.9348305 0.09124052 0.3431721 0.003421187 -0.04348391 -0.9990484 0.00342226 -0.04348528 -0.9990482 -0.003173947 0.05374383 -0.9985498 -0.004150569 0.0529204 -0.9985901 -0.01251274 0.152442 -0.9882333 0.003423571 -0.04348474 -0.9990483 -0.0107733 0.1528716 -0.9881873 -0.0283221 0.3443515 -0.9384135 -0.02551424 0.3431605 -0.9389303 -0.04001063 0.5002705 -0.8649443 -0.03500539 0.5189165 -0.8541079 -0.01702982 0.6189645 -0.7852343 -0.04297095 0.6722763 -0.7390522 -0.04907476 0.6759988 -0.7352669 -0.03256386 0.7611157 -0.6477982 -0.038271 0.7666419 -0.6409334 -0.06347584 0.8065233 -0.5877848 -0.058627 0.7449389 -0.6645518 -0.06347751 0.8065119 -0.5878004 -0.0689122 0.8737325 -0.4815005 -0.06876063 0.8739591 -0.4811109 -0.06347137 0.8065261 -0.5877814 0.8395489 0.09009224 0.5357621 0.8661912 0.08234035 0.4928824 0.8736088 0.09427344 0.47741 0.7814441 0.07577913 0.6193566 0.8739557 0.09564805 0.4765006 0.8354364 0.1190865 0.53653 0.8728439 0.110723 0.4752726 0.8777124 0.1229938 0.4631345 0.9359943 0.09192389 0.3398011 0.9433128 0.09564661 0.3178252 0.8149214 0.1493605 0.5599952 0.8877141 0.1506431 0.4350522 0.9354554 0.09148818 0.3413991 0.9450059 0.09561759 0.3127639 0.9533466 0.09851473 0.2853509 0.8262428 0.1966954 0.5278578 0.9029452 0.1743875 0.3927839 0.9408618 0.09360092 0.3256043 0.9561683 0.09836351 0.2758025 0.9639523 0.098028 0.2473589 0.8607828 0.2826651 0.4232652 0.9189859 0.2020658 0.338577 0.9508886 0.09497588 0.2946024 0.8419317 0.2402467 0.4831486 0.9633207 0.09561485 0.2507411 0.9706094 0.0979368 0.2198314 0.9183714 0.2248014 0.325666 0.9708572 0.09445798 0.2202595 0.9777899 0.09134256 0.1886363 0.8791705 0.3253971 0.3481035 0.9335005 0.2390593 0.2672594 0.9818787 0.09149509 0.1659607 0.9815615 0.0979669 0.1641327 0.9367876 0.2450083 0.2497998 0.9874665 0.08996939 0.1296744 0.8968279 0.3578949 0.2600209 0.9429065 0.2765607 0.1855843 0.9905819 0.09073263 0.1025434 0.9899511 0.09848541 0.1014763 0.9532008 0.2555663 0.1615372 0.9939678 0.08746695 0.06616479 0.9103935 0.3810346 0.1612339 0.9456983 0.312425 0.08969587 0.9953764 0.08948159 0.03491365 0.9945376 0.09805899 0.0357688 0.9639415 0.2581904 0.06445604 0.9962812 0.0861541 0.001220703 0.9178366 0.3929356 0.05636906 0.9575271 0.2883415 0.00100708 0.9951362 0.09357154 -0.03079372 0.9947115 0.09793603 -0.03094643 0.9173567 0.3943126 -0.05453842 0.9672695 0.2495539 -0.04596161 0.9931262 0.09772253 -0.06442606 0.9540929 0.2839207 -0.09537267 0.9928036 0.09735459 -0.06973522 0.9904428 0.09827214 -0.09677666 0.9102336 0.3815199 -0.1609885 0.9582719 0.245832 -0.1458817 0.98973 0.09793531 -0.1041307 0.9867733 0.09784412 -0.1292483 0.9452399 0.2679889 -0.186289 0.9857026 0.09744715 -0.1374576 0.9823273 0.09775352 -0.1596163 0.8970575 0.3573825 -0.259934 0.9407526 0.2388123 -0.2407349 0.9806849 0.0974459 -0.1695919 0.9771029 0.09723418 -0.1892496 0.9327203 0.2425951 -0.2667967 0.9749884 0.0968976 -0.2000211 0.9714489 0.09695869 -0.2165319 0.8796105 0.324475 -0.3478524 0.9189155 0.2241972 -0.3245458 0.9687055 0.0968064 -0.2285572 0.9653117 0.0966227 -0.2425639 0.9171423 0.2140029 -0.3362336 0.9544313 0.09497618 -0.2829143 0.9593166 0.09512895 -0.265824 0.8597307 0.2864243 -0.4228764 0.8954731 0.2036872 -0.3957771 0.962081 0.09637898 -0.2551693 0.9451242 0.09393864 -0.3129152 0.9549463 0.09155762 -0.2823027 0.9017304 0.1794244 -0.3933054 0.9434848 0.09527927 -0.3174247 0.8421157 0.2407658 -0.4825692 0.8891299 0.1493023 -0.4326165 0.9348723 0.09131419 -0.3430388 0.8259386 0.1960852 -0.5285604 0.8784584 0.1222895 -0.4619048 0.9309835 0.09335774 -0.3529222 0.8148124 0.148661 -0.5603399 0.8734378 0.1091377 -0.4745478 0.8320795 0.1257092 -0.5402231 0.003416955 -0.04348331 0.9990484 0.003493309 -0.04350358 0.9990472 0.01351976 -0.1419425 0.9897826 0.01107853 -0.1409084 0.9899607 0.01788425 -0.238538 0.9709685 0.003423511 -0.04348522 0.9990482 0.02200448 -0.2461088 0.9689925 0.03158694 -0.4308039 0.9018927 0.0372641 -0.4371592 0.8986119 0.04501545 -0.5846518 0.8100345 0.05731576 -0.6058136 0.7935395 0.09589314 -0.6944472 0.7131252 0.07004207 -0.744979 0.6634007 0.06653231 -0.7536157 0.6539394 0.1017209 -0.8253651 0.5553604 0.07974773 -0.865994 0.4936547 0.07706034 -0.8667991 0.4926673 0.07825094 -0.9164277 0.3924757 0.09112954 -0.9495665 0.3000317 0.07495558 -0.9518694 0.2971978 0.08209592 -0.9765146 0.1991971 0.08642923 -0.9916473 0.09573745 0.07806849 -0.9942288 0.07358211 0.07846552 -0.9917605 -0.1012635 0.07806849 -0.9918788 -0.1004086 0.07510781 -0.9532376 -0.2927405 0.07587188 -0.9509627 -0.2998558 0.0683636 -0.8775877 -0.4745169 0.07022339 -0.8700865 -0.4878711 0.06079399 -0.7789389 -0.6241461 0.06848609 -0.7549953 -0.652144 0.08533209 -0.67991 -0.7283137 0.0629611 -0.6259796 -0.7772938 0.06088542 -0.6128523 -0.7878484 0.05652141 -0.5273097 -0.8477911 0.05761975 -0.4336435 -0.8992404 0.03460913 -0.4376805 -0.8984643 0.04864794 -0.3402306 -0.9390829 0.03189247 -0.2316402 -0.9722786 0.01818948 -0.2171143 -0.9759768 0.0125432 -0.1437128 -0.98954 0.01135301 -0.1443853 -0.9894564 -0.07291013 0.9269874 0.3679383 -0.06878972 0.873727 0.481528 -0.06347954 0.8065271 0.5877792 -0.06875997 0.8736758 0.481625 -0.06348198 0.8065198 0.587789 -0.04480129 0.7535653 0.6558448 -0.06106787 0.7758767 0.6279221 -0.05469018 0.7482978 0.6611047 -0.06348693 0.8065258 0.5877803 -0.037813 0.677918 0.7341645 -0.0533787 0.6773511 0.7337208 -0.04120016 0.6024991 0.7970556 -0.03085494 0.5151347 0.8565537 -0.04001033 0.5001755 0.8649993 -0.02548372 0.3431607 0.9389309 -0.02832156 0.3443148 0.938427 -0.01120048 0.1522907 0.9882723 -0.01199418 0.1519567 0.9883143 -0.003234982 0.0541411 0.998528 0.003423154 -0.04348427 0.9990483 -0.004303157 0.05475109 0.9984909 0.8860023 -0.4574214 0.07593172 0.8769875 -0.4551265 -0.1541198 0.8903245 -0.4506098 -0.06537121 0.8849133 -0.4423498 0.1457917 0.8620885 -0.4180886 0.2863659 0.8294874 -0.3879019 0.4018492 0.7915155 -0.3558234 0.4968832 0.7560606 -0.3221337 0.5697388 0.73045 -0.3063226 0.6104174 0.6770116 -0.2120792 0.7047537 0.7022457 -0.24397 0.6688271 0.6637051 -0.3880845 0.6394421 0.6352494 -0.3886573 0.6673858 0.58618 -0.2965844 0.7539435 0.6085324 -0.3178933 0.7270709 0.8199301 -0.5665288 0.08221882 0.8403472 -0.533049 -0.09836345 0.8179056 -0.5723202 -0.05899292 0.8327544 -0.5047311 0.2275227 0.8277305 -0.5497654 0.1123396 0.7969238 -0.4779651 0.3694074 0.7928335 -0.5340898 0.2935358 0.7471496 -0.4790046 0.4607844 0.7076334 -0.4120181 0.5740175 0.7435654 -0.4478666 0.4965139 0.5499879 -0.4737812 0.6877824 0.5532003 -0.4782133 0.6821155 0.531921 -0.4561721 0.7134194 0.4203464 -0.2650322 0.8677942 0.4628217 -0.3861578 0.7979212 0.449632 -0.3756241 0.8103935 0.4707639 -0.3295195 0.8184121 0.5113208 -0.4384712 0.7391171 0.7302352 -0.6791154 0.07455861 0.7290065 -0.6798099 0.08005124 0.7241908 -0.674536 0.1433488 0.7239453 -0.6745653 -0.1444472 0.7271419 -0.6832558 -0.06653106 0.7296648 -0.6798872 -0.07309466 0.7256392 -0.6761054 -0.1277865 0.7240695 -0.6747503 0.1429522 0.7114884 -0.6591789 0.2434497 0.703369 -0.6519141 0.2833374 0.6908929 -0.6411467 0.3340628 0.6721926 -0.6173185 0.408748 0.6739539 -0.6168527 0.4065453 0.6488393 -0.5839859 0.4878197 0.6364108 -0.5716802 0.5178448 0.6141057 -0.5514499 0.5646037 0.584237 -0.5171244 0.6254995 0.595005 -0.5240475 0.6093796 0.622102 -0.1240298 0.7730497 0.5672999 -0.03747814 0.8226581 0.5161353 0.01214647 0.8564209 0.6337015 0.05459886 0.7716485 0.5119004 0.03515821 0.8583251 0.755002 0.06714111 0.6522761 0.4272032 -0.01980674 0.9039387 0.3646152 0.008850574 0.9311163 0.3389399 0.02551352 0.940462 0.3570111 0.02023404 0.933881 0.4921766 0.04074257 0.8695415 0.572794 -0.2183075 0.7900943 0.509305 -0.1188418 0.8523411 0.5146095 -0.1857074 0.8370722 0.4762833 -0.1026667 0.8732777 0.435786 -0.06793606 0.8974828 0.2421662 -0.06500494 0.9680548 0.2207438 -0.06506645 0.9731591 0.2273393 -0.01895254 0.9736312 0.2580705 0.01928812 0.9659336 0.1871112 0.02887082 0.9819145 0.1933975 0.01910471 0.9809345 0.1919336 0.01181077 0.9813368 0.1954467 0.03549414 0.9800719 0.383539 -0.285205 0.8783827 0.3973618 -0.2844707 0.8724564 0.3284808 -0.1406031 0.9339867 0.3430935 -0.2633782 0.9016201 0.368732 -0.1654746 0.9146884 0.3429114 -0.1814659 0.9216735 0.2790016 -0.1158183 0.9532808 0.1746304 -0.1524125 0.9727666 0.2795541 -0.001983702 0.9601279 0.2912474 0.04077398 0.9557784 0.2977439 0.01391667 0.9545444 0.2567611 0.01941043 0.9662801 0.1814969 0.02078348 0.9831719 0.2874854 0.02716153 0.9573998 0.2565721 0.02139371 0.9662883 0.3380658 0.02997022 0.9406452 0.1597665 0.01678538 0.9870122 0.1734717 0.01193302 0.9847666 0.1296134 0.02096641 0.991343 0.1657183 0.03415077 0.9855817 0.3084902 0.02633821 0.9508628 0.4930697 0.04733538 0.8687012 0.1713628 0.01351976 0.9851153 0.3811203 0.04080379 0.9236246 0.3406904 0.0352196 0.9395156 0.6319685 0.06122219 0.7725721 0.5694203 0.0523703 0.8203766 0.7545218 0.07144498 0.6523746 0.1663292 0.07352054 0.9833257 0.1637058 0.06851595 0.9841271 0.3031737 0.0740996 0.95005 0.04016339 0.01696872 0.9990491 0.05578857 0.01236015 0.9983662 0.03341835 0.01767051 0.9992853 0.01739591 0.05591124 0.9982842 0.01730412 0.05832141 0.9981479 0.01730418 0.06231951 0.9979063 0.01728552 0.05455893 0.9983609 0.01733571 0.0547226 0.9983512 0.01733487 0.04898327 0.9986491 0.01730442 0.05014324 0.9985921 0.01754826 0.04461848 0.9988501 0.0177924 0.04171913 0.9989711 0.01831144 0.03817933 0.9991032 0.01971548 0.03189277 0.9992969 0.02569663 0.02081364 0.9994532 0.02240061 0.02551352 0.9994235 0.3466388 0.06702047 0.9356013 0.5616355 0.07266497 0.8241878 0.1483241 0.05844455 0.9872103 0.1995625 0.05966424 0.978067 0.6734691 0.08594226 0.7342025 0.4441527 0.05749905 0.8941042 0.56918 0.09112983 0.8171472 0.7641005 0.09442532 0.6381492 0.1013855 0.01385581 0.9947507 0.09253454 0.009735643 0.9956619 0.1260144 0.02792519 0.9916353 0.1272954 0.02548348 0.9915375 0.08374434 0.01416081 0.9963867 -0.9003417 -0.1764304 0.3978154 0.05963444 0.01556473 0.998099 0.05569732 0.01831144 0.9982798 0.05255323 0.02273643 0.9983593 0.05142438 0.02835208 0.9982744 0.01734364 0.06670773 0.9976218 0.01733481 0.05765044 0.9981864 0.01734584 0.05805015 0.998163 0.0173062 0.06068742 0.9980068 0.01730173 0.06452101 0.9977664 0.2479407 0.2421725 0.9380182 0.1254646 0.1665434 0.9780194 0.2004529 0.1739009 0.9641459 0.01730394 0.06886136 0.9974762 0.01794517 0.2535824 0.9671474 0.01672458 0.1655983 0.9860514 0.01721262 0.1640084 0.9863088 0.1339169 0.2532764 0.9580801 0.4673963 0.2237642 0.8552604 0.319567 0.1749973 0.9312642 0.4492756 0.166361 0.8777675 0.6608684 0.1911433 0.7257528 0.5579745 0.1613221 0.8140269 0.6667932 0.1475625 0.7304877 0.7575147 0.1364509 0.6383986 -0.01644963 0.003448605 0.9998589 -0.008697867 0.008758902 0.9999238 -0.01055961 0.005005121 0.9999318 0.01730668 0.05015343 0.9985916 -0.02539193 -0.01028496 0.9996247 -0.02368289 0.00137335 0.9997187 -0.04645049 -0.01278758 0.9988388 -0.04904341 -0.0144658 0.998692 -0.03598153 -0.02536106 0.9990307 -0.06503701 -0.02148568 0.9976516 -0.07220834 -0.02557504 0.9970617 -0.04077374 -0.01327586 0.9990803 -0.07272607 -0.02591037 0.9970154 0.01800632 0.1593716 0.9870545 0.01678538 -3.05189e-5 0.9998592 0.01638865 0.03326565 0.9993123 0.01672446 0.03198403 0.9993485 0.01678544 -0.01071214 0.9998018 -0.02893191 -0.02191251 0.9993413 -0.03592061 -0.02975583 0.9989116 -0.03671377 -0.04675441 0.9982315 -0.05368363 -0.03640967 0.9978941 -0.04718184 -0.009033501 0.9988455 -0.006134271 0.01135295 0.9999168 -0.1059938 -0.03161805 0.9938641 -0.1840304 -0.04626697 0.9818311 -0.1179858 -0.05435401 0.9915266 -0.0599097 -0.06247329 0.9962469 -0.001739561 0.004059016 0.9999904 -0.0203253 -0.02615433 0.9994513 -0.0145272 -0.01260447 0.9998151 -0.1469504 -0.1628815 0.975641 -0.0484941 -0.06634753 0.9966174 -0.09042781 -0.1112418 0.9896708 -0.0137335 -0.08877974 0.9959567 -0.1048949 -0.1388934 0.9847364 -0.179026 -0.2068901 0.9618452 -0.06192249 -0.1056864 0.9924697 -0.1143856 -0.1227173 0.9858278 -0.09113073 -0.09561711 0.9912379 -0.05896317 -0.1319957 0.9894951 -0.09686672 -0.1762768 0.9795629 -0.1061756 -0.1478646 0.9832919 -0.1162798 -0.1899237 0.9748888 -0.04110866 -0.09033536 0.9950626 -0.06018352 -0.07318466 0.9955009 -0.08478152 0.02148526 0.996168 0.07748794 0.03296059 0.9964483 0.01898276 0.02777218 0.9994341 -0.002716124 0.03558468 0.9993631 0.1008965 0.03656202 0.994225 0.08105736 0.03317368 0.9961573 -0.004944086 0.03396779 0.9994108 -0.2200396 0.01022374 0.9754375 -0.03515797 0.01931858 0.9991951 -0.06393808 0.01355057 0.9978619 -0.2150656 -0.0218209 0.9763559 -0.06299179 -0.00238049 0.9980112 -0.0712921 -0.01159715 0.997388 0.5439409 0.7839426 -0.2992697 0.5812408 0.749677 -0.316455 0.9025626 -0.1962053 -0.3832549 -0.2194297 -0.04443526 0.9746159 -0.2254744 -0.0737949 0.9714503 -0.07876861 -0.02923685 0.9964641 -0.2478476 -0.1077027 0.9627937 -0.08084428 -0.03524917 0.9961032 -0.09698987 -0.04791504 0.9941314 -0.2187007 -0.09659332 0.9709994 -0.09640985 -0.04721307 0.9942214 -0.2388097 -0.1289114 0.9624718 -0.09375381 -0.05304169 0.9941815 -0.07733422 -0.05386537 0.9955491 -0.1883955 -0.1289134 0.9735957 -0.05914646 -0.05276793 0.9968538 -0.1379465 -0.1202454 0.9831134 -0.04324549 -0.04397797 0.9980961 -0.09601372 -0.09528124 0.9908093 -0.03100693 -0.02826023 0.9991196 0.08264607 0.03497505 0.9959651 -0.03613454 0.07403928 0.9966005 0.08124053 0.02655118 0.9963409 0.08160758 0.02841311 0.9962595 -0.04348939 0.04455757 0.9980598 0.09918808 0.07568812 0.9921861 0.3415663 0.001403808 0.9398567 0.1392563 0.006256282 0.9902367 0.165811 0.01266545 0.9860763 0.1590681 0.01675522 0.9871255 0.1449647 0.2225133 0.9640919 0.115363 0.02252322 0.993068 0.3009823 -0.08844518 0.9495195 0.2986915 -0.06402927 0.9521995 0.3090035 -0.03576809 0.9503881 0.1695921 -0.03024393 0.9850503 0.2400958 -0.07077437 0.9681658 0.2241607 -0.04986768 0.9732756 0.3986788 -0.1667901 0.9017962 0.1799685 -0.04370272 0.9827011 0.2514472 -0.08972626 0.963703 0.1559507 -0.01525932 0.987647 0.2143358 -0.03524959 0.9761238 0.1938862 -0.01522886 0.980906 0.3894627 -0.232408 0.8912382 0.4320978 -0.2971397 0.851469 0.4422017 -0.3252192 0.8358769 0.3848425 -0.2156461 0.8974369 0.3836936 -0.198439 0.9018875 0.3877435 -0.1820762 0.9036058 0.2137582 -0.06757003 0.974547 0.2976207 -0.1536323 0.9422416 0.293507 -0.143259 0.9451617 0.4377337 -0.3020768 0.8468406 0.4410063 -0.2985414 0.8463962 0.3042762 -0.1573263 0.9395023 0.2066417 -0.06491315 0.976261 0.2838594 -0.130073 0.9500027 0.1987119 -0.06018424 0.9782083 0.2734553 -0.115486 0.9549268 0.1901615 -0.05304133 0.980319 0.2624301 -0.1000402 0.9597513 0.5044831 -0.4246447 0.7517805 0.4857849 -0.4078371 0.773099 0.4690837 -0.3940058 0.7903923 0.4270889 -0.314045 0.8479214 0.4258346 -0.3147752 0.8482816 0.4582716 -0.3782817 0.8042949 0.4415531 -0.3637899 0.8201755 0.431263 -0.3133989 0.8460458 0.4349919 -0.3052238 0.8471249 0.4170095 -0.3211193 0.8502856 0.4092032 -0.3202699 0.8543887 0.4255596 -0.3510622 0.8340591 0.4196981 -0.3197787 0.8494676 0.4057881 -0.3438333 0.8468263 0.4059086 -0.3449002 0.8463346 0.4133599 -0.3370605 0.8458864 0.3956494 -0.3232582 0.8596311 0.404134 -0.3303083 0.8529785 0.4063057 -0.3183181 0.8564984 0.2488803 -0.02136307 0.9682987 0.3251199 -0.1684043 0.9305575 0.3224676 -0.1658422 0.9319394 0.2508023 -0.02377402 0.9677464 0.2096329 -0.006592035 0.977758 0.3088245 -0.173441 0.9351715 0.2346886 -0.03326535 0.9715012 0.2849858 -0.1076708 0.9524654 0.3846682 -0.3111162 0.8690438 0.3268235 -0.1672112 0.9301757 0.2481179 -0.02438449 0.968423 0.3257905 -0.1677935 0.9304332 0.3251215 -0.1697175 0.9303182 0.2458927 -0.03631776 0.9686164 0.323628 -0.1721906 0.9303846 0.2400947 -0.04855602 0.9695344 0.3212499 -0.173138 0.9310327 0.2336512 -0.05804651 0.9705863 0.31755 -0.1743243 0.93208 0.314102 -0.1693807 0.9341574 0.2273679 -0.06311368 0.9717615 0.3095523 -0.163886 0.936653 0.2210776 -0.06677496 0.9729676 -0.1812515 0.07852506 0.9802967 0.275951 -0.03860628 -0.9603962 -0.2157078 0.04443556 0.9754464 -0.4615764 0.1670024 0.8712391 -0.2912422 0.03671425 0.9559446 -0.2908464 0.0365923 0.9560698 -0.1399298 0.1404487 0.98015 -0.2484833 0.092197 0.9642384 -0.1666945 0.0564906 0.9843891 -0.2155572 0.06024491 0.974631 -0.3900685 0.219465 0.8942492 -0.342023 0.1068459 0.9335975 -0.3350735 0.0914669 0.9377418 -0.3600006 0.06250262 0.9308561 -0.113438 0.07831096 0.9904541 -0.1082515 0.0729103 0.9914463 -0.1539072 0.05761981 0.9864039 -0.4840331 0.1265017 0.8658577 -0.4631591 0.05877989 0.8843238 0.04391694 0.07184195 0.9964488 -0.02743631 0.03860616 0.9988778 -0.346823 0.01129215 0.9378626 -0.3976613 0.004669368 0.9175204 -0.1778977 0.03134346 0.9835497 0.02765011 0.03408956 0.9990363 0.03039693 0.03149563 0.9990416 -0.08447706 0.05945134 0.9946503 -0.025361 0.03766006 0.9989688 -0.08612531 0.04834246 0.9951108 -0.1955062 0.0832259 0.9771647 -0.2935962 0.6745083 0.6773772 -0.3704431 0.7494621 0.5487062 -0.3556977 0.7809481 0.5134194 -0.475125 0.7652419 0.4343512 -0.4220508 0.8184959 0.3897919 -0.4326983 0.8062204 0.4034611 -0.2840704 0.7203695 0.6327496 -0.2671049 0.724986 0.6348625 -0.2710394 0.7267798 0.6311331 -0.3433424 0.7963408 0.4979533 -0.3394031 0.7956944 0.5016733 -0.422533 0.8358798 0.3503865 -0.5151886 0.8557789 -0.04715156 -0.4231459 0.8417445 0.3352817 -0.4185638 0.8411866 0.3423587 -0.4497884 0.8151308 0.3650373 -0.3814923 0.7216614 0.5776404 -0.4572682 0.7748809 0.4364236 -0.3091578 0.6250298 0.71677 -0.3946218 0.684591 0.6128694 -0.4622147 0.7218423 0.5150741 -0.3214032 0.5711154 0.7553325 -0.3992512 0.6583281 0.6381244 -0.5132461 0.6401156 0.5716909 -0.4547355 0.7141788 0.532132 -0.4051487 0.6241884 0.6680147 -0.4811413 0.6819602 0.550848 -0.3281771 0.5193213 0.7890534 -0.4109113 0.5718088 0.710061 -0.4976471 0.6376694 0.587984 -0.3304023 0.4693568 0.8188642 -0.4127772 0.5268899 0.7429684 -0.4960992 0.541299 0.6788823 -0.3274462 0.4177541 0.8475025 -0.4099639 0.4971266 0.7647187 -0.5039916 0.4280296 0.7501887 -0.4351454 0.5220036 0.7335945 -0.5525245 0.5021368 0.6652634 -0.4072809 0.4683502 0.784073 -0.4598675 0.5089734 0.7276455 -0.3203576 0.3690658 0.8724457 -0.3987638 0.4193947 0.8155339 -0.4779919 0.479823 0.7357267 -0.3091228 0.3169966 0.8966361 -0.3896993 0.3712047 0.8428176 -0.4817498 0.4446076 0.7551433 -0.3765432 0.3468482 0.8590178 -0.4757627 0.4067285 0.7798859 -0.2917055 0.2713795 0.9172028 -0.3644351 0.3076685 0.8789352 -0.4348396 0.2922533 0.8517645 -0.2729032 0.2256593 0.9352015 -0.3497546 0.2798343 0.8940718 -0.4664903 0.2395779 0.851463 -0.3468143 0.2689001 0.8985615 -0.4829962 0.3162701 0.8165096 -0.3422079 0.259807 0.9029918 -0.3365698 0.2524273 0.9071941 -0.2488517 0.1778646 0.9520699 -0.3193491 0.2208343 0.9215468 -0.3550953 0.2419286 0.9029828 -0.3114143 0.1981283 0.9293904 -0.3670558 0.2238897 0.902853 -0.2230956 0.131599 0.9658728 -0.2845308 0.1567773 0.9457606 -0.3709571 0.1982812 0.9072351 -0.2808662 0.1394107 0.9495677 -0.3657057 0.1651672 0.9159581 -0.09839481 0.08563762 0.9914559 -0.1120653 0.1124621 0.9873164 -0.1246713 0.1404803 0.9822028 -0.1355369 0.170207 0.9760428 -0.1441418 0.2019146 0.9687381 -0.1499686 0.2354817 0.9602384 -0.1531764 0.2714388 0.9501884 -0.1535136 0.3096213 0.938386 -0.1505506 0.3499928 0.9245754 -0.1438983 0.392264 0.9085276 -0.1334005 0.4364282 0.8897948 -0.1186586 0.4820202 0.868088 -0.1131029 0.5213235 0.8458307 -0.09903621 0.5250294 0.8453024 -0.1026353 0.527307 0.8434532 0.06741726 0.2348465 0.9696918 0.07156628 0.2631322 0.9621018 0.08035629 0.2655756 0.9607354 0.07751762 0.267863 0.9603335 0.02896225 0.03665298 0.9989084 0.02877914 0.0421769 0.9986957 0.02807778 0.05011272 0.9983488 0.02758926 0.06039738 0.9977931 0.02777242 0.07309335 0.9969384 0.02899301 0.08819973 0.9956809 0.031282 0.1059012 0.9938845 0.03482228 0.126288 0.9913823 0.03994935 0.1494516 0.9879617 0.04699873 0.1752383 0.9834036 0.05606424 0.203748 0.9774168 -0.3415724 0.7954559 0.5005781 -0.5165446 0.8543968 -0.05646127 -0.3459646 0.7831814 0.516658 -0.2765947 0.718725 0.6379105 -0.3483806 0.7914328 0.5022601 -0.515524 0.8555036 -0.04846388 0.04290997 0.269454 0.9620568 0.06485378 0.2560886 0.9644754 -0.1259553 0.5165784 0.846925 -0.1124346 0.5165464 0.8488453 -0.2829485 0.7108353 0.643936 -0.4428322 0.8295702 0.3401659 -0.4402737 0.8246358 0.3551549 -0.4424354 0.8284105 0.3434925 -0.3495403 0.6785409 0.6460682 -0.3897882 0.724978 0.5678664 -0.3966869 0.7443296 0.5372272 -0.440173 0.8246796 0.3551781 -0.3714808 0.7080476 0.6005586 -0.4041686 0.7247751 0.5579865 -0.4058147 0.6861646 0.6037321 -0.4081605 0.7397183 0.5349972 -0.3789013 0.7415967 0.5535957 -0.3264355 0.6823223 0.6541224 -0.3750218 0.7347229 0.5652794 -0.4296481 0.8153792 0.38802 -0.4675567 0.8556409 0.2219673 -0.4594407 0.848656 0.2621015 -0.3756335 0.7514503 0.5424224 -0.4735639 0.8596602 0.191629 -0.4300163 0.8288115 0.3579909 -0.438104 0.8138877 0.3816434 -0.3673639 0.7518187 0.5475513 -0.3099547 0.6912942 0.6527177 -0.3570435 0.758584 0.5450415 -0.2941783 0.6992037 0.6515931 -0.3587588 0.7674174 0.5313782 -0.5059138 0.8623759 0.01895231 -0.3498403 0.7701187 0.5334126 -0.4291638 0.8500263 0.3054076 -0.1510394 0.5122643 0.8454422 -0.1792083 0.5099137 0.8413515 -0.2123828 0.5100057 0.8335393 -0.2529131 0.5132728 0.8201134 -0.3320237 0.6360304 0.6965815 -0.3738036 0.6191504 0.6905966 -0.2839241 0.5438902 0.7896648 -0.3821268 0.6441009 0.6626563 -0.3280565 0.5188354 0.7894232 0.006988704 0.2772005 0.9607867 -0.03360116 0.2867853 0.9574055 -0.08160781 0.2989947 0.9507588 -0.1402655 0.3148955 0.9387047 -0.2327099 0.4493056 0.8625374 -0.2837972 0.4260772 0.8590212 -0.1748471 0.3381274 0.9247153 -0.300794 0.4436528 0.8442128 -0.2287721 0.3081527 0.9234205 0.1632462 0.01718217 0.9864357 0.1178955 0.03875929 0.9922693 0.05450695 0.07052946 0.9960194 -0.01886075 0.1015979 0.9946467 -0.1167057 0.2302069 0.9661184 -0.1760981 0.202345 0.9633514 -0.06412023 0.1129506 0.9915296 -0.1954432 0.2085052 0.9582942 -0.1149662 0.07892286 0.9902293 0.2546502 -0.1188713 0.9596995 0.2887098 -0.1332154 0.9481036 0.2335627 -0.1133174 0.9657162 0.1522914 -0.05960416 0.9865368 0.1865037 -0.03564655 0.9818074 0.08862632 -0.03003036 0.9956122 0.1321769 -0.0260325 0.9908843 -0.04126119 0.0784024 0.9960677 0.02514743 0.1120344 0.9933862 0.05298167 -0.007904469 0.9985643 -0.03415066 0.04165828 0.9985482 -0.09061223 0.02490383 0.9955748 0.07809752 -0.1146284 0.9903339 0.07062 -0.1091039 0.9915186 0.03341853 -0.09488427 0.9949272 -0.1234493 0.09949195 0.9873509 -0.03439497 -0.0609771 0.9975464 -0.05005097 -0.05435413 0.9972665 0.04025501 -0.09506779 0.9946566 0.4127725 -0.3303096 0.8488312 0.367603 -0.2986603 0.8807213 0.3584495 -0.2851421 0.8889365 0.3446845 -0.2749785 0.8975408 0.3205157 -0.2593852 0.9110375 0.3013773 -0.2429025 0.9220467 0.2836115 -0.2316074 0.9305496 0.2597492 -0.2175716 0.9408469 0.2451281 -0.2060639 0.9473384 0.2136616 -0.2050553 0.9551445 0.2022799 -0.1831445 0.9620504 0.2233683 -0.193948 0.9552438 0.1667269 -0.1626373 0.9724975 0.1536307 -0.1542411 0.9760161 0.12406 -0.1356572 0.982958 -0.4240916 0.7288846 0.5374696 -0.4048057 0.6481959 0.6449608 -0.4178723 0.711103 0.5654338 -0.4155805 0.7220852 0.5530696 -0.4320368 0.7276811 0.5327518 -0.4300096 0.6529188 0.6235293 -0.3433137 0.4546793 0.8218287 -0.4503734 0.735271 0.5064983 -0.4560183 0.6582693 0.5989399 -0.386375 0.4651455 0.7964636 -0.4482662 0.7244651 0.5236486 -0.4708802 0.7435385 0.4747867 -0.481903 0.665081 0.5704706 -0.4306245 0.4747856 0.7675554 -0.4719552 0.7152881 0.5153846 -0.4847978 0.7398775 0.4664252 -0.5125749 0.6702996 0.5366243 -0.4767781 0.4834314 0.7341504 -0.4911715 0.7219861 0.4873261 -0.5049131 0.7516626 0.4243419 -0.543309 0.6770762 0.49637 -0.5254145 0.4902566 0.6954051 -0.5008267 0.7462655 0.4384752 -0.5284444 0.745926 0.4053899 -0.5755625 0.6810676 0.4526309 -0.576938 0.4949325 0.6497572 -0.5488812 0.7603767 0.3472128 -0.6092244 0.6854614 0.3987334 -0.6307037 0.4976413 0.5954544 -0.5468752 0.7537655 0.3643698 -0.5700023 0.7702065 0.2861456 -0.6423082 0.6880871 0.3376039 -0.6858966 0.4979267 0.5306742 -0.5977511 0.7324022 0.3260072 -0.6007134 0.757339 0.2560883 -0.673869 0.6894339 0.2656716 -0.7412496 0.4956008 0.4526908 -0.6164207 0.7662073 0.1815264 -0.6997236 0.6902626 0.1841859 -0.792955 0.4918811 0.359549 -0.5982968 0.7760096 0.1996255 -0.6259496 0.7704277 0.1209477 -0.7120403 0.6955599 0.09589087 -0.836142 0.4876402 0.2511447 -0.6229329 0.7814205 0.03656232 -0.7198156 0.6925013 0.04803651 -0.8653441 0.4841276 0.1296154 -0.6397713 0.7672189 0.04547339 -0.6530231 0.7560565 -0.04403942 -0.7241583 0.6882067 -0.0443443 -0.6190578 0.785084 -0.02026492 -0.8737128 0.4819337 0.06607472 -0.7176927 0.688913 -0.1015684 -0.8736526 0.4814154 -0.07050013 -0.5069472 0.861972 -0.003021299 -0.5050612 0.8630812 -0.002044737 -0.5071708 0.8609818 0.03857642 -0.5025577 0.8623166 -0.06201475 -0.4933202 0.8695974 -0.02087545 -0.5045197 0.8610498 0.06366389 -0.4986919 0.8624867 0.08615708 -0.5006115 0.8591548 0.1060248 -0.4999334 0.8572205 0.1234498 -0.4938628 0.8575915 0.1436542 -0.4960952 0.8531434 0.1613568 -0.4940774 0.8505737 0.1800335 -0.488764 0.8501716 0.1957497 -0.489003 0.8469583 0.2086572 -0.4864199 0.8423079 0.2321924 -0.4824516 0.8416656 0.2425686 -0.4829648 0.8370475 0.2570929 -0.4804075 0.8322669 0.2766593 -0.47561 0.831646 0.2866356 -0.4718949 0.8242443 0.3129485 -0.4739682 0.822379 0.3147173 -0.4670404 0.8166416 0.339072 -0.4685928 0.8183131 0.3328431 -0.4640475 0.8159973 0.3446861 -0.4568978 0.8124119 0.3622588 -0.4617298 0.8141693 0.3520426 -0.4657763 0.8153374 0.3439151 -0.4582723 0.8117731 0.3619545 -0.4469581 0.8025408 0.3951665 -0.4541273 0.8108981 0.36907 -0.4409418 0.8017094 0.4035251 -0.4499119 0.811868 0.3720883 -0.4467094 0.8067443 0.3868002 -0.4431061 0.8033224 0.3979073 -0.4394792 0.8020191 0.404504 -0.4362981 0.8025859 0.4068168 -0.3533813 0.7605374 0.5447059 -0.4413698 0.8001691 0.4061061 -0.4318755 0.8004546 0.4156394 -0.4396355 0.800866 0.4066132 -0.2555693 0.2251414 0.9402105 -0.3135213 0.2435108 0.9178273 -0.3792564 0.2623086 0.8873324 -0.4406028 0.2714055 0.8556917 -0.5085126 0.2837074 0.8129731 -0.5762442 0.285299 0.7658637 -0.6493501 0.2891663 0.7033686 -0.72093 0.2555392 0.6441736 -0.7956727 0.2474212 0.5528904 -0.8637332 0.2420504 0.4420143 -0.9194449 0.2394518 0.3119038 -0.9566748 0.2410075 0.1633675 -0.967235 0.2427167 0.07446604 -0.8638845 0.4841611 -0.1388942 -0.9673265 0.2388408 -0.08505612 -0.1901927 0.1213425 0.9742191 -0.2534347 0.1483862 0.955904 -0.311567 0.1587591 0.936868 -0.3528322 0.1523212 0.9232052 -0.4576081 0.2046326 0.8652864 -0.390854 0.2185144 0.8941391 -0.5040844 0.1803375 0.8446167 -0.6020539 0.2124752 0.7696658 -0.5257268 0.299975 0.7960065 -0.5408983 0.2156207 0.8129802 -0.6844829 0.2165942 0.6961107 -0.6206953 0.2034091 0.7572067 -0.7604114 0.2055454 0.6160565 -0.835125 0.1945898 0.5144912 -0.900398 0.1797561 0.3961959 -0.951524 0.1582414 0.2637459 -0.9831088 0.1337953 0.1248838 -0.9907416 0.1143856 0.07312375 -0.9568327 0.2337147 -0.1727682 -0.988021 0.127264 -0.0872842 -0.09030449 -0.03976571 0.99512 -0.117896 -0.02539205 0.9927014 -0.04498571 -0.05829221 0.9972855 -0.1785683 -0.005676567 0.9839112 -0.1806434 -0.002990841 0.9835441 -0.2353664 0.01199412 0.9718328 -0.2616712 0.0197764 0.9649545 -0.2967064 0.02945089 0.9545146 -0.3437086 0.03851538 0.9382862 -0.3553656 0.04171973 0.933796 -0.3986072 0.04294008 0.916116 -0.4221768 0.05136436 0.9050571 -0.4592232 -0.01016288 0.8882628 -0.4811962 0.05288976 0.875016 -0.5072256 0.06705021 0.8592011 -0.525089 0.06082546 0.848871 -0.5993466 0.0668382 0.7976944 -0.5619438 0.0597254 0.8250164 -0.615182 0.05969613 0.7861218 -0.6864054 0.06219792 0.7245544 -0.6706904 0.05206578 0.739908 -0.7685158 0.05093729 0.6378001 -0.7481049 0.04043722 0.6623473 -0.8413887 0.03286933 0.53943 -0.8307692 0.02548366 0.5560334 -0.9062163 0.01751816 0.4224513 -0.90096 0.009369373 0.4338012 -0.95689 0.001159667 0.2904485 -0.9545859 -0.00463891 0.2978999 -0.9887416 -0.01046782 0.1492664 -0.9883465 -0.01388597 0.1515861 -0.9969773 -0.0169993 0.07581019 -0.9972385 -0.01428288 0.07287931 -0.989474 -0.01379477 -0.1440522 -0.9970524 -0.01785355 -0.07461869 -0.9972224 -0.01739603 -0.07242256 -0.9774916 0.1872643 -0.09717231 -0.996038 -0.01590019 0.08749699 -0.9988992 -0.01742655 0.04355114 -0.9889962 -0.01257377 -0.1474063 -0.9987087 -0.009064137 -0.04999035 -0.9841189 -0.00689727 0.177377 -0.9965953 -0.04413032 0.06964415 -0.9998366 -0.01214659 0.01339787 -0.9963868 -0.01110893 -0.08420211 -0.9999684 -0.006927847 0.003906428 -0.9935732 -0.04416084 -0.104222 -0.984071 -0.008819818 0.1775569 -0.93826 0.007629811 0.3458466 -0.9657912 -0.001556396 0.2593165 -0.9032825 0.02407979 0.4283702 -0.8611974 0.04486352 0.5062869 -0.7613074 0.06033688 0.6455777 -0.8192902 0.05588078 0.5706496 -0.7018017 0.07431554 0.7084855 -0.5718291 0.07345849 0.8170774 -0.6434922 0.07849472 0.7614175 -0.4997504 0.07126212 0.863233 -0.4132952 0.0555455 0.9089015 -0.4244655 0.06421303 0.9031643 -0.3162959 0.03613412 0.9479722 -0.2660971 0.02285885 0.9636752 -0.213786 0.007232964 0.9768538 -0.3493856 0.04907512 0.935693 -0.1823496 -0.00451672 0.9832234 -0.1076113 -0.03192323 0.9936805 -0.04525983 -0.05279809 0.9975791 -0.05386531 -0.0536822 0.9971043 -0.09601193 -0.03518807 0.994758 0.07394665 -0.1110268 0.9910625 0.0433374 -0.09595274 0.994442 -0.04614436 -0.05563569 0.9973844 0.04355031 -0.09604257 0.9944241 0.001709043 -0.01910513 0.9998161 -3.96753e-4 -1.52597e-4 1 -0.08658176 -0.0127263 0.9961634 0.0874378 -0.01266551 0.9960895 -0.1716394 -0.01916599 0.9849734 -0.1738985 -1.22077e-4 0.9847636 -0.25816 -0.01281791 0.9660171 -0.3401651 -0.01922696 0.9401692 -0.3422747 -1.22077e-4 0.9395999 -0.4221115 -0.0129401 0.9064517 -0.487142 -0.00991857 0.8732665 -0.5000254 1.52596e-4 0.8660107 -0.572655 -3.66226e-4 0.8197965 -0.573661 6.10375e-5 0.8190928 -0.6424002 -3.05193e-4 0.7663694 -0.6428492 -6.10377e-5 0.7659928 -0.7070915 -3.05189e-4 0.707122 -0.7071373 -1.52598e-4 0.7070763 -0.7659928 -1.83113e-4 0.6428492 -0.7745849 -0.009766221 0.6323946 -0.8190751 -0.01260441 0.5735479 -0.8659244 -0.018983 0.4998148 -0.8660449 6.10385e-5 0.4999665 -0.9062877 -0.01263475 0.4224724 -0.9412208 -0.01641947 0.3373928 -0.9397453 -3.05191e-5 0.3418754 -0.9693774 -0.04440522 0.2415279 -0.9823386 -0.0122075 0.1867139 0.08612531 -0.1168887 0.9894037 0.04358059 -0.09607273 0.9944199 -0.9840953 -0.009094715 -0.1774088 -0.987025 -0.01217716 -0.1601043 -0.9567462 -0.002960324 -0.2909089 -0.9641628 0.006042778 -0.2652425 -0.985399 -0.007110893 -0.1701132 -0.9604325 -0.04367262 -0.2750676 -0.9083984 0.0132147 -0.4178968 -0.9404599 0.01529026 -0.3395605 -0.9441906 -0.01214647 -0.3291758 -0.9035732 0.02127164 -0.4279055 -0.9408121 -0.007141411 -0.3388535 -0.8980379 -0.04370397 -0.4377419 -0.8437548 0.03070193 -0.5358501 -0.8617394 0.04010218 -0.5057638 -0.8726042 -0.0121771 -0.4882762 -0.7699936 0.0421772 -0.6366562 -0.8135456 0.06088542 -0.578305 -0.8677402 -0.007080316 -0.4969677 -0.8083004 -0.04394757 -0.5871279 -0.6912295 0.0559417 -0.7204669 -0.7681211 0.0700733 -0.6364589 -0.7745099 -0.01220756 -0.6324442 -0.7028883 0.06369358 -0.7084428 -0.7714625 -0.009644031 -0.6362017 -0.7070498 -0.01269614 -0.7070498 -0.6034835 0.06003093 -0.7951126 -0.6390513 0.07315564 -0.7656774 -0.6427862 -0.01910471 -0.7658073 -0.6427654 -9.15577e-5 -0.7660631 -0.5117384 0.05429279 -0.8574241 -0.5781244 0.07211673 -0.8127556 -0.5735824 -0.01266556 -0.8190501 -0.500511 0.05578863 -0.8639308 -0.5002629 -0.0190742 -0.8656635 -0.4998713 -6.10381e-5 -0.8660997 -0.4123757 0.0418418 -0.9100526 -0.4247328 0.04821997 -0.9040336 -0.4226326 -0.01266551 -0.9062126 -0.3094933 0.01815879 -0.9507282 -0.3459011 0.03701937 -0.9375405 -0.3424525 -0.01910477 -0.939341 -0.341721 -3.0519e-5 -0.9398014 -0.2033157 -0.009064018 -0.9790713 -0.2699075 0.01828068 -0.9627128 -0.2588042 -0.01272654 -0.9658461 -0.180918 -0.01648038 -0.9833602 -0.1693482 -0.01648008 -0.9854185 -0.1733152 0 -0.9848664 -0.08780419 -0.04580956 -0.995084 -0.09494435 -0.04236024 -0.994581 -0.06955301 -0.04483252 -0.9965704 -0.0318005 -0.06302118 -0.9975055 -0.04345965 -0.05685764 -0.9974361 -0.07055985 -0.02447617 -0.9972073 0.09134256 -0.1199997 -0.988563 0.0441001 -0.09567743 -0.994435 0.0466023 -0.09741622 -0.9941521 -0.08737629 0 -0.9961755 0.08746802 -0.01272648 -0.996086 0.0698893 -0.01907455 -0.9973724 0.04379481 0 -0.9990407 0.07403999 -0.1107548 -0.9910861 -0.03112894 -0.0624715 -0.9975613 0.04635912 -0.09763187 -0.9941423 -0.1596449 -0.01773154 -0.9870153 -0.01168876 -0.07330679 -0.997241 -0.0587182 -0.05740588 -0.9966226 -0.2502533 0.008301079 -0.9681448 -0.3411465 0.03155708 -0.9394804 -0.4205514 0.04339796 -0.9062302 -0.4930686 0.04449701 -0.8688519 -0.5540783 0.04071277 -0.8314684 -0.6637419 0.0445587 -0.7466333 -0.5946411 0.02850514 -0.8034858 -0.7438172 0.03515821 -0.6674578 -0.8311944 0.02356088 -0.5554825 -0.9044075 0.009338855 -0.4265676 -0.9577007 -0.004059076 -0.2877375 0.08334827 -0.1170721 -0.9896197 0.04278749 -0.09570729 -0.9944896 -0.01001012 -0.07199388 -0.9973549 0.04196363 -0.09634858 -0.9944627 -0.08014351 -0.04397821 -0.9958127 0.005523979 -0.08429437 -0.9964256 -0.001800596 -0.08231031 -0.9966052 -0.1464934 -0.02261489 -0.9889531 -0.2734175 0.01742619 -0.9617377 -0.1998069 -0.01318413 -0.9797466 -0.3316476 0.02758896 -0.9429998 -0.45486 0.01696872 -0.8904013 -0.3623554 -0.004669427 -0.9320283 -0.5409541 0.283524 -0.7918226 -0.5210916 0.1753656 -0.8352908 -0.5795235 0.2314248 -0.781406 -0.4689345 0.2708009 -0.8406945 -0.5068923 0.2453128 -0.8263666 -0.6195684 0.2860556 -0.7309632 -0.6315006 0.1767969 -0.7549503 -0.6661111 0.2254145 -0.7109743 -0.7046942 0.2507174 -0.6637371 -0.7466903 0.2159866 -0.6291292 -0.784034 0.2415887 -0.5717742 -0.8253416 0.207045 -0.5253034 -0.857123 0.234324 -0.4587294 -0.8940266 0.2002968 -0.4007463 -0.9168856 0.2304803 -0.325883 -0.9463127 0.191875 -0.2601467 0.08041644 -0.1127967 -0.9903587 0.03219765 -0.08975678 -0.9954431 -0.1443567 0.08847564 -0.9855625 -0.08383589 0.01565629 -0.9963567 -0.09467107 0.08633929 -0.9917575 0.02755886 -0.08063191 -0.9963629 -0.2013326 -0.03842318 -0.9787691 -0.1729499 0.1971207 -0.9650036 -0.1717002 0.1213437 -0.9776476 -0.2441533 0.2222405 -0.9439271 -0.2299297 0.1222589 -0.9654974 -0.2642664 0.1395035 -0.9543071 -0.3220972 0.2444874 -0.9145924 -0.3369595 0.1823811 -0.9236859 -0.3914062 0.2598693 -0.8827622 -0.3906688 0.1644037 -0.9057314 -0.4224163 0.1913554 -0.8859726 0 -1 4.67458e-6 0 -1 -4.68701e-6 0 -1 0 0 -1 -9.37528e-6 0 -1 9.99518e-6 0 -1 9.95948e-6 0 -1 -1.87893e-5 0 -1 1.99955e-5 0 -1 -1.99363e-5 0 -1 5.00105e-6 0.1740217 -0.01910513 -0.9845564 0.1748121 -0.01907426 0.9844172 0.1731324 -1.22075e-4 0.9848986 0.1581789 -0.1536621 0.9753807 0.25889 -0.01260417 0.9658247 0.1690781 -0.1592203 0.9726569 0.2396997 -0.1990478 0.9502231 0.3425166 -0.01904392 0.9393188 0.3416941 -9.15579e-5 0.9398113 0.247968 -0.2037458 0.9471006 0.3172476 -0.2469007 0.9156386 0.4225964 -0.01257377 0.9062308 0.3222263 -0.2504441 0.9129338 0.3895116 -0.2966123 0.871953 0.4999911 -0.01904374 0.8658211 0.4999303 -6.10378e-5 0.8660657 0.3913509 -0.2989685 0.8703231 0.455255 -0.347217 0.8198679 0.5735127 -0.01266533 0.8190988 0.4548581 -0.3487429 0.8194405 0.5134888 -0.3975456 0.7604517 0.6492944 -0.009674549 0.7604756 0.6530191 -0.01226866 0.7572422 0.5127284 -0.4042314 0.7574342 0.5688831 -0.4422273 0.6934026 0.7682694 -0.007111012 0.6400873 0.6940041 -0.0443747 0.7186025 0.6105962 -0.4763121 0.632692 0.7743746 -0.01214677 0.6326109 0.5611352 -0.4546214 0.6916984 0.6448485 -0.5199623 0.5601872 0.8673182 -0.007141411 0.4977031 0.8083954 -0.04297113 0.5870694 0.6048276 -0.5013373 0.6187443 0.6714164 -0.5591373 0.4863802 0.8726274 -0.01190233 0.4882416 0.6416435 -0.5446828 0.5400133 0.6912941 -0.5931744 0.4126218 0.9405452 -0.007385671 0.3395887 0.8981237 -0.0428797 0.4376476 0.6716946 -0.583464 0.4565045 0.7056105 -0.6217429 0.339926 0.9442231 -0.01208543 0.3290849 0.6952111 -0.6167447 0.3691983 0.7156273 -0.6446689 0.2688485 0.9813944 -0.007110834 0.191872 0.9604637 -0.0433675 0.2750068 0.7126037 -0.6436598 0.2791023 0.7224526 -0.6619939 0.1995656 0.9848551 1.22077e-4 0.1733796 0.7242893 -0.663647 0.1870236 0.7270562 -0.6738004 0.1318424 0.9961432 -3.05191e-4 0.08774238 0.9962101 -3.05193e-5 0.08697992 0.7303462 -0.6766635 0.0933876 0.7309349 -0.6793879 0.06454807 0.9990339 -2.74669e-4 0.0439471 0.9990513 0 0.04355108 0.7324544 -0.6799924 0.03347927 0.9854185 -0.01648008 -0.1693482 0.9972065 -0.02450668 -0.07055979 0.9961755 0 -0.08737629 0.9965718 -0.04489362 -0.06949204 0.7312319 -0.680357 -0.04913532 0.7309922 -0.681643 -0.03183132 0.7301684 -0.6801476 -0.06521916 0.7310726 -0.6806559 0.04733431 0 -1 -1.62091e-5 0 -1 -4.6723e-6 0 -1 -1.40037e-5 0 -1 -1.8792e-5 0 -1 9.9469e-6 0 -1 -9.98229e-6 0 -1 9.89063e-6 0 -1 -3.74814e-5 0 -1 1.97833e-5 0 -1 1.99256e-5 0 -1 -2.53052e-5 0 -1 -1.50069e-5 0 -1 8.27596e-5 0 -1 -1.49134e-4 0 -1 5.00266e-5 0 -1 2.75666e-5 0 -1 -3.31767e-5 0 -1 3.99282e-5 0 -1 -3.30751e-5 0 -1 -1.87765e-5 0 -1 -1.87068e-5 0 -1 -9.34411e-6 0 -1 1.99016e-5 0.9658883 -0.0127263 -0.2586465 0.939341 -0.01910477 -0.3424525 0 -1 1.98796e-5 0.9848925 0 -0.1731672 0.9063159 -0.01269578 -0.4224103 0.865663 -0.01910465 -0.5002626 0.9399138 -3.05187e-5 -0.3414123 0.819239 -0.01269614 -0.5733117 0.7658224 -0.01910507 -0.6427683 0.8663457 -6.10382e-5 -0.499445 0 -1 3.75363e-5 0.707355 -0.01269614 -0.7067446 0.6428012 -0.01910519 -0.7657947 0.7664673 -9.15586e-5 -0.6422834 0.5740674 -0.01269596 -0.8187097 0.5002758 -0.01910519 -0.8656554 0.6433789 -9.15581e-5 -0.765548 0 -1 2.54544e-5 0.4233008 -0.01269596 -0.9059002 0.3424525 -0.01910477 -0.939341 0 -1 -4.00397e-5 0.5007956 -6.10391e-5 -0.8655655 0.2595334 -0.01269584 -0.9656507 0.3429092 -3.05188e-5 -0.9393686 0.1743233 0 -0.9846885 -0.9986489 0.009338855 -0.05111962 -0.9962048 0 -0.08704048 -0.9848281 4.88309e-4 -0.1735329 -0.9848281 -4.88309e-4 0.1735329 -0.9964335 -0.005981624 0.0841704 -0.9986489 -0.009338855 0.05111962 -0.9962048 0 0.08704048 -0.98063 -9.15564e-5 -0.1958696 -0.9397453 1.22077e-4 -0.3418754 -0.9964335 0.005981624 -0.0841704 -0.9392657 -1.52597e-4 -0.3431909 -0.8660789 1.52597e-4 -0.4999074 -0.8654083 -9.15582e-5 -0.5010676 -0.7799838 9.15581e-5 -0.6257998 -0.7667431 -0.002655148 -0.6419486 -0.7071373 -4.27273e-4 -0.7070763 -0.6425892 -0.005188286 -0.7661934 -0.6424181 0 -0.7663544 -0.5727944 -3.96757e-4 -0.8196991 -0.4984722 -0.002655148 -0.8669016 -0.4797863 1.52594e-4 -0.8773854 -0.342483 -1.83113e-4 -0.9395241 -0.3403508 2.74673e-4 -0.9402986 -0.1746888 -2.74668e-4 -0.9846237 -0.1718229 3.35711e-4 -0.9851279 -0.001586973 -3.35713e-4 -0.9999987 0.001586973 3.35713e-4 -0.9999987 0.1718229 -3.35711e-4 -0.9851279 0.1746888 2.74668e-4 -0.9846237 0.3403508 -2.74673e-4 -0.9402986 0.342483 1.83113e-4 -0.9395241 0.4797863 -1.52594e-4 -0.8773854 0.4984722 0.002655148 -0.8669016 0.5727944 3.96757e-4 -0.8196991 0.6425892 0.005188286 -0.7661934 0.7071373 4.27273e-4 -0.7070763 0.7667431 0.002655148 -0.6419486 0.6424181 0 -0.7663544 0.7799838 -9.15581e-5 -0.6257998 0.8654083 9.15582e-5 -0.5010676 0.8660789 -1.52597e-4 -0.4999074 0.9392657 1.52597e-4 -0.3431909 0.9397453 -1.22077e-4 -0.3418754 0.98063 9.15564e-5 -0.1958696 0.9848281 -4.88309e-4 -0.1735329 0.9964335 -0.005981624 -0.0841704 0.9986489 -0.009338855 -0.05111962 0.9986489 0.009338855 0.05111962 0.9962048 0 0.08704048 0.9848281 4.88309e-4 0.1735329 0.9962048 0 -0.08704048 0.98063 -9.15564e-5 0.1958696 0.9397453 1.22077e-4 0.3418754 0.9964335 0.005981624 0.0841704 0.9392657 -1.52597e-4 0.3431909 0.8660789 1.52597e-4 0.4999074 0.8654083 -9.15582e-5 0.5010676 0.7799838 9.15581e-5 0.6257998 0.7667431 -0.002655148 0.6419486 0.7071373 -4.27273e-4 0.7070763 0.6425892 -0.005188286 0.7661934 0.6424181 0 0.7663544 0.5727944 -3.96757e-4 0.8196991 0.4984722 -0.002655148 0.8669016 0.4797863 1.52594e-4 0.8773854 0.342483 -1.83113e-4 0.9395241 0.3403508 2.74673e-4 0.9402986 0.1746888 -2.74668e-4 0.9846237 0.1718229 3.35711e-4 0.9851279 0.001586973 -3.35713e-4 0.9999987 -0.001586973 3.35713e-4 0.9999987 -0.1718229 -3.35711e-4 0.9851279 -0.1746888 2.74668e-4 0.9846237 -0.3403508 -2.74673e-4 0.9402986 -0.342483 1.83113e-4 0.9395241 -0.4797863 -1.52594e-4 0.8773854 -0.4984722 0.002655148 0.8669016 -0.5727944 3.96757e-4 0.8196991 -0.6425892 0.005188286 0.7661934 -0.7071373 4.27273e-4 0.7070763 -0.7667431 0.002655148 0.6419486 -0.6424181 0 0.7663544 -0.7799838 -9.15581e-5 0.6257998 -0.8654083 9.15582e-5 0.5010676 -0.8660789 -1.52597e-4 0.4999074 -0.9392657 1.52597e-4 0.3431909 -0.9397453 -1.22077e-4 0.3418754 -0.98063 9.15564e-5 0.1958696 0.7293429 -0.6769113 -0.09924775 0.7273032 -0.6734978 -0.132026 0.7208582 -0.6641234 -0.1982513 0.7232775 -0.6609265 -0.2001152 0.706389 -0.6431845 -0.2955139 0.7172668 -0.6423722 -0.2699745 0.6871453 -0.6134103 -0.389306 0.705023 -0.6249712 -0.3351919 0.6873198 -0.6003099 -0.4089249 0.6609785 -0.5743048 -0.4829923 0.667365 -0.5675669 -0.482174 0.6265199 -0.5311183 -0.5704264 0.6411783 -0.5291117 -0.5558161 0.5842936 -0.4831523 -0.6520466 0.6076083 -0.4856532 -0.628453 0.5342716 -0.4318181 -0.726696 0.5658584 -0.438074 -0.6984952 0.4779902 -0.3776434 -0.793039 0.5168121 -0.3985502 -0.7576696 0.4554392 -0.3504834 -0.8183744 0.4124968 -0.3197186 -0.8530102 0.3900038 -0.299423 -0.8707715 0.340689 -0.2665266 -0.9016066 0.3179492 -0.2491589 -0.9147832 0.2628308 -0.2151904 -0.9405388 0.2404635 -0.2007271 -0.9496768 0.1793936 -0.1662092 -0.9696352 0.1587925 -0.1546419 -0.975126 0.1404783 -0.1435301 -0.9796249 0.1626372 -0.157571 -0.9740229 0.2004495 -0.1836945 -0.9623286 0.2369205 -0.1993514 -0.9508563 0.2432042 -0.2063986 -0.9477612 0.3066016 -0.2438224 -0.9200795 0.3026329 -0.2460189 -0.9208084 0.3719042 -0.2908153 -0.8815406 0.3589065 -0.2878882 -0.8878663 0.4330369 -0.340228 -0.8347001 0.4128955 -0.333118 -0.8476732 0.4899593 -0.3915035 -0.7788869 0.4647766 -0.3811846 -0.7991753 0.5423957 -0.4436035 -0.7134585 0.5146118 -0.4311728 -0.741124 0.5899116 -0.495118 -0.6378578 0.5621638 -0.4820204 -0.672033 0.6318105 -0.5441896 -0.5519721 0.6067261 -0.5321366 -0.5905202 0.667336 -0.5887486 -0.4561116 0.6471315 -0.5792565 -0.4956641 0.6957451 -0.6266192 -0.3511228 0.6817043 -0.6206967 -0.3873174 0.7163116 -0.6557313 -0.2385671 0.7085604 -0.653382 -0.2665227 0.7282281 -0.6746051 -0.1207966 0.7300799 -0.6799674 -0.06802725 0.7305938 -0.6801764 -0.05993926 0.7257776 -0.6742611 -0.1364514 0.7264249 -0.6737482 0.135537 0.7308159 -0.6801538 0.05743736 0.7298988 -0.6800913 0.0687294 0.727392 -0.676944 0.1124628 0.7039273 -0.6514953 -0.2829138 0.6735306 -0.617253 -0.4066392 0.6358934 -0.5733295 -0.5166557 0.5941735 -0.5240409 -0.6101959 0.3305257 -0.264207 -0.9060616 0.3559757 -0.2835842 -0.8904277 0.2880061 -0.231821 -0.9291456 0.2100647 -0.219129 -0.9528145 0.2414993 -0.2008171 -0.949395 0.05984771 0.06698918 -0.9959572 0.1004062 -0.04071182 -0.9941133 0.05459892 0.01190251 -0.9984374 0.1259515 -0.05197364 -0.9906741 -0.01535117 0.09110015 -0.9957235 -0.04861754 0.08444744 -0.9952412 0.0237134 -0.07281887 -0.9970633 -0.02935904 0.04974561 -0.9983304 -0.8871744 -0.4272745 -0.1742364 -0.3640347 -0.1344987 -0.921623 -0.05618578 0.1081599 -0.9925445 0.7098742 -0.6514912 -0.2676525 0.6815469 -0.6203566 -0.3881387 0.6553862 -0.5924234 -0.4685122 0.6050742 -0.5353988 -0.5892652 0.6307141 -0.5649142 -0.5320448 0.574351 -0.5043082 -0.6448211 0.2454912 -0.1089512 -0.9632568 0.1661141 0.01199388 -0.9860336 0.196358 -0.07446587 -0.9777005 0.11991 0.03378474 -0.9922099 0.1425837 -0.04525935 -0.9887475 0.8249424 -0.513094 -0.2370755 0.8511087 -0.4376703 -0.2899287 0.8164873 -0.4443024 -0.3687057 0.7661216 -0.4928534 -0.4124965 0.8312032 -0.3877829 -0.3984038 0.7552941 -0.4440878 -0.4819929 0.7959735 -0.3502088 -0.493741 0.7061932 -0.4426869 -0.5525575 0.7006319 -0.4105763 -0.5835598 -0.1408172 0.3155112 -0.9384154 -0.08966463 0.1770099 -0.9801162 -0.2855975 0.4380097 -0.8523976 -0.1696237 0.2018822 -0.9646095 -0.1222306 0.2312768 -0.9651792 -0.3376972 0.4504054 -0.826496 -0.3895453 0.4618755 -0.7968222 -0.4419506 0.4723783 -0.7625867 -0.4957488 0.4814354 -0.7228093 -0.5513949 0.4884333 -0.676311 -0.609371 0.4930939 -0.6209071 -0.6687429 0.4951786 -0.5546001 -0.7276132 0.4947196 -0.4752177 -0.7834961 0.4917604 -0.379876 -0.8311519 0.4876921 -0.2671014 -0.2091189 0.3141667 -0.9260501 -0.1779595 0.3358372 -0.9249562 -0.2597164 0.4026062 -0.877756 -0.2532461 0.5137558 -0.8197082 -0.2186397 0.4151836 -0.8830738 -0.3745059 0.6416133 -0.6693862 -0.2891688 0.4398113 -0.8502632 -0.2477868 0.4649322 -0.8499646 -0.4024301 0.6454264 -0.6492108 -0.4325166 0.6507282 -0.6240851 -0.4616321 0.6573208 -0.5956721 -0.493961 0.6625213 -0.5630881 -0.5266401 0.6701111 -0.5230693 -0.5621411 0.6768339 -0.4752823 -0.5999804 0.682749 -0.4169862 -0.6342209 0.6874465 -0.3538098 -0.6678901 0.6884908 -0.2826722 -0.6979749 0.6885445 -0.1968185 -0.31542 0.5249675 -0.7905185 -0.2895984 0.5435195 -0.7878575 -0.3616544 0.610845 -0.7043257 -0.3497772 0.6789542 -0.6455054 -0.3297609 0.619633 -0.712259 -0.3998907 0.7242774 -0.5617026 -0.3891178 0.635315 -0.6670548 -0.3511571 0.6573591 -0.6667591 -0.4122208 0.7211042 -0.5568507 -0.4285782 0.7251008 -0.5390264 -0.4146014 0.7224166 -0.5533715 -0.4500036 0.7263537 -0.519526 -0.4360968 0.7299411 -0.5263132 -0.4681717 0.7310681 -0.4963414 -0.4920688 0.7325639 -0.4703388 -0.4739023 0.7402435 -0.4769237 -0.5096473 0.7462659 -0.4281904 -0.4944058 0.7286076 -0.4740191 -0.5444647 0.742535 -0.3901284 -0.5165451 0.7507835 -0.4117102 -0.5641496 0.7699413 -0.2982043 -0.544281 0.7650269 -0.344227 -0.5847702 0.7721554 -0.2486364 -0.6231369 0.7538498 -0.2083532 -0.6426391 0.7551627 -0.1294006 -0.6027636 0.7815478 -0.1608082 -0.6147426 0.7844278 -0.08224844 -0.3985853 0.6920612 -0.6018149 -0.3792323 0.7070091 -0.5969262 -0.4053602 0.7412274 -0.5350376 -0.3912004 0.7344239 -0.5546024 -0.4005382 0.7438219 -0.5350683 -0.4456413 0.8330827 -0.3276847 -0.451231 0.8437119 -0.2907594 -0.4434461 0.8292412 -0.3401686 -0.4422212 0.8280432 -0.3446518 -0.428367 0.8140072 -0.3922933 -0.4385576 0.8012755 -0.4069705 -0.4420095 0.8266734 -0.3481935 -0.4416698 0.8217829 -0.3600012 -0.4423201 0.8323296 -0.3340366 -0.4488806 0.8094988 -0.3784416 -0.441977 0.7998129 -0.4061476 -0.4305381 0.7998847 -0.4181167 -0.4412971 0.799472 -0.4075554 -0.4395958 0.8001779 -0.4080086 -0.4541258 0.8099798 -0.371083 -0.4471115 0.8027254 -0.3946179 -0.4576092 0.8159387 -0.3533242 -0.4619357 0.81559 -0.348466 -0.466979 0.8157866 -0.3412081 -0.4639858 0.8163929 -0.3438311 -0.4656637 0.8143775 -0.3463332 -0.4561041 0.8067961 -0.3755649 -0.470794 0.8206697 -0.323812 -0.4726588 0.8227809 -0.3156349 -0.4754545 0.8285891 -0.2956064 -0.4809222 0.8307642 -0.2802582 -0.4784168 0.8328042 -0.2784864 -0.4851332 0.8377825 -0.2505321 -0.4904688 0.838567 -0.2371621 -0.4927979 0.8451452 -0.2070746 -0.4961812 0.8483118 -0.1848548 -0.4970626 0.8523952 -0.1623305 -0.4995677 0.8549935 -0.1393503 -0.4983769 0.857892 -0.1250672 -0.5028343 0.8577727 -0.1066951 -0.5027192 0.8603481 -0.08411204 -0.5075682 0.8599146 -0.05404984 0.006653249 0.2776362 -0.9606633 -0.03390693 0.2873086 -0.9572378 -0.08188229 0.2996045 -0.9505432 -0.1512823 0.5126569 -0.8451607 -0.1794248 0.5103186 -0.8410599 -0.2125966 0.5104639 -0.8332043 -0.2945095 0.6991016 -0.6515528 -0.3101366 0.6914745 -0.6524404 -0.3272538 0.6825848 -0.6534394 -0.3498479 0.7700438 -0.5335158 -0.3594207 0.7643755 -0.5353009 -0.3673653 0.7516385 -0.5477976 -0.3475252 0.7525796 -0.5593303 -0.3771261 0.749888 -0.5435475 -0.367056 0.7318537 -0.5741603 -0.3821666 0.7434579 -0.5488343 -0.4238212 0.8354043 -0.3499646 -0.4249457 0.8333806 -0.3534092 -0.4298374 0.8297045 -0.3561326 -0.4236651 0.8264858 -0.3707146 -0.4245181 0.8209587 -0.3818526 -0.427208 0.8159618 -0.3894863 -0.4281609 0.817989 -0.3841514 -0.4278511 0.8099536 -0.4011466 -0.4283937 0.7989236 -0.4221373 0.4047798 0.1803701 0.8964486 0.356006 0.1574178 0.9211295 0.467373 0.2008171 0.8609502 0.3077852 0.1514968 0.9393173 0.2775744 0.1352317 0.9511387 0.4934626 0.2311818 0.8384806 0.5852096 0.2668921 0.7657012 0.6091977 0.2924979 0.7371045 0.6979756 0.3178276 0.6417286 0.7207885 0.3454548 0.6009368 0.7890263 0.3588508 0.4986617 0.8082153 0.3864674 0.4443322 0.8561386 0.3890651 0.340081 0.8681653 0.414627 0.272715 0.8967576 0.4077114 0.172039 0.898581 0.4290714 0.09192425 0.910153 0.4142719 6.1039e-4 0.8984187 0.429372 -0.09210634 0.8969789 0.408464 -0.1690743 0.8679788 0.4146705 -0.2732424 0.8574488 0.390285 -0.3353496 0.8078189 0.3861013 -0.4453701 0.7915462 0.3605234 -0.4934346 0.7201314 0.3445619 -0.6022357 0.7013719 0.3196627 -0.6370975 0.6083723 0.2912154 -0.7382932 0.588879 0.268574 -0.7622923 0.4746652 0.2257506 -0.850723 0.4532986 0.2144265 -0.8651831 0.3625962 0.1742634 -0.9155088 0.3240512 0.1578139 -0.9327839 0.2755007 0.1362091 -0.9516021 0.1652941 0.07672834 0.9832552 0.165294 0.07672756 0.9832553 0.1652984 0.07672876 0.9832544 0.239943 0.1170111 0.9637094 0.2395452 0.1111814 0.9644982 0.1652982 0.07672947 0.9832544 -0.4207667 0.8483392 -0.321366 -0.4323053 0.8513653 -0.2971355 -0.4371567 0.8308541 -0.3443479 -0.7049179 -0.327221 0.629299 -0.4441698 0.8702726 -0.2129293 -0.4433559 0.8673319 -0.22621 -0.7048996 -0.3272018 0.6293295 -0.6458451 -0.2928918 0.7050521 -0.6491225 -0.30129 0.6984729 -0.6000392 -0.2795869 0.7495226 -0.7049021 -0.3272036 0.6293258 -0.5727531 -0.2553538 0.7789406 -0.4630282 -0.2189099 0.858885 -0.410212 -0.1753038 0.8949831 -0.3102265 -0.1478039 0.9391025 -0.2287443 -0.08850681 0.9694548 -0.1492707 -0.07025575 0.9862974 -0.02877926 -0.001525938 0.9995847 0.01788383 0.02020329 0.9996359 0.07059115 0.04641985 0.9964247 0.06869906 0.03186219 0.9971286 -0.4250995 0.8537697 -0.3006124 -0.4577562 0.8769974 -0.1460645 -0.4796712 0.8621692 -0.1630339 -0.4442971 0.8461726 -0.2942652 -0.4353862 0.8708029 -0.2283443 -0.4464991 0.8761514 -0.1816515 -0.4493405 0.881834 -0.1430454 -0.45086 0.8867657 -0.1018425 -0.5878114 0.7819173 -0.2075651 -0.5092961 0.8422551 -0.1767032 -0.5229389 0.8396931 -0.1464595 -0.4844949 0.8304624 -0.274949 -0.4841642 0.860655 -0.1576646 -0.5732422 0.7819936 -0.2447029 -0.4528436 0.8878641 -0.08142518 -0.4516192 0.888162 -0.08490365 -0.5971373 0.7856235 -0.1619345 -0.5257493 0.8413454 -0.1254022 -0.4526604 0.8892066 -0.0664097 -0.5297523 0.8424826 -0.09790557 -0.4544324 0.8898208 -0.04135364 -0.4533287 0.8899026 -0.05066144 -0.6014766 0.7915515 -0.1080387 -0.53116 0.8441366 -0.07281929 -0.453026 0.8910366 -0.02865743 -0.5334137 0.84477 -0.04281836 -0.4537327 0.8911375 7.32467e-4 -0.4538543 0.8910756 7.62986e-4 -0.6041928 0.7949696 -0.05453819 -0.5337437 0.845646 7.93489e-4 -0.4539153 0.8900989 0.04104858 -0.4539403 0.8906069 0.02752816 -0.6063824 0.7951731 6.40899e-4 -0.5314956 0.8460286 0.04181158 -0.4536032 0.88978 0.05035626 -0.6038414 0.7951627 0.05560493 -0.5301427 0.8449752 0.070468 -0.4524465 0.8880161 0.08197444 -0.4529 0.8891367 0.06570708 -0.5992698 0.793065 0.1091967 -0.5249041 0.8454195 0.09869992 -0.4522874 0.8877896 0.08523875 -0.5239142 0.8434143 0.1190229 -0.4492471 0.8818916 0.1429839 -0.4512595 0.8866184 0.1013548 -0.5969233 0.7865996 0.1579363 -0.5231291 0.8396435 0.1460647 -0.4577521 0.87702 0.1459411 -0.5872143 0.7801853 0.2156161 -0.5138532 0.8402569 0.1729833 -0.4433528 0.867326 0.226239 -0.4440177 0.8703651 0.2128685 -0.4796712 0.8621692 0.1630339 -0.487276 0.8523514 0.189893 -0.4323661 0.8513343 0.2971354 -0.4388948 0.8663145 0.238476 -0.4464333 0.8761727 0.1817107 -0.4334086 0.8607132 0.2670768 -0.4228138 0.8545698 0.3015608 -0.4209223 0.8482842 0.3213073 -0.3573534 0.7651862 0.5355265 -0.4296842 0.8185334 0.3812803 -0.4371532 0.8307559 0.3445893 -0.7049034 -0.3272114 -0.6293202 -0.7049055 -0.3272082 -0.6293195 -0.704904 -0.3272095 -0.6293206 -0.7651509 -0.3552758 -0.5369576 -0.7653604 -0.3552435 -0.5366801 -0.8180611 -0.3797476 -0.431935 -0.7049043 -0.3272075 -0.6293213 -0.8839291 -0.4102398 -0.2244386 -0.8846903 -0.4106357 -0.2206842 -0.8154178 -0.3785018 -0.4379842 -0.9070848 -0.4209481 0 -0.8846666 -0.4106694 0.2207165 -0.883952 -0.4101752 0.2244671 -0.8180321 -0.3798093 0.4319358 -0.8154484 -0.3784714 0.4379537 -0.7652683 -0.3553043 0.5367712 -0.7049098 -0.3272088 0.6293145 -0.7651758 -0.3551817 0.5369842 -0.4876086 0.7882248 -0.3754192 -0.452967 0.8253327 -0.3371158 -0.4617286 0.8370873 -0.2934139 -0.5001792 0.8071109 -0.3136764 -0.4679253 0.8492057 -0.244736 -0.5092769 0.8213987 -0.2567901 -0.4770511 0.8552799 -0.2022836 -0.472653 0.863087 -0.1779888 -0.5041067 0.8381025 -0.2084727 -0.50009 0.8395872 0.2121399 -0.4684689 0.8651261 0.1791473 -0.4763425 0.8567939 0.1974892 -0.4825459 0.85104 0.2070757 -0.5096729 0.8223741 0.2528527 -0.4679542 0.8491724 0.2447962 -0.4991753 0.806994 0.3155706 -0.4476267 0.8459342 0.2898724 -0.4556812 0.8274042 0.3282638 -0.4907144 0.7864432 0.3751086 0.1652874 0.07674598 -0.9832549 0.1653037 0.0767306 -0.9832534 0.07440632 0.04626744 -0.9961542 0.08661228 0.0401932 -0.995431 0.01147502 0.006286799 -0.9999144 0.1652933 0.07672601 -0.9832555 -0.03402918 -7.93506e-4 -0.9994207 -0.1525043 -0.07156741 -0.9857082 -0.2287714 -0.0882613 -0.9694708 -0.3118717 -0.1480772 -0.9385144 -0.4104275 -0.1750909 -0.894926 -0.4627918 -0.2183947 -0.8591435 -0.5734809 -0.2589225 -0.7772252 -0.6044983 -0.2763229 -0.7471462 -0.6481449 -0.2940869 -0.7024393 -0.6396304 -0.296895 -0.7090321 0.2431475 0.1176825 -0.962824 0.1652916 0.0767253 -0.9832558 0.2469292 0.1145988 -0.9622335 -0.470768 0.7170323 -0.5140451 -0.3137989 0.6216161 -0.7177212 -0.3925076 0.6785031 -0.6209439 -0.5143717 0.6324203 -0.5791947 -0.4801275 0.6830494 -0.5503826 -0.3261291 0.5654308 -0.7575803 -0.4050828 0.6220445 -0.6700513 -0.540776 0.6761607 -0.5003681 -0.5590574 0.7136695 -0.4220551 -0.5726647 0.7456178 -0.3407483 -0.5692756 0.7754026 -0.2732694 -0.4975811 0.6373884 -0.5883445 -0.3337941 0.5052539 -0.7958015 -0.4210768 0.565739 -0.7089667 -0.4862334 0.5325617 -0.692788 -0.4131962 0.5287715 -0.7413972 -0.4938566 0.4256469 -0.7582417 -0.4585534 0.5101617 -0.7276427 -0.3301249 0.4507057 -0.8293865 -0.4071573 0.478084 -0.7782408 -0.5562086 0.504723 -0.6602172 -0.5889637 0.5681495 -0.5747416 -0.6130384 0.6209123 -0.4885202 -0.6310806 0.6643467 -0.4004758 -0.6302853 0.7019446 -0.3316841 -0.6118247 0.6908702 -0.3851867 -0.4775993 0.4812311 -0.7350616 -0.3259788 0.3969671 -0.8579947 -0.4007235 0.4313347 -0.8083139 -0.4818462 0.4463517 -0.7540521 -0.3175519 0.3420893 -0.8843843 -0.4108861 0.3834795 -0.8271132 -0.4761542 0.4080973 -0.7789312 -0.3789566 0.3497802 -0.8567647 -0.4291965 0.2850527 -0.8570503 -0.2979021 0.2917981 -0.908905 -0.3636298 0.3127552 -0.8774724 -0.4658743 0.2836751 -0.8381465 -0.4355937 0.2263574 -0.8712179 -0.3389802 0.2375639 -0.9103055 -0.2812017 0.2394213 -0.9293025 -0.3646139 0.2674405 -0.8919262 -0.4653922 0.2415925 -0.8514946 -0.5302165 0.3520432 -0.7713211 -0.5312807 0.3415114 -0.7753134 -0.5798574 0.4414546 -0.6847506 -0.5689409 0.4265073 -0.7031343 -0.5769372 0.4313296 -0.6936126 -0.6167577 0.5139393 -0.5962184 -0.6058596 0.5063377 -0.6136419 -0.6442615 0.5725108 -0.507108 -0.6325357 0.570277 -0.5241019 -0.6556133 0.6185019 -0.4331589 -0.6738672 0.5991559 -0.4323371 -0.6606471 0.6626613 -0.3527398 -0.6424551 0.6977249 -0.3169091 -0.3569207 0.159981 -0.9203335 -0.2501354 0.1720062 -0.9528097 -0.3278039 0.2400619 -0.9137368 -0.2768691 0.1731652 -0.9451758 -0.254863 0.1913533 -0.9478549 -0.3144993 0.2049663 -0.9268652 -0.3054957 0.1558912 -0.9393458 -0.2297755 0.1413322 -0.962927 -0.2870017 0.1570819 -0.9449632 -0.3052226 0.1143249 -0.9453936 -0.04171991 0.01480185 -0.9990198 -0.1976433 0.08768206 -0.9763448 -0.2555658 0.09283864 -0.9623239 -0.2213875 0.07233089 -0.9724998 -0.3836584 0.07892292 -0.9200965 -0.3733431 0.1383441 -0.9173199 -0.1651691 0.06412053 -0.9841787 -0.460048 0.1694737 -0.8715702 -0.5634434 0.2321892 -0.7928555 -0.468189 0.2466225 -0.8485143 -0.4767082 0.2379879 -0.8462334 -0.5413731 0.2721056 -0.7955337 -0.6183166 0.3313151 -0.7126816 -0.5376845 0.341386 -0.7709416 -0.5484303 0.3345211 -0.766368 -0.5974232 0.3681592 -0.7124214 -0.6558596 0.4228448 -0.6253403 -0.5877656 0.4309589 -0.6846941 -0.6368088 0.4587611 -0.6196876 -0.6844732 0.5048401 -0.5259591 -0.6214957 0.5164176 -0.5891147 -0.6656467 0.5376507 -0.5175387 -0.699451 0.5719091 -0.4285885 -0.6390734 0.5970484 -0.4848901 -0.6724313 0.5757157 -0.4651749 -0.6923947 0.5925046 -0.4117379 -0.7000281 0.5994966 -0.3880262 -0.6861333 0.6081872 -0.399161 -0.7416396 0.646146 -0.1801835 -0.7318465 0.6279902 -0.2646305 -0.6993427 0.6494441 -0.2985673 -0.6642183 0.7063957 -0.2445802 -0.6977317 0.6527158 -0.2951824 -0.133612 0.4282726 -0.8937173 -0.1440193 0.3810911 -0.9132513 -0.1499431 0.3360214 -0.9298424 -0.1518322 0.2933794 -0.943862 -0.1500303 0.253367 -0.9556652 -0.1451178 0.2159523 -0.9655597 -0.1369991 0.1810379 -0.9738873 -0.1260762 0.1485385 -0.9808369 -0.1129528 0.1182022 -0.9865444 -0.09842407 0.08954304 -0.991108 -0.08356028 0.061953 -0.994575 -0.08298188 0.04880028 -0.9953555 0.02963387 0.03418117 -0.9989763 -0.02850455 0.04007118 -0.9987902 0.05636924 0.1977348 -0.9786335 0.04709112 0.167581 -0.984733 0.04016363 0.1405424 -0.9892597 0.03527987 0.1167349 -0.9925363 0.03213638 0.0960735 -0.9948554 0.03024458 0.07849568 -0.9964556 0.02963411 0.06384611 -0.9975197 0.02993941 0.0520659 -0.9981948 0.03064072 0.04309231 -0.9986011 0.03094661 0.03695893 -0.9988375 0.03366279 0.0318011 -0.9989273 -0.716038 0.5914897 -0.3707149 -0.7266653 0.5565201 -0.4027941 -0.7555601 0.5621914 -0.3362588 -0.7620081 0.5297555 -0.3724281 -0.720779 0.4847716 -0.4954535 -0.7290999 0.5878578 -0.3504807 -0.783135 0.5398321 -0.3086761 -0.8004272 0.4952351 -0.3377255 -0.7621904 0.4560508 -0.4594384 -0.8334513 0.484036 -0.266586 -0.8470284 0.4396893 -0.2986909 -0.8078944 0.4133775 -0.4200306 -0.7999124 0.5254823 -0.2898423 -0.8815372 0.4139273 -0.2270603 -0.8983671 0.3547262 -0.2590481 -0.8560916 0.3514581 -0.3789253 -0.933826 0.2981724 -0.1976422 -0.9284238 0.2747031 -0.2501351 -0.9029399 0.2606642 -0.3416925 -0.9380273 0.29469 -0.1823806 -0.9184771 0.3437689 -0.1955063 -0.9624382 -0.001922667 -0.2714945 -0.9516387 0.1332758 -0.2768059 -0.9569869 0.1198179 -0.2642343 -0.9433333 0.1940379 -0.2692055 -0.9455009 0.05340778 -0.3212097 -0.9656221 0.1167048 -0.2322803 -0.9735198 0.01269578 -0.2282502 -0.9654649 0.1614143 -0.204507 -0.9213753 0.3831993 -0.06500589 -0.9249404 0.3700128 -0.08704024 -0.8982173 0.4205577 -0.1278154 -0.9957496 0.00814861 -0.09174066 -0.98093 0.1536051 -0.1190874 -0.9765365 0.2077776 -0.05661386 -0.8942497 0.4383505 -0.09036797 -0.8538592 0.4939187 -0.1642224 -0.8509122 0.5119634 -0.1176524 -0.8229835 0.5345151 -0.1923326 -0.8157283 0.5618051 -0.1377045 -0.805931 0.5561892 -0.2028027 -0.7818083 0.5818776 -0.2240408 -0.7854396 0.599151 -0.1552506 -0.7589806 0.6040349 -0.2430849 -0.7615775 0.6255226 -0.1694734 -0.7457709 0.6167656 -0.2518457 -0.7040879 0.4008448 -0.5861601 -0.7553175 0.3687929 -0.5417447 -0.8071827 0.3217988 -0.4948755 -0.8557071 0.2565779 -0.4493699 -0.9271854 0.1777156 -0.3297643 -0.8949978 0.1690443 -0.412799 -0.9297024 -0.05578881 -0.364062 -0.9325468 0.07672542 -0.3528028 -0.930759 0.1061134 -0.3498967 -0.9179267 -4.88308e-4 -0.3967499 -0.6793944 0.3082774 -0.6658742 -0.7403308 0.2747018 -0.6135547 -0.7962685 0.2274878 -0.5605406 -0.8422062 0.165902 -0.5129963 -0.9108998 0.09332698 -0.4019349 -0.8731956 0.09247428 -0.4785164 -0.8914273 -0.09720277 -0.442616 -0.9081312 0.02005112 -0.4182054 -0.9088813 0.03286874 -0.415758 -0.9096823 0.0460838 -0.4127401 -0.6385807 0.2113444 -0.739965 -0.7094511 0.1818643 -0.6808851 -0.7696986 0.142678 -0.6222596 -0.8145304 0.09512871 -0.572268 -0.9051598 0.04290956 -0.4229003 -0.8795361 0.03579914 -0.4744837 -0.8422319 0.04474079 -0.5372558 -0.8512432 -0.1227179 -0.510221 -0.8815416 0.006042718 -0.472068 -0.8853395 -0.03924804 -0.4632856 -0.8521583 0.009857714 -0.5231913 -0.8511195 -0.06122148 -0.52139 -0.8621279 -0.05810791 -0.5033479 -0.8608525 -0.03988844 -0.5072886 -0.8508506 -0.04614531 -0.5233774 -0.8579168 -0.03268569 -0.5127481 -0.385123 -0.7438469 -0.5462344 -0.8342615 -0.07055944 -0.5468356 -0.8229854 -0.06418222 -0.5644253 -0.8774286 -0.04297107 -0.4777789 -0.8172176 -0.1123113 -0.56528 -0.8321607 -0.08911538 -0.5473272 -0.8481929 -0.04880034 -0.5274348 -0.8294593 -0.1286397 -0.5435525 -0.8029777 -0.1479547 -0.5773529 -0.7862268 -0.195107 -0.5863282 -0.7174667 -0.2567548 -0.6475481 -0.7717717 -0.1712742 -0.6124 -0.7771952 -0.1705398 -0.6057093 -0.7752804 -0.1861979 -0.6035486 -0.748659 -0.2804076 -0.6007339 -0.7054819 -0.2802273 -0.6509746 -0.6011579 -0.3719317 -0.7073019 -0.6959331 -0.3179202 -0.6438976 -0.6421953 -0.3578739 -0.6778728 -0.6410238 -0.3319566 -0.6920212 -0.4143658 -0.4389953 -0.7972354 -0.5458655 -0.4098112 -0.7308117 -0.5668379 -0.3916562 -0.724776 -0.5378978 -0.4016914 -0.7411545 -0.2002987 -0.4116456 -0.8890604 -0.2038064 -0.471184 -0.8581659 -0.4196092 -0.4507389 -0.787885 -0.4269615 -0.4665753 -0.7746041 -0.2978379 -0.4873934 -0.8208168 -0.3885069 -0.5068291 -0.7695367 -0.3017445 -0.5249934 -0.7958218 -0.07706141 -0.2801985 -0.9568439 -0.08505576 -0.2192163 -0.9719619 -0.09225821 -0.3317391 -0.9388491 -0.08984971 -0.4107331 -0.9073178 -0.1647433 -0.5123585 -0.8428218 -0.08978694 -0.4923329 -0.8657636 -0.1883023 -0.6004616 -0.7771667 -0.177744 -0.5694281 -0.8025951 -0.0859729 -0.525329 -0.8465448 0.06366294 -0.6699263 -0.7396931 -0.1005008 -0.5913465 -0.8001306 -0.07742643 -0.6412327 -0.7634304 -0.03289937 -0.06708049 -0.997205 0.01422202 -0.1576329 -0.9873954 0.01687693 -0.09927803 -0.9949167 0.01126152 -0.1422498 -0.9897668 0.01687687 0 -0.9998577 0.01635801 -0.01626646 -0.9997339 0.01605296 -0.03604286 -0.9992213 0.01684647 -0.03198397 -0.9993465 -0.002288937 -0.2056084 -0.9786317 0.01187205 -0.242935 -0.9699699 0.01519858 -0.2494956 -0.9682567 0.01443529 -0.3180345 -0.9479693 0.01715195 -0.3993169 -0.9166526 0.0157786 -0.427457 -0.903898 0.01379454 -0.4953225 -0.8685997 0.0137642 -0.5715057 -0.8204827 0.01477098 -0.5860806 -0.8101182 0.01574784 -0.6396186 -0.7685312 0.01712173 0.06882363 -0.997482 0.01715892 0.06668859 -0.9976263 0.01736503 0.03021341 -0.9993926 0.01794523 0.2516917 -0.9676412 0.01791453 0.1633976 -0.9863977 0.01702958 0.1591566 -0.9871066 0.01684665 0.1589143 -0.9871487 0.01690751 0.03198391 -0.9993454 0.1338251 0.07409971 -0.9882308 0.1337035 0.2525748 -0.9582951 0.1970939 0.1664525 -0.9661509 0.1268664 0.1659304 -0.9779428 0.01840305 0.253645 -0.9671224 0.6607419 0.19102 -0.7259005 0.7615445 0.1390147 -0.6330283 0.6629114 0.1490261 -0.7337164 0.4672482 0.2240411 -0.8552688 0.5636898 0.1584252 -0.8106512 0.4453126 0.1630666 -0.880401 0.2477847 0.2432069 -0.9377917 0.3264353 0.1671546 -0.9303222 0.6721522 0.2784256 0.6860689 0.6887977 0.3619629 0.6281247 0.708851 0.4397587 0.5514913 0.7298865 0.5094801 0.4557365 0.7492151 0.5671987 0.3419978 0.7641154 0.6089546 0.2128426 0.7722597 0.6311691 0.07239168 0.7722057 0.6312664 -0.07211768 0.7639001 0.6092889 -0.212659 0.7488519 0.5676589 -0.3420298 0.7295051 0.5098266 -0.4559598 0.7084487 0.4401825 -0.5516701 0.6884214 0.3623238 -0.6283292 0.6718776 0.2784866 -0.6863132 0.476764 0.3462048 0.8079841 0.4904812 0.4621895 0.738789 0.507131 0.56884 0.647487 0.5246499 0.6630224 0.5339887 0.5408616 0.739969 0.3998933 0.553347 0.7950605 0.2483667 0.5602126 0.824052 0.0842638 0.5601186 0.8241096 -0.08432447 0.5530462 0.79525 -0.2484298 0.540469 0.7401883 -0.4000185 0.5240761 0.6632744 -0.5342391 0.5065253 0.569303 -0.647554 0.4900829 0.4626153 -0.7387868 0.4764357 0.3464848 -0.8080578 0.2521185 0.3883864 0.8863365 0.2543165 0.526853 0.8110173 0.2566382 0.6550392 0.7106762 0.2885329 0.7668066 0.573373 0.2996025 0.8536093 0.4261332 0.3082747 0.9143559 0.2625263 0.3134957 0.9454618 0.0884453 0.3089166 0.9462211 -0.09610533 0.3071117 0.9141939 -0.2644463 0.2996102 0.8538448 -0.4256559 0.2888044 0.7673475 -0.5725121 0.2796478 0.6579034 -0.6992569 0.2541959 0.5246893 -0.8124566 0.2520592 0.3884806 -0.886312 0.1387401 0.4253455 0.8943335 0.1494814 0.5838564 0.7979768 0.1801558 0.7143056 0.676248 0.2111925 0.826367 0.5220301 0.2202895 0.7386628 0.6370635 0.2268195 0.9048365 0.360311 0.1957192 0.8539863 0.4820802 0.2352722 0.9542123 0.1847324 0.1767348 0.9364718 0.3029609 0.2389936 0.9710203 0.001342773 0.164864 0.9804251 0.1076408 0.1751178 0.9780717 -0.112737 0.1832367 0.9339762 -0.306778 0.3188681 0.9354542 -0.1524755 0.1952956 0.854216 -0.4818451 0.2759575 0.8993188 -0.3392245 0.2076524 0.7462242 -0.6324793 0.2315481 0.8267616 -0.5126898 0.2182138 0.6181402 -0.7551724 0.1924555 0.7197702 -0.6670021 0.1386182 0.4252545 -0.8943957 0.1506445 0.5737676 -0.8050448 0.01861655 0.2502556 0.9680009 0.01889145 0.4301092 0.9025793 0.01913577 0.426542 0.9042654 0.01922738 0.5917769 0.8058725 0.01919674 0.5878981 0.8087071 0.01904398 0.7149747 0.6988911 0.01675516 0.7272784 0.6861382 0.01843351 0.7911157 0.6113888 0.01629704 0.831089 0.5559006 0.01846414 0.8449574 0.534515 0.01815885 0.8897857 0.4560171 0.01818913 0.8912376 0.4531722 0.01794499 0.9287455 0.3702836 0.01794505 0.9296661 0.3679661 0.01773172 0.9593763 0.2815717 0.0177316 0.9599482 0.2796161 0.01754838 0.9814891 0.1907128 0.01757866 0.9818136 0.1890321 0.01742637 0.9949829 0.09851557 0.01751768 0.9951522 0.09677463 0.01736533 0.9998348 0.005371332 0.01751798 0.9998404 0.003540217 0.01736521 0.9959839 -0.08783334 0.01757895 0.9958059 -0.089787 0.01739591 0.9834509 -0.180338 0.01770091 0.9830743 -0.1823503 0.01754868 0.9622179 -0.2717148 0.01788407 0.9617115 -0.2734798 0.01773136 0.9323475 -0.3611283 0.01809793 0.9318166 -0.3624782 0.01800596 0.8939524 -0.4478002 0.01831132 0.8935927 -0.4485054 0.01825058 0.8477061 -0.530152 0.01858615 0.8473954 -0.5306369 0.0185554 0.7938866 -0.6077827 0.01892185 0.7934058 -0.6083989 0.01666343 0.7175045 -0.6963548 0.01898294 0.7319741 -0.681068 0.01879972 0.6643695 -0.7471678 0.01675486 0.5906322 -0.806767 0.01941001 0.572627 -0.8195863 0.01886075 0.4290372 -0.90309 0.01910507 0.4302306 -0.9025168 -1 0 0 -1 2.65316e-6 0 -1 -1.26947e-6 0 -1 5.28138e-6 0 -1 -2.58319e-6 0 -1 2.62204e-6 0 -1 1.35021e-5 0 -1 -6.8624e-5 0 -1 1.6185e-5 0 -1 1.55717e-5 0 -1 -8.88168e-6 0 -1 1.5363e-5 0 -1 -1.85008e-5 0 -1 -5.12328e-6 0 -1 4.73142e-6 0 -1 5.51564e-5 0 -1 -6.17535e-6 0 -1 2.40203e-6 0 -1 -2.63602e-6 0 -1 -2.65218e-6 0 0.01693826 -0.03155702 0.9993584 0.01684647 -0.03198397 0.9993465 -4.57786e-4 -0.1211607 0.9926329 0.01681613 -0.1589143 0.9871492 0.01379454 -0.2502244 0.9680896 0.01559531 -0.3136154 0.9494221 0.0129401 -0.4286723 0.9033675 0.003021299 -0.1382497 0.9903928 0.0137946 -0.1887909 0.9819204 0.01831161 -0.2429042 0.9698775 0.01895272 -0.4909106 0.8710039 0.01196348 -0.5914908 0.8062232 -1 2.50838e-6 0 0.01788425 -0.3964147 0.9178974 0.01516801 -0.6401408 0.7681079 0.01461857 -0.7181431 0.6957421 0.01889133 -0.5742487 0.818463 -1 2.40204e-6 0 0.02124148 -0.7341449 0.6786605 0.01727366 -0.7936117 0.6081793 0.01229929 -0.6735951 0.7389982 0.02130204 -0.8052964 0.5924897 0.01663279 -0.8480302 0.5296869 -1 -4.73127e-6 0 0.01788425 -0.8495029 0.5272808 0.01684659 -0.8938176 0.4481143 -1 -2.56154e-6 0 0.0190134 -0.9173738 0.3975724 0.01586985 -0.9324156 0.3610394 -1 -5.51702e-5 0 -1 6.17528e-6 0 0.01745682 -0.8833413 0.4684053 -1 6.66057e-6 0 0.01983761 -0.9417988 0.3355916 0.01580893 -0.9619982 0.2725982 -1 -4.62434e-6 0 0.01904368 -0.9652179 0.2607526 0.01709085 -0.9837014 0.1789963 -1 -1.24579e-5 0 -1 1.52981e-5 0 0.02151596 -0.9943755 0.1037041 0.01675474 -0.9959782 0.08801597 -1 1.53601e-5 0 0.01739597 -0.9790908 0.2026789 0.01803678 -0.9998373 2.13634e-4 0.01629692 -0.999853 -0.005340754 0.02102762 -0.9943125 -0.1044058 0.01767045 -0.9948571 -0.09973591 0.01779264 -0.9818913 -0.1886081 0.01669383 -0.9791099 -0.202646 0.01562595 -0.9592873 -0.2819997 0.01986783 -0.9417561 -0.3357093 0.01602256 -0.9285469 -0.3708694 0.01867759 -0.9654385 -0.259961 0.01855564 -0.9172239 -0.3979398 0.01736539 -0.8898171 -0.455987 -1 -1.61863e-5 0 -1 3.43264e-5 0 0.01742655 -0.8835973 -0.4679232 0.01446604 -0.8314041 -0.55548 -1 6.27959e-6 0 0.01608347 -0.8024347 -0.5965233 0.01205503 -0.7286137 -0.6848188 -1 -3.93296e-6 0 0.01812833 -0.849651 -0.5270339 -1 -2.65332e-6 0 0.01410007 -0.6740569 -0.7385449 -1 2.58334e-6 0 0.01895225 -0.7352318 -0.677551 -1 1.2695e-6 0 0.01129198 -0.9982447 0.0581386 0 -0.9951928 0.09793531 6.71425e-4 -0.9807994 0.1950184 -6.71425e-4 -0.9807994 -0.1950184 -0.007446527 -0.9955187 -0.09427213 -0.01129198 -0.9982447 -0.0581386 0 -0.9951928 -0.09793531 -9.15559e-5 -0.9754979 0.2200089 1.52595e-4 -0.9239954 0.382404 0.007446527 -0.9955187 0.09427213 -1.83118e-4 -0.923372 0.3839067 1.83116e-4 -0.831651 0.5552987 -1.52597e-4 -0.8307098 0.5567058 1.83113e-4 -0.7072746 0.7069389 -6.1039e-5 -0.706435 0.7077779 9.15579e-5 -0.5553902 0.83159 3.05193e-5 -0.5552072 0.8317121 9.15577e-5 -0.3819484 0.9241837 -1.22076e-4 -0.195535 0.9806967 2.13632e-4 -0.1940087 0.9809998 0 -0.3826816 0.9238803 -1.83117e-4 -9.15583e-4 0.9999997 1.83117e-4 9.15583e-4 0.9999997 -2.13632e-4 0.1940087 0.9809998 1.22076e-4 0.195535 0.9806967 -9.15577e-5 0.3819484 0.9241837 0 0.3826816 0.9238803 -3.05193e-5 0.5552072 0.8317121 -9.15579e-5 0.5553902 0.83159 6.1039e-5 0.706435 0.7077779 -1.83113e-4 0.7072746 0.7069389 1.52597e-4 0.8307098 0.5567058 -1.83116e-4 0.831651 0.5552987 1.83118e-4 0.923372 0.3839067 -1.52595e-4 0.9239954 0.382404 9.15559e-5 0.9754979 0.2200089 -6.71425e-4 0.9807994 0.1950184 -0.007446527 0.9955158 0.09430235 -0.01132249 0.9982426 0.058169 0.01132249 0.9982426 -0.058169 0 0.9951958 -0.09790509 6.71425e-4 0.9807994 -0.1950184 0 0.9951958 0.09790509 -9.15559e-5 0.9754979 -0.2200089 1.52595e-4 0.9239954 -0.382404 0.007446527 0.9955158 -0.09430235 -1.83118e-4 0.923372 -0.3839067 1.83116e-4 0.831651 -0.5552987 -1.52597e-4 0.8307098 -0.5567058 1.83113e-4 0.7072746 -0.7069389 -6.1039e-5 0.706435 -0.7077779 9.15579e-5 0.5553902 -0.83159 3.05193e-5 0.5552072 -0.8317121 9.15577e-5 0.3819484 -0.9241837 -1.22076e-4 0.195535 -0.9806967 2.13632e-4 0.1940087 -0.9809998 0 0.3826816 -0.9238803 -1.83117e-4 9.15583e-4 -0.9999997 1.83117e-4 -9.15583e-4 -0.9999997 -2.13632e-4 -0.1940087 -0.9809998 1.22076e-4 -0.195535 -0.9806967 -9.15577e-5 -0.3819484 -0.9241837 0 -0.3826816 -0.9238803 -3.05193e-5 -0.5552072 -0.8317121 -9.15579e-5 -0.5553902 -0.83159 6.1039e-5 -0.706435 -0.7077779 -1.83113e-4 -0.7072746 -0.7069389 1.52597e-4 -0.8307098 -0.5567058 -1.83116e-4 -0.831651 -0.5552987 1.83118e-4 -0.923372 -0.3839067 -1.52595e-4 -0.9239954 -0.382404 9.15559e-5 -0.9754979 -0.2200089 -0.008087396 -0.1134989 0.9935052 -0.08633881 -0.2204096 0.9715787 -0.1930941 -0.2866656 0.9383697 -0.06537175 -0.281538 0.9573207 -0.08713161 -0.3186484 0.9438598 -0.2023106 -0.3583849 0.9113895 -0.08942085 -0.4064531 0.9092854 -0.200511 -0.4131993 0.8882914 -0.089787 -0.4876332 0.8684194 -0.2042983 -0.4708873 0.8582118 -0.0867058 -0.5246602 0.8468848 -0.1918402 -0.5992338 0.7772491 -0.09744745 -0.5981743 0.7954192 -0.07468068 -0.6149945 0.784987 -0.1743274 -0.5188927 0.8368754 -0.1828697 -0.5671647 0.803046 -0.08938962 -0.652706 0.7523194 -0.108801 -0.6624198 0.7411899 -0.03396791 -0.6868965 0.7259611 -0.1629117 -0.7636831 0.6246984 -0.07382482 -0.756743 0.6495307 -0.06247347 -0.8010156 0.595375 -0.1490229 -0.7294282 0.6676278 -0.1778041 -0.8349711 0.5207774 0.07208549 -0.8516898 0.5190648 -0.08075362 -0.8726335 0.4816529 -0.1965474 -0.8922765 0.4064625 -0.02957254 -0.905367 0.4235992 -0.09680813 -0.9279481 0.3599175 -0.2195525 -0.9346087 0.2798272 -0.08575886 -0.9516793 0.2948762 -0.1128306 -0.9672856 0.2272177 -0.2665567 -0.9381061 0.2211437 -0.123511 -0.9736528 0.1916908 -0.2909102 -0.9567503 3.66232e-4 -0.1447504 -0.987739 0.05847388 -0.1425236 -0.9897913 5.7986e-4 -0.291705 -0.9540382 0.0686993 -0.2910339 -0.9541922 -0.06940132 -0.145635 -0.9875229 -0.05990809 -0.2218135 -0.9339181 -0.2803494 -0.1232677 -0.9736292 -0.1919668 -0.0895133 -0.9654802 -0.2446127 -0.2666178 -0.9380455 -0.221327 -0.199136 -0.8887726 -0.4128297 0.1029421 -0.9735707 -0.2038699 -0.0819143 -0.9231535 -0.3756033 -0.177164 -0.8311907 -0.5270057 0.07971554 -0.9361693 -0.3423923 -0.07574903 -0.8647665 -0.4964281 -0.1563786 -0.7623003 -0.6280478 0.01828104 -0.8658335 -0.4999983 -0.06930893 -0.7880042 -0.6117562 -0.1471623 -0.728823 -0.6687006 -0.07477134 -0.7537258 -0.6529218 -0.04806709 -0.6926247 -0.7196949 -0.1071229 -0.6689844 -0.7355166 -0.3071717 -0.3065918 0.9009147 -0.3254517 -0.3564587 0.8757959 -0.2813833 -0.2998777 0.9115355 -0.4040146 -0.3938822 0.8256083 -0.4080105 -0.4189669 0.8111685 -0.4135109 -0.4396358 0.7973263 -0.290484 -0.4957577 0.8184397 -0.3873521 -0.5070492 0.7699738 -0.2993901 -0.5228799 0.7980991 -0.2666769 -0.2758021 0.9234808 -0.2171145 -0.2221807 0.9505246 -0.2642065 -0.2953972 0.9181151 -0.4506775 -0.3904325 0.8027779 -0.3614684 -0.3229228 0.8746779 -0.5127017 -0.3953226 0.7621398 -0.4837646 -0.3869873 0.7849922 -0.5926443 -0.3855744 0.7071813 -0.4234572 -0.4491546 0.7867301 -0.6007406 -0.3747762 0.7061541 -0.4268975 -0.4665415 0.7746596 -0.535562 -0.4048761 0.7411131 -0.5687359 -0.3896764 0.7243562 -0.5405645 -0.3923305 0.7442224 -0.3023577 -0.2643609 0.9158019 -0.3856126 -0.3434042 0.8563742 -0.4929226 -0.3442004 0.7990955 -0.6710623 -0.3648298 0.6454259 -0.4094141 -0.2740312 0.8702225 -0.6047762 -0.3251252 0.7270072 -0.6807324 -0.3386723 0.6495417 -0.6442643 -0.3459678 0.6820778 -0.7240124 -0.2551119 0.6408775 -0.6397132 -0.3134628 0.7017893 -0.698138 -0.3122165 0.6443013 -0.6344951 -0.2863315 0.7179347 -0.6875689 -0.2675625 0.6750255 -0.63179 -0.2870691 0.7200227 -0.7656403 -0.1963008 0.6125855 -0.7390533 -0.3167284 0.5945448 -0.7351738 -0.3242956 0.5952745 -0.7410265 -0.299084 0.6011894 -0.5169031 -0.2669206 0.8133662 -0.5006691 -0.211987 0.8392807 -0.5347542 -0.2316698 0.8126298 -0.6480408 -0.2846203 0.7064236 -0.6316186 -0.2665213 0.7280278 -0.7436377 -0.2786123 0.607765 -0.7486663 -0.2804409 0.6007093 -0.7402733 -0.2910309 0.6060499 -0.7915712 -0.1371523 0.5954867 -0.7861753 -0.195201 0.5863659 -0.8029913 -0.1466448 0.577668 -0.7628564 -0.2138781 0.6101691 -0.6215851 -0.2492811 0.7426244 -0.5089979 -0.1088007 0.853864 -0.5115356 -0.1614781 0.8439528 -0.6364183 -0.198131 0.7454636 -0.6400487 -0.1373364 0.7559606 -0.7666414 -0.1622093 0.6212481 -0.7557668 -0.2332244 0.6119013 -0.5113542 -0.06229025 0.8571096 -0.6462519 -0.08133465 0.7587775 -0.7943612 -0.080724 0.6020579 -0.7698389 -0.1012616 0.630154 -0.5043031 0.004120111 0.8635169 -0.5215947 -0.004760861 0.8531801 -0.6509755 -0.01489335 0.7589527 -0.6463942 -0.01342839 0.7628856 -0.7784173 0.00891149 0.6276839 -0.7498614 -0.02365249 0.661172 -0.777322 -0.009613513 0.6290296 -0.802254 2.74671e-4 0.5969829 -0.3021044 0.01019322 0.9532205 -0.3415392 0.03790467 0.939103 -0.4339794 0.03640908 0.9001868 -0.4188755 0.04092615 0.907121 -0.6640609 0.07776212 0.7436237 -0.5639868 0.05029487 0.8242508 -0.6539117 0.03445655 0.7557859 -0.5780596 0.1054735 0.8091492 -0.5894111 0.006836175 0.8078043 -0.7321364 0.04541325 0.6796426 -0.6971158 -0.002807736 0.7169531 -0.5947233 0.006958305 0.8039004 -0.7222304 0.01138353 0.6915589 -0.1756368 0.03561568 0.9838107 -0.5631715 0.2310611 0.7933781 -0.5425754 0.2715318 0.7949104 -0.5568839 0.4098118 0.7224506 -0.6387917 0.211252 0.7398093 -0.7096124 0.181775 0.6807408 -0.7697752 0.1425837 0.6221864 -0.8145597 0.09506756 0.5722366 -0.8423522 0.04394721 0.5371327 -0.8292365 0.01168882 0.5587756 -0.823378 -0.06399875 0.5638731 -0.618082 0.3302826 0.713364 -0.5988743 0.3685474 0.7110011 -0.5843647 0.4973829 0.6411928 -0.5411715 0.3390104 0.7695488 -0.6796039 0.3081535 0.6657177 -0.74048 0.2745785 0.6134298 -0.7963732 0.2274 0.5604277 -0.8422632 0.1658096 0.5129327 -0.8733019 0.09277784 0.4782637 -0.8575366 0.01321488 0.5142534 -0.8801537 0.03384619 0.4734805 -0.8401585 -0.07297098 0.5374097 -0.8460537 -0.05209624 0.5305461 -0.8512156 -0.0611608 0.5212402 -0.8539386 -0.049869 0.5179788 -0.8322181 -0.09027469 0.5470501 -0.5454658 0.4084966 0.7318453 -0.6559746 0.421772 0.6259438 -0.6398019 0.4582133 0.6170041 -0.589999 0.6525635 0.4754601 -0.5931382 0.4250086 0.6837798 -0.704144 0.400842 0.5860949 -0.7553811 0.3687942 0.541655 -0.8072283 0.3217927 0.494805 -0.855727 0.2565747 0.4493337 -0.8950887 0.1695324 0.4124018 -0.9077951 0.03338801 0.4180831 -0.9122089 0.08978646 0.3997666 -0.8291721 -0.1205807 0.5458332 -0.8793492 -0.02056992 0.475733 -0.8531507 -0.0569784 0.5185435 0.9293291 -0.2765312 -0.2447 -0.8781098 -0.03860723 0.4768992 -0.831991 -0.1171947 0.5422698 -0.8521599 -0.0877735 0.5158677 -0.5900332 0.4904176 0.641367 -0.684293 0.5037437 0.5272432 -0.6699826 0.5379881 0.5115587 -0.5207136 0.8185476 0.2425643 -0.5871526 0.566003 0.5786989 -0.6306512 0.4981363 0.5950962 -0.7207936 0.484761 0.4954426 -0.7621904 0.4560508 0.4594384 -0.807915 0.4133575 0.4200108 -0.8561008 0.3514314 0.3789294 -0.9029329 0.2612115 0.3412931 -0.9289408 0.1729518 0.327348 -0.849036 -0.1179251 0.5150066 -0.9064852 -0.00149542 0.422235 -0.8930029 -0.02737605 0.4492177 0.9240476 -0.3130922 -0.2193384 -0.9126717 -0.003296017 0.4086803 -0.6247282 0.5636593 0.5403731 -0.7001154 0.5698586 0.4302322 -0.685291 0.5979434 0.4157403 -0.3663472 0.9303339 -0.01638853 -0.6084372 0.6200652 0.4953014 -0.6457592 0.5723602 0.5053702 -0.7270034 0.551242 0.4093877 -0.7595978 0.5321366 0.3739544 -0.8009926 0.491369 0.342005 -0.8444439 0.44296 0.3011664 -0.8983671 0.3547262 0.2590481 -0.9280899 0.2748562 0.2512038 -0.8896917 -0.09549415 0.4464634 -0.9348192 0.05084586 0.3514652 0.8908805 -0.4316609 -0.1414251 -0.9414471 0.04968476 0.33348 -0.3072926 0.9474219 -0.08923661 -0.6324816 0.660956 0.4038617 -0.6558264 0.6209735 0.4292826 -0.6853817 0.5986446 0.4145801 -0.6999961 0.5994952 0.3880864 -0.6861293 0.6081531 0.3992197 -0.6530793 0.6560397 0.3782849 -0.7159594 0.5915615 0.3707522 -0.7355579 0.58244 0.3460031 -0.7830258 0.539942 0.3087607 -0.7542466 0.5749474 0.3170924 -0.8119664 0.5137621 0.2770543 -0.8814891 0.4139944 0.2271246 -0.8321432 0.4961546 0.2477263 -0.9338411 0.2981675 0.1975779 -0.918462 0.3437938 0.1955336 -0.9380236 0.2946984 0.1823858 -0.928244 -0.05502623 0.3678795 -0.9556587 0.1277853 0.2653065 -0.9563245 0.1457605 0.2533718 -0.7432696 0.6442952 0.180095 -0.7118275 0.6506062 0.2646006 -0.7332963 0.6239444 0.2701297 -0.6198459 0.7058187 0.3429448 -0.6620882 0.6966362 0.2762923 -0.6101453 0.7218466 0.3265889 -0.6896136 0.6534484 0.3121512 -0.4938275 0.8695465 -0.004821956 -0.7120481 0.6881819 0.13926 -0.7416138 0.6197205 0.2568181 -0.7610935 0.6263502 0.1685893 -0.7589297 0.6041345 0.2429966 -0.7866571 0.5978362 0.1541513 -0.7837557 0.5757389 0.2329202 -0.8000571 0.5622526 0.2092386 -0.8147009 0.5638054 0.1355953 -0.8229613 0.5345816 0.192243 -0.8509492 0.5119368 0.1175007 -0.8538336 0.4940131 0.1640708 -0.8942777 0.4383187 0.09024566 -0.8982003 0.4206413 0.1276603 -0.9213682 0.3832269 0.06494438 -0.9249373 0.370042 0.08694839 -0.962909 -0.001953184 0.2698196 -0.9685042 0.1528719 0.1965452 -0.9633504 0.1163979 0.2416768 -0.9957525 0.00814861 0.09171038 -0.9765167 0.2078955 0.05652117 -0.9809383 0.1536016 0.1190237 -0.9748898 0.01596128 0.2221152 -0.5387917 0.6818977 0.494691 -0.5568499 0.7179903 0.4176222 -0.5713521 0.7483946 0.3368417 -0.562435 0.7779298 0.2801646 -0.5959783 0.7596831 0.2601759 -0.671395 0.7109481 0.2092406 -0.6842095 0.7176585 0.1297065 -0.6903165 0.7073768 0.1519252 -0.6801697 0.7136791 0.1674254 -0.6818279 0.7280034 0.07156735 -0.682215 0.7306482 0.02713108 -0.6802134 0.7324014 -0.02996987 -0.6804038 0.7328365 0.001190245 -0.678218 0.7294895 -0.08868741 -0.6712408 0.7195527 -0.1779883 -0.6724358 0.7249599 -0.1492097 -0.6753914 0.7258703 -0.1302257 -0.6687914 0.7107244 -0.2181491 -0.7141184 0.649082 -0.2621598 -0.7259615 0.6492666 -0.2267885 -0.7213322 0.6709443 -0.1717951 -0.752486 0.6586083 9.15582e-5 -0.7128801 0.6835506 -0.1567189 -0.731161 0.6748522 -0.09989106 -0.7180966 0.6957867 0.01477146 -0.4800369 0.8772447 0.002563595 -0.4821444 0.8760879 -0.002655148 -0.5112014 0.8594592 0.001770079 -0.5097939 0.8602772 0.00576812 -0.5256021 0.8503265 0.02621597 -0.5074102 0.8616451 0.01013231 -0.92019 0.3914722 -3.05194e-5 -0.982944 0.1839053 0 -0.8959237 0.444208 -3.05193e-5 -0.8538961 0.5204436 -6.10384e-5 -0.8198108 0.5726346 -9.15581e-5 -0.7919155 0.6106308 -1.22077e-4 -0.7692984 0.6388897 -1.52596e-4 -0.9999248 0.0122686 0 -0.5736379 -0.8145559 0.08624708 -0.4521728 -0.8325643 0.3199635 -0.5445212 -0.7955405 0.2657295 -0.8071137 -0.5903961 -4.2727e-4 -0.7994402 -0.5931025 0.09552383 -0.6533263 -0.6773145 0.3382452 -0.7700244 -0.5726276 0.2813544 -0.5783331 -0.8158007 -4.27265e-4 -0.9524763 -0.3046129 0 -0.94532 -0.3119632 0.0951271 -0.8116304 -0.4781154 0.3356513 -0.9185699 -0.2921307 0.2662504 -0.917092 -0.2478132 0.3122996 -0.9453173 -0.3119623 -0.09515732 -0.7999649 -0.5925269 -0.09470051 -0.5731495 -0.8149832 -0.08545356 -0.9154483 -0.2472955 -0.3174893 -0.9185623 -0.2921283 -0.2662787 -0.8102779 -0.4779571 -0.3391265 -0.7700378 -0.5726071 -0.2813593 -0.6523606 -0.6773868 -0.33996 -0.5445212 -0.7955405 -0.2657295 -0.4516225 -0.8328983 -0.3198713 -0.2903013 -0.6640734 0.6890078 -0.2584055 -0.6025697 0.7550739 -0.3383063 -0.6788406 0.6517089 -0.4263869 -0.5817613 0.6926384 -0.3932673 -0.5287105 0.7522009 -0.5005779 -0.5663471 0.654731 -0.5514618 -0.4839216 0.6794923 -0.5220633 -0.4356936 0.7332264 -0.6433887 -0.4321303 0.6319133 -0.6621451 -0.3731281 0.6498764 -0.6447912 -0.3351376 0.6869696 -0.7613227 -0.2812615 0.5841915 -0.7555375 -0.2523341 0.6045582 -0.740247 -0.2316419 0.6311708 -0.8106258 -0.2854785 0.5112611 -0.693999 -0.4607433 0.553246 -0.5454772 -0.6146957 0.5697403 -0.3715701 -0.7404546 0.5600562 -0.8631061 -0.2727478 0.4250373 -0.7504132 -0.4748832 0.4597456 -0.5967146 -0.6509169 0.4692962 -0.4100841 -0.7915108 0.4531465 -0.8629976 -0.274217 -0.4243115 -0.7499791 -0.4761913 -0.4591005 -0.595978 -0.6520112 -0.4687131 -0.4090805 -0.7923418 -0.452601 -0.8106311 -0.2870368 -0.5103793 -0.693731 -0.4620906 -0.5524579 -0.5448907 -0.6157869 -0.5691229 -0.3707429 -0.7412416 -0.5595629 -0.7623768 -0.2834955 -0.581732 -0.6438136 -0.4335937 -0.6304765 -0.5003989 -0.5669926 -0.6543091 -0.3375112 -0.6786236 -0.6523467 -0.7555046 -0.2523639 -0.6045868 -0.6621054 -0.3732144 -0.6498674 -0.5514489 -0.4840018 -0.6794458 -0.4264459 -0.5817584 -0.6926045 -0.2903569 -0.6640306 -0.6890256 -0.7405824 -0.2248054 -0.6332458 -0.6385489 -0.333481 -0.6935746 -0.5219956 -0.435688 -0.733278 -0.3939194 -0.5257956 -0.7539008 -0.255324 -0.6013512 -0.7570908 -1 -1.56332e-5 0 -1 -1.58239e-5 0 -1 1.21954e-5 0 -1 3.47072e-6 0 -1 -5.03544e-6 0 -1 -1.52647e-6 0 -1 2.83036e-6 0 -1 -3.31219e-6 0 -1 7.76548e-7 0 -1 1.28958e-7 0 -1 -4.44733e-6 0 -1 -2.80404e-6 0 -1 3.87175e-6 0 -1 -1.97399e-6 0 -1 3.66184e-6 0 -1 -3.20626e-6 0 -1 3.73872e-6 0 -1 4.03036e-6 0 -1 2.89817e-6 0 -1 -2.83036e-6 0 -1 3.77666e-6 0 -1 -3.47062e-6 0 -1 8.00171e-6 0 -1 -1.62604e-5 0 -1 3.16478e-5 0 -0.421036 0.9070439 0 -0.4210109 0.9070557 0 -0.4210112 0.9070555 0 -0.4210446 0.9070399 0 -0.4210361 0.9070439 0 -0.4210346 0.9070447 -1.04731e-6 -0.421036 0.907044 0 -0.4210432 0.9070406 -6.34539e-7 -0.4210264 0.9070484 0 -0.4210283 0.9070476 4.75264e-7 -0.4210436 0.9070404 0 -0.4210461 0.9070392 1.70486e-6 -0.4210347 0.9070445 0 -0.4210305 0.9070465 0 -0.4210365 0.9070438 0 -0.4210903 0.9070187 0 -0.4210901 0.9070189 0 -0.4208847 0.9071142 0 -0.4210364 0.9070437 0 -0.4210391 0.9070426 0 -0.4210429 0.9070408 0 -0.4210308 0.9070464 0 -0.4210195 0.9070517 0 -0.4210345 0.9070447 0 -0.4210405 0.9070419 -5.66634e-7 -0.4210336 0.9070451 1.43468e-6 -0.421025 0.9070491 0 -0.4210456 0.9070396 2.23754e-6 -0.4210353 0.9070444 8.10851e-7 -0.4210274 0.907048 0 -0.421046 0.9070393 -7.35107e-7 -0.4210426 0.907041 3.54813e-6 -0.4210339 0.907045 -2.94274e-6 -0.420968 0.9070755 9.45958e-6 0.2896921 -0.2372594 0.9272468 0.3517374 -0.2821224 0.8925737 0.4099081 -0.3290618 0.850702 0.464221 -0.3776393 0.8011788 0.4649336 -0.3779532 0.8006173 0.5145965 -0.4270348 0.7435265 0.5151314 -0.4275416 0.7428647 0.5607926 -0.4761015 0.6773765 0.5631371 -0.4782332 0.6739212 0.6024248 -0.5234708 0.6025469 0.6081216 -0.5284366 0.5924044 0.6391282 -0.5674697 0.5191276 0.6488362 -0.5759566 0.4972783 0.6704235 -0.6064544 0.4274876 0.6835397 -0.6179843 0.3884185 0.6958179 -0.6387461 0.3283916 0.7101578 -0.6514689 0.2669539 0.7148608 -0.6627638 0.2229762 0 -1 -2.31909e-5 0 -1 4.02499e-5 0 -1 -2.05143e-5 0 -1 6.48156e-7 0 -1 2.05143e-5 0 -1 3.82909e-6 0 -1 -2.13106e-5 0 -1 6.46807e-6 0 -1 1.1915e-5 0 -1 1.42399e-5 0 -1 -1.43555e-5 0 -1 -1.27342e-5 0 -1 -1.0341e-5 0 -1 4.65191e-5 0 -1 -4.82694e-5 0 -1 1.50766e-4 0 -1 -6.53657e-5 0 -1 -8.65707e-5 0 -1 3.50938e-5 0 -1 -8.44259e-5 0 -1 1.1327e-4 0 -1 -6.48156e-7 0 -1 -3.82909e-6 0 -1 2.13106e-5 0 -1 -6.46807e-6 0 -1 -1.1915e-5 0 -1 -1.42399e-5 0 -1 1.43555e-5 0 -1 1.27342e-5 0 -1 1.0341e-5 0 -1 -4.65191e-5 0 -1 4.82694e-5 0 -1 -1.50766e-4 0 -1 6.53657e-5 0 -1 8.65707e-5 0 -1 -3.50938e-5 0 -1 8.44259e-5 0 -1 -1.1327e-4 0.9969176 0.07845646 0 0.9969168 0.07846653 1.27621e-6 0.9969168 0.07846605 0 0.9969166 0.07846826 0 0.9969176 0.0784564 0 0.9969187 0.07844144 0 0.9969177 0.07845431 0 0.9969168 0.07846629 0 0.9969182 0.07844984 0 0.9969182 0.07845026 0 0.9969158 0.07847899 0 0.9969171 0.07846295 0 0.996918 0.07845169 0 0.9969165 0.07847088 0 0.9969174 0.07845991 0 0.996918 0.07845216 0 0.9969142 0.07849854 0 0.9969177 0.07845449 0 0.9969167 0.0784679 -1.33444e-7 0.9969168 0.07846593 0 0.9969181 0.07845085 1.40281e-7 0.996918 0.07845044 -6.69123e-7 0.996917 0.07846373 -6.80157e-7 0.9969171 0.07846307 -4.44241e-7 0.996918 0.0784505 -3.08011e-7 0.9969173 0.07846081 3.39566e-7 0.9969175 0.07845795 4.19525e-7 0.9969181 0.07845008 -2.14233e-6 0.9969164 0.07847219 9.95301e-7 0.9969168 0.07846683 6.42857e-7 0.996915 0.0784893 1.55708e-6 0.9969171 0.07846289 -1.58225e-6 0.8413653 -0.38705 -0.3772227 0.7879748 -0.4404529 -0.430229 0.8718725 0.08185249 -0.4828442 0.8739233 0.05831682 -0.482553 -0.8791916 0.03058004 0.4754862 -0.8758689 0.05151629 0.4797914 -0.8692612 0.07077509 0.4892607 -0.8754522 0.06202572 0.4793084 -0.8864305 -0.02505624 0.4621829 -0.8880534 -0.09906595 0.4489403 -0.8901324 -0.05508768 0.4523603 0 1 0 0.8637539 -0.163064 -0.4768012 0.8397062 -0.02411133 -0.5425055 0.874374 -0.0162667 -0.48498 -0.850916 0.1200899 0.5113906 -0.8367838 0.02216893 0.5470845 -0.8368828 0.02108812 0.5469757 0.8360631 -0.02060317 -0.5482463 0.8743473 -0.03372377 -0.4841276 0.872501 -0.1077618 -0.476581 0.8619176 -0.2244977 -0.4546416 0.8420354 -0.3879345 -0.3748111 0.7688429 0.5040572 -0.3934552 -0.9015943 -0.002197325 0.4325773 0 0.9999999 -4.92762e-4 -0.4575771 0.8560382 -0.2404622 -0.4541933 0.8738994 -0.1732295 -0.44888 0.8555516 -0.2579503 0.7143002 0.3123127 -0.6262875 -0.4617281 0.8415727 -0.2802903 0.7147792 0.3125346 -0.62563 0.7147563 0.3125419 -0.6256526 -0.4647708 0.873326 -0.1459103 -0.4612663 0.8813623 -0.1021475 0.7136128 0.3119068 -0.6272726 0.7148541 0.3118519 -0.625885 0.71454 0.3120509 -0.6261444 0.7141391 0.3122243 -0.6265153 0.7140069 0.3122721 -0.6266422 -0.467675 0.8825826 -0.04825073 -0.4613278 0.8847203 -0.06668436 0.7841836 0.3386379 -0.5199813 0.7732316 0.3397995 -0.5353963 0.8241421 0.3655291 -0.432641 0.7135003 0.3119552 -0.6273766 -0.4648306 0.8848903 -0.03003036 0.842825 0.3636392 -0.3967528 0.8897604 0.3991928 -0.2212956 -0.4674375 0.8826866 0.04864811 -0.4663365 0.8846049 -0.002105832 0.9035129 0.3954032 -0.1652905 0.9112924 0.4117601 0 -0.4616684 0.8864389 0.03299152 0.9035174 0.3954052 0.1652608 0.8897663 0.3991954 0.2212666 0.9142553 0.4051387 0 -0.4629485 0.8838106 0.06750881 0.841018 0.3656507 0.3987335 0.8246256 0.3621089 0.4345917 -0.4641039 0.8736396 0.1461559 -0.4663965 0.8795672 0.0939995 0.7785739 0.3351307 0.5305753 -0.4580267 0.8752496 0.1554019 0.7134847 0.3119468 0.6273986 0.783918 0.3448372 0.5162945 -0.4580067 0.8555847 0.2412569 -0.4576609 0.8641417 0.2092984 0.7140275 0.3121863 0.6266613 0.7134928 0.3119726 0.6273765 -0.4572308 0.8486938 0.2658177 0.7144589 0.3123956 0.6260651 0.714031 0.3122102 0.6266455 -0.4570948 0.8374018 0.2997043 -0.6539963 0.7497351 0.100927 0.7147957 0.3125207 0.6256181 0.7144371 0.3123112 0.626132 0.7145839 0.3124754 0.6258826 0.6653467 0.3097687 0.6792328 0.6582364 0.2863304 0.6962327 0.6264607 0.2747308 0.7294313 0.7147654 0.3124814 0.6256723 0.7148289 0.3125778 0.6255515 -0.459957 0.8392513 0.2899947 -0.4491154 0.8260232 0.3405598 -0.4562633 0.8285986 0.32442 0.5778204 0.2458018 0.7782706 0.5625331 0.242568 0.7903907 0.649695 0.3013476 0.6979155 -0.4721326 0.8595744 0.1955062 -0.4790953 0.8722477 0.09824228 -0.4814395 0.8764794 0 -0.4790968 0.8722504 -0.09821206 -0.4721326 0.8595744 -0.1955062 -0.4722587 0.8331212 -0.2878904 -0.45705 0.8365517 -0.3021364 -0.4605948 0.8385744 -0.2909389 0.649999 0.2843784 -0.7047201 0.6201478 0.2768386 -0.7340144 0.6580235 0.2994539 -0.6908926 -0.4512959 0.8287949 -0.3308038 0.5778588 0.2457746 -0.7782507 0.5623431 0.2424429 -0.7905642 0.7149222 0.3125522 -0.6254578 0.6833959 0.2979328 -0.666488 -0.4522117 0.8260181 0.3364502 0.4986883 0.2108286 0.8407505 0.4963107 0.2131187 0.8415796 -0.4476856 0.8220947 0.3517639 0.3934592 0.160045 0.9053041 0.3906475 0.1634921 0.9059056 -0.4437208 0.8174914 0.3671783 0.2332254 0.08569705 0.9686392 0.227003 0.08871978 0.9698446 -0.443085 0.8160968 0.371028 -0.4413714 0.8134333 0.3788372 0.03775185 -0.003540158 0.9992809 0.03134298 -0.004821956 0.9994971 -0.06088566 -0.04968512 0.9969074 -0.1581259 -0.09249174 0.9830776 -0.06079429 -0.04721325 0.9970332 -0.452937 0.8267984 0.3335455 -0.1580047 -0.09259104 0.9830877 -0.1581288 -0.09246408 0.9830797 -0.4769847 0.8454737 0.2401251 -0.4621254 0.8281145 0.3172801 -0.4600074 0.8272687 0.3225209 -0.4653555 0.8348199 0.2941432 -0.4887442 0.8602313 0.1453658 -0.4940432 0.8680548 0.04901367 -0.4941364 0.8679966 -0.04910534 -0.4888586 0.8601874 -0.1452414 -0.4792354 0.8434763 -0.2426543 -0.4516295 0.8228703 -0.3448413 -0.4520865 0.825402 -0.3381264 -0.4681068 0.8348281 -0.2897208 -0.4518952 0.8255091 -0.3381203 -0.4437158 0.8174822 -0.3672047 -0.4431146 0.816095 -0.3709967 -0.1581836 -0.09240931 -0.983076 -0.4506458 0.8543836 -0.2587413 -0.391989 0.911579 0.1239691 -0.1580047 -0.09258252 -0.9830886 -0.4413996 0.81349 -0.3786826 -0.06192302 -0.04971539 -0.996842 -0.06360244 -0.04852586 -0.9967948 0.03366219 -0.002685606 -0.9994297 -0.1581131 -0.09249716 -0.9830791 0.03878915 -0.003753781 -0.9992404 0.2283455 0.0889638 -0.969507 0.2328935 0.085729 -0.9687163 0.3909513 0.163461 -0.9057801 0.3933967 0.1600444 -0.9053313 0.4961774 0.2130224 -0.8416826 0.4987176 0.210767 -0.8407486 -0.2236118 -0.1228995 0.9668989 -0.2236158 -0.1229933 0.9668861 -0.2594721 -0.13938 0.9556398 -0.1578602 -0.09252333 0.9831173 -0.1578664 -0.09251743 0.9831169 -0.2841957 -0.1555263 0.9460678 -0.3258492 -0.1759713 0.9289007 -0.4632214 0.8385779 0.2867285 -0.3829859 -0.1986192 0.9021487 -0.4131361 -0.1994418 0.8885616 -0.492003 0.8525284 0.1764325 -0.4731733 0.8369345 0.2750412 -0.4807028 0.8384146 0.2568774 -0.4862034 0.8449276 0.2229437 -0.4961743 0.8602024 0.1177414 -0.501883 0.8649356 0 -0.4998496 0.8639176 0.06161898 -0.4995111 0.8640959 -0.06186282 -0.4920004 0.8525238 -0.1764621 -0.4957291 0.8605294 -0.1172256 -0.4824135 0.8459862 -0.2271223 -0.2828868 -0.1558029 -0.9464147 -0.3254836 -0.1745373 -0.9292992 -0.2595016 -0.139349 -0.9556363 -0.4230589 0.8873494 -0.1833906 -0.4417638 0.8672305 -0.2296866 -0.382613 -0.1969066 -0.9026822 -0.4151194 -0.1985871 -0.8878283 -0.3525863 -0.1868069 -0.916944 -0.4526 0.8573764 -0.2450693 -0.2235836 -0.1228703 -0.9669092 -0.1578482 -0.0925104 -0.9831205 -0.2235239 -0.122932 -0.9669151 -0.1578673 -0.09251779 -0.9831167 -0.4873933 -0.2062799 0.8484671 -0.498809 -0.2256909 0.8368113 -0.571406 -0.3082107 0.7605928 -0.5639979 -0.2811444 0.7764433 -0.5910393 -0.3128241 0.7435144 -0.5572044 -0.2780001 0.7824572 -0.03826522 -0.02617359 0.9989248 -0.5029004 -0.2523658 0.8266819 -0.6571692 -0.3373283 0.6740463 -0.6752662 -0.3324143 0.6584196 -0.7482073 -0.3667485 0.5528848 -0.7648087 -0.3622007 0.5328025 -0.8063528 -0.3825606 0.4510461 -0.8451666 -0.4018761 0.3524045 -0.8793981 -0.4276289 0.2092671 -0.8873541 -0.4208027 0.1884883 -0.8438959 -0.4113119 0.3444741 -0.8987022 -0.4284607 0.09357219 -0.9067166 -0.4217407 0 -0.8987296 -0.4284897 -0.09317511 -0.8873095 -0.4208571 -0.1885769 -0.8995373 -0.4368439 3.35705e-4 -0.8866397 -0.4176228 -0.1986485 -0.8412752 -0.402341 -0.3610785 -0.8284189 -0.404077 -0.3878712 -0.764884 -0.3734387 -0.5248773 -0.8819428 -0.3912556 -0.2628615 -0.7593299 -0.3724012 -0.5336062 -0.6622799 -0.3258906 -0.6746709 -0.6557983 -0.3239622 -0.6818923 -0.5954322 -0.2961291 -0.7468386 -0.4731137 -0.2378386 -0.8482902 -0.4729609 -0.2381438 -0.8482899 -0.5945388 -0.2969489 -0.7472249 -0.4965229 -0.2081129 -0.8427064 -0.5955787 -0.06457823 -0.8006971 -0.4997245 -0.1801254 -0.8472487 0.7147127 0.3125728 -0.6256869 0.7145606 0.3124981 -0.6258978 0.4210301 -0.9070467 0 0.4210532 -0.907036 0 0.4210515 -0.9070367 0 0.7141458 0.3129562 -0.6261423 0.7145016 0.3123913 -0.6260186 0.4210394 -0.9070423 0 0.4210291 -0.9070472 0 0.4210277 -0.9070479 0 0.4210398 -0.9070422 0 0.4210302 -0.9070466 3.96888e-6 0.4210358 -0.9070441 0 0.4210245 -0.9070493 0 0.4210423 -0.907041 0 0.421035 -0.9070445 0 -0.456987 -0.2328271 -0.8584605 -0.4369204 -0.2262732 -0.8705752 -0.4688642 -0.2430843 -0.8491622 0.4210324 -0.9070456 0 0.4210292 -0.9070472 9.70241e-7 -0.4365404 -0.2217798 -0.8719211 0.4210472 -0.9070388 0 -0.4985993 -0.2569448 -0.8278757 -0.5034193 -0.2631697 -0.822989 0.4210472 -0.9070388 0 0.4210371 -0.9070435 0 -0.5953652 -0.295821 -0.7470143 -0.5963399 -0.2944772 -0.7467677 0.4210391 -0.9070426 0 -0.5172756 -0.2586836 -0.8157872 0.4210305 -0.9070465 2.20375e-6 0.4210375 -0.9070433 0 0.4210441 -0.9070401 3.55076e-6 0.4210001 -0.9070606 0 0.4210798 -0.9070236 3.02892e-6 0.4210641 -0.9070309 1.85488e-6 0.4209433 -0.907087 -8.22771e-6 0.4210522 -0.9070364 4.79755e-6 0.4211653 -0.906984 1.35576e-5 0.4209074 -0.9071037 -6.83204e-6 0.4211649 -0.9069842 1.02048e-5 -0.4751197 -0.2397572 0.8466274 -0.5016143 -0.2536454 0.8270715 -0.4694156 -0.2360354 0.8508445 -0.4728532 -0.2384808 0.8482552 -0.5032895 -0.2523314 0.8264555 -0.4444534 -0.2234627 0.8674823 0.4210294 -0.907047 0 -0.3506683 -0.1820484 0.918635 -0.4443861 -0.2254128 0.8670122 0.421032 -0.9070459 0 0.4210321 -0.9070457 0 0.4210401 -0.9070421 0 0.4210398 -0.9070422 0 0.4210376 -0.9070433 0 0.4210376 -0.9070432 1.74422e-6 0.4210253 -0.907049 0 0.4210255 -0.9070489 0 0.4210439 -0.9070402 0 0.4210436 -0.9070404 0 0.4210308 -0.9070464 0 0.4210305 -0.9070466 0 0.4210391 -0.9070426 0 0.4210404 -0.907042 0 0.4210486 -0.9070381 0 0.4210495 -0.9070377 0 0.4210244 -0.9070494 0 0.4210211 -0.9070509 0 0.7144822 0.312423 0.6260249 0.7140343 0.3122002 0.6266468 0.7143811 0.3123612 0.6261711 0.7143843 0.3130355 0.6258305 0.4210331 -0.9070453 0 0.4210283 -0.9070475 0 0.4210377 -0.9070432 -1.02297e-5 0.4210583 -0.9070337 -2.94817e-5 0.9512044 0.09165036 0.2946363 0.9596697 0.1062061 0.2602965 0.9692121 0.09488254 0.2272115 0.05084437 -0.7610789 0.6466637 0.0390343 -0.7167481 0.696239 0.04272741 -0.6337093 0.7723904 0.9647808 0.09280961 0.2461393 0.9832628 0.09271687 0.1568374 0.04612779 -0.8096629 0.5850797 0.04623878 -0.809899 0.584744 0.04623019 -0.8098697 0.5847854 0.9489501 0.09524899 0.3007013 0.01840317 -0.4655129 0.8848499 0.03634804 -0.4366344 0.8989046 0.06909608 -0.7255092 0.6847352 0.03009188 -0.6197525 0.7842203 0.9404112 0.09094649 0.3276516 0.03363215 -0.3182545 0.9474086 0.02664345 -0.196698 0.9801022 0.936984 0.09047102 0.3374552 0.021577 -0.07754909 0.9967551 0.01489311 -0.04217684 0.9989992 -1.22076e-4 -0.2112524 0.9774315 -0.02138197 0.0418238 0.9988962 -0.01641923 -0.02066135 0.9996518 0.9515473 0.09045785 0.2938966 -0.02171361 0.04193097 0.9988846 0.9843107 0.09580028 0.1481715 0.9727641 0.09265583 0.2124736 0.9505224 0.08633899 0.2984173 0.9512423 0.08877933 0.295392 0.9506128 0.08639991 0.2981117 0.9525387 0.08917742 0.2910628 0.9585314 0.09378397 0.2691139 0.9659538 0.09546309 0.2404584 0.9930509 0.09637832 0.06753808 0.9941204 0.09625637 0.04959309 0.9880037 0.09689897 0.1202463 0.990979 0.0989117 0.09042745 0.9770609 0.0941506 0.1910175 0.9818297 0.09711176 0.163033 0.9942275 0.09891307 -0.04156726 0.9941354 0.0962578 -0.04928863 0.9950049 0.09982705 0 0.9946083 0.1010478 -0.02331638 0.9952255 0.0975998 -8.24014e-4 0.9951921 0.09531062 0.02255344 0.994489 0.0943644 0.04568678 0.993007 0.09842479 0.06518924 0.9909854 0.09467017 -0.0947923 0.9842249 0.09607255 -0.1485645 0.9929851 0.09872776 -0.06506574 0.9932717 0.09463942 -0.06674504 0.9832561 0.09268569 -0.1568973 0.9645441 0.09469956 -0.246347 0.9818503 0.09576791 -0.1637027 0.9878894 0.09738504 -0.1207929 0.9483853 0.09830242 -0.3014996 0.951383 0.0924434 -0.2938108 0.9659624 0.09326654 -0.2412846 0.9495159 0.09818053 -0.2979598 0.9564194 0.09348112 -0.2766285 0.9696719 0.09256333 -0.2262049 0.978062 0.09168088 -0.1870546 0.9719398 0.09473109 -0.2153118 0.9369654 0.09045845 -0.3375102 -0.02234995 0.04174357 -0.9988784 0.9662129 0.07822114 -0.2455894 0.9547818 0.08673453 -0.2843745 0.9474762 0.08978819 -0.3069646 0.9438639 0.09079426 -0.3176122 0.9450765 0.09061038 -0.3140387 0.9416344 0.09119087 -0.3240512 -0.0219109 0.04191792 -0.9988809 0.02011203 -0.05832189 -0.9980953 -0.01190227 -0.07666301 -0.996986 0.01535099 -0.2040801 -0.9788339 -0.0213983 0.04199326 -0.9988887 0.01614481 -0.2254475 -0.9741216 0.033724 -0.4334679 -0.9005378 0.07318502 -0.04507684 -0.9962992 0.01840317 -0.4655733 -0.884818 0.03726351 -0.636227 -0.7706016 0.0621373 -0.2982043 -0.9524774 0.04358148 -0.6281166 -0.7768979 0.05685669 -0.7218334 -0.6897274 0.04621624 -0.8096419 -0.5851019 0.06900483 -0.7139151 -0.696824 -0.01541197 -0.7910185 -0.6115981 0.04614102 -0.8089627 -0.5860464 0.04624807 -0.8097476 -0.584953 0.04736053 -0.8091074 -0.5857494 0.04539293 -0.8099535 -0.5847349 0.04492062 -0.8100743 -0.584604 0.05246245 -0.8900918 -0.4527519 0.04968523 -0.8521881 -0.5208715 0.05279755 -0.8919741 -0.4489932 0.04959404 -0.8520417 -0.5211195 0.04616034 -0.8089507 -0.5860615 0.05710166 -0.9496709 -0.3080013 0.05740612 -0.9507262 -0.3046706 0.05997067 -0.9859614 -0.1558323 0.06012225 -0.9862498 -0.1539375 0.06097602 -0.9981393 0 0.06100827 -0.9981374 1.52597e-4 0.06009143 -0.9862136 0.1541807 0.05999958 -0.9859651 0.1557976 0.05737584 -0.9506691 0.304855 0.0571022 -0.9496798 0.3079737 0.05276709 -0.8919448 0.4490548 0.05246245 -0.8900918 0.4527519 0.04968523 -0.8521881 0.5208715 0.04616385 -0.8089621 0.5860456 0.04959404 -0.8520417 0.5211195 0.04624086 -0.8096082 0.5851464 0.04615235 -0.8089556 0.5860555 -0.001220762 0.1213447 0.9926097 -0.02838307 0.130379 0.9910579 -0.02420186 0.206067 0.9782386 -0.0221616 0.04205119 0.9988697 -0.02150809 0.04199063 0.9988865 -0.03640973 0.2199846 0.9748237 -0.04153615 0.3051582 0.9513955 0.05218684 0.1132851 0.992191 -0.04330664 0.3066871 0.9508247 -0.04815942 0.4100573 0.9107874 -0.03769141 0.4048699 0.9135972 -0.05133306 0.5528838 0.8316757 -0.05066227 0.5605207 0.8265894 -0.0630533 0.6743289 0.7357342 -0.01019328 0.4591259 0.8883128 -0.07141488 0.6780754 0.7315146 -0.07745647 0.7508827 0.6558779 -0.03296047 0.6125163 0.7897706 -0.07504701 0.7440307 0.6639175 -0.08054071 0.7743082 0.6276624 -0.05905336 0.8208573 0.5680722 -0.08334839 0.8345522 0.5445877 -0.1205198 0.8700075 0.4780815 -0.07855546 0.7731337 0.6293594 -0.0979349 0.8633473 0.4950155 -0.09982728 0.9168488 0.3865524 -0.06656366 0.8278498 0.5569865 -0.04193335 0.8106811 0.5839846 -0.09070283 0.9133157 0.3970234 -0.0929917 0.9749027 0.2022807 -0.09454804 0.9746261 0.2028907 -0.09509712 0.9954681 -3.0519e-5 -0.09457707 0.9746113 -0.2029486 -0.09296137 0.9748738 -0.2024336 -0.09585893 0.995395 -3.05186e-5 -0.09744882 0.9145177 -0.3926337 -0.08920776 0.921468 -0.3780726 -0.096807 0.8641521 -0.4938317 -0.09137511 0.8443804 -0.5278942 -0.07696974 0.8323231 -0.5489206 -0.07712173 0.768013 -0.6357738 -0.07275754 0.7786951 -0.6231697 -0.06976675 0.7486045 -0.659336 -0.07944041 0.78534 -0.6139465 -0.08099895 0.8092265 -0.5818862 -0.0811209 0.8069672 -0.5849986 -0.07065099 0.7304067 -0.6793487 -0.05841469 0.6753402 -0.7351894 -0.05435538 0.6207073 -0.7821559 -0.04120081 0.5488864 -0.8348811 -0.07190293 0.6569536 -0.7504945 -0.0715689 0.6914259 -0.7188938 -0.06570786 0.7108842 -0.7002329 -0.0376299 0.4710611 -0.8812977 -0.03836208 0.4011081 -0.9152271 -0.06091582 0.5504403 -0.8326493 -0.04333716 0.3066867 -0.9508234 -0.04147511 0.3049752 -0.9514567 -0.04864734 0.3922002 -0.9185927 -0.03643995 0.2200134 -0.974816 -0.02291953 0.2099075 -0.9774526 0.001220762 0.1330631 -0.9911069 -0.003112912 0.1070304 -0.994251 -0.02148431 0.0421077 -0.9988821 -0.02499514 0.08694887 -0.9958993 0.04736614 -0.8098942 0.5846607 0.02887094 -0.7794554 0.6257922 0.04736572 -0.8097654 0.584839 0.0473712 -0.8096638 0.5849791 -0.9969175 -0.07845747 6.90967e-7 -0.9969155 -0.07848286 2.81416e-7 -0.9969168 -0.07846719 3.0957e-7 -0.9969167 -0.07846742 0 -0.9969173 -0.07846027 0 -0.9969169 -0.07846575 0 -0.996917 -0.07846379 3.26922e-7 -0.9969177 -0.07845455 0 -0.9969171 -0.07846295 2.44319e-7 -0.9969176 -0.07845556 2.6278e-7 -0.9969183 -0.07844787 4.01403e-7 -0.9969181 -0.07845044 4.44126e-7 -0.996917 -0.07846403 -1.7155e-7 -0.9969163 -0.07847231 7.84331e-7 -0.9969179 -0.07845371 -6.26776e-7 -0.9969189 -0.07844054 0 -0.9969173 -0.07846039 -1.5073e-7 -0.9969177 -0.07845485 -6.28812e-7 -0.9969169 -0.0784657 -1.48564e-7 -0.9969174 -0.07845807 0 -0.9969164 -0.0784707 0 -0.9969179 -0.07845318 3.17959e-7 -0.08273607 0.7132211 -0.6960391 -0.07455921 0.721665 -0.6882156 -0.08301216 0.7482998 -0.6581462 -0.9969173 -0.07846081 0 -0.9969183 -0.0784468 0 -0.07096064 0.6694565 -0.7394543 -0.9969131 -0.07851356 1.38264e-6 -0.07605338 0.767767 -0.6361995 -0.08093732 0.7889252 -0.6091357 -0.9969181 -0.07844954 -2.54945e-7 -0.08789467 0.7269316 -0.6810616 -0.09155809 0.7099722 -0.6982527 -0.9969211 -0.07841199 0 -0.07849669 0.7979379 -0.5976064 -0.08337777 0.804144 -0.5885581 -0.9969108 -0.07854229 1.566e-6 -0.9969168 -0.07846623 1.33959e-6 -0.08600229 0.8676527 -0.4896759 -0.9969181 -0.07844972 0 -0.08169919 0.8088133 -0.5823627 -0.08103209 0.8091136 -0.5820388 -0.08124214 0.8111096 -0.5792245 -0.9969164 -0.07847177 2.157e-6 -0.996921 -0.07841354 3.11066e-6 -0.9969174 -0.07845866 3.16366e-6 -0.08285957 0.8047299 0.5878301 -0.0806322 0.8032094 0.5902146 -0.07107961 0.7861793 0.6138974 -0.08103489 0.8081775 0.5833376 -0.07718265 0.7937702 0.6033008 -0.07312327 0.7537557 0.6530738 -0.08353084 0.8075667 0.583831 -0.07547444 0.7412242 0.6670011 -0.07925897 0.7173292 0.6922117 -0.9969167 -0.07846772 0 -0.06937086 0.6559562 0.7516044 -0.07087403 0.6682409 0.7405613 -0.07385665 0.7152803 0.6949239 -0.9969164 -0.0784713 4.4019e-7 -0.9969169 -0.07846564 0 -0.9969173 -0.07845985 0 -0.9969172 -0.07846212 2.07352e-7 -0.996919 -0.07843804 0 -0.9969183 -0.07844871 1.87139e-7 -0.996917 -0.07846331 0 -0.9969164 -0.07847142 0 -0.9969192 -0.07843565 0 -0.9969185 -0.07844513 0 -0.9969173 -0.07846057 0 -0.9969158 -0.07847893 0 -0.9969175 -0.07845771 0 -0.9969167 -0.07846754 0 -0.9969176 -0.07845568 0 -0.9969235 -0.07838165 0 -0.9969226 -0.07839268 0 -0.996916 -0.0784769 0 -0.9969086 -0.07857209 0 -0.99693 -0.07829898 0 0.02252286 -0.7971525 -0.6033578 0.03570759 -0.7753436 -0.6305294 0.04742711 -0.8100454 -0.5844461 -0.07229894 0.6973231 -0.7131013 -0.08124274 0.8110849 0.5792592 -0.08124041 0.8111417 -0.5791797 -0.07352125 0.7152227 0.6950188 - - - - - - - - - - 0.05477386 0.01459586 0.05148983 0.01559686 0.05042797 0.01612287 0.04856598 0.01647984 0.05042797 0.01612287 0.05148983 0.01559686 0.05208384 0.01561486 0.05477386 0.01459586 0.05042797 0.01612287 0.05208384 0.01561486 0.05042797 0.01612287 0.05371499 0.01512485 0.04715389 0.01756197 0.05371499 0.01512485 0.05042797 0.01612287 0.04715389 0.01756197 0.05042797 0.01612287 0.04802387 0.016846 0.04856598 0.01647984 0.04802387 0.016846 0.05042797 0.01612287 0.05599999 0.01472598 0.05272185 0.01573199 0.05148983 0.01559686 0.04983294 0.01655 0.05148983 0.01559686 0.05272185 0.01573199 0.05477386 0.01459586 0.05599999 0.01472598 0.05148983 0.01559686 0.04856598 0.01647984 0.05148983 0.01559686 0.04983294 0.01655 0.057253 0.01549887 0.05398386 0.01650798 0.05272185 0.01573199 0.05111998 0.01722186 0.05272185 0.01573199 0.05398386 0.01650798 0.05599999 0.01472598 0.057253 0.01549887 0.05272185 0.01573199 0.04983294 0.01655 0.05272185 0.01573199 0.05111998 0.01722186 0.05839186 0.01682382 0.05513298 0.01783597 0.05398386 0.01650798 0.052293 0.01842099 0.05398386 0.01650798 0.05513298 0.01783597 0.057253 0.01549887 0.05839186 0.01682382 0.05398386 0.01650798 0.05111998 0.01722186 0.05398386 0.01650798 0.052293 0.01842099 0.05765998 0.01904797 0.05603796 0.01955896 0.05513298 0.01783597 0.05294096 0.02005195 0.05513298 0.01783597 0.05603796 0.01955896 0.05928796 0.01854497 0.05765998 0.01904797 0.05513298 0.01783597 0.05839186 0.01682382 0.05928796 0.01854497 0.05513298 0.01783597 0.052293 0.01842099 0.05513298 0.01783597 0.05294096 0.02005195 0.08996796 0.024782 0.05603796 0.01955896 0.05765998 0.01904797 0.06214886 0.02351099 0.05603796 0.01955896 0.08996796 0.024782 0.05826985 0.02496784 0.05603796 0.01955896 0.06214886 0.02351099 0.05826985 0.02496784 0.05294096 0.02005195 0.05603796 0.01955896 0.08996796 0.024782 0.05765998 0.01904797 0.05928796 0.01854497 0.07152897 0.01310884 0.05928796 0.01854497 0.05839186 0.01682382 0.070719 0.01522582 0.05928796 0.01854497 0.07152897 0.01310884 0.08996796 0.024782 0.05928796 0.01854497 0.070719 0.01522582 0.070463 0.01182097 0.05839186 0.01682382 0.057253 0.01549887 0.07152897 0.01310884 0.05839186 0.01682382 0.070463 0.01182097 0.069283 0.01104086 0.057253 0.01549887 0.05599999 0.01472598 0.070463 0.01182097 0.057253 0.01549887 0.069283 0.01104086 0.06810897 0.01085084 0.05599999 0.01472598 0.05477386 0.01459586 0.069283 0.01104086 0.05599999 0.01472598 0.06810897 0.01085084 0.05208384 0.01561486 0.05371499 0.01512485 0.05477386 0.01459586 0.06225585 0.01261287 0.05477386 0.01459586 0.05371499 0.01512485 0.06595498 0.01157999 0.05477386 0.01459586 0.06225585 0.01261287 0.06810897 0.01085084 0.05477386 0.01459586 0.06595498 0.01157999 0.05326396 0.01670295 0.05371499 0.01512485 0.04715389 0.01756197 0.06225585 0.01261287 0.05371499 0.01512485 0.05326396 0.01670295 0.02385985 0.02330183 0.02869486 0.02220398 0.02874886 0.02222198 0.02917885 0.022098 0.02874886 0.02222198 0.02869486 0.02220398 0.02496695 0.0233289 0.02385985 0.02330183 0.02874886 0.02222198 0.02971899 0.022731 0.02496695 0.0233289 0.02874886 0.02222198 0.03009796 0.02210187 0.02971899 0.022731 0.02874886 0.02222198 0.02999287 0.02205985 0.03009796 0.02210187 0.02874886 0.02222198 0.02972197 0.02205985 0.02999287 0.02205985 0.02874886 0.02222198 0.02917885 0.022098 0.02972197 0.02205985 0.02874886 0.02222198 0.02385985 0.02330183 0.02864295 0.02218699 0.02869486 0.02220398 0.02917885 0.022098 0.02869486 0.02220398 0.02864295 0.02218699 0.02385985 0.02330183 0.02840799 0.02205795 0.02864295 0.02218699 0.02917885 0.022098 0.02864295 0.02218699 0.02840799 0.02205795 0.02385985 0.02330183 0.02838397 0.02192986 0.02840799 0.02205795 0.02903199 0.02182799 0.02840799 0.02205795 0.02838397 0.02192986 0.02903199 0.02182799 0.02917885 0.022098 0.02840799 0.02205795 0.02385985 0.02330183 0.02857995 0.02178984 0.02838397 0.02192986 0.02903199 0.02182799 0.02838397 0.02192986 0.02857995 0.02178984 0.02385985 0.02330183 0.02895295 0.02163797 0.02857995 0.02178984 0.02952086 0.02154296 0.02857995 0.02178984 0.02895295 0.02163797 0.02903199 0.02182799 0.02857995 0.02178984 0.02952086 0.02154296 0.02385985 0.02330183 0.02955085 0.02145385 0.02895295 0.02163797 0.03041183 0.02123785 0.02895295 0.02163797 0.02955085 0.02145385 0.02952086 0.02154296 0.02895295 0.02163797 0.03041183 0.02123785 0.02536797 0.02381891 0.02955085 0.02145385 0.02385985 0.02330183 0.02536797 0.02381891 0.03021496 0.021281 0.02955085 0.02145385 0.03041183 0.02123785 0.02955085 0.02145385 0.03021496 0.021281 0.02496695 0.0233289 0.01834297 0.02508497 0.02385985 0.02330183 0.01665097 0.02618283 0.02385985 0.02330183 0.01834297 0.02508497 0.01512783 0.02756196 0.02536797 0.02381891 0.02385985 0.02330183 0.01665097 0.02618283 0.01512783 0.02756196 0.02385985 0.02330183 0.02496695 0.0233289 0.01904886 0.02476799 0.01834297 0.02508497 0.01557284 0.02677083 0.01834297 0.02508497 0.01904886 0.02476799 0.01557284 0.02677083 0.01665097 0.02618283 0.01834297 0.02508497 0.02496695 0.0233289 0.02020382 0.02444297 0.01904886 0.02476799 0.01771098 0.02546799 0.01904886 0.02476799 0.02020382 0.02444297 0.01557284 0.02677083 0.01904886 0.02476799 0.01771098 0.02546799 0.02496695 0.0233289 0.02132797 0.024378 0.02020382 0.02444297 0.01771098 0.02546799 0.02020382 0.02444297 0.02132797 0.024378 0.02971899 0.022731 0.02132797 0.024378 0.02496695 0.0233289 0.022578 0.02453899 0.02132797 0.024378 0.02971899 0.022731 0.02291285 0.02495998 0.02132797 0.024378 0.022578 0.02453899 0.02205383 0.02537697 0.02132797 0.024378 0.02291285 0.02495998 0.01960796 0.02508985 0.02132797 0.024378 0.02205383 0.02537697 0.01771098 0.02546799 0.02132797 0.024378 0.01960796 0.02508985 0.02536797 0.02381891 0.03110986 0.02106899 0.03021496 0.021281 0.031596 0.02090787 0.03021496 0.021281 0.03110986 0.02106899 0.03041183 0.02123785 0.03021496 0.021281 0.031596 0.02090787 0.02536797 0.02381891 0.032175 0.02082896 0.03110986 0.02106899 0.03302484 0.02054697 0.03110986 0.02106899 0.032175 0.02082896 0.031596 0.02090787 0.03110986 0.02106899 0.03302484 0.02054697 0.02536797 0.02381891 0.033445 0.02054995 0.032175 0.02082896 0.03302484 0.02054697 0.032175 0.02082896 0.033445 0.02054995 0.02536797 0.02381891 0.03495287 0.02021795 0.033445 0.02054995 0.03467297 0.02014595 0.033445 0.02054995 0.03495287 0.02021795 0.03302484 0.02054697 0.033445 0.02054995 0.03467297 0.02014595 0.02536797 0.02381891 0.03615099 0.019948 0.03495287 0.02021795 0.03652 0.01969999 0.03495287 0.02021795 0.03615099 0.019948 0.03467297 0.02014595 0.03495287 0.02021795 0.03652 0.01969999 0.02645999 0.02570599 0.03615099 0.019948 0.02536797 0.02381891 0.03351783 0.022861 0.03740698 0.01965999 0.03615099 0.019948 0.03652 0.01969999 0.03615099 0.019948 0.03740698 0.01965999 0.02645999 0.02570599 0.03351783 0.022861 0.03615099 0.019948 0.01924598 0.028665 0.02536797 0.02381891 0.01512783 0.02756196 0.01924598 0.028665 0.02645999 0.02570599 0.02536797 0.02381891 0.01325899 0.02906197 0.01512783 0.02756196 0.01665097 0.02618283 0.01421684 0.02856296 0.01924598 0.028665 0.01512783 0.02756196 0.01325899 0.02906197 0.01421684 0.02856296 0.01512783 0.02756196 0.01325899 0.02906197 0.01665097 0.02618283 0.01557284 0.02677083 0.040416 0.02014297 0.03878599 0.01933383 0.03740698 0.01965999 0.03856682 0.01919597 0.03740698 0.01965999 0.03878599 0.01933383 0.03351783 0.022861 0.040416 0.02014297 0.03740698 0.01965999 0.03652 0.01969999 0.03740698 0.01965999 0.03856682 0.01919597 0.040416 0.02014297 0.04113495 0.01875185 0.03878599 0.01933383 0.04079896 0.01862984 0.03878599 0.01933383 0.04113495 0.01875185 0.03856682 0.01919597 0.03878599 0.01933383 0.04079896 0.01862984 0.040416 0.02014297 0.04379987 0.01805299 0.04113495 0.01875185 0.04321485 0.01799297 0.04113495 0.01875185 0.04379987 0.01805299 0.04079896 0.01862984 0.04113495 0.01875185 0.04321485 0.01799297 0.04715389 0.01756197 0.045816 0.01748895 0.04379987 0.01805299 0.04580599 0.01727795 0.04379987 0.01805299 0.045816 0.01748895 0.040416 0.02014297 0.04715389 0.01756197 0.04379987 0.01805299 0.04321485 0.01799297 0.04379987 0.01805299 0.04580599 0.01727795 0.04715389 0.01756197 0.04802387 0.016846 0.045816 0.01748895 0.04856598 0.01647984 0.045816 0.01748895 0.04802387 0.016846 0.04580599 0.01727795 0.045816 0.01748895 0.04856598 0.01647984 0.05326396 0.01670295 0.04715389 0.01756197 0.040416 0.02014297 0.04471898 0.02126795 0.040416 0.02014297 0.03351783 0.022861 0.05326396 0.01670295 0.040416 0.02014297 0.04471898 0.02126795 0.04471898 0.02126795 0.03351783 0.022861 0.02645999 0.02570599 0.03673595 0.02626997 0.02645999 0.02570599 0.01924598 0.028665 0.04471898 0.02126795 0.02645999 0.02570599 0.03673595 0.02626997 0.01421684 0.02856296 0.01189899 0.03172791 0.01924598 0.028665 0.03673595 0.02626997 0.01924598 0.028665 0.01189899 0.03172791 0.01087695 0.03235197 0.01189899 0.03172791 0.01421684 0.02856296 0.03673595 0.02626997 0.01189899 0.03172791 0.02945798 0.031663 0.01009386 0.03472495 0.02945798 0.031663 0.01189899 0.03172791 0.008298993 0.03681695 0.01009386 0.03472495 0.01189899 0.03172791 0.008298993 0.03681695 0.01189899 0.03172791 0.01087695 0.03235197 0.01325899 0.02906197 0.01087695 0.03235197 0.01421684 0.02856296 0.022578 0.02453899 0.02971899 0.022731 0.03069382 0.02321583 0.03009796 0.02210187 0.03069382 0.02321583 0.02971899 0.022731 0.02382493 0.02469998 0.022578 0.02453899 0.03069382 0.02321583 0.03290086 0.02415382 0.02382493 0.02469998 0.03069382 0.02321583 0.03165996 0.02313095 0.03069382 0.02321583 0.03009796 0.02210187 0.03290086 0.02415382 0.03069382 0.02321583 0.03165996 0.02313095 0.02291285 0.02495998 0.022578 0.02453899 0.02382493 0.02469998 0.03300487 0.02419096 0.02382493 0.02469998 0.03290086 0.02415382 0.027417 0.02519899 0.02382493 0.02469998 0.03300487 0.02419096 0.03661698 0.02716797 0.02382493 0.02469998 0.027417 0.02519899 0.02291285 0.02495998 0.02382493 0.02469998 0.03661698 0.02716797 0.03356099 0.023458 0.03291589 0.02303797 0.03443884 0.02385985 0.03790485 0.02596497 0.03443884 0.02385985 0.03291589 0.02303797 0.03643 0.02483797 0.03356099 0.023458 0.03443884 0.02385985 0.03600084 0.02475982 0.03643 0.02483797 0.03443884 0.02385985 0.03876495 0.027085 0.03600084 0.02475982 0.03443884 0.02385985 0.03876495 0.027085 0.03443884 0.02385985 0.03790485 0.02596497 0.03356099 0.023458 0.03143388 0.02230197 0.03291589 0.02303797 0.03724282 0.024818 0.03291589 0.02303797 0.03143388 0.02230197 0.03790485 0.02596497 0.03291589 0.02303797 0.03724282 0.024818 0.0326249 0.02321195 0.03009796 0.02210187 0.03143388 0.02230197 0.03138095 0.02227687 0.03143388 0.02230197 0.03009796 0.02210187 0.03356099 0.023458 0.0326249 0.02321195 0.03143388 0.02230197 0.03724282 0.024818 0.03143388 0.02230197 0.03138095 0.02227687 0.0326249 0.02321195 0.03165996 0.02313095 0.03009796 0.02210187 0.03080385 0.02213698 0.03133183 0.02225196 0.03009796 0.02210187 0.03138095 0.02227687 0.03009796 0.02210187 0.03133183 0.02225196 0.03026497 0.02207297 0.03080385 0.02213698 0.03009796 0.02210187 0.02999287 0.02205985 0.03026497 0.02207297 0.03009796 0.02210187 0.03411698 0.02411592 0.03165996 0.02313095 0.0326249 0.02321195 0.03290086 0.02415382 0.03165996 0.02313095 0.03411698 0.02411592 0.03531485 0.02434682 0.0326249 0.02321195 0.03356099 0.023458 0.03411698 0.02411592 0.0326249 0.02321195 0.03531485 0.02434682 0.03531485 0.02434682 0.03356099 0.023458 0.03643 0.02483797 0.03888487 0.02573496 0.03891187 0.02632898 0.04021787 0.02688795 0.042732 0.03030186 0.04021787 0.02688795 0.03891187 0.02632898 0.03994786 0.02595084 0.03888487 0.02573496 0.04021787 0.02688795 0.03994786 0.02595084 0.04021787 0.02688795 0.04120987 0.02709496 0.042732 0.03030186 0.04120987 0.02709496 0.04021787 0.02688795 0.03888487 0.02573496 0.03754097 0.02563196 0.03891187 0.02632898 0.04114699 0.02924299 0.03891187 0.02632898 0.03754097 0.02563196 0.042732 0.03030186 0.03891187 0.02632898 0.04114699 0.02924299 0.03888487 0.02573496 0.03741395 0.025563 0.03754097 0.02563196 0.04114699 0.02924299 0.03754097 0.02563196 0.03741395 0.025563 0.03888487 0.02573496 0.03643 0.02483797 0.03741395 0.025563 0.03600084 0.02475982 0.03741395 0.025563 0.03643 0.02483797 0.03983891 0.02817696 0.03741395 0.025563 0.03600084 0.02475982 0.04114699 0.02924299 0.03741395 0.025563 0.03983891 0.02817696 0.03888487 0.02573496 0.03531485 0.02434682 0.03643 0.02483797 0.03725183 0.025074 0.03411698 0.02411592 0.03531485 0.02434682 0.03888487 0.02573496 0.03725183 0.025074 0.03531485 0.02434682 0.03300487 0.02419096 0.03290086 0.02415382 0.03411698 0.02411592 0.03549796 0.02497684 0.03300487 0.02419096 0.03411698 0.02411592 0.03725183 0.025074 0.03549796 0.02497684 0.03411698 0.02411592 0.027417 0.02519899 0.03300487 0.02419096 0.03549796 0.02497684 0.03672498 0.02519297 0.03549796 0.02497684 0.03725183 0.025074 0.03100699 0.02573299 0.03549796 0.02497684 0.03672498 0.02519297 0.03100699 0.02573299 0.027417 0.02519899 0.03549796 0.02497684 0.03840595 0.02529597 0.03725183 0.025074 0.03888487 0.02573496 0.03672498 0.02519297 0.03725183 0.025074 0.03840595 0.02529597 0.2258239 0.09735 0.225709 0.09752196 0.225702 0.09753799 0.03840595 0.02529597 0.03888487 0.02573496 0.03994786 0.02595084 0.03983891 0.02817696 0.03600084 0.02475982 0.03876495 0.027085 0.04159283 0.02613782 0.04120987 0.02709496 0.04276084 0.02730786 0.04385387 0.03094995 0.04276084 0.02730786 0.04120987 0.02709496 0.04536998 0.026519 0.04159283 0.02613782 0.04276084 0.02730786 0.04452782 0.02753984 0.04276084 0.02730786 0.04649198 0.02781885 0.04582285 0.02977287 0.04649198 0.02781885 0.04276084 0.02730786 0.04536998 0.026519 0.04276084 0.02730786 0.04452782 0.02753984 0.04429584 0.02967482 0.04276084 0.02730786 0.04385387 0.03094995 0.04582285 0.02977287 0.04276084 0.02730786 0.04429584 0.02967482 0.04159283 0.02613782 0.03994786 0.02595084 0.04120987 0.02709496 0.04385387 0.03094995 0.04120987 0.02709496 0.042732 0.03030186 0.04014986 0.02546083 0.03840595 0.02529597 0.03994786 0.02595084 0.04159283 0.02613782 0.04014986 0.02546083 0.03994786 0.02595084 0.04014986 0.02546083 0.03672498 0.02519297 0.03840595 0.02529597 0.04014986 0.02546083 0.03859299 0.02534896 0.03672498 0.02519297 0.03100699 0.02573299 0.03672498 0.02519297 0.03859299 0.02534896 0.228227 0.09265297 0.2284229 0.09219199 0.229303 0.09027796 0.04037797 0.02546 0.03859299 0.02534896 0.04014986 0.02546083 0.03100699 0.02573299 0.03859299 0.02534896 0.04037797 0.02546 0.04393386 0.02574497 0.04014986 0.02546083 0.04159283 0.02613782 0.04235297 0.02558696 0.04037797 0.02546 0.04014986 0.02546083 0.04393386 0.02574497 0.04235297 0.02558696 0.04014986 0.02546083 0.04536998 0.026519 0.04393386 0.02574497 0.04159283 0.02613782 0.04536998 0.026519 0.04452782 0.02753984 0.04649198 0.02781885 0.04768699 0.02744698 0.04536998 0.026519 0.04649198 0.02781885 0.04733383 0.02870082 0.04768699 0.02744698 0.04649198 0.02781885 0.04733383 0.02870082 0.04649198 0.02781885 0.04582285 0.02977287 0.03100699 0.02573299 0.04037797 0.02546 0.04235297 0.02558696 0.04677498 0.02583783 0.04235297 0.02558696 0.04393386 0.02574497 0.04405587 0.02568387 0.04235297 0.02558696 0.04677498 0.02583783 0.03100699 0.02573299 0.04235297 0.02558696 0.04405587 0.02568387 0.04781585 0.02631795 0.04393386 0.02574497 0.04536998 0.026519 0.04677498 0.02583783 0.04393386 0.02574497 0.04781585 0.02631795 0.04768699 0.02744698 0.04842787 0.027242 0.04536998 0.026519 0.04781585 0.02631795 0.04536998 0.026519 0.04842787 0.027242 0.05397486 0.026133 0.05559682 0.02628898 0.05760395 0.02625 0.058025 0.02631998 0.05760395 0.02625 0.05559682 0.02628898 0.05733686 0.02618283 0.05397486 0.026133 0.05760395 0.02625 0.05852997 0.02625596 0.05733686 0.02618283 0.05760395 0.02625 0.06066387 0.026317 0.05852997 0.02625596 0.05760395 0.02625 0.06066387 0.026317 0.05760395 0.02625 0.058025 0.02631998 0.05397486 0.026133 0.05511695 0.02631199 0.05559682 0.02628898 0.05329185 0.026802 0.05559682 0.02628898 0.05511695 0.02631199 0.056728 0.02650797 0.05559682 0.02628898 0.05329185 0.026802 0.05844783 0.02633899 0.058025 0.02631998 0.05559682 0.02628898 0.056728 0.02650797 0.05844783 0.02633899 0.05559682 0.02628898 0.05397486 0.026133 0.05287587 0.02648496 0.05511695 0.02631199 0.05329185 0.026802 0.05511695 0.02631199 0.05287587 0.02648496 0.05075883 0.02618098 0.05121994 0.02668792 0.05287587 0.02648496 0.05329185 0.026802 0.05287587 0.02648496 0.05121994 0.02668792 0.05397486 0.026133 0.05075883 0.02618098 0.05287587 0.02648496 0.04781585 0.02631795 0.05087095 0.02673995 0.05121994 0.02668792 0.04963582 0.02770799 0.05121994 0.02668792 0.05087095 0.02673995 0.05075883 0.02618098 0.04781585 0.02631795 0.05121994 0.02668792 0.05132198 0.02771699 0.05121994 0.02668792 0.04963582 0.02770799 0.05132198 0.02771699 0.05329185 0.026802 0.05121994 0.02668792 0.04781585 0.02631795 0.04913687 0.027067 0.05087095 0.02673995 0.04963582 0.02770799 0.05087095 0.02673995 0.04913687 0.027067 0.04781585 0.02631795 0.04842787 0.027242 0.04913687 0.027067 0.04963582 0.02770799 0.04913687 0.027067 0.04842787 0.027242 0.04733383 0.02870082 0.04842787 0.027242 0.04768699 0.02744698 0.04845899 0.029127 0.04842787 0.027242 0.04733383 0.02870082 0.04845899 0.029127 0.04963582 0.02770799 0.04842787 0.027242 0.04677498 0.02583783 0.04781585 0.02631795 0.05075883 0.02618098 0.05004698 0.02592384 0.05075883 0.02618098 0.05397486 0.026133 0.05004698 0.02592384 0.04677498 0.02583783 0.05075883 0.02618098 0.05351787 0.02602487 0.05397486 0.026133 0.05733686 0.02618283 0.05351787 0.02602487 0.05004698 0.02592384 0.05397486 0.026133 0.05351787 0.02602487 0.05733686 0.02618283 0.05720198 0.02616482 0.05852997 0.02625596 0.05720198 0.02616482 0.05733686 0.02618283 0.05706685 0.02615886 0.05351787 0.02602487 0.05720198 0.02616482 0.05852997 0.02625596 0.05706685 0.02615886 0.05720198 0.02616482 0.04600983 0.025774 0.04677498 0.02583783 0.05004698 0.02592384 0.04600983 0.025774 0.04405587 0.02568387 0.04677498 0.02583783 0.05084395 0.02595496 0.05004698 0.02592384 0.05351787 0.02602487 0.04823899 0.02586096 0.04600983 0.025774 0.05004698 0.02592384 0.05084395 0.02595496 0.04823899 0.02586096 0.05004698 0.02592384 0.05370485 0.02605897 0.05351787 0.02602487 0.05706685 0.02615886 0.05370485 0.02605897 0.05084395 0.02595496 0.05351787 0.02602487 0.05370485 0.02605897 0.05706685 0.02615886 0.05679595 0.026178 0.05852997 0.02625596 0.05679595 0.026178 0.05706685 0.02615886 0.03458899 0.02629697 0.05370485 0.02605897 0.05679595 0.026178 0.05863696 0.02626097 0.05679595 0.026178 0.05852997 0.02625596 0.03458899 0.02629697 0.05679595 0.026178 0.05863696 0.02626097 0.03458899 0.02629697 0.04405587 0.02568387 0.04600983 0.025774 0.03458899 0.02629697 0.03100699 0.02573299 0.04405587 0.02568387 0.03458899 0.02629697 0.04600983 0.025774 0.04823899 0.02586096 0.03458899 0.02629697 0.04823899 0.02586096 0.05084395 0.02595496 0.03458899 0.02629697 0.05084395 0.02595496 0.05370485 0.02605897 0.0609079 0.02634096 0.06111097 0.02638 0.06080389 0.02637583 0.05761384 0.02644598 0.06080389 0.02637583 0.06111097 0.02638 0.05968087 0.02631199 0.0609079 0.02634096 0.06080389 0.02637583 0.03458899 0.02629697 0.05968087 0.02631199 0.06080389 0.02637583 0.05761384 0.02644598 0.03458899 0.02629697 0.06080389 0.02637583 0.06234598 0.02644383 0.06146287 0.02639389 0.06111097 0.02638 0.03815895 0.0268839 0.06111097 0.02638 0.06146287 0.02639389 0.0609079 0.02634096 0.06234598 0.02644383 0.06111097 0.02638 0.05761384 0.02644598 0.06111097 0.02638 0.03815895 0.0268839 0.06234598 0.02644383 0.06187283 0.02641385 0.06146287 0.02639389 0.03815895 0.0268839 0.06146287 0.02639389 0.06187283 0.02641385 0.03815895 0.0268839 0.06187283 0.02641385 0.06234598 0.02644383 0.06295597 0.02648997 0.06234598 0.02644383 0.0609079 0.02634096 0.03834682 0.02698493 0.03815895 0.0268839 0.06234598 0.02644383 0.03834682 0.02698493 0.06234598 0.02644383 0.06295597 0.02648997 0.05968087 0.02631199 0.05962491 0.02628386 0.0609079 0.02634096 0.06066387 0.026317 0.0609079 0.02634096 0.05962491 0.02628386 0.06356 0.02653586 0.06295597 0.02648997 0.0609079 0.02634096 0.06066387 0.026317 0.06356 0.02653586 0.0609079 0.02634096 0.05863696 0.02626097 0.05852997 0.02625596 0.05962491 0.02628386 0.06066387 0.026317 0.05962491 0.02628386 0.05852997 0.02625596 0.05968087 0.02631199 0.05863696 0.02626097 0.05962491 0.02628386 0.03458899 0.02629697 0.05863696 0.02626097 0.05968087 0.02631199 0.03661698 0.02716797 0.027417 0.02519899 0.03100699 0.02573299 0.03661698 0.02716797 0.03100699 0.02573299 0.03458899 0.02629697 0.05761384 0.02644598 0.03815895 0.0268839 0.03458899 0.02629697 0.03661698 0.02716797 0.03458899 0.02629697 0.03815895 0.0268839 0.03702396 0.02736896 0.03661698 0.02716797 0.03815895 0.0268839 0.03731983 0.027278 0.03815895 0.0268839 0.03834682 0.02698493 0.03731983 0.027278 0.03702396 0.02736896 0.03815895 0.0268839 0.02004498 0.02742499 0.03410089 0.02898997 0.03331995 0.03036195 0.033508 0.03044492 0.03331995 0.03036195 0.03410089 0.02898997 0.03104794 0.02999997 0.02004498 0.02742499 0.03331995 0.03036195 0.033508 0.03044492 0.03104794 0.02999997 0.03331995 0.03036195 0.02059584 0.02662897 0.03522884 0.02788895 0.03410089 0.02898997 0.035133 0.02848196 0.03410089 0.02898997 0.03522884 0.02788895 0.02004498 0.02742499 0.02059584 0.02662897 0.03410089 0.02898997 0.033508 0.03044492 0.03410089 0.02898997 0.03369086 0.03053987 0.034298 0.02943295 0.03369086 0.03053987 0.03410089 0.02898997 0.03448587 0.02917695 0.034298 0.02943295 0.03410089 0.02898997 0.035133 0.02848196 0.03448587 0.02917695 0.03410089 0.02898997 0.02205383 0.02537697 0.03661698 0.02716797 0.03522884 0.02788895 0.03615885 0.02774995 0.03522884 0.02788895 0.03661698 0.02716797 0.02127283 0.02593886 0.02205383 0.02537697 0.03522884 0.02788895 0.02059584 0.02662897 0.02127283 0.02593886 0.03522884 0.02788895 0.03562682 0.02808499 0.035133 0.02848196 0.03522884 0.02788895 0.03615885 0.02774995 0.03562682 0.02808499 0.03522884 0.02788895 0.02205383 0.02537697 0.02291285 0.02495998 0.03661698 0.02716797 0.03702396 0.02736896 0.03615885 0.02774995 0.03661698 0.02716797 0.01960796 0.02508985 0.02205383 0.02537697 0.02127283 0.02593886 0.01960796 0.02508985 0.02127283 0.02593886 0.02059584 0.02662897 0.01820397 0.02633798 0.02059584 0.02662897 0.02004498 0.02742499 0.01960796 0.02508985 0.02059584 0.02662897 0.01820397 0.02633798 0.019885 0.02833497 0.01963299 0.028301 0.02004498 0.02742499 0.01820397 0.02633798 0.02004498 0.02742499 0.01963299 0.028301 0.02663499 0.02931886 0.019885 0.02833497 0.02004498 0.02742499 0.03104794 0.02999997 0.02663499 0.02931886 0.02004498 0.02742499 0.01609599 0.04047298 0.01963299 0.028301 0.019885 0.02833497 0.01845699 0.02814197 0.01963299 0.028301 0.01609599 0.04047298 0.01820397 0.02633798 0.01963299 0.028301 0.01845699 0.02814197 0.02860999 0.03127098 0.019885 0.02833497 0.02663499 0.02931886 0.020675 0.03956395 0.01609599 0.04047298 0.019885 0.02833497 0.02167296 0.03767287 0.020675 0.03956395 0.019885 0.02833497 0.02268898 0.03600895 0.02167296 0.03767287 0.019885 0.02833497 0.023696 0.03457999 0.02268898 0.03600895 0.019885 0.02833497 0.02560496 0.03246086 0.023696 0.03457999 0.019885 0.02833497 0.02727288 0.03135496 0.02560496 0.03246086 0.019885 0.02833497 0.02860999 0.03127098 0.02727288 0.03135496 0.019885 0.02833497 0.030366 0.03191 0.02663499 0.02931886 0.03104794 0.02999997 0.03027182 0.03187495 0.02663499 0.02931886 0.030366 0.03191 0.03027182 0.03187495 0.02860999 0.03127098 0.02663499 0.02931886 0.03369086 0.03053987 0.03477895 0.03187882 0.03104794 0.02999997 0.030366 0.03191 0.03104794 0.02999997 0.03477895 0.03187882 0.033508 0.03044492 0.03369086 0.03053987 0.03104794 0.02999997 0.01251 0.073291 5.48e-4 0.07626497 2.09e-4 0.06944096 0 0.06944096 2.09e-4 0.06944096 5.48e-4 0.07626497 0.01240599 0.07175797 0.01251 0.073291 2.09e-4 0.06944096 0.012407 0.06710195 0.01240599 0.07175797 2.09e-4 0.06944096 5.64e-4 0.06246298 0.012407 0.06710195 2.09e-4 0.06944096 4.02e-4 0.06195282 5.64e-4 0.06246298 2.09e-4 0.06944096 4.02e-4 0.06195282 2.09e-4 0.06944096 0 0.06944096 0.01364094 0.08593195 0.001003921 0.07985496 5.48e-4 0.07626497 4.03e-4 0.07692998 5.48e-4 0.07626497 0.001003921 0.07985496 0.01251 0.073291 0.01364094 0.08593195 5.48e-4 0.07626497 4.03e-4 0.07692998 0 0.06944096 5.48e-4 0.07626497 0.01364094 0.08593195 0.001663923 0.08350098 0.001003921 0.07985496 0.001537919 0.08401095 0.001003921 0.07985496 0.001663923 0.08350098 0.001537919 0.08401095 4.03e-4 0.07692998 0.001003921 0.07985496 0.01364094 0.08593195 0.002532899 0.08714395 0.001663923 0.08350098 0.001537919 0.08401095 0.001663923 0.08350098 0.002532899 0.08714395 0.01609599 0.09840798 0.003615975 0.09077996 0.002532899 0.08714395 0.003242969 0.090451 0.002532899 0.08714395 0.003615975 0.09077996 0.01364094 0.08593195 0.01609599 0.09840798 0.002532899 0.08714395 0.003242969 0.090451 0.001537919 0.08401095 0.002532899 0.08714395 0.01609599 0.09840798 0.0049299 0.09441298 0.003615975 0.09077996 0.003242969 0.090451 0.003615975 0.09077996 0.0049299 0.09441298 0.01609599 0.09840798 0.006437957 0.09795296 0.0049299 0.09441298 0.00534296 0.09617197 0.0049299 0.09441298 0.006437957 0.09795296 0.00534296 0.09617197 0.003242969 0.090451 0.0049299 0.09441298 0.01609599 0.09840798 0.008098959 0.101308 0.006437957 0.09795296 0.007693946 0.101206 0.006437957 0.09795296 0.008098959 0.101308 0.007693946 0.101206 0.00534296 0.09617197 0.006437957 0.09795296 0.019885 0.110547 0.009909987 0.104506 0.008098959 0.101308 0.007693946 0.101206 0.008098959 0.101308 0.009909987 0.104506 0.01609599 0.09840798 0.019885 0.110547 0.008098959 0.101308 0.019885 0.110547 0.01185786 0.107345 0.009909987 0.104506 0.01019597 0.105623 0.009909987 0.104506 0.01185786 0.107345 0.01019597 0.105623 0.007693946 0.101206 0.009909987 0.104506 0.019885 0.110547 0.01382082 0.109439 0.01185786 0.107345 0.01243084 0.108781 0.01185786 0.107345 0.01382082 0.109439 0.01243084 0.108781 0.01019597 0.105623 0.01185786 0.107345 0.019885 0.110547 0.01475197 0.110149 0.01382082 0.109439 0.01457285 0.110973 0.01382082 0.109439 0.01475197 0.110149 0.01457285 0.110973 0.01243084 0.108781 0.01382082 0.109439 0.019885 0.110547 0.01563996 0.110631 0.01475197 0.110149 0.01457285 0.110973 0.01475197 0.110149 0.01563996 0.110631 0.019885 0.110547 0.016478 0.11088 0.01563996 0.110631 0.01651698 0.112206 0.01563996 0.110631 0.016478 0.11088 0.01651698 0.112206 0.01457285 0.110973 0.01563996 0.110631 0.016478 0.11088 0.019885 0.110547 0.01845699 0.11074 0.01651698 0.112206 0.016478 0.11088 0.01726984 0.1109 0.01845699 0.11074 0.01726984 0.1109 0.016478 0.11088 0.02004384 0.111457 0.01726984 0.1109 0.01845699 0.11074 0.01820397 0.112544 0.01651698 0.112206 0.01726984 0.1109 0.02004384 0.111457 0.01820397 0.112544 0.01726984 0.1109 0.019885 0.110547 0.01963299 0.110581 0.01845699 0.11074 0.02004384 0.111457 0.01845699 0.11074 0.01963299 0.110581 0.034096 0.109883 0.01963299 0.110581 0.019885 0.110547 0.034096 0.109883 0.02004384 0.111457 0.01963299 0.110581 0.02560496 0.10642 0.019885 0.110547 0.01609599 0.09840798 0.03104895 0.108883 0.026636 0.109565 0.019885 0.110547 0.034096 0.109883 0.019885 0.110547 0.026636 0.109565 0.02860999 0.10761 0.03104895 0.108883 0.019885 0.110547 0.02727288 0.107526 0.02860999 0.10761 0.019885 0.110547 0.02560496 0.10642 0.02727288 0.107526 0.019885 0.110547 0.01969397 0.09721499 0.01609599 0.09840798 0.01364094 0.08593195 0.02369499 0.1043 0.02560496 0.10642 0.01609599 0.09840798 0.02268797 0.102871 0.02369499 0.1043 0.01609599 0.09840798 0.02167195 0.101207 0.02268797 0.102871 0.01609599 0.09840798 0.02067399 0.099316 0.02167195 0.101207 0.01609599 0.09840798 0.01969397 0.09721499 0.02067399 0.099316 0.01609599 0.09840798 0.012869 0.07626998 0.01364094 0.08593195 0.01251 0.073291 0.01642698 0.08890795 0.01969397 0.09721499 0.01364094 0.08593195 0.01374197 0.080361 0.01642698 0.08890795 0.01364094 0.08593195 0.012869 0.07626998 0.01374197 0.080361 0.01364094 0.08593195 0.02354699 0.07178097 0.01251 0.073291 0.01240599 0.07175797 0.02380895 0.07630795 0.012869 0.07626998 0.01251 0.073291 0.02380895 0.07630795 0.01251 0.073291 0.02354699 0.07178097 0.02354699 0.067101 0.01240599 0.07175797 0.012407 0.06710195 0.02354699 0.07178097 0.01240599 0.07175797 0.02354699 0.067101 5.64e-4 0.06246298 0.01251 0.06558597 0.012407 0.06710195 0.02354699 0.067101 0.012407 0.06710195 0.01251 0.06558597 0.001708984 0.0551669 0.01364094 0.05294698 0.01251 0.06558597 0.01287084 0.06259799 0.01251 0.06558597 0.01364094 0.05294698 0.001032948 0.05883193 0.001708984 0.0551669 0.01251 0.06558597 5.64e-4 0.06246298 0.001032948 0.05883193 0.01251 0.06558597 0.02354699 0.067101 0.01251 0.06558597 0.01287084 0.06259799 0.006490886 0.04081487 0.01609599 0.04047298 0.01364094 0.05294698 0.01642698 0.04997396 0.01364094 0.05294698 0.01609599 0.04047298 0.004993975 0.04430598 0.006490886 0.04081487 0.01364094 0.05294698 0.003681898 0.047903 0.004993975 0.04430598 0.01364094 0.05294698 0.002590954 0.05152183 0.003681898 0.047903 0.01364094 0.05294698 0.001708984 0.0551669 0.002590954 0.05152183 0.01364094 0.05294698 0.01374197 0.05851984 0.01287084 0.06259799 0.01364094 0.05294698 0.01642698 0.04997396 0.01374197 0.05851984 0.01364094 0.05294698 0.01726984 0.02798187 0.01845699 0.02814197 0.01609599 0.04047298 0.01647686 0.02800196 0.01726984 0.02798187 0.01609599 0.04047298 0.01563799 0.02825099 0.01647686 0.02800196 0.01609599 0.04047298 0.01475 0.02873384 0.01563799 0.02825099 0.01609599 0.04047298 0.01381886 0.02944499 0.01475 0.02873384 0.01609599 0.04047298 0.0118559 0.03153896 0.01381886 0.02944499 0.01609599 0.04047298 0.009909987 0.03437584 0.0118559 0.03153896 0.01609599 0.04047298 0.008130967 0.03751283 0.009909987 0.03437584 0.01609599 0.04047298 0.006490886 0.04081487 0.008130967 0.03751283 0.01609599 0.04047298 0.01969283 0.04166597 0.01642698 0.04997396 0.01609599 0.04047298 0.020675 0.03956395 0.01969283 0.04166597 0.01609599 0.04047298 0.01820397 0.02633798 0.01845699 0.02814197 0.01726984 0.02798187 0.01820397 0.02633798 0.01726984 0.02798187 0.01647686 0.02800196 0.01651698 0.02667587 0.01647686 0.02800196 0.01563799 0.02825099 0.01651698 0.02667587 0.01820397 0.02633798 0.01647686 0.02800196 0.01651698 0.02667587 0.01563799 0.02825099 0.01475 0.02873384 0.01457285 0.02790898 0.01475 0.02873384 0.01381886 0.02944499 0.01457285 0.02790898 0.01651698 0.02667587 0.01475 0.02873384 0.01243084 0.030101 0.01381886 0.02944499 0.0118559 0.03153896 0.01243084 0.030101 0.01457285 0.02790898 0.01381886 0.02944499 0.01243084 0.030101 0.0118559 0.03153896 0.009909987 0.03437584 0.01019597 0.03325897 0.009909987 0.03437584 0.008130967 0.03751283 0.01243084 0.030101 0.009909987 0.03437584 0.01019597 0.03325897 0.007694959 0.03767496 0.008130967 0.03751283 0.006490886 0.04081487 0.007694959 0.03767496 0.01019597 0.03325897 0.008130967 0.03751283 0.005343973 0.04270899 0.006490886 0.04081487 0.004993975 0.04430598 0.005343973 0.04270899 0.007694959 0.03767496 0.006490886 0.04081487 0.005343973 0.04270899 0.004993975 0.04430598 0.003681898 0.047903 0.003242969 0.04843199 0.003681898 0.047903 0.002590954 0.05152183 0.003242969 0.04843199 0.005343973 0.04270899 0.003681898 0.047903 0.003242969 0.04843199 0.002590954 0.05152183 0.001708984 0.0551669 0.001536965 0.05487185 0.001708984 0.0551669 0.001032948 0.05883193 0.001536965 0.05487185 0.003242969 0.04843199 0.001708984 0.0551669 4.02e-4 0.06195282 0.001032948 0.05883193 5.64e-4 0.06246298 4.02e-4 0.06195282 0.001536965 0.05487185 0.001032948 0.05883193 0.034096 0.109883 0.026636 0.109565 0.03104895 0.108883 0.03027182 0.107007 0.030366 0.106972 0.03104895 0.108883 0.033508 0.108437 0.03104895 0.108883 0.030366 0.106972 0.02860999 0.10761 0.03027182 0.107007 0.03104895 0.108883 0.033508 0.108437 0.03331995 0.108519 0.03104895 0.108883 0.034096 0.109883 0.03104895 0.108883 0.03331995 0.108519 0.03534787 0.10644 0.030366 0.106972 0.03027182 0.107007 0.03369086 0.108342 0.033508 0.108437 0.030366 0.106972 0.03477483 0.107011 0.03369086 0.108342 0.030366 0.106972 0.03190785 0.106412 0.03477483 0.107011 0.030366 0.106972 0.03534787 0.10644 0.03190785 0.106412 0.030366 0.106972 0.03534787 0.10644 0.03027182 0.107007 0.02860999 0.10761 0.03213596 0.10764 0.02860999 0.10761 0.02727288 0.107526 0.03534787 0.10644 0.02860999 0.10761 0.03213596 0.10764 0.03099083 0.107547 0.02727288 0.107526 0.02560496 0.10642 0.03213596 0.10764 0.02727288 0.107526 0.03099083 0.107547 0.02986997 0.106412 0.02560496 0.10642 0.02369499 0.1043 0.03099083 0.107547 0.02560496 0.10642 0.02986997 0.106412 0.02881598 0.104264 0.02369499 0.1043 0.02268797 0.102871 0.02986997 0.106412 0.02369499 0.1043 0.02881598 0.104264 0.02881598 0.104264 0.02268797 0.102871 0.02167195 0.101207 0.02787399 0.101176 0.02167195 0.101207 0.02067399 0.099316 0.02881598 0.104264 0.02167195 0.101207 0.02787399 0.101176 0.02787399 0.101176 0.02067399 0.099316 0.01969397 0.09721499 0.02708399 0.09726297 0.01969397 0.09721499 0.01642698 0.08890795 0.02787399 0.101176 0.01969397 0.09721499 0.02708399 0.09726297 0.02708399 0.09726297 0.01642698 0.08890795 0.01374197 0.080361 0.02431398 0.080388 0.01374197 0.080361 0.012869 0.07626998 0.02708399 0.09726297 0.01374197 0.080361 0.02431398 0.080388 0.02431398 0.080388 0.012869 0.07626998 0.02380895 0.07630795 0.034298 0.109449 0.03331995 0.108519 0.033508 0.108437 0.034298 0.109449 0.034096 0.109883 0.03331995 0.108519 0.034298 0.109449 0.033508 0.108437 0.03369086 0.108342 0.034298 0.109449 0.03369086 0.108342 0.03477483 0.107011 0.03323882 0.105107 0.03540086 0.104462 0.03477483 0.107011 0.03542697 0.108035 0.03477483 0.107011 0.03540086 0.104462 0.03190785 0.106412 0.03323882 0.105107 0.03477483 0.107011 0.03542697 0.108035 0.034298 0.109449 0.03477483 0.107011 0.03406995 0.102288 0.03560882 0.100744 0.03540086 0.104462 0.03604996 0.10545 0.03540086 0.104462 0.03560882 0.100744 0.03371793 0.103883 0.03406995 0.102288 0.03540086 0.104462 0.03323882 0.105107 0.03371793 0.103883 0.03540086 0.104462 0.03604996 0.10545 0.03542697 0.108035 0.03540086 0.104462 0.03441184 0.098109 0.03550398 0.09598195 0.03560882 0.100744 0.03615885 0.09727197 0.03560882 0.100744 0.03550398 0.09598195 0.03429198 0.100339 0.03441184 0.098109 0.03560882 0.100744 0.03406995 0.102288 0.03429198 0.100339 0.03560882 0.100744 0.03625386 0.101817 0.03604996 0.10545 0.03560882 0.100744 0.03615885 0.09727197 0.03625386 0.101817 0.03560882 0.100744 0.03444099 0.095618 0.03537595 0.09323799 0.03550398 0.09598195 0.03615885 0.09727197 0.03550398 0.09598195 0.03537595 0.09323799 0.03441184 0.098109 0.03444099 0.095618 0.03550398 0.09598195 0.03440994 0.092848 0.03521895 0.09028798 0.03537595 0.09323799 0.03588998 0.09195196 0.03537595 0.09323799 0.03521895 0.09028798 0.03444099 0.095618 0.03440994 0.092848 0.03537595 0.09323799 0.03588998 0.09195196 0.03615885 0.09727197 0.03537595 0.09323799 0.03423684 0.08672899 0.035052 0.087134 0.03521895 0.09028798 0.03588998 0.09195196 0.03521895 0.09028798 0.035052 0.087134 0.03440994 0.092848 0.03423684 0.08672899 0.03521895 0.09028798 0.03423684 0.08672899 0.03489089 0.08382397 0.035052 0.087134 0.03556984 0.08600097 0.035052 0.087134 0.03489089 0.08382397 0.03556984 0.08600097 0.03588998 0.09195196 0.035052 0.087134 0.03403896 0.08015197 0.03474897 0.08037197 0.03489089 0.08382397 0.03556984 0.08600097 0.03489089 0.08382397 0.03474897 0.08037197 0.03423684 0.08672899 0.03403896 0.08015197 0.03489089 0.08382397 0.03403896 0.08015197 0.034639 0.07685196 0.03474897 0.08037197 0.03529298 0.07957696 0.03474897 0.08037197 0.034639 0.07685196 0.03529298 0.07957696 0.03556984 0.08600097 0.03474897 0.08037197 0.03391283 0.07310301 0.03456896 0.07326698 0.034639 0.07685196 0.03529298 0.07957696 0.034639 0.07685196 0.03456896 0.07326698 0.03403896 0.08015197 0.03391283 0.07310301 0.034639 0.07685196 0.03391283 0.07310301 0.03454285 0.06964397 0.03456896 0.07326698 0.03513383 0.07285398 0.03456896 0.07326698 0.03454285 0.06964397 0.03513383 0.07285398 0.03529298 0.07957696 0.03456896 0.07326698 0.033912 0.06587797 0.03456383 0.06601595 0.03454285 0.06964397 0.03513383 0.06602698 0.03454285 0.06964397 0.03456383 0.06601595 0.03391283 0.07310301 0.033912 0.06587797 0.03454285 0.06964397 0.03513383 0.06602698 0.03513383 0.07285398 0.03454285 0.06964397 0.033912 0.06587797 0.03463 0.06241887 0.03456383 0.06601595 0.03513383 0.06602698 0.03456383 0.06601595 0.03463 0.06241887 0.03396499 0.06224685 0.03473585 0.058878 0.03463 0.06241887 0.03529298 0.05930387 0.03463 0.06241887 0.03473585 0.058878 0.033912 0.06587797 0.03396499 0.06224685 0.03463 0.06241887 0.03529298 0.05930387 0.03513383 0.06602698 0.03463 0.06241887 0.03404086 0.05869096 0.03487485 0.05539697 0.03473585 0.058878 0.03529298 0.05930387 0.03473585 0.058878 0.03487485 0.05539697 0.03396499 0.06224685 0.03404086 0.05869096 0.03473585 0.058878 0.03413999 0.05525696 0.03503698 0.05205297 0.03487485 0.05539697 0.03556895 0.05287986 0.03487485 0.05539697 0.03503698 0.05205297 0.03404086 0.05869096 0.03413999 0.05525696 0.03487485 0.05539697 0.03556895 0.05287986 0.03529298 0.05930387 0.03487485 0.05539697 0.03424495 0.051907 0.03520482 0.04885995 0.03503698 0.05205297 0.03556895 0.05287986 0.03503698 0.05205297 0.03520482 0.04885995 0.03413999 0.05525696 0.03424495 0.051907 0.03503698 0.05205297 0.03434598 0.04868698 0.03536397 0.04586786 0.03520482 0.04885995 0.03588998 0.04692995 0.03520482 0.04885995 0.03536397 0.04586786 0.03424495 0.051907 0.03434598 0.04868698 0.03520482 0.04885995 0.03588998 0.04692995 0.03556895 0.05287986 0.03520482 0.04885995 0.03441596 0.04566997 0.03549587 0.04308187 0.03536397 0.04586786 0.03588998 0.04692995 0.03536397 0.04586786 0.03549587 0.04308187 0.03434598 0.04868698 0.03441596 0.04566997 0.03536397 0.04586786 0.03440195 0.04047387 0.03558397 0.04053884 0.03549587 0.04308187 0.03615999 0.04161083 0.03549587 0.04308187 0.03558397 0.04053884 0.03444099 0.04290884 0.03440195 0.04047387 0.03549587 0.04308187 0.03441596 0.04566997 0.03444099 0.04290884 0.03549587 0.04308187 0.03615999 0.04161083 0.03588998 0.04692995 0.03549587 0.04308187 0.03404682 0.03644984 0.03560996 0.03823983 0.03558397 0.04053884 0.03615999 0.04161083 0.03558397 0.04053884 0.03560996 0.03823983 0.03440195 0.04047387 0.03404682 0.03644984 0.03558397 0.04053884 0.03404682 0.03644984 0.03540599 0.03446286 0.03560996 0.03823983 0.03625386 0.03706485 0.03560996 0.03823983 0.03540599 0.03446286 0.03625386 0.03706485 0.03615999 0.04161083 0.03560996 0.03823983 0.03190785 0.03246897 0.03477895 0.03187882 0.03540599 0.03446286 0.03604882 0.03343182 0.03540599 0.03446286 0.03477895 0.03187882 0.03322494 0.033746 0.03190785 0.03246897 0.03540599 0.03446286 0.03404682 0.03644984 0.03322494 0.033746 0.03540599 0.03446286 0.03604882 0.03343182 0.03625386 0.03706485 0.03540599 0.03446286 0.03542697 0.03084695 0.03477895 0.03187882 0.03369086 0.03053987 0.03190785 0.03246897 0.030366 0.03191 0.03477895 0.03187882 0.03542697 0.03084695 0.03604882 0.03343182 0.03477895 0.03187882 0.03542697 0.03084695 0.03369086 0.03053987 0.034298 0.02943295 0.03213596 0.03124094 0.030366 0.03191 0.03190785 0.03246897 0.03213596 0.03124094 0.03027182 0.03187495 0.030366 0.03191 0.03534787 0.03244096 0.03190785 0.03246897 0.03322494 0.033746 0.03534787 0.03244096 0.03213596 0.03124094 0.03190785 0.03246897 0.03693085 0.03379899 0.03322494 0.033746 0.03404682 0.03644984 0.03534787 0.03244096 0.03322494 0.033746 0.03693085 0.03379899 0.038414 0.03659784 0.03404682 0.03644984 0.03440195 0.04047387 0.03693085 0.03379899 0.03404682 0.03644984 0.038414 0.03659784 0.03973299 0.04067498 0.03440195 0.04047387 0.03444099 0.04290884 0.038414 0.03659784 0.03440195 0.04047387 0.03973299 0.04067498 0.03973299 0.04067498 0.03444099 0.04290884 0.03441596 0.04566997 0.04084396 0.04584795 0.03441596 0.04566997 0.03434598 0.04868698 0.03973299 0.04067498 0.03441596 0.04566997 0.04084396 0.04584795 0.04084396 0.04584795 0.03434598 0.04868698 0.03424495 0.051907 0.04171484 0.05193096 0.03424495 0.051907 0.03413999 0.05525696 0.04084396 0.04584795 0.03424495 0.051907 0.04171484 0.05193096 0.04231095 0.05866396 0.03413999 0.05525696 0.03404086 0.05869096 0.04171484 0.05193096 0.03413999 0.05525696 0.04231095 0.05866396 0.04231095 0.05866396 0.03404086 0.05869096 0.03396499 0.06224685 0.04261487 0.06579297 0.03396499 0.06224685 0.033912 0.06587797 0.04231095 0.05866396 0.03396499 0.06224685 0.04261487 0.06579297 0.04261487 0.073062 0.033912 0.06587797 0.03391283 0.07310301 0.04261487 0.06579297 0.033912 0.06587797 0.04261487 0.073062 0.04261487 0.073062 0.03391283 0.07310301 0.03403896 0.08015197 0.04231184 0.08021199 0.03403896 0.08015197 0.03423684 0.08672899 0.04261487 0.073062 0.03403896 0.08015197 0.04231184 0.08021199 0.04171186 0.08697497 0.03423684 0.08672899 0.03440994 0.092848 0.04231184 0.08021199 0.03423684 0.08672899 0.04171186 0.08697497 0.04083585 0.09307998 0.03440994 0.092848 0.03444099 0.095618 0.04171186 0.08697497 0.03440994 0.092848 0.04083585 0.09307998 0.04083585 0.09307998 0.03444099 0.095618 0.03441184 0.098109 0.03972095 0.09825199 0.03441184 0.098109 0.03429198 0.100339 0.04083585 0.09307998 0.03441184 0.098109 0.03972095 0.09825199 0.03840196 0.102314 0.03429198 0.100339 0.03406995 0.102288 0.03972095 0.09825199 0.03429198 0.100339 0.03840196 0.102314 0.03840196 0.102314 0.03406995 0.102288 0.03371793 0.103883 0.036924 0.105093 0.03371793 0.103883 0.03323882 0.105107 0.03840196 0.102314 0.03371793 0.103883 0.036924 0.105093 0.036924 0.105093 0.03323882 0.105107 0.03190785 0.106412 0.036924 0.105093 0.03190785 0.106412 0.03534787 0.10644 0.02380895 0.06257295 0.01287084 0.06259799 0.01374197 0.05851984 0.02354699 0.067101 0.01287084 0.06259799 0.02380895 0.06257295 0.02431398 0.05849283 0.01374197 0.05851984 0.01642698 0.04997396 0.02380895 0.06257295 0.01374197 0.05851984 0.02431398 0.05849283 0.02431398 0.05849283 0.01642698 0.04997396 0.01969283 0.04166597 0.02708399 0.041619 0.01969283 0.04166597 0.020675 0.03956395 0.02708399 0.041619 0.02431398 0.05849283 0.01969283 0.04166597 0.02787399 0.037705 0.020675 0.03956395 0.02167296 0.03767287 0.02787399 0.037705 0.02708399 0.041619 0.020675 0.03956395 0.02787399 0.037705 0.02167296 0.03767287 0.02268898 0.03600895 0.02881598 0.03461796 0.02268898 0.03600895 0.023696 0.03457999 0.02881598 0.03461796 0.02787399 0.037705 0.02268898 0.03600895 0.02986997 0.03246986 0.023696 0.03457999 0.02560496 0.03246086 0.02986997 0.03246986 0.02881598 0.03461796 0.023696 0.03457999 0.03099083 0.03133487 0.02560496 0.03246086 0.02727288 0.03135496 0.03099083 0.03133487 0.02986997 0.03246986 0.02560496 0.03246086 0.03099083 0.03133487 0.02727288 0.03135496 0.02860999 0.03127098 0.03213596 0.03124094 0.02860999 0.03127098 0.03027182 0.03187495 0.03213596 0.03124094 0.03099083 0.03133487 0.02860999 0.03127098 2.64e-4 0.06944096 0 0.06944096 4.03e-4 0.07692998 6.89e-4 0.06169492 0 0.06944096 2.64e-4 0.06944096 6.89e-4 0.06169492 4.02e-4 0.06195282 0 0.06944096 6.9e-4 0.07718795 4.03e-4 0.07692998 0.001537919 0.08401095 6.9e-4 0.07718795 2.64e-4 0.06944096 4.03e-4 0.07692998 0.001885831 0.08449399 0.001537919 0.08401095 0.003242969 0.090451 0.001885831 0.08449399 6.9e-4 0.07718795 0.001537919 0.08401095 0.003672957 0.09110701 0.003242969 0.090451 0.00534296 0.09617197 0.003672957 0.09110701 0.001885831 0.08449399 0.003242969 0.090451 0.005861997 0.09694999 0.00534296 0.09617197 0.007693946 0.101206 0.005861997 0.09694999 0.003672957 0.09110701 0.00534296 0.09617197 0.008297979 0.102064 0.007693946 0.101206 0.01019597 0.105623 0.008297979 0.102064 0.005861997 0.09694999 0.007693946 0.101206 0.008297979 0.102064 0.01019597 0.105623 0.01087695 0.10653 0.01325899 0.109819 0.01087695 0.10653 0.01019597 0.105623 0.01325899 0.109819 0.01019597 0.105623 0.01243084 0.108781 0.009804964 0.103643 0.008297979 0.102064 0.01087695 0.10653 0.009804964 0.103643 0.01087695 0.10653 0.01189899 0.107154 0.01421582 0.110317 0.01189899 0.107154 0.01087695 0.10653 0.01421582 0.110317 0.01087695 0.10653 0.01325899 0.109819 9.73e-4 0.06944096 2.64e-4 0.06944096 6.9e-4 0.07718795 0.001185894 0.06392896 2.64e-4 0.06944096 9.73e-4 0.06944096 6.89e-4 0.06169492 2.64e-4 0.06944096 0.001185894 0.06392896 0.001792967 0.08020997 6.9e-4 0.07718795 0.001885831 0.08449399 0.001311898 0.07642096 9.73e-4 0.06944096 6.9e-4 0.07718795 0.001792967 0.08020997 0.001311898 0.07642096 6.9e-4 0.07718795 0.003441989 0.08801198 0.001885831 0.08449399 0.003672957 0.09110701 0.002492964 0.08407795 0.001792967 0.08020997 0.001885831 0.08449399 0.003441989 0.08801198 0.002492964 0.08407795 0.001885831 0.08449399 0.004654884 0.09200596 0.003672957 0.09110701 0.005861997 0.09694999 0.004654884 0.09200596 0.003441989 0.08801198 0.003672957 0.09110701 0.007871985 0.099922 0.005861997 0.09694999 0.008297979 0.102064 0.006127953 0.09598797 0.004654884 0.09200596 0.005861997 0.09694999 0.007871985 0.099922 0.006127953 0.09598797 0.005861997 0.09694999 0.009804964 0.103643 0.007871985 0.099922 0.008297979 0.102064 0.02943295 0.1071979 0.009804964 0.103643 0.01189899 0.107154 0.02536797 0.1150619 0.01189899 0.107154 0.01421582 0.110317 0.01924484 0.110216 0.01189899 0.107154 0.02536797 0.1150619 0.02943295 0.1071979 0.01189899 0.107154 0.01924484 0.110216 0.00733298 0.06944096 9.73e-4 0.06944096 0.001311898 0.07642096 0.007995963 0.062756 9.73e-4 0.06944096 0.00733298 0.06944096 0.001185894 0.06392896 9.73e-4 0.06944096 0.007995963 0.062756 0.007994949 0.07612097 0.001311898 0.07642096 0.001792967 0.08020997 0.007994949 0.07612097 0.00733298 0.06944096 0.001311898 0.07642096 0.009952962 0.08271497 0.001792967 0.08020997 0.002492964 0.08407795 0.007994949 0.07612097 0.001792967 0.08020997 0.009952962 0.08271497 0.009952962 0.08271497 0.002492964 0.08407795 0.003441989 0.08801198 0.01316183 0.08917099 0.003441989 0.08801198 0.004654884 0.09200596 0.009952962 0.08271497 0.003441989 0.08801198 0.01316183 0.08917099 0.01754283 0.095438 0.004654884 0.09200596 0.006127953 0.09598797 0.01316183 0.08917099 0.004654884 0.09200596 0.01754283 0.095438 0.01754283 0.095438 0.006127953 0.09598797 0.007871985 0.099922 0.02300482 0.101464 0.007871985 0.099922 0.009804964 0.103643 0.01754283 0.095438 0.007871985 0.099922 0.02300482 0.101464 0.02300482 0.101464 0.009804964 0.103643 0.02943295 0.1071979 0.01325899 0.109819 0.01243084 0.108781 0.01457285 0.110973 0.01557284 0.112111 0.01457285 0.110973 0.01651698 0.112206 0.01557284 0.112111 0.01325899 0.109819 0.01457285 0.110973 0.01771098 0.113413 0.01651698 0.112206 0.01820397 0.112544 0.01771098 0.113413 0.01557284 0.112111 0.01651698 0.112206 0.01771098 0.113413 0.01820397 0.112544 0.01960796 0.113792 0.02127283 0.112943 0.01960796 0.113792 0.01820397 0.112544 0.02059584 0.112253 0.02127283 0.112943 0.01820397 0.112544 0.02004384 0.111457 0.02059584 0.112253 0.01820397 0.112544 0.02020382 0.114439 0.01771098 0.113413 0.01960796 0.113792 0.02020382 0.114439 0.01960796 0.113792 0.02132797 0.114503 0.02291285 0.1139219 0.02132797 0.114503 0.01960796 0.113792 0.02205383 0.113505 0.02291285 0.1139219 0.01960796 0.113792 0.02127283 0.112943 0.02205383 0.113505 0.01960796 0.113792 0.01512783 0.111319 0.01325899 0.109819 0.01557284 0.112111 0.01512783 0.111319 0.01421582 0.110317 0.01325899 0.109819 0.01785784 0.11353 0.01557284 0.112111 0.01771098 0.113413 0.01664882 0.112697 0.01512783 0.111319 0.01557284 0.112111 0.01785784 0.11353 0.01664882 0.112697 0.01557284 0.112111 0.01834595 0.113798 0.01785784 0.11353 0.01771098 0.113413 0.01904797 0.114113 0.01834595 0.113798 0.01771098 0.113413 0.02020382 0.114439 0.01904797 0.114113 0.01771098 0.113413 0.02496695 0.115553 0.02020382 0.114439 0.02132797 0.114503 0.02291285 0.1139219 0.022578 0.114343 0.02132797 0.114503 0.02971982 0.11615 0.02132797 0.114503 0.022578 0.114343 0.02874886 0.1166599 0.02496695 0.115553 0.02132797 0.114503 0.02971982 0.11615 0.02874886 0.1166599 0.02132797 0.114503 0.02536797 0.1150619 0.01421582 0.110317 0.01512783 0.111319 0.02388083 0.115587 0.01512783 0.111319 0.01664882 0.112697 0.02955085 0.117427 0.01512783 0.111319 0.02388083 0.115587 0.02536797 0.1150619 0.01512783 0.111319 0.02955085 0.117427 0.02388083 0.115587 0.01664882 0.112697 0.01785784 0.11353 0.02388083 0.115587 0.01785784 0.11353 0.01834595 0.113798 0.02496695 0.115553 0.01834595 0.113798 0.01904797 0.114113 0.02874886 0.1166599 0.01834595 0.113798 0.02496695 0.115553 0.02869486 0.116677 0.01834595 0.113798 0.02874886 0.1166599 0.02869486 0.116677 0.02864295 0.116694 0.01834595 0.113798 0.02388083 0.115587 0.01834595 0.113798 0.02864295 0.116694 0.02496695 0.115553 0.01904797 0.114113 0.02020382 0.114439 0.02291285 0.1139219 0.02382493 0.114182 0.022578 0.114343 0.02971982 0.11615 0.022578 0.114343 0.02382493 0.114182 0.02741295 0.1136839 0.02382493 0.114182 0.02291285 0.1139219 0.03069382 0.115665 0.02382493 0.114182 0.02741295 0.1136839 0.02971982 0.11615 0.02382493 0.114182 0.03069382 0.115665 0.03662699 0.111715 0.02291285 0.1139219 0.02205383 0.113505 0.03662699 0.111715 0.03813797 0.111995 0.02291285 0.1139219 0.03458487 0.112586 0.02291285 0.1139219 0.03813797 0.111995 0.03100198 0.113151 0.02741295 0.1136839 0.02291285 0.1139219 0.03458487 0.112586 0.03100198 0.113151 0.02291285 0.1139219 0.03662699 0.111715 0.02205383 0.113505 0.02127283 0.112943 0.03522795 0.110992 0.02127283 0.112943 0.02059584 0.112253 0.03522795 0.110992 0.03662699 0.111715 0.02127283 0.112943 0.034096 0.109883 0.02059584 0.112253 0.02004384 0.111457 0.034096 0.109883 0.03522795 0.110992 0.02059584 0.112253 0.03834784 0.111895 0.03813797 0.111995 0.03662699 0.111715 0.04605185 0.113106 0.03458487 0.112586 0.03813797 0.111995 0.06111097 0.112503 0.03813797 0.111995 0.03834784 0.111895 0.06111097 0.112503 0.06080496 0.1125079 0.05761384 0.112437 0.05761384 0.112437 0.03813797 0.111995 0.06111097 0.112503 0.059744 0.112566 0.03813797 0.111995 0.05761384 0.112437 0.05872386 0.112617 0.03813797 0.111995 0.059744 0.112566 0.05774194 0.112662 0.03813797 0.111995 0.05872386 0.112617 0.05679595 0.112703 0.03813797 0.111995 0.05774194 0.112662 0.05367696 0.112822 0.03813797 0.111995 0.05679595 0.112703 0.04830998 0.113018 0.04605185 0.113106 0.03813797 0.111995 0.05084896 0.112926 0.04830998 0.113018 0.03813797 0.111995 0.05367696 0.112822 0.05084896 0.112926 0.03813797 0.111995 0.03702396 0.111513 0.03662699 0.111715 0.03522795 0.110992 0.0385499 0.111787 0.03834784 0.111895 0.03662699 0.111715 0.03731983 0.111604 0.0385499 0.111787 0.03662699 0.111715 0.03702396 0.111513 0.03731983 0.111604 0.03662699 0.111715 0.035133 0.1104 0.03522795 0.110992 0.034096 0.109883 0.03615885 0.111132 0.03702396 0.111513 0.03522795 0.110992 0.03562682 0.110797 0.03615885 0.111132 0.03522795 0.110992 0.035133 0.1104 0.03562682 0.110797 0.03522795 0.110992 0.03448683 0.109705 0.035133 0.1104 0.034096 0.109883 0.034298 0.109449 0.03448683 0.109705 0.034096 0.109883 0.03549796 0.1139039 0.02741295 0.1136839 0.03100198 0.113151 0.03290086 0.114728 0.03069382 0.115665 0.02741295 0.1136839 0.03300487 0.11469 0.03290086 0.114728 0.02741295 0.1136839 0.03549796 0.1139039 0.03300487 0.11469 0.02741295 0.1136839 0.03672498 0.113689 0.03100198 0.113151 0.03458487 0.112586 0.03672498 0.113689 0.03549796 0.1139039 0.03100198 0.113151 0.228227 0.09265297 0.229303 0.09027796 0.230357 0.08782398 0.03859299 0.113533 0.03672498 0.113689 0.03458487 0.112586 0.04038 0.113422 0.03859299 0.113533 0.03458487 0.112586 0.04235297 0.113295 0.04038 0.113422 0.03458487 0.112586 0.04406785 0.113197 0.04235297 0.113295 0.03458487 0.112586 0.04605185 0.113106 0.04406785 0.113197 0.03458487 0.112586 0.06295597 0.112394 0.03834784 0.111895 0.0385499 0.111787 0.06146287 0.1124899 0.06111097 0.112503 0.03834784 0.111895 0.061872 0.11247 0.06146287 0.1124899 0.03834784 0.111895 0.06234699 0.112439 0.061872 0.11247 0.03834784 0.111895 0.06295597 0.112394 0.06234699 0.112439 0.03834784 0.111895 0.03851598 0.110088 0.0385499 0.111787 0.03731983 0.111604 0.06356 0.112348 0.06295597 0.112394 0.0385499 0.111787 0.03977096 0.110232 0.06356 0.112348 0.0385499 0.111787 0.03977096 0.110232 0.0385499 0.111787 0.03851598 0.110088 0.03733599 0.109641 0.03731983 0.111604 0.03702396 0.111513 0.03851598 0.110088 0.03731983 0.111604 0.03733599 0.109641 0.03733599 0.109641 0.03702396 0.111513 0.03615885 0.111132 0.03628695 0.1089439 0.03615885 0.111132 0.03562682 0.110797 0.03733599 0.109641 0.03615885 0.111132 0.03628695 0.1089439 0.03628695 0.1089439 0.03562682 0.110797 0.035133 0.1104 0.03542697 0.108035 0.035133 0.1104 0.03448683 0.109705 0.03628695 0.1089439 0.035133 0.1104 0.03542697 0.108035 0.03542697 0.108035 0.03448683 0.109705 0.034298 0.109449 0.06102395 0.112534 0.06080496 0.1125079 0.06111097 0.112503 0.059744 0.112566 0.05761384 0.112437 0.06080496 0.1125079 0.06102395 0.112534 0.059744 0.112566 0.06080496 0.1125079 0.06102395 0.112534 0.06111097 0.112503 0.06146287 0.1124899 0.06102395 0.112534 0.06146287 0.1124899 0.061872 0.11247 0.06102395 0.112534 0.061872 0.11247 0.06234699 0.112439 0.06104195 0.112551 0.06234699 0.112439 0.06295597 0.112394 0.06104195 0.112551 0.06102395 0.112534 0.06234699 0.112439 0.06104195 0.112551 0.06295597 0.112394 0.06356 0.112348 0.07646 0.11262 0.06356 0.112348 0.03977096 0.110232 0.07613295 0.112878 0.06356 0.112348 0.07646 0.11262 0.06104195 0.112551 0.06356 0.112348 0.07613295 0.112878 0.05978983 0.112592 0.05872386 0.112617 0.059744 0.112566 0.06102395 0.112534 0.05978983 0.112592 0.059744 0.112566 0.05864685 0.112623 0.05774194 0.112662 0.05872386 0.112617 0.05978983 0.112592 0.05864685 0.112623 0.05872386 0.112617 0.05706685 0.112723 0.05679595 0.112703 0.05774194 0.112662 0.05720198 0.112717 0.05706685 0.112723 0.05774194 0.112662 0.05733686 0.112699 0.05720198 0.112717 0.05774194 0.112662 0.05760395 0.112632 0.05733686 0.112699 0.05774194 0.112662 0.05864685 0.112623 0.05760395 0.112632 0.05774194 0.112662 0.054223 0.112833 0.05679595 0.112703 0.05706685 0.112723 0.054223 0.112833 0.05367696 0.112822 0.05679595 0.112703 0.05463784 0.112746 0.05706685 0.112723 0.05720198 0.112717 0.054223 0.112833 0.05706685 0.112723 0.05463784 0.112746 0.05463784 0.112746 0.05720198 0.112717 0.05733686 0.112699 0.05559796 0.112593 0.05733686 0.112699 0.05760395 0.112632 0.05511796 0.11257 0.05733686 0.112699 0.05559796 0.112593 0.05463784 0.112746 0.05733686 0.112699 0.05511796 0.11257 0.05802798 0.112562 0.05760395 0.112632 0.05864685 0.112623 0.05802798 0.112562 0.05676686 0.112379 0.05760395 0.112632 0.05559796 0.112593 0.05760395 0.112632 0.05676686 0.112379 0.05844783 0.112543 0.05864685 0.112623 0.05978983 0.112592 0.05802798 0.112562 0.05864685 0.112623 0.05844783 0.112543 0.06104195 0.112551 0.05978983 0.112592 0.06102395 0.112534 0.06104195 0.112551 0.05844783 0.112543 0.05978983 0.112592 0.03411698 0.114766 0.03069382 0.115665 0.03290086 0.114728 0.03165996 0.115751 0.02971982 0.11615 0.03069382 0.115665 0.03165996 0.115751 0.03069382 0.115665 0.03411698 0.114766 0.03725087 0.113807 0.03290086 0.114728 0.03300487 0.11469 0.03411698 0.114766 0.03290086 0.114728 0.03725087 0.113807 0.03725087 0.113807 0.03300487 0.11469 0.03549796 0.1139039 0.03725087 0.113807 0.03549796 0.1139039 0.03672498 0.113689 0.229303 0.09027796 0.2284229 0.09219199 0.230357 0.08782398 0.03725087 0.113807 0.03672498 0.113689 0.03840595 0.113586 0.040151 0.113421 0.03672498 0.113689 0.03859299 0.113533 0.03840595 0.113586 0.03672498 0.113689 0.040151 0.113421 0.04393386 0.113137 0.03859299 0.113533 0.04038 0.113422 0.040151 0.113421 0.03859299 0.113533 0.04393386 0.113137 0.04393386 0.113137 0.04038 0.113422 0.04235297 0.113295 0.04393386 0.113137 0.04235297 0.113295 0.04406785 0.113197 0.04616385 0.1130599 0.04406785 0.113197 0.04605185 0.113106 0.04616385 0.1130599 0.04393386 0.113137 0.04406785 0.113197 0.048702 0.112993 0.04605185 0.113106 0.04830998 0.113018 0.04616385 0.1130599 0.04605185 0.113106 0.048702 0.112993 0.05141484 0.11292 0.04830998 0.113018 0.05084896 0.112926 0.048702 0.112993 0.04830998 0.113018 0.05141484 0.11292 0.05141484 0.11292 0.05084896 0.112926 0.05367696 0.112822 0.05141484 0.11292 0.05367696 0.112822 0.054223 0.112833 0.03165996 0.115751 0.02874886 0.1166599 0.02971982 0.11615 0.03009796 0.11678 0.02869486 0.116677 0.02874886 0.1166599 0.03165996 0.115751 0.03009796 0.11678 0.02874886 0.1166599 0.03009796 0.11678 0.02864295 0.116694 0.02869486 0.116677 0.02840799 0.116824 0.02388083 0.115587 0.02864295 0.116694 0.02901798 0.117034 0.02840799 0.116824 0.02864295 0.116694 0.02917885 0.116784 0.02864295 0.116694 0.03009796 0.11678 0.02901798 0.117034 0.02864295 0.116694 0.02917885 0.116784 0.02895498 0.117245 0.02955085 0.117427 0.02388083 0.115587 0.02858185 0.117093 0.02895498 0.117245 0.02388083 0.115587 0.02838397 0.116952 0.02858185 0.117093 0.02388083 0.115587 0.02840799 0.116824 0.02838397 0.116952 0.02388083 0.115587 0.03019696 0.117578 0.02955085 0.117427 0.02895498 0.117245 0.03021585 0.117601 0.02536797 0.1150619 0.02955085 0.117427 0.031237 0.117878 0.03021585 0.117601 0.02955085 0.117427 0.031237 0.117878 0.02955085 0.117427 0.03019696 0.117578 0.02942585 0.117298 0.02895498 0.117245 0.02858185 0.117093 0.03019696 0.117578 0.02895498 0.117245 0.02942585 0.117298 0.02942585 0.117298 0.02858185 0.117093 0.02838397 0.116952 0.02901798 0.117034 0.02838397 0.116952 0.02840799 0.116824 0.02942585 0.117298 0.02838397 0.116952 0.02901798 0.117034 0.03494495 0.1186619 0.03614687 0.118932 0.02536797 0.1150619 0.02645885 0.113176 0.02536797 0.1150619 0.03614687 0.118932 0.033445 0.118332 0.03494495 0.1186619 0.02536797 0.1150619 0.032175 0.118053 0.033445 0.118332 0.02536797 0.1150619 0.03110897 0.117813 0.032175 0.118053 0.02536797 0.1150619 0.03021585 0.117601 0.03110897 0.117813 0.02536797 0.1150619 0.02645885 0.113176 0.01924484 0.110216 0.02536797 0.1150619 0.03737282 0.11939 0.03614687 0.118932 0.03494495 0.1186619 0.033517 0.11602 0.02645885 0.113176 0.03614687 0.118932 0.03740096 0.119221 0.033517 0.11602 0.03614687 0.118932 0.03737282 0.11939 0.03740096 0.119221 0.03614687 0.118932 0.03557085 0.118952 0.03494495 0.1186619 0.033445 0.118332 0.03737282 0.11939 0.03494495 0.1186619 0.03557085 0.118952 0.03394997 0.118561 0.033445 0.118332 0.032175 0.118053 0.03557085 0.118952 0.033445 0.118332 0.03394997 0.118561 0.03249597 0.1182039 0.032175 0.118053 0.03110897 0.117813 0.03394997 0.118561 0.032175 0.118053 0.03249597 0.1182039 0.031237 0.117878 0.03110897 0.117813 0.03021585 0.117601 0.03249597 0.1182039 0.03110897 0.117813 0.031237 0.117878 0.03670299 0.112589 0.01924484 0.110216 0.02645885 0.113176 0.02943295 0.1071979 0.01924484 0.110216 0.03670299 0.112589 0.03670299 0.112589 0.02645885 0.113176 0.033517 0.11602 0.04197084 0.120344 0.04041486 0.118738 0.033517 0.11602 0.04467797 0.11759 0.033517 0.11602 0.04041486 0.118738 0.04031497 0.119923 0.04197084 0.120344 0.033517 0.11602 0.03877782 0.119546 0.04031497 0.119923 0.033517 0.11602 0.03740096 0.119221 0.03877782 0.119546 0.033517 0.11602 0.03670299 0.112589 0.033517 0.11602 0.04467797 0.11759 0.04580485 0.12139 0.04715287 0.12132 0.04041486 0.118738 0.04467797 0.11759 0.04041486 0.118738 0.04715287 0.12132 0.04378783 0.120826 0.04580485 0.12139 0.04041486 0.118738 0.04197084 0.120344 0.04378783 0.120826 0.04041486 0.118738 0.05208384 0.123267 0.053716 0.123757 0.04715287 0.12132 0.05321484 0.122155 0.04715287 0.12132 0.053716 0.123757 0.05042797 0.122759 0.05208384 0.123267 0.04715287 0.12132 0.04801785 0.122034 0.05042797 0.122759 0.04715287 0.12132 0.04580485 0.12139 0.04801785 0.122034 0.04715287 0.12132 0.04467797 0.11759 0.04715287 0.12132 0.05321484 0.122155 0.05148983 0.123284 0.053716 0.123757 0.05208384 0.123267 0.05477494 0.124286 0.053716 0.123757 0.05148983 0.123284 0.068089 0.1280249 0.053716 0.123757 0.05477494 0.124286 0.06216984 0.126241 0.053716 0.123757 0.068089 0.1280249 0.05321484 0.122155 0.053716 0.123757 0.06216984 0.126241 0.05148983 0.123284 0.05208384 0.123267 0.05042797 0.122759 0.05148983 0.123284 0.05042797 0.122759 0.04801785 0.122034 0.04876887 0.122462 0.04801785 0.122034 0.04580485 0.12139 0.04876887 0.122462 0.05148983 0.123284 0.04801785 0.122034 0.04618698 0.121712 0.04580485 0.12139 0.04378783 0.120826 0.04876887 0.122462 0.04580485 0.12139 0.04618698 0.121712 0.04374986 0.121034 0.04378783 0.120826 0.04197084 0.120344 0.04618698 0.121712 0.04378783 0.120826 0.04374986 0.121034 0.04374986 0.121034 0.04197084 0.120344 0.04031497 0.119923 0.04147297 0.120427 0.04031497 0.119923 0.03877782 0.119546 0.04374986 0.121034 0.04031497 0.119923 0.04147297 0.120427 0.03934288 0.11988 0.03877782 0.119546 0.03740096 0.119221 0.04147297 0.120427 0.03877782 0.119546 0.03934288 0.11988 0.03934288 0.11988 0.03740096 0.119221 0.03737282 0.11939 0.03143388 0.11658 0.03138095 0.116605 0.03133183 0.11663 0.03674799 0.115243 0.03133183 0.11663 0.03138095 0.116605 0.03080385 0.116744 0.03143388 0.11658 0.03133183 0.11663 0.03164494 0.116766 0.03080385 0.116744 0.03133183 0.11663 0.03674799 0.115243 0.03164494 0.116766 0.03133183 0.11663 0.03674799 0.115243 0.03138095 0.116605 0.03143388 0.11658 0.03026497 0.116809 0.03009796 0.11678 0.03143388 0.11658 0.03291589 0.115844 0.03143388 0.11658 0.03009796 0.11678 0.03080385 0.116744 0.03026497 0.116809 0.03143388 0.11658 0.03724396 0.114062 0.03143388 0.11658 0.03291589 0.115844 0.03724396 0.114062 0.03674799 0.115243 0.03143388 0.11658 0.02972197 0.116822 0.02917885 0.116784 0.03009796 0.11678 0.02999287 0.116822 0.02972197 0.116822 0.03009796 0.11678 0.03026497 0.116809 0.02999287 0.116822 0.03009796 0.11678 0.03356099 0.115424 0.03443884 0.115022 0.03009796 0.11678 0.03291589 0.115844 0.03009796 0.11678 0.03443884 0.115022 0.0326249 0.11567 0.03009796 0.11678 0.03165996 0.115751 0.03356099 0.115424 0.03009796 0.11678 0.0326249 0.11567 0.02967995 0.11708 0.02917885 0.116784 0.02972197 0.116822 0.02901798 0.117034 0.02917885 0.116784 0.02967995 0.11708 0.03034299 0.117049 0.02972197 0.116822 0.02999287 0.116822 0.02967995 0.11708 0.02972197 0.116822 0.03034299 0.117049 0.03034299 0.117049 0.02999287 0.116822 0.03026497 0.116809 0.030999 0.116943 0.03026497 0.116809 0.03080385 0.116744 0.03034299 0.117049 0.03026497 0.116809 0.030999 0.116943 0.030999 0.116943 0.03080385 0.116744 0.03164494 0.116766 0.05249089 0.1205 0.0539 0.118982 0.05603796 0.119323 0.05827283 0.113912 0.05603796 0.119323 0.0539 0.118982 0.05513298 0.121046 0.05249089 0.1205 0.05603796 0.119323 0.05839186 0.122058 0.05513298 0.121046 0.05603796 0.119323 0.05839186 0.122058 0.05603796 0.119323 0.05765998 0.119834 0.08736896 0.127887 0.05765998 0.119834 0.05603796 0.119323 0.06213498 0.115381 0.08736896 0.127887 0.05603796 0.119323 0.05827283 0.113912 0.06213498 0.115381 0.05603796 0.119323 0.05249089 0.1205 0.05191683 0.118673 0.0539 0.118982 0.05827283 0.113912 0.0539 0.118982 0.05191683 0.118673 0.04994785 0.120007 0.05017 0.1184239 0.05191683 0.118673 0.05827283 0.113912 0.05191683 0.118673 0.05017 0.1184239 0.05249089 0.1205 0.04994785 0.120007 0.05191683 0.118673 0.04751396 0.119565 0.05008095 0.118412 0.05017 0.1184239 0.05231183 0.113795 0.05017 0.1184239 0.05008095 0.118412 0.04994785 0.120007 0.04751396 0.119565 0.05017 0.1184239 0.05827283 0.113912 0.05017 0.1184239 0.05231183 0.113795 0.04751396 0.119565 0.04756587 0.118106 0.05008095 0.118412 0.05231183 0.113795 0.05008095 0.118412 0.04756587 0.118106 0.04520297 0.119173 0.04531997 0.117865 0.04756587 0.118106 0.05231183 0.113795 0.04756587 0.118106 0.04531997 0.117865 0.04751396 0.119565 0.04520297 0.119173 0.04756587 0.118106 0.04300493 0.118822 0.04355084 0.117695 0.04531997 0.117865 0.05231183 0.113795 0.04531997 0.117865 0.04355084 0.117695 0.04520297 0.119173 0.04300493 0.118822 0.04531997 0.117865 0.04093384 0.11851 0.04327899 0.117671 0.04355084 0.117695 0.04355299 0.114816 0.04355084 0.117695 0.04327899 0.117671 0.04300493 0.118822 0.04093384 0.11851 0.04355084 0.117695 0.05176997 0.111195 0.04355084 0.117695 0.04355299 0.114816 0.05231183 0.113795 0.04355084 0.117695 0.05176997 0.111195 0.04093384 0.11851 0.04143697 0.117518 0.04327899 0.117671 0.04355299 0.114816 0.04327899 0.117671 0.04143697 0.117518 0.03899896 0.1182309 0.03982585 0.1173959 0.04143697 0.117518 0.04355299 0.114816 0.04143697 0.117518 0.03982585 0.1173959 0.04093384 0.11851 0.03899896 0.1182309 0.04143697 0.117518 0.03721582 0.117981 0.038396 0.117297 0.03982585 0.1173959 0.04355299 0.114816 0.03982585 0.1173959 0.038396 0.117297 0.03899896 0.1182309 0.03721582 0.117981 0.03982585 0.1173959 0.03721582 0.117981 0.03712385 0.117215 0.038396 0.117297 0.04355299 0.114816 0.038396 0.117297 0.03712385 0.117215 0.03556686 0.117751 0.03605896 0.117147 0.03712385 0.117215 0.04355299 0.114816 0.03712385 0.117215 0.03605896 0.117147 0.03721582 0.117981 0.03556686 0.117751 0.03712385 0.117215 0.03408199 0.117538 0.0359869 0.117143 0.03605896 0.117147 0.03750598 0.115011 0.03605896 0.117147 0.0359869 0.117143 0.03556686 0.117751 0.03408199 0.117538 0.03605896 0.117147 0.04295682 0.113082 0.03605896 0.117147 0.03750598 0.115011 0.04355299 0.114816 0.03605896 0.117147 0.04295682 0.113082 0.03408199 0.117538 0.03495395 0.117075 0.0359869 0.117143 0.03674799 0.115243 0.0359869 0.117143 0.03495395 0.117075 0.03750598 0.115011 0.0359869 0.117143 0.03674799 0.115243 0.03278696 0.117335 0.03402584 0.117011 0.03495395 0.117075 0.03674799 0.115243 0.03495395 0.117075 0.03402584 0.117011 0.03408199 0.117538 0.03278696 0.117335 0.03495395 0.117075 0.03278696 0.117335 0.03323799 0.11695 0.03402584 0.117011 0.03674799 0.115243 0.03402584 0.117011 0.03323799 0.11695 0.03172791 0.117138 0.032579 0.1168889 0.03323799 0.11695 0.03674799 0.115243 0.03323799 0.11695 0.032579 0.1168889 0.03278696 0.117335 0.03172791 0.117138 0.03323799 0.11695 0.03172791 0.117138 0.03204596 0.116829 0.032579 0.1168889 0.03674799 0.115243 0.032579 0.1168889 0.03204596 0.116829 0.030999 0.116943 0.03164494 0.116766 0.03204596 0.116829 0.03674799 0.115243 0.03204596 0.116829 0.03164494 0.116766 0.03172791 0.117138 0.030999 0.116943 0.03204596 0.116829 0.03034299 0.117049 0.030999 0.116943 0.03172791 0.117138 0.03096795 0.117299 0.03172791 0.117138 0.03278696 0.117335 0.03096795 0.117299 0.03034299 0.117049 0.03172791 0.117138 0.03193593 0.117559 0.03278696 0.117335 0.03408199 0.117538 0.03193593 0.117559 0.03096795 0.117299 0.03278696 0.117335 0.03315097 0.117833 0.03408199 0.117538 0.03556686 0.117751 0.03315097 0.117833 0.03193593 0.117559 0.03408199 0.117538 0.03456687 0.118126 0.03556686 0.117751 0.03721582 0.117981 0.03456687 0.118126 0.03315097 0.117833 0.03556686 0.117751 0.03615784 0.118441 0.03721582 0.117981 0.03899896 0.1182309 0.03615784 0.118441 0.03456687 0.118126 0.03721582 0.117981 0.03789496 0.1187829 0.03899896 0.1182309 0.04093384 0.11851 0.03789496 0.1187829 0.03615784 0.118441 0.03899896 0.1182309 0.03979295 0.1191599 0.04093384 0.11851 0.04300493 0.118822 0.03979295 0.1191599 0.03789496 0.1187829 0.04093384 0.11851 0.04183799 0.119575 0.04300493 0.118822 0.04520297 0.119173 0.04183799 0.119575 0.03979295 0.1191599 0.04300493 0.118822 0.04402095 0.120034 0.04520297 0.119173 0.04751396 0.119565 0.04402095 0.120034 0.04183799 0.119575 0.04520297 0.119173 0.04632484 0.120539 0.04751396 0.119565 0.04994785 0.120007 0.04632484 0.120539 0.04402095 0.120034 0.04751396 0.119565 0.04876285 0.121097 0.04994785 0.120007 0.05249089 0.1205 0.04876285 0.121097 0.04632484 0.120539 0.04994785 0.120007 0.05131983 0.121709 0.05249089 0.1205 0.05513298 0.121046 0.05131983 0.121709 0.04876285 0.121097 0.05249089 0.1205 0.05131983 0.121709 0.05513298 0.121046 0.05398386 0.1223739 0.057253 0.123383 0.05398386 0.1223739 0.05513298 0.121046 0.05839186 0.122058 0.057253 0.123383 0.05513298 0.121046 0.05003386 0.122387 0.05131983 0.121709 0.05398386 0.1223739 0.05003386 0.122387 0.05398386 0.1223739 0.05272185 0.12315 0.05599999 0.124155 0.05272185 0.12315 0.05398386 0.1223739 0.057253 0.123383 0.05599999 0.124155 0.05398386 0.1223739 0.02967995 0.11708 0.03034299 0.117049 0.03096795 0.117299 0.03019595 0.117352 0.03096795 0.117299 0.03193593 0.117559 0.03019595 0.117352 0.02967995 0.11708 0.03096795 0.117299 0.03106486 0.11764 0.03193593 0.117559 0.03315097 0.117833 0.03106486 0.11764 0.03019595 0.117352 0.03193593 0.117559 0.03219199 0.117948 0.03315097 0.117833 0.03456687 0.118126 0.03219199 0.117948 0.03106486 0.11764 0.03315097 0.117833 0.03352898 0.118279 0.03456687 0.118126 0.03615784 0.118441 0.03352898 0.118279 0.03219199 0.117948 0.03456687 0.118126 0.035052 0.118638 0.03615784 0.118441 0.03789496 0.1187829 0.035052 0.118638 0.03352898 0.118279 0.03615784 0.118441 0.036731 0.119028 0.03789496 0.1187829 0.03979295 0.1191599 0.036731 0.119028 0.035052 0.118638 0.03789496 0.1187829 0.03858095 0.11946 0.03979295 0.1191599 0.04183799 0.119575 0.03858095 0.11946 0.036731 0.119028 0.03979295 0.1191599 0.04058796 0.119937 0.04183799 0.119575 0.04402095 0.120034 0.04058796 0.119937 0.03858095 0.11946 0.04183799 0.119575 0.04274284 0.120464 0.04402095 0.120034 0.04632484 0.120539 0.04274284 0.120464 0.04058796 0.119937 0.04402095 0.120034 0.04503196 0.121044 0.04632484 0.120539 0.04876285 0.121097 0.04503196 0.121044 0.04274284 0.120464 0.04632484 0.120539 0.04746782 0.121685 0.04876285 0.121097 0.05131983 0.121709 0.04746782 0.121685 0.04503196 0.121044 0.04876285 0.121097 0.05003386 0.122387 0.04746782 0.121685 0.05131983 0.121709 0.04876887 0.122462 0.05003386 0.122387 0.05272185 0.12315 0.04876887 0.122462 0.05272185 0.12315 0.05148983 0.123284 0.05477494 0.124286 0.05148983 0.123284 0.05272185 0.12315 0.05599999 0.124155 0.05477494 0.124286 0.05272185 0.12315 0.02901798 0.117034 0.02967995 0.11708 0.03019595 0.117352 0.02942585 0.117298 0.03019595 0.117352 0.03106486 0.11764 0.02942585 0.117298 0.02901798 0.117034 0.03019595 0.117352 0.03019696 0.117578 0.03106486 0.11764 0.03219199 0.117948 0.03019696 0.117578 0.02942585 0.117298 0.03106486 0.11764 0.031237 0.117878 0.03219199 0.117948 0.03352898 0.118279 0.031237 0.117878 0.03019696 0.117578 0.03219199 0.117948 0.03249597 0.1182039 0.03352898 0.118279 0.035052 0.118638 0.03249597 0.1182039 0.031237 0.117878 0.03352898 0.118279 0.03394997 0.118561 0.035052 0.118638 0.036731 0.119028 0.03394997 0.118561 0.03249597 0.1182039 0.035052 0.118638 0.03557085 0.118952 0.036731 0.119028 0.03858095 0.11946 0.03557085 0.118952 0.03394997 0.118561 0.036731 0.119028 0.03737282 0.11939 0.03858095 0.11946 0.04058796 0.119937 0.03737282 0.11939 0.03557085 0.118952 0.03858095 0.11946 0.03934288 0.11988 0.04058796 0.119937 0.04274284 0.120464 0.03934288 0.11988 0.03737282 0.11939 0.04058796 0.119937 0.04147297 0.120427 0.04274284 0.120464 0.04503196 0.121044 0.04147297 0.120427 0.03934288 0.11988 0.04274284 0.120464 0.04374986 0.121034 0.04503196 0.121044 0.04746782 0.121685 0.04374986 0.121034 0.04147297 0.120427 0.04503196 0.121044 0.04618698 0.121712 0.04746782 0.121685 0.05003386 0.122387 0.04618698 0.121712 0.04374986 0.121034 0.04746782 0.121685 0.04876887 0.122462 0.04618698 0.121712 0.05003386 0.122387 0.05839186 0.122058 0.05765998 0.119834 0.05928796 0.120337 0.08736896 0.127887 0.05928796 0.120337 0.05765998 0.119834 0.07063496 0.123632 0.05839186 0.122058 0.05928796 0.120337 0.07063496 0.123632 0.05928796 0.120337 0.08736896 0.127887 0.06926095 0.127834 0.05477494 0.124286 0.05599999 0.124155 0.068089 0.1280249 0.05477494 0.124286 0.06926095 0.127834 0.07043898 0.127053 0.05599999 0.124155 0.057253 0.123383 0.06926095 0.127834 0.05599999 0.124155 0.07043898 0.127053 0.07150197 0.125764 0.057253 0.123383 0.05839186 0.122058 0.07043898 0.127053 0.057253 0.123383 0.07150197 0.125764 0.07150197 0.125764 0.05839186 0.122058 0.07063496 0.123632 0.122922 0.133946 0.141405 0.134874 0.132374 0.134656 0.126545 0.1357139 0.132374 0.134656 0.141405 0.134874 0.147531 0.1347129 0.141405 0.134874 0.122922 0.133946 0.1410509 0.136189 0.126545 0.1357139 0.141405 0.134874 0.147531 0.1347129 0.1410509 0.136189 0.141405 0.134874 0.126545 0.1357139 0.122922 0.133946 0.132374 0.134656 0.112342 0.134196 0.120205 0.133659 0.122922 0.133946 0.147531 0.1347129 0.122922 0.133946 0.120205 0.133659 0.126545 0.1357139 0.112342 0.134196 0.122922 0.133946 0.102804 0.131076 0.120205 0.133659 0.113027 0.132737 0.112342 0.134196 0.113027 0.132737 0.120205 0.133659 0.09237897 0.1290079 0.120205 0.133659 0.102804 0.131076 0.08736896 0.127887 0.120205 0.133659 0.09237897 0.1290079 0.122503 0.122529 0.120205 0.133659 0.08736896 0.127887 0.147531 0.1347129 0.120205 0.133659 0.15375 0.13428 0.122503 0.122529 0.15375 0.13428 0.120205 0.133659 0.112342 0.134196 0.102804 0.131076 0.113027 0.132737 0.09845095 0.131925 0.09237897 0.1290079 0.102804 0.131076 0.112342 0.134196 0.09845095 0.131925 0.102804 0.131076 0.08484697 0.129072 0.08736896 0.127887 0.09237897 0.1290079 0.09845095 0.131925 0.08484697 0.129072 0.09237897 0.1290079 0.07063496 0.123632 0.08736896 0.127887 0.08167099 0.126524 0.08484697 0.129072 0.08167099 0.126524 0.08736896 0.127887 0.122503 0.122529 0.08736896 0.127887 0.08996897 0.114099 0.06213498 0.115381 0.08996897 0.114099 0.08736896 0.127887 0.07150197 0.125764 0.07063496 0.123632 0.08167099 0.126524 0.08484697 0.129072 0.07150197 0.125764 0.08167099 0.126524 0.07043898 0.127053 0.07150197 0.125764 0.08484697 0.129072 0.08386498 0.1303279 0.08484697 0.129072 0.09845095 0.131925 0.08386498 0.1303279 0.07043898 0.127053 0.08484697 0.129072 0.09755998 0.133149 0.09845095 0.131925 0.112342 0.134196 0.09755998 0.133149 0.08386498 0.1303279 0.09845095 0.131925 0.111558 0.135388 0.112342 0.134196 0.126545 0.1357139 0.111558 0.135388 0.09755998 0.133149 0.112342 0.134196 0.125889 0.136871 0.126545 0.1357139 0.1410509 0.136189 0.125889 0.136871 0.111558 0.135388 0.126545 0.1357139 0.125889 0.136871 0.1410509 0.136189 0.1409389 0.136492 0.147531 0.1347129 0.1409389 0.136492 0.1410509 0.136189 0.1405529 0.137305 0.125889 0.136871 0.1409389 0.136492 0.150231 0.136089 0.1405529 0.137305 0.1409389 0.136492 0.147531 0.1347129 0.150231 0.136089 0.1409389 0.136492 0.06926095 0.127834 0.07043898 0.127053 0.08386498 0.1303279 0.08276796 0.131119 0.08386498 0.1303279 0.09755998 0.133149 0.08276796 0.131119 0.06926095 0.127834 0.08386498 0.1303279 0.09655296 0.133952 0.09755998 0.133149 0.111558 0.135388 0.09655296 0.133952 0.08276796 0.131119 0.09755998 0.133149 0.110656 0.136205 0.111558 0.135388 0.125889 0.136871 0.110656 0.136205 0.09655296 0.133952 0.111558 0.135388 0.125116 0.137703 0.125889 0.136871 0.1405529 0.137305 0.125116 0.137703 0.110656 0.136205 0.125889 0.136871 0.125116 0.137703 0.1405529 0.137305 0.140258 0.137764 0.150231 0.136089 0.140258 0.137764 0.1405529 0.137305 0.1399379 0.1381469 0.125116 0.137703 0.140258 0.137764 0.149687 0.137337 0.1399379 0.1381469 0.140258 0.137764 0.149687 0.137337 0.140258 0.137764 0.150231 0.136089 0.068089 0.1280249 0.06926095 0.127834 0.08276796 0.131119 0.081658 0.13137 0.08276796 0.131119 0.09655296 0.133952 0.081658 0.13137 0.068089 0.1280249 0.08276796 0.131119 0.09551495 0.134266 0.09655296 0.133952 0.110656 0.136205 0.09551495 0.134266 0.081658 0.13137 0.09655296 0.133952 0.109706 0.136586 0.110656 0.136205 0.125116 0.137703 0.109706 0.136586 0.09551495 0.134266 0.110656 0.136205 0.124277 0.138154 0.125116 0.137703 0.1399379 0.1381469 0.124277 0.138154 0.109706 0.136586 0.125116 0.137703 0.124277 0.138154 0.1399379 0.1381469 0.139421 0.138568 0.149687 0.137337 0.139421 0.138568 0.1399379 0.1381469 0.139241 0.138667 0.124277 0.138154 0.139421 0.138568 0.14898 0.13817 0.139241 0.138667 0.139421 0.138568 0.14898 0.13817 0.139421 0.138568 0.149687 0.137337 0.07192498 0.128894 0.068089 0.1280249 0.081658 0.13137 0.06287997 0.126442 0.06216984 0.126241 0.068089 0.1280249 0.07192498 0.128894 0.06287997 0.126442 0.068089 0.1280249 0.08081001 0.131097 0.081658 0.13137 0.09551495 0.134266 0.08081001 0.131097 0.07192498 0.128894 0.081658 0.13137 0.09805595 0.134725 0.09551495 0.134266 0.109706 0.136586 0.08949899 0.133034 0.08081001 0.131097 0.09551495 0.134266 0.09805595 0.134725 0.08949899 0.133034 0.09551495 0.134266 0.110869 0.136795 0.109706 0.136586 0.124277 0.138154 0.106506 0.136158 0.09805595 0.134725 0.109706 0.136586 0.110869 0.136795 0.106506 0.136158 0.109706 0.136586 0.130809 0.138667 0.124277 0.138154 0.139241 0.138667 0.114799 0.137305 0.110869 0.136795 0.124277 0.138154 0.122904 0.138149 0.114799 0.137305 0.124277 0.138154 0.130809 0.138667 0.122904 0.138149 0.124277 0.138154 0.130809 0.138667 0.139241 0.138667 0.138502 0.1388379 0.14898 0.13817 0.138502 0.1388379 0.139241 0.138667 0.1370519 0.138414 0.130809 0.138667 0.138502 0.1388379 0.147149 0.138588 0.138502 0.1388379 0.14898 0.13817 0.1448619 0.138742 0.138502 0.1388379 0.147149 0.138588 0.1370519 0.138414 0.138502 0.1388379 0.1448619 0.138742 0.074651 0.124715 0.06216984 0.126241 0.06287997 0.126442 0.05321484 0.122155 0.06216984 0.126241 0.074651 0.124715 0.083485 0.128686 0.06287997 0.126442 0.07192498 0.128894 0.074651 0.124715 0.06287997 0.126442 0.083485 0.128686 0.083485 0.128686 0.07192498 0.128894 0.08081001 0.131097 0.09255999 0.132042 0.08081001 0.131097 0.08949899 0.133034 0.083485 0.128686 0.08081001 0.131097 0.09255999 0.132042 0.09255999 0.132042 0.08949899 0.133034 0.09805595 0.134725 0.101733 0.134754 0.09805595 0.134725 0.106506 0.136158 0.09255999 0.132042 0.09805595 0.134725 0.101733 0.134754 0.101733 0.134754 0.106506 0.136158 0.110869 0.136795 0.120984 0.135851 0.110869 0.136795 0.114799 0.137305 0.120984 0.135851 0.101733 0.134754 0.110869 0.136795 0.129067 0.1374509 0.114799 0.137305 0.122904 0.138149 0.129067 0.1374509 0.120984 0.135851 0.114799 0.137305 0.1370519 0.138414 0.122904 0.138149 0.130809 0.138667 0.1370519 0.138414 0.129067 0.1374509 0.122904 0.138149 0.159747 0.133608 0.159632 0.1350859 0.150231 0.136089 0.149687 0.137337 0.150231 0.136089 0.159632 0.1350859 0.155301 0.134131 0.159747 0.133608 0.150231 0.136089 0.15375 0.13428 0.155301 0.134131 0.150231 0.136089 0.147531 0.1347129 0.15375 0.13428 0.150231 0.136089 0.1656 0.132688 0.169061 0.133442 0.159632 0.1350859 0.159219 0.13631 0.159632 0.1350859 0.169061 0.133442 0.159747 0.133608 0.1656 0.132688 0.159632 0.1350859 0.159219 0.13631 0.149687 0.137337 0.159632 0.1350859 0.176847 0.130152 0.178416 0.131108 0.169061 0.133442 0.168779 0.13464 0.169061 0.133442 0.178416 0.131108 0.171394 0.131516 0.176847 0.130152 0.169061 0.133442 0.1656 0.132688 0.171394 0.131516 0.169061 0.133442 0.168779 0.13464 0.159219 0.13631 0.169061 0.133442 0.187195 0.126782 0.187582 0.128037 0.178416 0.131108 0.178265 0.132279 0.178416 0.131108 0.187582 0.128037 0.182299 0.128509 0.187195 0.126782 0.178416 0.131108 0.176847 0.130152 0.182299 0.128509 0.178416 0.131108 0.178265 0.132279 0.168779 0.13464 0.178416 0.131108 0.1933079 0.124249 0.196416 0.124202 0.187582 0.128037 0.187565 0.129179 0.187582 0.128037 0.196416 0.124202 0.191779 0.1249279 0.1933079 0.124249 0.187582 0.128037 0.187195 0.126782 0.191779 0.1249279 0.187582 0.128037 0.187565 0.129179 0.178265 0.132279 0.187582 0.128037 0.202718 0.119322 0.204759 0.119588 0.196416 0.124202 0.196537 0.12531 0.196416 0.124202 0.204759 0.119588 0.196875 0.122519 0.202718 0.119322 0.196416 0.124202 0.1933079 0.124249 0.196875 0.122519 0.196416 0.124202 0.196537 0.12531 0.187565 0.129179 0.196416 0.124202 0.208124 0.115811 0.212454 0.114187 0.204759 0.119588 0.205026 0.120652 0.204759 0.119588 0.212454 0.114187 0.202718 0.119322 0.208124 0.115811 0.204759 0.119588 0.205026 0.120652 0.196537 0.12531 0.204759 0.119588 0.217158 0.10835 0.219337 0.108049 0.212454 0.114187 0.2128739 0.115193 0.212454 0.114187 0.219337 0.108049 0.212795 0.112249 0.217158 0.10835 0.212454 0.114187 0.208124 0.115811 0.212795 0.112249 0.212454 0.114187 0.2128739 0.115193 0.205026 0.120652 0.212454 0.114187 0.223713 0.101046 0.225241 0.101242 0.219337 0.108049 0.219915 0.108974 0.219337 0.108049 0.225241 0.101242 0.220746 0.104639 0.223713 0.101046 0.219337 0.108049 0.217158 0.10835 0.220746 0.104639 0.219337 0.108049 0.219915 0.108974 0.2128739 0.115193 0.219337 0.108049 0.226473 0.09712499 0.2300119 0.093849 0.225241 0.101242 0.225976 0.102056 0.225241 0.101242 0.2300119 0.093849 0.223713 0.101046 0.226473 0.09712499 0.225241 0.101242 0.225976 0.102056 0.219915 0.108974 0.225241 0.101242 0.231348 0.08779895 0.233526 0.085994 0.2300119 0.093849 0.230895 0.09451395 0.2300119 0.093849 0.233526 0.085994 0.229155 0.09255099 0.231348 0.08779895 0.2300119 0.093849 0.226473 0.09712499 0.229155 0.09255099 0.2300119 0.093849 0.230895 0.09451395 0.225976 0.102056 0.2300119 0.093849 0.232831 0.083673 0.235678 0.07781195 0.233526 0.085994 0.234533 0.08647 0.233526 0.085994 0.235678 0.07781195 0.231348 0.08779895 0.232831 0.083673 0.233526 0.085994 0.234533 0.08647 0.230895 0.09451395 0.233526 0.085994 0.23499 0.06944096 0.236407 0.06944096 0.235678 0.07781195 0.23677 0.07805997 0.235678 0.07781195 0.236407 0.06944096 0.234566 0.075836 0.23499 0.06944096 0.235678 0.07781195 0.232831 0.083673 0.234566 0.075836 0.235678 0.07781195 0.23677 0.07805997 0.234533 0.08647 0.235678 0.07781195 0.234775 0.06492197 0.236407 0.06944096 0.23499 0.06944096 0.237529 0.06944096 0.23677 0.07805997 0.236407 0.06944096 0.235562 0.06039083 0.237529 0.06944096 0.236407 0.06944096 0.234775 0.06492197 0.235562 0.06039083 0.236407 0.06944096 0.2291229 0.06944096 0.23499 0.06944096 0.234566 0.075836 0.228248 0.05966883 0.234775 0.06492197 0.23499 0.06944096 0.2291229 0.06944096 0.228248 0.05966883 0.23499 0.06944096 0.228283 0.07901799 0.234566 0.075836 0.232831 0.083673 0.228283 0.07901799 0.2291229 0.06944096 0.234566 0.075836 0.228283 0.07901799 0.232831 0.083673 0.231348 0.08779895 0.225744 0.088458 0.231348 0.08779895 0.229155 0.09255099 0.225744 0.088458 0.228283 0.07901799 0.231348 0.08779895 0.225744 0.088458 0.229155 0.09255099 0.226473 0.09712499 0.221567 0.097382 0.226473 0.09712499 0.223713 0.101046 0.221567 0.097382 0.225744 0.088458 0.226473 0.09712499 0.221567 0.097382 0.223713 0.101046 0.220746 0.104639 0.21596 0.105401 0.220746 0.104639 0.217158 0.10835 0.21596 0.105401 0.221567 0.097382 0.220746 0.104639 0.21596 0.105401 0.217158 0.10835 0.212795 0.112249 0.209133 0.112302 0.212795 0.112249 0.208124 0.115811 0.209133 0.112302 0.21596 0.105401 0.212795 0.112249 0.2013069 0.11789 0.208124 0.115811 0.202718 0.119322 0.2013069 0.11789 0.209133 0.112302 0.208124 0.115811 0.193944 0.121505 0.202718 0.119322 0.196875 0.122519 0.193944 0.121505 0.2013069 0.11789 0.202718 0.119322 0.193944 0.121505 0.196875 0.122519 0.1933079 0.124249 0.184521 0.124204 0.1933079 0.124249 0.191779 0.1249279 0.1929489 0.121888 0.193944 0.121505 0.1933079 0.124249 0.184521 0.124204 0.1929489 0.121888 0.1933079 0.124249 0.184521 0.124204 0.191779 0.1249279 0.187195 0.126782 0.169648 0.126846 0.187195 0.126782 0.182299 0.128509 0.169648 0.126846 0.184521 0.124204 0.187195 0.126782 0.15631 0.1292 0.182299 0.128509 0.176847 0.130152 0.169648 0.126846 0.182299 0.128509 0.15631 0.1292 0.15631 0.1292 0.176847 0.130152 0.171394 0.131516 0.15631 0.1292 0.171394 0.131516 0.1656 0.132688 0.15631 0.1292 0.1656 0.132688 0.159747 0.133608 0.15631 0.1292 0.159747 0.133608 0.155301 0.134131 0.122503 0.122529 0.155301 0.134131 0.15375 0.13428 0.143715 0.129154 0.155301 0.134131 0.122503 0.122529 0.154955 0.1294389 0.15631 0.1292 0.155301 0.134131 0.1492339 0.129877 0.154955 0.1294389 0.155301 0.134131 0.143715 0.129154 0.1492339 0.129877 0.155301 0.134131 0.14898 0.13817 0.149687 0.137337 0.159219 0.13631 0.15864 0.1371639 0.159219 0.13631 0.168779 0.13464 0.15864 0.1371639 0.14898 0.13817 0.159219 0.13631 0.168325 0.135506 0.168779 0.13464 0.178265 0.132279 0.168325 0.135506 0.15864 0.1371639 0.168779 0.13464 0.177936 0.13315 0.178265 0.132279 0.187565 0.129179 0.177936 0.13315 0.168325 0.135506 0.178265 0.132279 0.187361 0.130047 0.187565 0.129179 0.196537 0.12531 0.187361 0.130047 0.177936 0.13315 0.187565 0.129179 0.196461 0.126165 0.196537 0.12531 0.205026 0.120652 0.196461 0.126165 0.187361 0.130047 0.196537 0.12531 0.20508 0.121481 0.205026 0.120652 0.2128739 0.115193 0.20508 0.121481 0.196461 0.126165 0.205026 0.120652 0.213061 0.115981 0.2128739 0.115193 0.219915 0.108974 0.213061 0.115981 0.20508 0.121481 0.2128739 0.115193 0.220232 0.1097 0.219915 0.108974 0.225976 0.102056 0.220232 0.1097 0.213061 0.115981 0.219915 0.108974 0.22642 0.102694 0.225976 0.102056 0.230895 0.09451395 0.22642 0.102694 0.220232 0.1097 0.225976 0.102056 0.231456 0.09503298 0.230895 0.09451395 0.234533 0.08647 0.231456 0.09503298 0.22642 0.102694 0.230895 0.09451395 0.23519 0.08683896 0.234533 0.08647 0.23677 0.07805997 0.23519 0.08683896 0.231456 0.09503298 0.234533 0.08647 0.237489 0.07825297 0.23677 0.07805997 0.237529 0.06944096 0.237489 0.07825297 0.23519 0.08683896 0.23677 0.07805997 0.2382709 0.06944096 0.237489 0.07825297 0.237529 0.06944096 0.23665 0.06012797 0.2382709 0.06944096 0.237529 0.06944096 0.235562 0.06039083 0.23665 0.06012797 0.237529 0.06944096 0.15545 0.137889 0.14898 0.13817 0.15864 0.1371639 0.15545 0.137889 0.147149 0.138588 0.14898 0.13817 0.163312 0.136795 0.15864 0.1371639 0.168325 0.135506 0.163312 0.136795 0.15545 0.137889 0.15864 0.1371639 0.170724 0.135352 0.168325 0.135506 0.177936 0.13315 0.170724 0.135352 0.163312 0.136795 0.168325 0.135506 0.17776 0.133581 0.177936 0.13315 0.187361 0.130047 0.17776 0.133581 0.170724 0.135352 0.177936 0.13315 0.190703 0.129144 0.187361 0.130047 0.196461 0.126165 0.184378 0.131519 0.17776 0.133581 0.187361 0.130047 0.190703 0.129144 0.184378 0.131519 0.187361 0.130047 0.196716 0.126467 0.196461 0.126165 0.20508 0.121481 0.196716 0.126467 0.190703 0.129144 0.196461 0.126165 0.207229 0.120582 0.20508 0.121481 0.213061 0.115981 0.200498 0.124545 0.196716 0.126467 0.20508 0.121481 0.2022359 0.123592 0.200498 0.124545 0.20508 0.121481 0.207229 0.120582 0.2022359 0.123592 0.20508 0.121481 0.2158139 0.114251 0.213061 0.115981 0.220232 0.1097 0.211758 0.1174499 0.207229 0.120582 0.213061 0.115981 0.2158139 0.114251 0.211758 0.1174499 0.213061 0.115981 0.222889 0.107473 0.220232 0.1097 0.22642 0.102694 0.222889 0.107473 0.2158139 0.114251 0.220232 0.1097 0.228664 0.10021 0.22642 0.102694 0.231456 0.09503298 0.228664 0.10021 0.222889 0.107473 0.22642 0.102694 0.233066 0.09268999 0.231456 0.09503298 0.23519 0.08683896 0.233066 0.09268999 0.228664 0.10021 0.231456 0.09503298 0.236147 0.08503395 0.23519 0.08683896 0.237489 0.07825297 0.236147 0.08503395 0.233066 0.09268999 0.23519 0.08683896 0.237984 0.07722198 0.237489 0.07825297 0.2382709 0.06944096 0.237984 0.07722198 0.236147 0.08503395 0.237489 0.07825297 0.238584 0.06944096 0.237984 0.07722198 0.2382709 0.06944096 0.237367 0.05992382 0.238584 0.06944096 0.2382709 0.06944096 0.23665 0.06012797 0.237367 0.05992382 0.2382709 0.06944096 0.157588 0.1382949 0.147149 0.138588 0.15545 0.137889 0.149043 0.138678 0.147149 0.138588 0.157588 0.1382949 0.1448619 0.138742 0.147149 0.138588 0.149043 0.138678 0.1663089 0.137111 0.15545 0.137889 0.163312 0.136795 0.157588 0.1382949 0.15545 0.137889 0.1663089 0.137111 0.1663089 0.137111 0.163312 0.136795 0.170724 0.135352 0.175085 0.135127 0.170724 0.135352 0.17776 0.133581 0.1663089 0.137111 0.170724 0.135352 0.175085 0.135127 0.183793 0.132355 0.17776 0.133581 0.184378 0.131519 0.175085 0.135127 0.17776 0.133581 0.183793 0.132355 0.183793 0.132355 0.184378 0.131519 0.190703 0.129144 0.192299 0.128821 0.190703 0.129144 0.196716 0.126467 0.183793 0.132355 0.190703 0.129144 0.192299 0.128821 0.192299 0.128821 0.196716 0.126467 0.200498 0.124545 0.203479 0.12651 0.200498 0.124545 0.2022359 0.123592 0.192299 0.128821 0.200498 0.124545 0.203479 0.12651 0.211129 0.121407 0.2022359 0.123592 0.207229 0.120582 0.203479 0.12651 0.2022359 0.123592 0.211129 0.121407 0.211129 0.121407 0.207229 0.120582 0.211758 0.1174499 0.218104 0.115537 0.211758 0.1174499 0.2158139 0.114251 0.211129 0.121407 0.211758 0.1174499 0.218104 0.115537 0.224272 0.108981 0.2158139 0.114251 0.222889 0.107473 0.218104 0.115537 0.2158139 0.114251 0.224272 0.108981 0.229512 0.1018339 0.222889 0.107473 0.228664 0.10021 0.224272 0.108981 0.222889 0.107473 0.229512 0.1018339 0.233718 0.09419697 0.228664 0.10021 0.233066 0.09268999 0.229512 0.1018339 0.228664 0.10021 0.233718 0.09419697 0.236799 0.086178 0.233066 0.09268999 0.236147 0.08503395 0.233718 0.09419697 0.233066 0.09268999 0.236799 0.086178 0.238682 0.07788795 0.236147 0.08503395 0.237984 0.07722198 0.236799 0.086178 0.236147 0.08503395 0.238682 0.07788795 0.238682 0.07788795 0.237984 0.07722198 0.238584 0.06944096 0.238682 0.07788795 0.238584 0.06944096 0.239318 0.06944096 0.238039 0.06200796 0.239318 0.06944096 0.238584 0.06944096 0.237367 0.05992382 0.238039 0.06200796 0.238584 0.06944096 0.24037 0.07542997 0.239318 0.06944096 0.24063 0.06944096 0.238682 0.06097698 0.24063 0.06944096 0.239318 0.06944096 0.240154 0.08147096 0.24037 0.07542997 0.24063 0.06944096 0.238682 0.06097698 0.24037 0.063452 0.24063 0.06944096 0.241203 0.06944096 0.24063 0.06944096 0.24037 0.063452 0.240154 0.08147096 0.24063 0.06944096 0.241203 0.06944096 0.24037 0.07542997 0.238682 0.07788795 0.239318 0.06944096 0.238039 0.06200796 0.238682 0.06097698 0.239318 0.06944096 0.239589 0.08137696 0.236799 0.086178 0.238682 0.07788795 0.24037 0.07542997 0.239589 0.08137696 0.238682 0.07788795 0.236492 0.09296798 0.233718 0.09419697 0.236799 0.086178 0.238294 0.08723896 0.236492 0.09296798 0.236799 0.086178 0.239589 0.08137696 0.238294 0.08723896 0.236799 0.086178 0.234198 0.09851998 0.229512 0.1018339 0.233718 0.09419697 0.236492 0.09296798 0.234198 0.09851998 0.233718 0.09419697 0.231429 0.103851 0.224272 0.108981 0.229512 0.1018339 0.234198 0.09851998 0.231429 0.103851 0.229512 0.1018339 0.224552 0.113687 0.218104 0.115537 0.224272 0.108981 0.228205 0.10892 0.224552 0.113687 0.224272 0.108981 0.231429 0.103851 0.228205 0.10892 0.224272 0.108981 0.220498 0.118117 0.211129 0.121407 0.218104 0.115537 0.224552 0.113687 0.220498 0.118117 0.218104 0.115537 0.211306 0.125838 0.203479 0.12651 0.211129 0.121407 0.216072 0.122177 0.211306 0.125838 0.211129 0.121407 0.220498 0.118117 0.216072 0.122177 0.211129 0.121407 0.206236 0.12907 0.195296 0.130773 0.203479 0.12651 0.192299 0.128821 0.203479 0.12651 0.195296 0.130773 0.211306 0.125838 0.206236 0.12907 0.203479 0.12651 0.2009 0.131848 0.1867229 0.134139 0.195296 0.130773 0.183793 0.132355 0.195296 0.130773 0.1867229 0.134139 0.206236 0.12907 0.2009 0.131848 0.195296 0.130773 0.183793 0.132355 0.192299 0.128821 0.195296 0.130773 0.189602 0.13596 0.177907 0.136564 0.1867229 0.134139 0.175085 0.135127 0.1867229 0.134139 0.177907 0.136564 0.195341 0.134151 0.189602 0.13596 0.1867229 0.134139 0.2009 0.131848 0.195341 0.134151 0.1867229 0.134139 0.175085 0.135127 0.183793 0.132355 0.1867229 0.134139 0.183728 0.137261 0.1689929 0.138021 0.177907 0.136564 0.1663089 0.137111 0.177907 0.136564 0.1689929 0.138021 0.189602 0.13596 0.183728 0.137261 0.177907 0.136564 0.1663089 0.137111 0.175085 0.135127 0.177907 0.136564 0.171764 0.138307 0.160129 0.138501 0.1689929 0.138021 0.157588 0.1382949 0.1689929 0.138021 0.160129 0.138501 0.177767 0.138045 0.171764 0.138307 0.1689929 0.138021 0.183728 0.137261 0.177767 0.138045 0.1689929 0.138021 0.157588 0.1382949 0.1663089 0.137111 0.1689929 0.138021 0.1657609 0.138045 0.160129 0.138501 0.171764 0.138307 0.157917 0.138537 0.157588 0.1382949 0.160129 0.138501 0.1657609 0.138045 0.157917 0.138537 0.160129 0.138501 0.171639 0.138878 0.171764 0.138307 0.177767 0.138045 0.171639 0.138878 0.1657609 0.138045 0.171764 0.138307 0.1836979 0.137847 0.177767 0.138045 0.183728 0.137261 0.1836979 0.137847 0.171639 0.138878 0.177767 0.138045 0.1836979 0.137847 0.183728 0.137261 0.189602 0.13596 0.195416 0.134732 0.189602 0.13596 0.195341 0.134151 0.195416 0.134732 0.1836979 0.137847 0.189602 0.13596 0.195416 0.134732 0.195341 0.134151 0.2009 0.131848 0.206436 0.129615 0.2009 0.131848 0.206236 0.12907 0.206436 0.129615 0.195416 0.134732 0.2009 0.131848 0.211567 0.126354 0.206236 0.12907 0.211306 0.125838 0.211567 0.126354 0.206436 0.129615 0.206236 0.12907 0.2164109 0.12264 0.211306 0.125838 0.216072 0.122177 0.2164109 0.12264 0.211567 0.126354 0.211306 0.125838 0.220896 0.118528 0.216072 0.122177 0.220498 0.118117 0.220896 0.118528 0.2164109 0.12264 0.216072 0.122177 0.220896 0.118528 0.220498 0.118117 0.224552 0.113687 0.2250159 0.114023 0.224552 0.113687 0.228205 0.10892 0.2250159 0.114023 0.220896 0.118528 0.224552 0.113687 0.231928 0.104134 0.228205 0.10892 0.231429 0.103851 0.231928 0.104134 0.2250159 0.114023 0.228205 0.10892 0.231928 0.104134 0.231429 0.103851 0.234198 0.09851998 0.23703 0.093167 0.234198 0.09851998 0.236492 0.09296798 0.23703 0.093167 0.231928 0.104134 0.234198 0.09851998 0.23703 0.093167 0.236492 0.09296798 0.238294 0.08723896 0.23703 0.093167 0.238294 0.08723896 0.239589 0.08137696 0.240154 0.08147096 0.239589 0.08137696 0.24037 0.07542997 0.240154 0.08147096 0.23703 0.093167 0.239589 0.08137696 0.157917 0.138537 0.149043 0.138678 0.157588 0.1382949 0.15062 0.1382099 0.149043 0.138678 0.157917 0.138537 0.15062 0.1382099 0.1448619 0.138742 0.149043 0.138678 0.15062 0.1382099 0.157917 0.138537 0.1657609 0.138045 0.15062 0.1382099 0.1370519 0.138414 0.1448619 0.138742 0.238682 0.06097698 0.239589 0.05750387 0.24037 0.063452 0.241203 0.06944096 0.24037 0.063452 0.239589 0.05750387 0.2368 0.05263996 0.238294 0.05164295 0.239589 0.05750387 0.240146 0.05736196 0.239589 0.05750387 0.238294 0.05164295 0.238682 0.06097698 0.2368 0.05263996 0.239589 0.05750387 0.240146 0.05736196 0.241203 0.06944096 0.239589 0.05750387 0.23372 0.04455399 0.236492 0.04591399 0.238294 0.05164295 0.240146 0.05736196 0.238294 0.05164295 0.236492 0.04591399 0.2368 0.05263996 0.23372 0.04455399 0.238294 0.05164295 0.23372 0.04455399 0.234198 0.04036086 0.236492 0.04591399 0.2370139 0.04567188 0.236492 0.04591399 0.234198 0.04036086 0.2370139 0.04567188 0.240146 0.05736196 0.236492 0.04591399 0.229515 0.03683882 0.231429 0.03503096 0.234198 0.04036086 0.2370139 0.04567188 0.234198 0.04036086 0.231429 0.03503096 0.23372 0.04455399 0.229515 0.03683882 0.234198 0.04036086 0.224277 0.02960985 0.228205 0.029962 0.231429 0.03503096 0.231908 0.03471696 0.231429 0.03503096 0.228205 0.029962 0.229515 0.03683882 0.224277 0.02960985 0.231429 0.03503096 0.231908 0.03471696 0.2370139 0.04567188 0.231429 0.03503096 0.218112 0.02297896 0.224552 0.025195 0.228205 0.029962 0.231908 0.03471696 0.228205 0.029962 0.224552 0.025195 0.224277 0.02960985 0.218112 0.02297896 0.228205 0.029962 0.218112 0.02297896 0.220498 0.02076482 0.224552 0.025195 0.224985 0.02481997 0.224552 0.025195 0.220498 0.02076482 0.224985 0.02481997 0.231908 0.03471696 0.224552 0.025195 0.211141 0.017048 0.216072 0.01670396 0.220498 0.02076482 0.216449 0.01627296 0.220498 0.02076482 0.216072 0.01670396 0.218112 0.02297896 0.211141 0.017048 0.220498 0.02076482 0.216449 0.01627296 0.224985 0.02481997 0.220498 0.02076482 0.2034969 0.01190698 0.211306 0.01304394 0.216072 0.01670396 0.216449 0.01627296 0.216072 0.01670396 0.211306 0.01304394 0.211141 0.017048 0.2034969 0.01190698 0.216072 0.01670396 0.2034969 0.01190698 0.206236 0.009811997 0.211306 0.01304394 0.206551 0.009332954 0.211306 0.01304394 0.206236 0.009811997 0.206551 0.009332954 0.216449 0.01627296 0.211306 0.01304394 0.1953189 0.007638931 0.2009 0.00703299 0.206236 0.009811997 0.206551 0.009332954 0.206236 0.009811997 0.2009 0.00703299 0.2034969 0.01190698 0.1953189 0.007638931 0.206236 0.009811997 0.186754 0.004307985 0.195341 0.004729986 0.2009 0.00703299 0.1955839 0.004209995 0.2009 0.00703299 0.195341 0.004729986 0.1953189 0.007638931 0.186754 0.004307985 0.2009 0.00703299 0.1955839 0.004209995 0.206551 0.009332954 0.2009 0.00703299 0.177946 0.001966953 0.189602 0.002921998 0.195341 0.004729986 0.1955839 0.004209995 0.195341 0.004729986 0.189602 0.002921998 0.186754 0.004307985 0.177946 0.001966953 0.195341 0.004729986 0.177946 0.001966953 0.183728 0.001619935 0.189602 0.002921998 0.183872 0.001063883 0.189602 0.002921998 0.183728 0.001619935 0.183872 0.001063883 0.1955839 0.004209995 0.189602 0.002921998 0.169041 6.52e-4 0.177767 8.37e-4 0.183728 0.001619935 0.183872 0.001063883 0.183728 0.001619935 0.177767 8.37e-4 0.177946 0.001966953 0.169041 6.52e-4 0.183728 0.001619935 0.160176 3.81e-4 0.171764 5.75e-4 0.177767 8.37e-4 0.183872 0.001063883 0.177767 8.37e-4 0.171764 5.75e-4 0.169041 6.52e-4 0.160176 3.81e-4 0.177767 8.37e-4 0.15013 7.17e-4 0.171764 5.75e-4 0.160176 3.81e-4 0.171764 2e-6 0.183872 0.001063883 0.171764 5.75e-4 0.1657249 8.4e-4 0.171764 2e-6 0.171764 5.75e-4 0.15013 7.17e-4 0.1657249 8.4e-4 0.171764 5.75e-4 0.1579059 3.44e-4 0.160176 3.81e-4 0.169041 6.52e-4 0.15013 7.17e-4 0.160176 3.81e-4 0.1579059 3.44e-4 0.166357 0.001238942 0.169041 6.52e-4 0.177946 0.001966953 0.149143 2.05e-4 0.1579059 3.44e-4 0.169041 6.52e-4 0.157667 2.8e-4 0.149143 2.05e-4 0.169041 6.52e-4 0.166357 0.001238942 0.157667 2.8e-4 0.169041 6.52e-4 0.175104 0.003074944 0.177946 0.001966953 0.186754 0.004307985 0.175104 0.003074944 0.166357 0.001238942 0.177946 0.001966953 0.183784 0.005762994 0.186754 0.004307985 0.1953189 0.007638931 0.183784 0.005762994 0.175104 0.003074944 0.186754 0.004307985 0.192265 0.009267985 0.1953189 0.007638931 0.2034969 0.01190698 0.192265 0.009267985 0.183784 0.005762994 0.1953189 0.007638931 0.20041 0.01354295 0.2034969 0.01190698 0.211141 0.017048 0.20041 0.01354295 0.192265 0.009267985 0.2034969 0.01190698 0.205696 0.01663899 0.211141 0.017048 0.218112 0.02297896 0.205696 0.01663899 0.20041 0.01354295 0.211141 0.017048 0.214779 0.02321696 0.218112 0.02297896 0.224277 0.02960985 0.210449 0.01985597 0.205696 0.01663899 0.218112 0.02297896 0.214779 0.02321696 0.210449 0.01985597 0.218112 0.02297896 0.222182 0.030227 0.224277 0.02960985 0.229515 0.03683882 0.222182 0.030227 0.214779 0.02321696 0.224277 0.02960985 0.228491 0.03814399 0.229515 0.03683882 0.23372 0.04455399 0.228491 0.03814399 0.222182 0.030227 0.229515 0.03683882 0.23319 0.04628795 0.23372 0.04455399 0.2368 0.05263996 0.23319 0.04628795 0.228491 0.03814399 0.23372 0.04455399 0.2363 0.05426883 0.2368 0.05263996 0.238682 0.06097698 0.2363 0.05426883 0.23319 0.04628795 0.2368 0.05263996 0.238039 0.06200796 0.2363 0.05426883 0.238682 0.06097698 0.136524 5.14e-4 0.1579059 3.44e-4 0.149143 2.05e-4 0.15013 7.17e-4 0.1579059 3.44e-4 0.136524 5.14e-4 0.144857 1.39e-4 0.149143 2.05e-4 0.157667 2.8e-4 0.136524 5.14e-4 0.149143 2.05e-4 0.144857 1.39e-4 0.154397 4.07e-4 0.157667 2.8e-4 0.166357 0.001238942 0.138659 4.6e-5 0.144857 1.39e-4 0.157667 2.8e-4 0.146638 0 0.138659 4.6e-5 0.157667 2.8e-4 0.154397 4.07e-4 0.146638 0 0.157667 2.8e-4 0.161866 0.001230955 0.166357 0.001238942 0.175104 0.003074944 0.161866 0.001230955 0.154397 4.07e-4 0.166357 0.001238942 0.1758649 0.003995895 0.175104 0.003074944 0.183784 0.005762994 0.168994 0.002430975 0.161866 0.001230955 0.175104 0.003074944 0.1758649 0.003995895 0.168994 0.002430975 0.175104 0.003074944 0.182451 0.005904972 0.183784 0.005762994 0.192265 0.009267985 0.182451 0.005904972 0.1758649 0.003995895 0.183784 0.005762994 0.19477 0.01070886 0.192265 0.009267985 0.20041 0.01354295 0.18874 0.008139967 0.182451 0.005904972 0.192265 0.009267985 0.19477 0.01070886 0.18874 0.008139967 0.192265 0.009267985 0.200633 0.01409184 0.20041 0.01354295 0.205696 0.01663899 0.191035 0.009468972 0.19477 0.01070886 0.20041 0.01354295 0.200633 0.01409184 0.191035 0.009468972 0.20041 0.01354295 0.209578 0.01969099 0.205696 0.01663899 0.210449 0.01985597 0.209578 0.01969099 0.200633 0.01409184 0.205696 0.01663899 0.209578 0.01969099 0.210449 0.01985597 0.214779 0.02321696 0.217663 0.02623695 0.214779 0.02321696 0.222182 0.030227 0.217663 0.02623695 0.209578 0.01969099 0.214779 0.02321696 0.2246789 0.03365695 0.222182 0.030227 0.228491 0.03814399 0.2246789 0.03365695 0.217663 0.02623695 0.222182 0.030227 0.230427 0.04183799 0.228491 0.03814399 0.23319 0.04628795 0.230427 0.04183799 0.2246789 0.03365695 0.228491 0.03814399 0.23471 0.05065596 0.23319 0.04628795 0.2363 0.05426883 0.23471 0.05065596 0.230427 0.04183799 0.23319 0.04628795 0.237367 0.05992382 0.2363 0.05426883 0.238039 0.06200796 0.237367 0.05992382 0.23471 0.05065596 0.2363 0.05426883 0.129814 2.64e-4 0.144857 1.39e-4 0.138659 4.6e-5 0.129814 2.64e-4 0.136524 5.14e-4 0.144857 1.39e-4 0.139481 2.61e-4 0.138659 4.6e-5 0.146638 0 0.138616 4.5e-5 0.129814 2.64e-4 0.138659 4.6e-5 0.139481 2.61e-4 0.138616 4.5e-5 0.138659 4.6e-5 0.149782 3.99e-4 0.146638 0 0.154397 4.07e-4 0.149782 3.99e-4 0.139481 2.61e-4 0.146638 0 0.160209 0.001334965 0.154397 4.07e-4 0.161866 0.001230955 0.160209 0.001334965 0.149782 3.99e-4 0.154397 4.07e-4 0.160209 0.001334965 0.161866 0.001230955 0.168994 0.002430975 0.170652 0.003123939 0.168994 0.002430975 0.1758649 0.003995895 0.170652 0.003123939 0.160209 0.001334965 0.168994 0.002430975 0.180981 0.005820989 0.1758649 0.003995895 0.182451 0.005904972 0.180981 0.005820989 0.170652 0.003123939 0.1758649 0.003995895 0.180981 0.005820989 0.182451 0.005904972 0.18874 0.008139967 0.191035 0.009468972 0.18874 0.008139967 0.19477 0.01070886 0.191035 0.009468972 0.180981 0.005820989 0.18874 0.008139967 0.237049 0.06944096 0.241203 0.06944096 0.240146 0.05736196 0.236051 0.08082097 0.240154 0.08147096 0.241203 0.06944096 0.236796 0.07517296 0.236051 0.08082097 0.241203 0.06944096 0.237049 0.06944096 0.236796 0.07517296 0.241203 0.06944096 0.233123 0.04712986 0.240146 0.05736196 0.2370139 0.04567188 0.236062 0.05812788 0.237049 0.06944096 0.240146 0.05736196 0.233123 0.04712986 0.236062 0.05812788 0.240146 0.05736196 0.2283239 0.03681695 0.2370139 0.04567188 0.231908 0.03471696 0.2283239 0.03681695 0.233123 0.04712986 0.2370139 0.04567188 0.221826 0.02752184 0.231908 0.03471696 0.224985 0.02481997 0.221826 0.02752184 0.2283239 0.03681695 0.231908 0.03471696 0.217956 0.02329099 0.224985 0.02481997 0.216449 0.01627296 0.217956 0.02329099 0.221826 0.02752184 0.224985 0.02481997 0.209187 0.015935 0.216449 0.01627296 0.206551 0.009332954 0.213741 0.019427 0.217956 0.02329099 0.216449 0.01627296 0.209187 0.015935 0.213741 0.019427 0.216449 0.01627296 0.194005 0.008056998 0.206551 0.009332954 0.1955839 0.004209995 0.204364 0.012869 0.209187 0.015935 0.206551 0.009332954 0.194005 0.008056998 0.204364 0.012869 0.206551 0.009332954 0.171657 0.004156947 0.1955839 0.004209995 0.183872 0.001063883 0.18299 0.005127966 0.194005 0.008056998 0.1955839 0.004209995 0.171657 0.004156947 0.18299 0.005127966 0.1955839 0.004209995 0.159657 0.001063883 0.183872 0.001063883 0.171764 2e-6 0.159657 0.001063883 0.147944 0.004209995 0.183872 0.001063883 0.171657 0.004156947 0.183872 0.001063883 0.147944 0.004209995 0.1657249 8.4e-4 0.159657 0.001063883 0.171764 2e-6 0.159601 0.137807 0.1597999 0.137261 0.1657609 0.138045 0.15062 0.1382099 0.1657609 0.138045 0.1597999 0.137261 0.171639 0.138878 0.159601 0.137807 0.1657609 0.138045 0.159601 0.137807 0.153926 0.13596 0.1597999 0.137261 0.14326 0.137242 0.1597999 0.137261 0.153926 0.13596 0.14326 0.137242 0.15062 0.1382099 0.1597999 0.137261 0.14794 0.13467 0.148187 0.134151 0.153926 0.13596 0.135911 0.135633 0.153926 0.13596 0.148187 0.134151 0.159601 0.137807 0.14794 0.13467 0.153926 0.13596 0.135911 0.135633 0.14326 0.137242 0.153926 0.13596 0.14794 0.13467 0.142628 0.131848 0.148187 0.134151 0.128653 0.133394 0.148187 0.134151 0.142628 0.131848 0.128653 0.133394 0.135911 0.135633 0.148187 0.134151 0.136999 0.129562 0.137293 0.12907 0.142628 0.131848 0.1215659 0.130541 0.142628 0.131848 0.137293 0.12907 0.14794 0.13467 0.136999 0.129562 0.142628 0.131848 0.1215659 0.130541 0.128653 0.133394 0.142628 0.131848 0.136999 0.129562 0.1322219 0.125838 0.137293 0.12907 0.114733 0.127099 0.137293 0.12907 0.1322219 0.125838 0.114733 0.127099 0.1215659 0.130541 0.137293 0.12907 0.127099 0.122625 0.127456 0.122178 0.1322219 0.125838 0.108235 0.123097 0.1322219 0.125838 0.127456 0.122178 0.136999 0.129562 0.127099 0.122625 0.1322219 0.125838 0.108235 0.123097 0.114733 0.127099 0.1322219 0.125838 0.118542 0.11406 0.12303 0.118117 0.127456 0.122178 0.108235 0.123097 0.127456 0.122178 0.12303 0.118117 0.127099 0.122625 0.118542 0.11406 0.127456 0.122178 0.118542 0.11406 0.1189759 0.113687 0.12303 0.118117 0.102154 0.118574 0.12303 0.118117 0.1189759 0.113687 0.102154 0.118574 0.108235 0.123097 0.12303 0.118117 0.111647 0.104215 0.115323 0.10892 0.1189759 0.113687 0.09656697 0.11357 0.1189759 0.113687 0.115323 0.10892 0.118542 0.11406 0.111647 0.104215 0.1189759 0.113687 0.09656697 0.11357 0.102154 0.118574 0.1189759 0.113687 0.111647 0.104215 0.1121 0.103851 0.115323 0.10892 0.09154695 0.108133 0.115323 0.10892 0.1121 0.103851 0.09154695 0.108133 0.09656697 0.11357 0.115323 0.10892 0.106534 0.09326398 0.1093299 0.09851998 0.1121 0.103851 0.08716398 0.102313 0.1121 0.103851 0.1093299 0.09851998 0.111647 0.104215 0.106534 0.09326398 0.1121 0.103851 0.08716398 0.102313 0.09154695 0.108133 0.1121 0.103851 0.106534 0.09326398 0.107036 0.09296798 0.1093299 0.09851998 0.08347696 0.096165 0.1093299 0.09851998 0.107036 0.09296798 0.08347696 0.096165 0.08716398 0.102313 0.1093299 0.09851998 0.103386 0.08154296 0.105234 0.08723896 0.107036 0.09296798 0.08054399 0.08974397 0.107036 0.09296798 0.105234 0.08723896 0.106534 0.09326398 0.103386 0.08154296 0.107036 0.09296798 0.08054399 0.08974397 0.08347696 0.096165 0.107036 0.09296798 0.103386 0.08154296 0.1039389 0.08137696 0.105234 0.08723896 0.07840895 0.08310997 0.105234 0.08723896 0.1039389 0.08137696 0.07840895 0.08310997 0.08054399 0.08974397 0.105234 0.08723896 0.102594 0.07553696 0.103159 0.07542997 0.1039389 0.08137696 0.07710999 0.07632195 0.1039389 0.08137696 0.103159 0.07542997 0.103386 0.08154296 0.102594 0.07553696 0.1039389 0.08137696 0.07710999 0.07632195 0.07840895 0.08310997 0.1039389 0.08137696 0.102325 0.06944096 0.102898 0.06944096 0.103159 0.07542997 0.07710999 0.07632195 0.103159 0.07542997 0.102898 0.06944096 0.102594 0.07553696 0.102325 0.06944096 0.103159 0.07542997 0.103382 0.05736196 0.102898 0.06944096 0.102325 0.06944096 0.1031579 0.06345599 0.102898 0.06944096 0.103382 0.05736196 0.07667195 0.06944096 0.102898 0.06944096 0.1031579 0.06345599 0.07710999 0.07632195 0.102898 0.06944096 0.07667195 0.06944096 0.106479 0.06944096 0.102325 0.06944096 0.102594 0.07553696 0.107478 0.05805999 0.103382 0.05736196 0.102325 0.06944096 0.106732 0.063708 0.102325 0.06944096 0.106479 0.06944096 0.106732 0.063708 0.107478 0.05805999 0.102325 0.06944096 0.107466 0.08075398 0.102594 0.07553696 0.103386 0.08154296 0.107466 0.08075398 0.106479 0.06944096 0.102594 0.07553696 0.110405 0.09175097 0.103386 0.08154296 0.106534 0.09326398 0.110405 0.09175097 0.107466 0.08075398 0.103386 0.08154296 0.115205 0.102065 0.106534 0.09326398 0.111647 0.104215 0.115205 0.102065 0.110405 0.09175097 0.106534 0.09326398 0.121702 0.111359 0.111647 0.104215 0.118542 0.11406 0.121702 0.111359 0.115205 0.102065 0.111647 0.104215 0.125572 0.11559 0.118542 0.11406 0.127099 0.122625 0.125572 0.11559 0.121702 0.111359 0.118542 0.11406 0.134341 0.122947 0.127099 0.122625 0.136999 0.129562 0.129787 0.119454 0.125572 0.11559 0.127099 0.122625 0.134341 0.122947 0.129787 0.119454 0.127099 0.122625 0.149523 0.130824 0.136999 0.129562 0.14794 0.13467 0.139165 0.126013 0.134341 0.122947 0.136999 0.129562 0.149523 0.130824 0.139165 0.126013 0.136999 0.129562 0.171871 0.134724 0.14794 0.13467 0.159601 0.137807 0.160538 0.133753 0.149523 0.130824 0.14794 0.13467 0.171871 0.134724 0.160538 0.133753 0.14794 0.13467 0.1836979 0.137847 0.159601 0.137807 0.171639 0.138878 0.195416 0.134732 0.159601 0.137807 0.1836979 0.137847 0.171871 0.134724 0.159601 0.137807 0.195416 0.134732 0.183185 0.133719 0.195416 0.134732 0.206436 0.129615 0.183185 0.133719 0.171871 0.134724 0.195416 0.134732 0.194148 0.130773 0.206436 0.129615 0.211567 0.126354 0.194148 0.130773 0.183185 0.133719 0.206436 0.129615 0.204435 0.125972 0.211567 0.126354 0.2164109 0.12264 0.204435 0.125972 0.194148 0.130773 0.211567 0.126354 0.213746 0.119451 0.2164109 0.12264 0.220896 0.118528 0.213746 0.119451 0.204435 0.125972 0.2164109 0.12264 0.213746 0.119451 0.220896 0.118528 0.2250159 0.114023 0.221789 0.111403 0.2250159 0.114023 0.231928 0.104134 0.221789 0.111403 0.213746 0.119451 0.2250159 0.114023 0.228277 0.102147 0.231928 0.104134 0.23703 0.093167 0.228277 0.102147 0.221789 0.111403 0.231928 0.104134 0.233089 0.09184497 0.23703 0.093167 0.240154 0.08147096 0.233089 0.09184497 0.228277 0.102147 0.23703 0.093167 0.236051 0.08082097 0.233089 0.09184497 0.240154 0.08147096 0.110439 0.047037 0.106514 0.04567188 0.103382 0.05736196 0.105231 0.05165499 0.103382 0.05736196 0.106514 0.04567188 0.107478 0.05805999 0.110439 0.047037 0.103382 0.05736196 0.103937 0.05751287 0.1031579 0.06345599 0.103382 0.05736196 0.105231 0.05165499 0.103937 0.05751287 0.103382 0.05736196 0.115252 0.03673487 0.11162 0.03471696 0.106514 0.04567188 0.10932 0.04038184 0.106514 0.04567188 0.11162 0.03471696 0.110439 0.047037 0.115252 0.03673487 0.106514 0.04567188 0.10703 0.04593098 0.105231 0.05165499 0.106514 0.04567188 0.10932 0.04038184 0.10703 0.04593098 0.106514 0.04567188 0.121739 0.02747792 0.118543 0.02481997 0.11162 0.03471696 0.115305 0.02998799 0.11162 0.03471696 0.118543 0.02481997 0.115252 0.03673487 0.121739 0.02747792 0.11162 0.03471696 0.1120859 0.03505384 0.10932 0.04038184 0.11162 0.03471696 0.115305 0.02998799 0.1120859 0.03505384 0.11162 0.03471696 0.129782 0.01943099 0.12708 0.01627296 0.118543 0.02481997 0.123002 0.02079182 0.118543 0.02481997 0.12708 0.01627296 0.121739 0.02747792 0.129782 0.01943099 0.118543 0.02481997 0.118953 0.025222 0.115305 0.02998799 0.118543 0.02481997 0.123002 0.02079182 0.118953 0.025222 0.118543 0.02481997 0.139093 0.01290982 0.136977 0.009332954 0.12708 0.01627296 0.13218 0.01307284 0.12708 0.01627296 0.136977 0.009332954 0.129782 0.01943099 0.139093 0.01290982 0.12708 0.01627296 0.127422 0.01673299 0.123002 0.02079182 0.12708 0.01627296 0.13218 0.01307284 0.127422 0.01673299 0.12708 0.01627296 0.160343 0.005162954 0.147944 0.004209995 0.136977 0.009332954 0.142566 0.007061958 0.136977 0.009332954 0.147944 0.004209995 0.14938 0.008108973 0.160343 0.005162954 0.136977 0.009332954 0.139093 0.01290982 0.14938 0.008108973 0.136977 0.009332954 0.1372399 0.009841978 0.13218 0.01307284 0.136977 0.009332954 0.142566 0.007061958 0.1372399 0.009841978 0.136977 0.009332954 0.153858 0.002939999 0.147944 0.004209995 0.159657 0.001063883 0.160343 0.005162954 0.171657 0.004156947 0.147944 0.004209995 0.148119 0.00475496 0.142566 0.007061958 0.147944 0.004209995 0.153858 0.002939999 0.148119 0.00475496 0.147944 0.004209995 0.15974 0.001630902 0.153858 0.002939999 0.159657 0.001063883 0.1657249 8.4e-4 0.15974 0.001630902 0.159657 0.001063883 0.109213 0.06944096 0.106479 0.06944096 0.107466 0.08075398 0.110158 0.05860096 0.106732 0.063708 0.106479 0.06944096 0.110158 0.05860096 0.106479 0.06944096 0.109213 0.06944096 0.110169 0.08034497 0.107466 0.08075398 0.110405 0.09175097 0.109455 0.074934 0.109213 0.06944096 0.107466 0.08075398 0.110169 0.08034497 0.109455 0.074934 0.107466 0.08075398 0.113007 0.09090799 0.110405 0.09175097 0.115205 0.102065 0.113007 0.09090799 0.110169 0.08034497 0.110405 0.09175097 0.117619 0.1007789 0.115205 0.102065 0.121702 0.111359 0.117619 0.1007789 0.113007 0.09090799 0.115205 0.102065 0.123836 0.109648 0.121702 0.111359 0.125572 0.11559 0.123836 0.109648 0.117619 0.1007789 0.121702 0.111359 0.131543 0.117358 0.125572 0.11559 0.129787 0.119454 0.131543 0.117358 0.123836 0.109648 0.125572 0.11559 0.131543 0.117358 0.129787 0.119454 0.134341 0.122947 0.1404629 0.123606 0.134341 0.122947 0.139165 0.126013 0.1404629 0.123606 0.131543 0.117358 0.134341 0.122947 0.1503199 0.128205 0.139165 0.126013 0.149523 0.130824 0.1503199 0.128205 0.1404629 0.123606 0.139165 0.126013 0.160822 0.1310279 0.149523 0.130824 0.160538 0.133753 0.160822 0.1310279 0.1503199 0.128205 0.149523 0.130824 0.171662 0.131991 0.160538 0.133753 0.171871 0.134724 0.171662 0.131991 0.160822 0.1310279 0.160538 0.133753 0.182519 0.131061 0.171871 0.134724 0.183185 0.133719 0.182519 0.131061 0.171662 0.131991 0.171871 0.134724 0.193072 0.128255 0.183185 0.133719 0.194148 0.130773 0.193072 0.128255 0.182519 0.131061 0.183185 0.133719 0.202996 0.123645 0.194148 0.130773 0.204435 0.125972 0.202996 0.123645 0.193072 0.128255 0.194148 0.130773 0.207617 0.120707 0.204435 0.125972 0.213746 0.119451 0.207617 0.120707 0.202996 0.123645 0.204435 0.125972 0.21602 0.11366 0.213746 0.119451 0.221789 0.111403 0.2119809 0.117362 0.207617 0.120707 0.213746 0.119451 0.21602 0.11366 0.2119809 0.117362 0.213746 0.119451 0.2197279 0.109606 0.221789 0.111403 0.228277 0.102147 0.2197279 0.109606 0.21602 0.11366 0.221789 0.111403 0.2259539 0.100701 0.228277 0.102147 0.233089 0.09184497 0.2259539 0.100701 0.2197279 0.109606 0.228277 0.102147 0.230554 0.09081798 0.233089 0.09184497 0.236051 0.08082097 0.230554 0.09081798 0.2259539 0.100701 0.233089 0.09184497 0.23337 0.08028095 0.236051 0.08082097 0.236796 0.07517296 0.23337 0.08028095 0.230554 0.09081798 0.236051 0.08082097 0.23337 0.08028095 0.236796 0.07517296 0.237049 0.06944096 0.234316 0.06944096 0.237049 0.06944096 0.236062 0.05812788 0.234316 0.06944096 0.23337 0.08028095 0.237049 0.06944096 0.233359 0.05853599 0.236062 0.05812788 0.233123 0.04712986 0.234073 0.06394797 0.234316 0.06944096 0.236062 0.05812788 0.233359 0.05853599 0.234073 0.06394797 0.236062 0.05812788 0.230521 0.04797399 0.233123 0.04712986 0.2283239 0.03681695 0.230521 0.04797399 0.233359 0.05853599 0.233123 0.04712986 0.2259089 0.03810298 0.2283239 0.03681695 0.221826 0.02752184 0.2259089 0.03810298 0.230521 0.04797399 0.2283239 0.03681695 0.219693 0.02923399 0.221826 0.02752184 0.217956 0.02329099 0.219693 0.02923399 0.2259089 0.03810298 0.221826 0.02752184 0.211986 0.02152395 0.217956 0.02329099 0.213741 0.019427 0.211986 0.02152395 0.219693 0.02923399 0.217956 0.02329099 0.211986 0.02152395 0.213741 0.019427 0.209187 0.015935 0.203065 0.01527583 0.209187 0.015935 0.204364 0.012869 0.203065 0.01527583 0.211986 0.02152395 0.209187 0.015935 0.193208 0.01067584 0.204364 0.012869 0.194005 0.008056998 0.193208 0.01067584 0.203065 0.01527583 0.204364 0.012869 0.1827059 0.007853984 0.194005 0.008056998 0.18299 0.005127966 0.1827059 0.007853984 0.193208 0.01067584 0.194005 0.008056998 0.1718659 0.006889939 0.18299 0.005127966 0.171657 0.004156947 0.1718659 0.006889939 0.1827059 0.007853984 0.18299 0.005127966 0.161009 0.007820963 0.171657 0.004156947 0.160343 0.005162954 0.161009 0.007820963 0.1718659 0.006889939 0.171657 0.004156947 0.150457 0.01062697 0.160343 0.005162954 0.14938 0.008108973 0.150457 0.01062697 0.161009 0.007820963 0.160343 0.005162954 0.140532 0.01523697 0.14938 0.008108973 0.139093 0.01290982 0.140532 0.01523697 0.150457 0.01062697 0.14938 0.008108973 0.135911 0.01817399 0.139093 0.01290982 0.129782 0.01943099 0.135911 0.01817399 0.140532 0.01523697 0.139093 0.01290982 0.1275089 0.025222 0.129782 0.01943099 0.121739 0.02747792 0.131547 0.02151983 0.135911 0.01817399 0.129782 0.01943099 0.1275089 0.025222 0.131547 0.02151983 0.129782 0.01943099 0.123801 0.02927595 0.121739 0.02747792 0.115252 0.03673487 0.123801 0.02927595 0.1275089 0.025222 0.121739 0.02747792 0.117574 0.03818082 0.115252 0.03673487 0.110439 0.047037 0.117574 0.03818082 0.123801 0.02927595 0.115252 0.03673487 0.112975 0.04806298 0.110439 0.047037 0.107478 0.05805999 0.112975 0.04806298 0.117574 0.03818082 0.110439 0.047037 0.110158 0.05860096 0.107478 0.05805999 0.106732 0.063708 0.110158 0.05860096 0.112975 0.04806298 0.107478 0.05805999 0.07716995 0.06210297 0.1031579 0.06345599 0.103937 0.05751287 0.07716995 0.06210297 0.07667195 0.06944096 0.1031579 0.06345599 0.078646 0.05487698 0.103937 0.05751287 0.105231 0.05165499 0.078646 0.05487698 0.07716995 0.06210297 0.103937 0.05751287 0.08106797 0.04783385 0.105231 0.05165499 0.10703 0.04593098 0.08106797 0.04783385 0.078646 0.05487698 0.105231 0.05165499 0.08438897 0.04104799 0.10703 0.04593098 0.10932 0.04038184 0.08438897 0.04104799 0.08106797 0.04783385 0.10703 0.04593098 0.08438897 0.04104799 0.10932 0.04038184 0.1120859 0.03505384 0.08854997 0.03458899 0.1120859 0.03505384 0.115305 0.02998799 0.08854997 0.03458899 0.08438897 0.04104799 0.1120859 0.03505384 0.09348195 0.02852499 0.115305 0.02998799 0.118953 0.025222 0.09348195 0.02852499 0.08854997 0.03458899 0.115305 0.02998799 0.09910798 0.02291995 0.118953 0.025222 0.123002 0.02079182 0.09910798 0.02291995 0.09348195 0.02852499 0.118953 0.025222 0.105341 0.01783299 0.123002 0.02079182 0.127422 0.01673299 0.105341 0.01783299 0.09910798 0.02291995 0.123002 0.02079182 0.112089 0.01331883 0.127422 0.01673299 0.13218 0.01307284 0.112089 0.01331883 0.105341 0.01783299 0.127422 0.01673299 0.112089 0.01331883 0.13218 0.01307284 0.1372399 0.009841978 0.119256 0.009423971 0.1372399 0.009841978 0.142566 0.007061958 0.119256 0.009423971 0.112089 0.01331883 0.1372399 0.009841978 0.126743 0.006188988 0.142566 0.007061958 0.148119 0.00475496 0.126743 0.006188988 0.119256 0.009423971 0.142566 0.007061958 0.13445 0.003645956 0.148119 0.00475496 0.153858 0.002939999 0.13445 0.003645956 0.126743 0.006188988 0.148119 0.00475496 0.142278 0.001816928 0.153858 0.002939999 0.15974 0.001630902 0.142278 0.001816928 0.13445 0.003645956 0.153858 0.002939999 0.15013 7.17e-4 0.15974 0.001630902 0.1657249 8.4e-4 0.15013 7.17e-4 0.142278 0.001816928 0.15974 0.001630902 0.120423 9.59e-4 0.127994 0.001606941 0.136524 5.14e-4 0.15013 7.17e-4 0.136524 5.14e-4 0.127994 0.001606941 0.129814 2.64e-4 0.120423 9.59e-4 0.136524 5.14e-4 0.110829 0.002091944 0.119365 0.003425896 0.127994 0.001606941 0.142278 0.001816928 0.127994 0.001606941 0.119365 0.003425896 0.120423 9.59e-4 0.110829 0.002091944 0.127994 0.001606941 0.15013 7.17e-4 0.127994 0.001606941 0.142278 0.001816928 0.101689 0.004138946 0.11075 0.005957961 0.119365 0.003425896 0.13445 0.003645956 0.119365 0.003425896 0.11075 0.005957961 0.110829 0.002091944 0.101689 0.004138946 0.119365 0.003425896 0.142278 0.001816928 0.119365 0.003425896 0.13445 0.003645956 0.09251898 0.006852984 0.102271 0.009182989 0.11075 0.005957961 0.126743 0.006188988 0.11075 0.005957961 0.102271 0.009182989 0.101689 0.004138946 0.09251898 0.006852984 0.11075 0.005957961 0.13445 0.003645956 0.11075 0.005957961 0.126743 0.006188988 0.083449 0.01021099 0.09405499 0.013071 0.102271 0.009182989 0.119256 0.009423971 0.102271 0.009182989 0.09405499 0.013071 0.09251898 0.006852984 0.083449 0.01021099 0.102271 0.009182989 0.126743 0.006188988 0.102271 0.009182989 0.119256 0.009423971 0.07462 0.01418197 0.086232 0.01758295 0.09405499 0.013071 0.112089 0.01331883 0.09405499 0.013071 0.086232 0.01758295 0.083449 0.01021099 0.07462 0.01418197 0.09405499 0.013071 0.119256 0.009423971 0.09405499 0.013071 0.112089 0.01331883 0.06617796 0.018727 0.07893198 0.02267295 0.086232 0.01758295 0.105341 0.01783299 0.086232 0.01758295 0.07893198 0.02267295 0.07462 0.01418197 0.06617796 0.018727 0.086232 0.01758295 0.112089 0.01331883 0.086232 0.01758295 0.105341 0.01783299 0.05827283 0.02380084 0.07228296 0.02828782 0.07893198 0.02267295 0.09910798 0.02291995 0.07893198 0.02267295 0.07228296 0.02828782 0.06617796 0.018727 0.05827283 0.02380084 0.07893198 0.02267295 0.105341 0.01783299 0.07893198 0.02267295 0.09910798 0.02291995 0.05104982 0.02935296 0.06640499 0.03436696 0.07228296 0.02828782 0.09348195 0.02852499 0.07228296 0.02828782 0.06640499 0.03436696 0.05827283 0.02380084 0.05104982 0.02935296 0.07228296 0.02828782 0.09910798 0.02291995 0.07228296 0.02828782 0.09348195 0.02852499 0.04464983 0.03532797 0.06141096 0.04084897 0.06640499 0.03436696 0.08854997 0.03458899 0.06640499 0.03436696 0.06141096 0.04084897 0.05104982 0.02935296 0.04464983 0.03532797 0.06640499 0.03436696 0.09348195 0.02852499 0.06640499 0.03436696 0.08854997 0.03458899 0.03919982 0.04166787 0.05740195 0.04766595 0.06141096 0.04084897 0.08438897 0.04104799 0.06141096 0.04084897 0.05740195 0.04766595 0.04464983 0.03532797 0.03919982 0.04166787 0.06141096 0.04084897 0.08854997 0.03458899 0.06141096 0.04084897 0.08438897 0.04104799 0.03481882 0.04831099 0.05446285 0.05475085 0.05740195 0.04766595 0.08106797 0.04783385 0.05740195 0.04766595 0.05446285 0.05475085 0.03919982 0.04166787 0.03481882 0.04831099 0.05740195 0.04766595 0.08438897 0.04104799 0.05740195 0.04766595 0.08106797 0.04783385 0.03160399 0.05519586 0.05266499 0.06203198 0.05446285 0.05475085 0.078646 0.05487698 0.05446285 0.05475085 0.05266499 0.06203198 0.03481882 0.04831099 0.03160399 0.05519586 0.05446285 0.05475085 0.08106797 0.04783385 0.05446285 0.05475085 0.078646 0.05487698 0.02897083 0.06944096 0.05205684 0.06944096 0.05266499 0.06203198 0.07716995 0.06210297 0.05266499 0.06203198 0.05205684 0.06944096 0.02963685 0.06225997 0.02897083 0.06944096 0.05266499 0.06203198 0.03160399 0.05519586 0.02963685 0.06225997 0.05266499 0.06203198 0.078646 0.05487698 0.05266499 0.06203198 0.07716995 0.06210297 0.02963685 0.07662498 0.05205684 0.06944096 0.02897083 0.06944096 0.07716995 0.06210297 0.05205684 0.06944096 0.07667195 0.06944096 0.05259186 0.07638996 0.07667195 0.06944096 0.05205684 0.06944096 0.05259186 0.07638996 0.05205684 0.06944096 0.02963685 0.07662498 0.00733298 0.06944096 0.02897083 0.06944096 0.02963685 0.06225997 0.007994949 0.07612097 0.02897083 0.06944096 0.00733298 0.06944096 0.007994949 0.07612097 0.02963685 0.07662498 0.02897083 0.06944096 0.009955942 0.0561589 0.02963685 0.06225997 0.03160399 0.05519586 0.007995963 0.062756 0.00733298 0.06944096 0.02963685 0.06225997 0.009955942 0.0561589 0.007995963 0.062756 0.02963685 0.06225997 0.01316899 0.04969882 0.03160399 0.05519586 0.03481882 0.04831099 0.01316899 0.04969882 0.009955942 0.0561589 0.03160399 0.05519586 0.01755595 0.043428 0.03481882 0.04831099 0.03919982 0.04166787 0.01755595 0.043428 0.01316899 0.04969882 0.03481882 0.04831099 0.02302289 0.03739899 0.03919982 0.04166787 0.04464983 0.03532797 0.02302289 0.03739899 0.01755595 0.043428 0.03919982 0.04166787 0.02945798 0.031663 0.04464983 0.03532797 0.05104982 0.02935296 0.02945798 0.031663 0.02302289 0.03739899 0.04464983 0.03532797 0.03673595 0.02626997 0.05104982 0.02935296 0.05827283 0.02380084 0.03673595 0.02626997 0.02945798 0.031663 0.05104982 0.02935296 0.04471898 0.02126795 0.05827283 0.02380084 0.06617796 0.018727 0.04471898 0.02126795 0.03673595 0.02626997 0.05827283 0.02380084 0.05326396 0.01670295 0.06617796 0.018727 0.07462 0.01418197 0.05326396 0.01670295 0.04471898 0.02126795 0.06617796 0.018727 0.06225585 0.01261287 0.07462 0.01418197 0.083449 0.01021099 0.06225585 0.01261287 0.05326396 0.01670295 0.07462 0.01418197 0.07775598 0.00851798 0.083449 0.01021099 0.09251898 0.006852984 0.06595498 0.01157999 0.06225585 0.01261287 0.083449 0.01021099 0.07775598 0.00851798 0.06595498 0.01157999 0.083449 0.01021099 0.08906698 0.005938947 0.09251898 0.006852984 0.101689 0.004138946 0.08906698 0.005938947 0.07775598 0.00851798 0.09251898 0.006852984 0.110464 0.002141952 0.101689 0.004138946 0.110829 0.002091944 0.09999597 0.003805935 0.08906698 0.005938947 0.101689 0.004138946 0.110464 0.002141952 0.09999597 0.003805935 0.101689 0.004138946 0.109787 0.002284944 0.110829 0.002091944 0.120423 9.59e-4 0.109787 0.002284944 0.110464 0.002141952 0.110829 0.002091944 0.124378 7.2e-4 0.120423 9.59e-4 0.129814 2.64e-4 0.124378 7.2e-4 0.109787 0.002284944 0.120423 9.59e-4 0.138616 4.5e-5 0.1386449 4.4e-5 0.129814 2.64e-4 0.124378 7.2e-4 0.129814 2.64e-4 0.1386449 4.4e-5 0.139393 2.17e-4 0.1386449 4.4e-5 0.138616 4.5e-5 0.124378 7.2e-4 0.1386449 4.4e-5 0.139393 2.17e-4 0.139481 2.61e-4 0.139393 2.17e-4 0.138616 4.5e-5 0.07710999 0.07632195 0.07667195 0.06944096 0.05259186 0.07638996 0.001935899 0.05776399 0.007995963 0.062756 0.009955942 0.0561589 0.001935899 0.05776399 0.001185894 0.06392896 0.007995963 0.062756 0.003337979 0.05125397 0.009955942 0.0561589 0.01316899 0.04969882 0.003337979 0.05125397 0.001935899 0.05776399 0.009955942 0.0561589 0.004315972 0.04790484 0.01316899 0.04969882 0.01755595 0.043428 0.004315972 0.04790484 0.003337979 0.05125397 0.01316899 0.04969882 0.006857991 0.04115986 0.01755595 0.043428 0.02302289 0.03739899 0.005488932 0.04453599 0.004315972 0.04790484 0.01755595 0.043428 0.006857991 0.04115986 0.005488932 0.04453599 0.01755595 0.043428 0.01009386 0.03472495 0.02302289 0.03739899 0.02945798 0.031663 0.00841397 0.03785985 0.006857991 0.04115986 0.02302289 0.03739899 0.01009386 0.03472495 0.00841397 0.03785985 0.02302289 0.03739899 0.06810897 0.01085084 0.06595498 0.01157999 0.07775598 0.00851798 0.08169698 0.0075019 0.07775598 0.00851798 0.08906698 0.005938947 0.08169698 0.0075019 0.06810897 0.01085084 0.07775598 0.00851798 0.095573 0.004607975 0.08906698 0.005938947 0.09999597 0.003805935 0.095573 0.004607975 0.08169698 0.0075019 0.08906698 0.005938947 0.109787 0.002284944 0.09999597 0.003805935 0.110464 0.002141952 0.109787 0.002284944 0.095573 0.004607975 0.09999597 0.003805935 6.89e-4 0.06169492 0.001185894 0.06392896 0.001935899 0.05776399 0.001884937 0.05438894 0.001935899 0.05776399 0.003337979 0.05125397 6.89e-4 0.06169492 0.001935899 0.05776399 0.001884937 0.05438894 0.001884937 0.05438894 0.003337979 0.05125397 0.004315972 0.04790484 0.003672957 0.04777598 0.004315972 0.04790484 0.005488932 0.04453599 0.001884937 0.05438894 0.004315972 0.04790484 0.003672957 0.04777598 0.005862951 0.04193097 0.005488932 0.04453599 0.006857991 0.04115986 0.003672957 0.04777598 0.005488932 0.04453599 0.005862951 0.04193097 0.005862951 0.04193097 0.006857991 0.04115986 0.00841397 0.03785985 0.008298993 0.03681695 0.00841397 0.03785985 0.01009386 0.03472495 0.005862951 0.04193097 0.00841397 0.03785985 0.008298993 0.03681695 0.125229 0.00116986 0.139393 2.17e-4 0.139481 2.61e-4 0.125229 0.00116986 0.124378 7.2e-4 0.139393 2.17e-4 0.150517 0.001223981 0.139481 2.61e-4 0.149782 3.99e-4 0.150517 0.001223981 0.139571 3.12e-4 0.139481 2.61e-4 0.125229 0.00116986 0.139481 2.61e-4 0.139571 3.12e-4 0.160787 0.002183914 0.149782 3.99e-4 0.160209 0.001334965 0.160787 0.002183914 0.150517 0.001223981 0.149782 3.99e-4 0.1710799 0.003984928 0.160209 0.001334965 0.170652 0.003123939 0.1710799 0.003984928 0.160787 0.002183914 0.160209 0.001334965 0.181262 0.006681919 0.170652 0.003123939 0.180981 0.005820989 0.181262 0.006681919 0.1710799 0.003984928 0.170652 0.003123939 0.191172 0.01031899 0.180981 0.005820989 0.191035 0.009468972 0.191172 0.01031899 0.181262 0.006681919 0.180981 0.005820989 0.200628 0.01491987 0.191035 0.009468972 0.200633 0.01409184 0.200628 0.01491987 0.191172 0.01031899 0.191035 0.009468972 0.209432 0.02048099 0.200633 0.01409184 0.209578 0.01969099 0.209432 0.02048099 0.200628 0.01491987 0.200633 0.01409184 0.2173759 0.02696895 0.209578 0.01969099 0.217663 0.02623695 0.2173759 0.02696895 0.209432 0.02048099 0.209578 0.01969099 0.224258 0.03430485 0.217663 0.02623695 0.2246789 0.03365695 0.224258 0.03430485 0.2173759 0.02696895 0.217663 0.02623695 0.229883 0.04237186 0.2246789 0.03365695 0.230427 0.04183799 0.229883 0.04237186 0.224258 0.03430485 0.2246789 0.03365695 0.234063 0.05104082 0.230427 0.04183799 0.23471 0.05065596 0.234063 0.05104082 0.229883 0.04237186 0.230427 0.04183799 0.23665 0.06012797 0.23471 0.05065596 0.237367 0.05992382 0.23665 0.06012797 0.234063 0.05104082 0.23471 0.05065596 0.150517 0.001223981 0.140105 7.37e-4 0.139571 3.12e-4 0.125229 0.00116986 0.139571 3.12e-4 0.140105 7.37e-4 0.150517 0.001223981 0.1403779 0.001046836 0.140105 7.37e-4 0.126017 0.002000987 0.140105 7.37e-4 0.1403779 0.001046836 0.126017 0.002000987 0.125229 0.00116986 0.140105 7.37e-4 0.151086 0.002484977 0.1403779 0.001046836 0.150517 0.001223981 0.151086 0.002484977 0.140434 0.001120865 0.1403779 0.001046836 0.126017 0.002000987 0.1403779 0.001046836 0.140434 0.001120865 0.161194 0.003411889 0.150517 0.001223981 0.160787 0.002183914 0.161194 0.003411889 0.151086 0.002484977 0.150517 0.001223981 0.171331 0.005176961 0.160787 0.002183914 0.1710799 0.003984928 0.171331 0.005176961 0.161194 0.003411889 0.160787 0.002183914 0.18136 0.007837951 0.1710799 0.003984928 0.181262 0.006681919 0.18136 0.007837951 0.171331 0.005176961 0.1710799 0.003984928 0.191117 0.01143586 0.181262 0.006681919 0.191172 0.01031899 0.191117 0.01143586 0.18136 0.007837951 0.181262 0.006681919 0.200416 0.01599097 0.191172 0.01031899 0.200628 0.01491987 0.200416 0.01599097 0.191117 0.01143586 0.191172 0.01031899 0.209059 0.02149397 0.200628 0.01491987 0.209432 0.02048099 0.209059 0.02149397 0.200416 0.01599097 0.200628 0.01491987 0.216838 0.02790397 0.209432 0.02048099 0.2173759 0.02696895 0.216838 0.02790397 0.209059 0.02149397 0.209432 0.02048099 0.223554 0.03513383 0.2173759 0.02696895 0.224258 0.03430485 0.223554 0.03513383 0.216838 0.02790397 0.2173759 0.02696895 0.229023 0.04305785 0.224258 0.03430485 0.229883 0.04237186 0.229023 0.04305785 0.223554 0.03513383 0.224258 0.03430485 0.233069 0.05153685 0.229883 0.04237186 0.234063 0.05104082 0.233069 0.05153685 0.229023 0.04305785 0.229883 0.04237186 0.235562 0.06039083 0.234063 0.05104082 0.23665 0.06012797 0.235562 0.06039083 0.233069 0.05153685 0.234063 0.05104082 0.151086 0.002484977 0.140738 0.001580834 0.140434 0.001120865 0.126017 0.002000987 0.140434 0.001120865 0.140738 0.001580834 0.151086 0.002484977 0.141116 0.002341926 0.140738 0.001580834 0.126689 0.003155887 0.140738 0.001580834 0.141116 0.002341926 0.126689 0.003155887 0.126017 0.002000987 0.140738 0.001580834 0.148869 0.003978967 0.141116 0.002341926 0.151086 0.002484977 0.148869 0.003978967 0.141142 0.002403974 0.141116 0.002341926 0.126689 0.003155887 0.141116 0.002341926 0.141142 0.002403974 0.155193 0.004293978 0.151086 0.002484977 0.161194 0.003411889 0.155193 0.004293978 0.148869 0.003978967 0.151086 0.002484977 0.162787 0.005098998 0.161194 0.003411889 0.171331 0.005176961 0.156198 0.004370987 0.155193 0.004293978 0.161194 0.003411889 0.162787 0.005098998 0.156198 0.004370987 0.161194 0.003411889 0.176363 0.007796943 0.171331 0.005176961 0.18136 0.007837951 0.169382 0.006199896 0.162787 0.005098998 0.171331 0.005176961 0.176363 0.007796943 0.169382 0.006199896 0.171331 0.005176961 0.1832489 0.009850978 0.18136 0.007837951 0.191117 0.01143586 0.1832489 0.009850978 0.176363 0.007796943 0.18136 0.007837951 0.193284 0.01380884 0.191117 0.01143586 0.200416 0.01599097 0.1890709 0.01199597 0.1832489 0.009850978 0.191117 0.01143586 0.193284 0.01380884 0.1890709 0.01199597 0.191117 0.01143586 0.200855 0.01771485 0.200416 0.01599097 0.209059 0.02149397 0.194736 0.01449483 0.193284 0.01380884 0.200416 0.01599097 0.200855 0.01771485 0.194736 0.01449483 0.200416 0.01599097 0.211199 0.02473396 0.209059 0.02149397 0.216838 0.02790397 0.206657 0.02137196 0.200855 0.01771485 0.209059 0.02149397 0.211199 0.02473396 0.206657 0.02137196 0.209059 0.02149397 0.222099 0.035438 0.216838 0.02790397 0.223554 0.03513383 0.215439 0.02837491 0.211199 0.02473396 0.216838 0.02790397 0.222099 0.035438 0.215439 0.02837491 0.216838 0.02790397 0.227266 0.04275482 0.223554 0.03513383 0.229023 0.04305785 0.227266 0.04275482 0.222099 0.035438 0.223554 0.03513383 0.22965 0.04711997 0.229023 0.04305785 0.233069 0.05153685 0.22965 0.04711997 0.227266 0.04275482 0.229023 0.04305785 0.233077 0.05598396 0.233069 0.05153685 0.235562 0.06039083 0.231612 0.05161082 0.22965 0.04711997 0.233069 0.05153685 0.233077 0.05598396 0.231612 0.05161082 0.233069 0.05153685 0.234133 0.06041985 0.233077 0.05598396 0.235562 0.06039083 0.234775 0.06492197 0.234133 0.06041985 0.235562 0.06039083 0.148869 0.003978967 0.141256 0.002695918 0.141142 0.002403974 0.126689 0.003155887 0.141142 0.002403974 0.141256 0.002695918 0.148869 0.003978967 0.1416299 0.004008889 0.141256 0.002695918 0.132623 0.004210889 0.141256 0.002695918 0.1416299 0.004008889 0.132623 0.004210889 0.126689 0.003155887 0.141256 0.002695918 0.1231819 0.004909992 0.1416299 0.004008889 0.148869 0.003978967 0.132623 0.004210889 0.1416299 0.004008889 0.1231819 0.004909992 0.12021 0.005222976 0.148869 0.003978967 0.155193 0.004293978 0.1231819 0.004909992 0.148869 0.003978967 0.12021 0.005222976 0.162787 0.005098998 0.155193 0.004293978 0.156198 0.004370987 0.169382 0.006199896 0.155193 0.004293978 0.162787 0.005098998 0.176363 0.007796943 0.155193 0.004293978 0.169382 0.006199896 0.15631 0.009680986 0.155193 0.004293978 0.176363 0.007796943 0.149378 0.00900197 0.12021 0.005222976 0.155193 0.004293978 0.154955 0.009442985 0.155193 0.004293978 0.15631 0.009680986 0.154955 0.009442985 0.149378 0.00900197 0.155193 0.004293978 0.15631 0.009680986 0.176363 0.007796943 0.1832489 0.009850978 0.169648 0.01203584 0.1832489 0.009850978 0.1890709 0.01199597 0.169648 0.01203584 0.15631 0.009680986 0.1832489 0.009850978 0.169648 0.01203584 0.1890709 0.01199597 0.193284 0.01380884 0.193947 0.01737797 0.193284 0.01380884 0.194736 0.01449483 0.192856 0.01695895 0.193284 0.01380884 0.193947 0.01737797 0.184521 0.014678 0.169648 0.01203584 0.193284 0.01380884 0.192856 0.01695895 0.184521 0.014678 0.193284 0.01380884 0.193947 0.01737797 0.194736 0.01449483 0.200855 0.01771485 0.201135 0.02089095 0.200855 0.01771485 0.206657 0.02137196 0.201135 0.02089095 0.193947 0.01737797 0.200855 0.01771485 0.201135 0.02089095 0.206657 0.02137196 0.211199 0.02473396 0.208926 0.02640396 0.211199 0.02473396 0.215439 0.02837491 0.208926 0.02640396 0.201135 0.02089095 0.211199 0.02473396 0.2157379 0.03321588 0.215439 0.02837491 0.222099 0.035438 0.2157379 0.03321588 0.208926 0.02640396 0.215439 0.02837491 0.221381 0.04118084 0.222099 0.035438 0.227266 0.04275482 0.221381 0.04118084 0.2157379 0.03321588 0.222099 0.035438 0.221381 0.04118084 0.227266 0.04275482 0.22965 0.04711997 0.225634 0.05012583 0.22965 0.04711997 0.231612 0.05161082 0.225634 0.05012583 0.221381 0.04118084 0.22965 0.04711997 0.225634 0.05012583 0.231612 0.05161082 0.233077 0.05598396 0.228248 0.05966883 0.233077 0.05598396 0.234133 0.06041985 0.228248 0.05966883 0.225634 0.05012583 0.233077 0.05598396 0.228248 0.05966883 0.234133 0.06041985 0.234775 0.06492197 0.069283 0.01104086 0.06810897 0.01085084 0.08169698 0.0075019 0.08281195 0.007750988 0.08169698 0.0075019 0.095573 0.004607975 0.08281195 0.007750988 0.069283 0.01104086 0.08169698 0.0075019 0.096619 0.004920959 0.095573 0.004607975 0.109787 0.002284944 0.096619 0.004920959 0.08281195 0.007750988 0.095573 0.004607975 0.110747 0.002664983 0.109787 0.002284944 0.124378 7.2e-4 0.110747 0.002664983 0.096619 0.004920959 0.109787 0.002284944 0.125229 0.00116986 0.110747 0.002664983 0.124378 7.2e-4 0.070463 0.01182097 0.069283 0.01104086 0.08281195 0.007750988 0.08391398 0.008540987 0.08281195 0.007750988 0.096619 0.004920959 0.08391398 0.008540987 0.070463 0.01182097 0.08281195 0.007750988 0.09763395 0.005721986 0.096619 0.004920959 0.110747 0.002664983 0.09763395 0.005721986 0.08391398 0.008540987 0.096619 0.004920959 0.111659 0.003480911 0.110747 0.002664983 0.125229 0.00116986 0.111659 0.003480911 0.09763395 0.005721986 0.110747 0.002664983 0.126017 0.002000987 0.111659 0.003480911 0.125229 0.00116986 0.07152897 0.01310884 0.070463 0.01182097 0.08391398 0.008540987 0.08490198 0.00979495 0.08391398 0.008540987 0.09763395 0.005721986 0.08490198 0.00979495 0.07152897 0.01310884 0.08391398 0.008540987 0.09853398 0.006943941 0.09763395 0.005721986 0.111659 0.003480911 0.09853398 0.006943941 0.08490198 0.00979495 0.09763395 0.005721986 0.112456 0.004669964 0.111659 0.003480911 0.126017 0.002000987 0.112456 0.004669964 0.09853398 0.006943941 0.111659 0.003480911 0.126689 0.003155887 0.112456 0.004669964 0.126017 0.002000987 0.08182495 0.01231884 0.07152897 0.01310884 0.08490198 0.00979495 0.08182495 0.01231884 0.070719 0.01522582 0.07152897 0.01310884 0.08737099 0.01099383 0.08490198 0.00979495 0.09853398 0.006943941 0.08737099 0.01099383 0.08182495 0.01231884 0.08490198 0.00979495 0.103049 0.007763922 0.09853398 0.006943941 0.112456 0.004669964 0.09258699 0.009830951 0.08737099 0.01099383 0.09853398 0.006943941 0.103049 0.007763922 0.09258699 0.009830951 0.09853398 0.006943941 0.113287 0.006108999 0.112456 0.004669964 0.126689 0.003155887 0.113287 0.006108999 0.103049 0.007763922 0.112456 0.004669964 0.12021 0.005222976 0.113287 0.006108999 0.126689 0.003155887 0.1231819 0.004909992 0.12021 0.005222976 0.126689 0.003155887 0.132623 0.004210889 0.1231819 0.004909992 0.126689 0.003155887 0.08996796 0.024782 0.070719 0.01522582 0.08182495 0.01231884 0.08996796 0.024782 0.08182495 0.01231884 0.08737099 0.01099383 0.122503 0.01635396 0.08737099 0.01099383 0.09258699 0.009830951 0.08996796 0.024782 0.08737099 0.01099383 0.122503 0.01635396 0.122503 0.01635396 0.09258699 0.009830951 0.103049 0.007763922 0.122503 0.01635396 0.103049 0.007763922 0.113287 0.006108999 0.122503 0.01635396 0.113287 0.006108999 0.12021 0.005222976 0.1339499 0.01455599 0.122503 0.01635396 0.12021 0.005222976 0.138723 0.01152098 0.1339499 0.01455599 0.12021 0.005222976 0.143847 0.009695947 0.138723 0.01152098 0.12021 0.005222976 0.149378 0.00900197 0.143847 0.009695947 0.12021 0.005222976 0.195917 0.01903897 0.193947 0.01737797 0.201135 0.02089095 0.191529 0.01702797 0.192856 0.01695895 0.193947 0.01737797 0.191529 0.01702797 0.193947 0.01737797 0.195917 0.01903897 0.200112 0.02148896 0.201135 0.02089095 0.208926 0.02640396 0.195917 0.01903897 0.201135 0.02089095 0.200112 0.02148896 0.207791 0.02763897 0.208926 0.02640396 0.2157379 0.03321588 0.200112 0.02148896 0.208926 0.02640396 0.207791 0.02763897 0.214277 0.03524684 0.2157379 0.03321588 0.221381 0.04118084 0.207791 0.02763897 0.2157379 0.03321588 0.214277 0.03524684 0.2193869 0.04410582 0.221381 0.04118084 0.225634 0.05012583 0.214277 0.03524684 0.221381 0.04118084 0.2193869 0.04410582 0.222898 0.05386698 0.225634 0.05012583 0.228248 0.05966883 0.2193869 0.04410582 0.225634 0.05012583 0.222898 0.05386698 0.224686 0.06418597 0.228248 0.05966883 0.2291229 0.06944096 0.222898 0.05386698 0.228248 0.05966883 0.224686 0.06418597 0.224686 0.07470095 0.2291229 0.06944096 0.228283 0.07901799 0.224686 0.06418597 0.2291229 0.06944096 0.224686 0.07470095 0.222891 0.08504098 0.228283 0.07901799 0.225744 0.088458 0.224686 0.07470095 0.228283 0.07901799 0.222891 0.08504098 0.2193599 0.09483295 0.225744 0.088458 0.221567 0.097382 0.222891 0.08504098 0.225744 0.088458 0.2193599 0.09483295 0.214224 0.103709 0.221567 0.097382 0.21596 0.105401 0.2193599 0.09483295 0.221567 0.097382 0.214224 0.103709 0.207723 0.111308 0.21596 0.105401 0.209133 0.112302 0.214224 0.103709 0.21596 0.105401 0.207723 0.111308 0.2000499 0.117433 0.209133 0.112302 0.2013069 0.11789 0.207723 0.111308 0.209133 0.112302 0.2000499 0.117433 0.2000499 0.117433 0.2013069 0.11789 0.193944 0.121505 0.191493 0.121868 0.193944 0.121505 0.1929489 0.121888 0.2000499 0.117433 0.193944 0.121505 0.191493 0.121868 0.152739 0.009168982 0.15631 0.009680986 0.169648 0.01203584 0.152739 0.009168982 0.154955 0.009442985 0.15631 0.009680986 0.152739 0.009168982 0.169648 0.01203584 0.184521 0.014678 0.182384 0.01441782 0.184521 0.014678 0.192856 0.01695895 0.182384 0.01441782 0.152739 0.009168982 0.184521 0.014678 0.182384 0.01441782 0.192856 0.01695895 0.191529 0.01702797 0.126655 0.02352398 0.124414 0.02765583 0.122503 0.01635396 0.08996796 0.024782 0.122503 0.01635396 0.124414 0.02765583 0.129952 0.01854795 0.126655 0.02352398 0.122503 0.01635396 0.1339499 0.01455599 0.129952 0.01854795 0.122503 0.01635396 0.100099 0.052953 0.124414 0.02765583 0.126655 0.02352398 0.09189897 0.038809 0.08996796 0.024782 0.124414 0.02765583 0.118334 0.03834986 0.09189897 0.038809 0.124414 0.02765583 0.100099 0.052953 0.118334 0.03834986 0.124414 0.02765583 0.121172 0.02304196 0.126655 0.02352398 0.129952 0.01854795 0.121172 0.02304196 0.100099 0.052953 0.126655 0.02352398 0.126107 0.01738697 0.129952 0.01854795 0.1339499 0.01455599 0.126107 0.01738697 0.121172 0.02304196 0.129952 0.01854795 0.132001 0.01300096 0.1339499 0.01455599 0.138723 0.01152098 0.132001 0.01300096 0.126107 0.01738697 0.1339499 0.01455599 0.1386 0.01008397 0.138723 0.01152098 0.143847 0.009695947 0.1386 0.01008397 0.132001 0.01300096 0.138723 0.01152098 0.145617 0.008779942 0.143847 0.009695947 0.149378 0.00900197 0.145617 0.008779942 0.1386 0.01008397 0.143847 0.009695947 0.145617 0.008779942 0.149378 0.00900197 0.154955 0.009442985 0.152739 0.009168982 0.145617 0.008779942 0.154955 0.009442985 0.06822896 0.02796697 0.08996796 0.024782 0.09189897 0.038809 0.06822896 0.02796697 0.06214886 0.02351099 0.08996796 0.024782 0.118334 0.03834986 0.093203 0.05300897 0.09189897 0.038809 0.09142696 0.05068999 0.09189897 0.038809 0.093203 0.05300897 0.07427197 0.03295296 0.06822896 0.02796697 0.09189897 0.038809 0.08019399 0.03842484 0.07427197 0.03295296 0.09189897 0.038809 0.08591598 0.04433 0.08019399 0.03842484 0.09189897 0.038809 0.09142696 0.05068999 0.08591598 0.04433 0.09189897 0.038809 0.109218 0.05322498 0.09467899 0.05527883 0.093203 0.05300897 0.08997195 0.05676597 0.093203 0.05300897 0.09467899 0.05527883 0.118334 0.03834986 0.109218 0.05322498 0.093203 0.05300897 0.089531 0.05250597 0.09142696 0.05068999 0.093203 0.05300897 0.08783799 0.05425685 0.089531 0.05250597 0.093203 0.05300897 0.08997195 0.05676597 0.08783799 0.05425685 0.093203 0.05300897 0.106734 0.0582 0.09597796 0.057684 0.09467899 0.05527883 0.09183299 0.05955797 0.09467899 0.05527883 0.09597796 0.057684 0.109218 0.05322498 0.106734 0.0582 0.09467899 0.05527883 0.08997195 0.05676597 0.09467899 0.05527883 0.09183299 0.05955797 0.106734 0.0582 0.09703797 0.06011188 0.09597796 0.057684 0.09183299 0.05955797 0.09597796 0.057684 0.09703797 0.06011188 0.105225 0.06369298 0.09783101 0.06250995 0.09703797 0.06011188 0.09331095 0.06263697 0.09703797 0.06011188 0.09783101 0.06250995 0.106734 0.0582 0.105225 0.06369298 0.09703797 0.06011188 0.09183299 0.05955797 0.09703797 0.06011188 0.09331095 0.06263697 0.105225 0.06369298 0.09838098 0.064875 0.09783101 0.06250995 0.09331095 0.06263697 0.09783101 0.06250995 0.09838098 0.064875 0.1047199 0.06944096 0.0988 0.06944096 0.09838098 0.064875 0.09427601 0.06596499 0.09838098 0.064875 0.0988 0.06944096 0.105225 0.06369298 0.1047199 0.06944096 0.09838098 0.064875 0.09331095 0.06263697 0.09838098 0.064875 0.09427601 0.06596499 0.105225 0.07518798 0.09839397 0.07393598 0.0988 0.06944096 0.09461396 0.06944096 0.0988 0.06944096 0.09839397 0.07393598 0.1047199 0.06944096 0.105225 0.07518798 0.0988 0.06944096 0.09427601 0.06596499 0.0988 0.06944096 0.09461396 0.06944096 0.105225 0.07518798 0.09785497 0.076285 0.09839397 0.07393598 0.09427601 0.07291698 0.09839397 0.07393598 0.09785497 0.076285 0.09461396 0.06944096 0.09839397 0.07393598 0.09427601 0.07291698 0.106734 0.08068096 0.09707099 0.07868099 0.09785497 0.076285 0.09331095 0.07624298 0.09785497 0.076285 0.09707099 0.07868099 0.105225 0.07518798 0.106734 0.08068096 0.09785497 0.076285 0.09427601 0.07291698 0.09785497 0.076285 0.09331095 0.07624298 0.106734 0.08068096 0.096017 0.08111798 0.09707099 0.07868099 0.09331095 0.07624298 0.09707099 0.07868099 0.096017 0.08111798 0.109218 0.085657 0.09471595 0.083543 0.096017 0.08111798 0.09183299 0.07932299 0.096017 0.08111798 0.09471595 0.083543 0.106734 0.08068096 0.109218 0.085657 0.096017 0.08111798 0.09331095 0.07624298 0.096017 0.08111798 0.09183299 0.07932299 0.109218 0.085657 0.09320795 0.085864 0.09471595 0.083543 0.08997297 0.082116 0.09471595 0.083543 0.09320795 0.085864 0.09183299 0.07932299 0.09471595 0.083543 0.08997297 0.082116 0.118334 0.100532 0.09189897 0.1000699 0.09320795 0.085864 0.09142696 0.08819198 0.09320795 0.085864 0.09189897 0.1000699 0.109218 0.085657 0.118334 0.100532 0.09320795 0.085864 0.08997297 0.082116 0.09320795 0.085864 0.09142696 0.08819198 0.124414 0.111226 0.08996897 0.114099 0.09189897 0.1000699 0.080177 0.1004739 0.09189897 0.1000699 0.08996897 0.114099 0.118334 0.100532 0.124414 0.111226 0.09189897 0.1000699 0.08590495 0.09456199 0.09142696 0.08819198 0.09189897 0.1000699 0.080177 0.1004739 0.08590495 0.09456199 0.09189897 0.1000699 0.124414 0.111226 0.122503 0.122529 0.08996897 0.114099 0.07424998 0.105948 0.080177 0.1004739 0.08996897 0.114099 0.06820696 0.110932 0.07424998 0.105948 0.08996897 0.114099 0.06213498 0.115381 0.06820696 0.110932 0.08996897 0.114099 0.126655 0.115357 0.122503 0.122529 0.124414 0.111226 0.138669 0.1273339 0.143715 0.129154 0.122503 0.122529 0.133971 0.124342 0.138669 0.1273339 0.122503 0.122529 0.129995 0.120387 0.133971 0.124342 0.122503 0.122529 0.126655 0.115357 0.129995 0.120387 0.122503 0.122529 0.121172 0.11584 0.124414 0.111226 0.118334 0.100532 0.121172 0.11584 0.126655 0.115357 0.124414 0.111226 0.121172 0.11584 0.118334 0.100532 0.109218 0.085657 0.100099 0.08592897 0.109218 0.085657 0.106734 0.08068096 0.121172 0.11584 0.109218 0.085657 0.100099 0.08592897 0.09558796 0.07530695 0.106734 0.08068096 0.105225 0.07518798 0.09730899 0.08089399 0.106734 0.08068096 0.09558796 0.07530695 0.100099 0.08592897 0.106734 0.08068096 0.09730899 0.08089399 0.09558796 0.07530695 0.105225 0.07518798 0.1047199 0.06944096 0.095007 0.06944096 0.1047199 0.06944096 0.105225 0.06369298 0.09558796 0.07530695 0.1047199 0.06944096 0.095007 0.06944096 0.09558796 0.06357496 0.105225 0.06369298 0.106734 0.0582 0.095007 0.06944096 0.105225 0.06369298 0.09558796 0.06357496 0.09730899 0.05798786 0.106734 0.0582 0.109218 0.05322498 0.09558796 0.06357496 0.106734 0.0582 0.09730899 0.05798786 0.100099 0.052953 0.109218 0.05322498 0.118334 0.03834986 0.09730899 0.05798786 0.109218 0.05322498 0.100099 0.052953 0.06644499 0.03052097 0.06214886 0.02351099 0.06822896 0.02796697 0.06644499 0.03052097 0.05826985 0.02496784 0.06214886 0.02351099 0.06644499 0.03052097 0.06822896 0.02796697 0.07427197 0.03295296 0.07448196 0.03703898 0.07427197 0.03295296 0.08019399 0.03842484 0.07448196 0.03703898 0.06644499 0.03052097 0.07427197 0.03295296 0.08221095 0.04439896 0.08019399 0.03842484 0.08591598 0.04433 0.08221095 0.04439896 0.07448196 0.03703898 0.08019399 0.03842484 0.08221095 0.04439896 0.08591598 0.04433 0.09142696 0.05068999 0.089531 0.05250597 0.08221095 0.04439896 0.09142696 0.05068999 0.089531 0.08637595 0.09142696 0.08819198 0.08590495 0.09456199 0.08997297 0.082116 0.09142696 0.08819198 0.089531 0.08637595 0.08221697 0.09447598 0.08590495 0.09456199 0.080177 0.1004739 0.089531 0.08637595 0.08590495 0.09456199 0.08221697 0.09447598 0.07448697 0.101839 0.080177 0.1004739 0.07424998 0.105948 0.08221697 0.09447598 0.080177 0.1004739 0.07448697 0.101839 0.07448697 0.101839 0.07424998 0.105948 0.06820696 0.110932 0.06644898 0.108358 0.06820696 0.110932 0.06213498 0.115381 0.07448697 0.101839 0.06820696 0.110932 0.06644898 0.108358 0.06644898 0.108358 0.06213498 0.115381 0.05827283 0.113912 0.182384 0.124464 0.15631 0.1292 0.154955 0.1294389 0.182384 0.124464 0.169648 0.126846 0.15631 0.1292 0.152739 0.129712 0.154955 0.1294389 0.1492339 0.129877 0.182384 0.124464 0.154955 0.1294389 0.152739 0.129712 0.145617 0.130102 0.1492339 0.129877 0.143715 0.129154 0.152739 0.129712 0.1492339 0.129877 0.145617 0.130102 0.1386 0.128798 0.143715 0.129154 0.138669 0.1273339 0.145617 0.130102 0.143715 0.129154 0.1386 0.128798 0.132001 0.125881 0.138669 0.1273339 0.133971 0.124342 0.1386 0.128798 0.138669 0.1273339 0.132001 0.125881 0.126107 0.121494 0.133971 0.124342 0.129995 0.120387 0.132001 0.125881 0.133971 0.124342 0.126107 0.121494 0.126107 0.121494 0.129995 0.120387 0.126655 0.115357 0.126107 0.121494 0.126655 0.115357 0.121172 0.11584 0.191493 0.121868 0.1929489 0.121888 0.184521 0.124204 0.182384 0.124464 0.184521 0.124204 0.169648 0.126846 0.191493 0.121868 0.184521 0.124204 0.182384 0.124464 0.05826985 0.02496784 0.05016487 0.02045691 0.05294096 0.02005195 0.04956996 0.01894485 0.05294096 0.02005195 0.05016487 0.02045691 0.04956996 0.01894485 0.052293 0.01842099 0.05294096 0.02005195 0.05222886 0.02504396 0.05016487 0.02045691 0.05826985 0.02496784 0.05222886 0.02504396 0.047634 0.02076786 0.05016487 0.02045691 0.04697483 0.01941084 0.05016487 0.02045691 0.047634 0.02076786 0.04697483 0.01941084 0.04956996 0.01894485 0.05016487 0.02045691 0.06135696 0.03039795 0.05826985 0.02496784 0.06644499 0.03052097 0.06135696 0.03039795 0.05222886 0.02504396 0.05826985 0.02496784 0.07053399 0.03717595 0.06644499 0.03052097 0.07448196 0.03703898 0.07053399 0.03717595 0.06135696 0.03039795 0.06644499 0.03052097 0.07942199 0.04517698 0.07448196 0.03703898 0.08221095 0.04439896 0.07942199 0.04517698 0.07053399 0.03717595 0.07448196 0.03703898 0.07942199 0.04517698 0.08221095 0.04439896 0.089531 0.05250597 0.08783799 0.05425685 0.07942199 0.04517698 0.089531 0.05250597 0.05222886 0.02504396 0.04537683 0.02101182 0.047634 0.02076786 0.04451197 0.019822 0.047634 0.02076786 0.04537683 0.02101182 0.04451197 0.019822 0.04697483 0.01941084 0.047634 0.02076786 0.05222886 0.02504396 0.04343295 0.02119797 0.04537683 0.02101182 0.04451197 0.019822 0.04537683 0.02101182 0.04343295 0.02119797 0.04355895 0.02406698 0.04343295 0.02119797 0.05222886 0.02504396 0.04355895 0.02406698 0.04150682 0.02135795 0.04343295 0.02119797 0.04219299 0.02018398 0.04343295 0.02119797 0.04150682 0.02135795 0.04219299 0.02018398 0.04451197 0.019822 0.04343295 0.02119797 0.05176997 0.02768695 0.05222886 0.02504396 0.06135696 0.03039795 0.05176997 0.02768695 0.04355895 0.02406698 0.05222886 0.02504396 0.06050586 0.03275996 0.06135696 0.03039795 0.07053399 0.03717595 0.06050586 0.03275996 0.05176997 0.02768695 0.06135696 0.03039795 0.069404 0.03927987 0.07053399 0.03717595 0.07942199 0.04517698 0.069404 0.03927987 0.06050586 0.03275996 0.07053399 0.03717595 0.07808995 0.04704385 0.07942199 0.04517698 0.08783799 0.05425685 0.07808995 0.04704385 0.069404 0.03927987 0.07942199 0.04517698 0.08636701 0.05592083 0.07808995 0.04704385 0.08783799 0.05425685 0.08997195 0.05676597 0.08636701 0.05592083 0.08783799 0.05425685 0.04355895 0.02406698 0.03989487 0.021483 0.04150682 0.02135795 0.04002285 0.02050387 0.04150682 0.02135795 0.03989487 0.021483 0.04002285 0.02050387 0.04219299 0.02018398 0.04150682 0.02135795 0.04355895 0.02406698 0.03845387 0.02158099 0.03989487 0.021483 0.03801697 0.02078884 0.03989487 0.021483 0.03845387 0.02158099 0.03801697 0.02078884 0.04002285 0.02050387 0.03989487 0.021483 0.04355895 0.02406698 0.03718996 0.02166295 0.03845387 0.02158099 0.03801697 0.02078884 0.03845387 0.02158099 0.03718996 0.02166295 0.04355895 0.02406698 0.03605985 0.02173388 0.03718996 0.02166295 0.03617286 0.02104598 0.03718996 0.02166295 0.03605985 0.02173388 0.03617286 0.02104598 0.03801697 0.02078884 0.03718996 0.02166295 0.04048997 0.024872 0.03605985 0.02173388 0.04355895 0.02406698 0.03675484 0.02364099 0.03501296 0.02180296 0.03605985 0.02173388 0.03451287 0.021281 0.03605985 0.02173388 0.03501296 0.02180296 0.03712898 0.023754 0.03675484 0.02364099 0.03605985 0.02173388 0.04048997 0.024872 0.03712898 0.023754 0.03605985 0.02173388 0.03451287 0.021281 0.03617286 0.02104598 0.03605985 0.02173388 0.04417598 0.02628988 0.04355895 0.02406698 0.05176997 0.02768695 0.04295682 0.02579897 0.04048997 0.024872 0.04355895 0.02406698 0.04417598 0.02628988 0.04295682 0.02579897 0.04355895 0.02406698 0.05235987 0.03017383 0.05176997 0.02768695 0.06050586 0.03275996 0.04812896 0.02803695 0.04417598 0.02628988 0.05176997 0.02768695 0.05016899 0.02903199 0.04812896 0.02803695 0.05176997 0.02768695 0.05235987 0.03017383 0.05016899 0.02903199 0.05176997 0.02768695 0.06072998 0.03525698 0.06050586 0.03275996 0.069404 0.03927987 0.05889987 0.03404599 0.05235987 0.03017383 0.06050586 0.03275996 0.06072998 0.03525698 0.05889987 0.03404599 0.06050586 0.03275996 0.06882399 0.04133486 0.069404 0.03927987 0.07808995 0.04704385 0.068421 0.041004 0.06072998 0.03525698 0.069404 0.03927987 0.06882399 0.04133486 0.068421 0.041004 0.069404 0.03927987 0.077026 0.04873496 0.07808995 0.04704385 0.08636701 0.05592083 0.077026 0.04873496 0.06882399 0.04133486 0.07808995 0.04704385 0.078956 0.05068182 0.077026 0.04873496 0.08636701 0.05592083 0.08514297 0.05746996 0.078956 0.05068182 0.08636701 0.05592083 0.08997195 0.05676597 0.08514297 0.05746996 0.08636701 0.05592083 0.03412598 0.02290683 0.03406786 0.02186799 0.03501296 0.02180296 0.03451287 0.021281 0.03501296 0.02180296 0.03406786 0.02186799 0.03675484 0.02364099 0.03412598 0.02290683 0.03501296 0.02180296 0.03412598 0.02290683 0.03327 0.02192896 0.03406786 0.02186799 0.03306198 0.021501 0.03406786 0.02186799 0.03327 0.02192896 0.03306198 0.021501 0.03451287 0.021281 0.03406786 0.02186799 0.03412598 0.02290683 0.03260195 0.02199 0.03327 0.02192896 0.03186899 0.02171397 0.03327 0.02192896 0.03260195 0.02199 0.03186899 0.02171397 0.03306198 0.021501 0.03327 0.02192896 0.03133183 0.02225196 0.03165197 0.02211385 0.03260195 0.02199 0.03103798 0.02192384 0.03260195 0.02199 0.03165197 0.02211385 0.03412598 0.02290683 0.03133183 0.02225196 0.03260195 0.02199 0.03103798 0.02192384 0.03186899 0.02171397 0.03260195 0.02199 0.03103798 0.02192384 0.03165197 0.02211385 0.03133183 0.02225196 0.03724282 0.024818 0.03133183 0.02225196 0.03412598 0.02290683 0.03080385 0.02213698 0.03103798 0.02192384 0.03133183 0.02225196 0.03724282 0.024818 0.03138095 0.02227687 0.03133183 0.02225196 0.03724282 0.024818 0.03412598 0.02290683 0.03675484 0.02364099 0.04254084 0.02724796 0.03675484 0.02364099 0.03712898 0.023754 0.03724282 0.024818 0.03675484 0.02364099 0.04254084 0.02724796 0.04254084 0.02724796 0.03712898 0.023754 0.04048997 0.024872 0.04254084 0.02724796 0.04048997 0.024872 0.04295682 0.02579897 0.04871785 0.03077799 0.04295682 0.02579897 0.04417598 0.02628988 0.04254084 0.02724796 0.04295682 0.02579897 0.04871785 0.03077799 0.04871785 0.03077799 0.04417598 0.02628988 0.04812896 0.02803695 0.04871785 0.03077799 0.04812896 0.02803695 0.05016899 0.02903199 0.05601096 0.035703 0.05016899 0.02903199 0.05235987 0.03017383 0.04871785 0.03077799 0.05016899 0.02903199 0.05601096 0.035703 0.05601096 0.035703 0.05235987 0.03017383 0.05889987 0.03404599 0.06443196 0.04263287 0.05889987 0.03404599 0.06072998 0.03525698 0.05601096 0.035703 0.05889987 0.03404599 0.06443196 0.04263287 0.06443196 0.04263287 0.06072998 0.03525698 0.068421 0.041004 0.07343196 0.05180597 0.068421 0.041004 0.06882399 0.04133486 0.06443196 0.04263287 0.068421 0.041004 0.07343196 0.05180597 0.07343196 0.05180597 0.06882399 0.04133486 0.077026 0.04873496 0.07343196 0.05180597 0.077026 0.04873496 0.078956 0.05068182 0.07936596 0.05821084 0.078956 0.05068182 0.08514297 0.05746996 0.07936596 0.05821084 0.07343196 0.05180597 0.078956 0.05068182 0.08243596 0.06361895 0.07936596 0.05821084 0.08514297 0.05746996 0.08663898 0.05902493 0.08514297 0.05746996 0.08997195 0.05676597 0.08243596 0.06361895 0.08514297 0.05746996 0.08663898 0.05902493 0.05111998 0.01722186 0.052293 0.01842099 0.04956996 0.01894485 0.04838395 0.01787286 0.04956996 0.01894485 0.04697483 0.01941084 0.04838395 0.01787286 0.05111998 0.01722186 0.04956996 0.01894485 0.04578685 0.018462 0.04697483 0.01941084 0.04451197 0.019822 0.04578685 0.018462 0.04838395 0.01787286 0.04697483 0.01941084 0.04333299 0.01899397 0.04451197 0.019822 0.04219299 0.02018398 0.04333299 0.01899397 0.04578685 0.018462 0.04451197 0.019822 0.04103487 0.01947093 0.04219299 0.02018398 0.04002285 0.02050387 0.04103487 0.01947093 0.04333299 0.01899397 0.04219299 0.02018398 0.03889799 0.01990085 0.04002285 0.02050387 0.03801697 0.02078884 0.03889799 0.01990085 0.04103487 0.01947093 0.04002285 0.02050387 0.03693687 0.02028685 0.03801697 0.02078884 0.03617286 0.02104598 0.03693687 0.02028685 0.03889799 0.01990085 0.03801697 0.02078884 0.03514999 0.020639 0.03617286 0.02104598 0.03451287 0.021281 0.03514999 0.020639 0.03693687 0.02028685 0.03617286 0.02104598 0.03355985 0.02096194 0.03451287 0.021281 0.03306198 0.021501 0.03355985 0.02096194 0.03514999 0.020639 0.03451287 0.021281 0.03219085 0.02126199 0.03306198 0.021501 0.03186899 0.02171397 0.03219085 0.02126199 0.03355985 0.02096194 0.03306198 0.021501 0.03109395 0.02154499 0.03186899 0.02171397 0.03103798 0.02192384 0.03109395 0.02154499 0.03219085 0.02126199 0.03186899 0.02171397 0.03037399 0.02181386 0.03103798 0.02192384 0.03080385 0.02213698 0.03037399 0.02181386 0.03109395 0.02154499 0.03103798 0.02192384 0.03037399 0.02181386 0.03080385 0.02213698 0.03026497 0.02207297 0.02970182 0.02178198 0.03037399 0.02181386 0.03026497 0.02207297 0.02970182 0.02178198 0.03026497 0.02207297 0.02999287 0.02205985 0.04983294 0.01655 0.05111998 0.01722186 0.04838395 0.01787286 0.04708784 0.01729798 0.04838395 0.01787286 0.04578685 0.018462 0.04708784 0.01729798 0.04983294 0.01655 0.04838395 0.01787286 0.04449594 0.01797497 0.04578685 0.018462 0.04333299 0.01899397 0.04449594 0.01797497 0.04708784 0.01729798 0.04578685 0.018462 0.04206287 0.01858592 0.04333299 0.01899397 0.04103487 0.01947093 0.04206287 0.01858592 0.04449594 0.01797497 0.04333299 0.01899397 0.03979897 0.01913398 0.04103487 0.01947093 0.03889799 0.01990085 0.03979897 0.01913398 0.04206287 0.01858592 0.04103487 0.01947093 0.03770697 0.01962697 0.03889799 0.01990085 0.03693687 0.02028685 0.03770697 0.01962697 0.03979897 0.01913398 0.03889799 0.01990085 0.03580296 0.020069 0.03693687 0.02028685 0.03514999 0.020639 0.03580296 0.020069 0.03770697 0.01962697 0.03693687 0.02028685 0.03408586 0.02047085 0.03514999 0.020639 0.03355985 0.02096194 0.03408586 0.02047085 0.03580296 0.020069 0.03514999 0.020639 0.03257596 0.02083599 0.03355985 0.02096194 0.03219085 0.02126199 0.03257596 0.02083599 0.03408586 0.02047085 0.03355985 0.02096194 0.03129982 0.02117395 0.03219085 0.02126199 0.03109395 0.02154499 0.03129982 0.02117395 0.03257596 0.02083599 0.03219085 0.02126199 0.03030699 0.02148687 0.03109395 0.02154499 0.03037399 0.02181386 0.03030699 0.02148687 0.03129982 0.02117395 0.03109395 0.02154499 0.02970182 0.02178198 0.03030699 0.02148687 0.03037399 0.02181386 0.02972197 0.02205985 0.02970182 0.02178198 0.02999287 0.02205985 0.04856598 0.01647984 0.04983294 0.01655 0.04708784 0.01729798 0.04580599 0.01727795 0.04708784 0.01729798 0.04449594 0.01797497 0.04580599 0.01727795 0.04856598 0.01647984 0.04708784 0.01729798 0.04321485 0.01799297 0.04449594 0.01797497 0.04206287 0.01858592 0.04321485 0.01799297 0.04580599 0.01727795 0.04449594 0.01797497 0.04079896 0.01862984 0.04206287 0.01858592 0.03979897 0.01913398 0.04079896 0.01862984 0.04321485 0.01799297 0.04206287 0.01858592 0.03856682 0.01919597 0.03979897 0.01913398 0.03770697 0.01962697 0.03856682 0.01919597 0.04079896 0.01862984 0.03979897 0.01913398 0.03652 0.01969999 0.03770697 0.01962697 0.03580296 0.020069 0.03652 0.01969999 0.03856682 0.01919597 0.03770697 0.01962697 0.03467297 0.02014595 0.03580296 0.020069 0.03408586 0.02047085 0.03467297 0.02014595 0.03652 0.01969999 0.03580296 0.020069 0.03302484 0.02054697 0.03408586 0.02047085 0.03257596 0.02083599 0.03302484 0.02054697 0.03467297 0.02014595 0.03408586 0.02047085 0.031596 0.02090787 0.03257596 0.02083599 0.03129982 0.02117395 0.031596 0.02090787 0.03302484 0.02054697 0.03257596 0.02083599 0.03041183 0.02123785 0.03129982 0.02117395 0.03030699 0.02148687 0.03041183 0.02123785 0.031596 0.02090787 0.03129982 0.02117395 0.02952086 0.02154296 0.03030699 0.02148687 0.02970182 0.02178198 0.02952086 0.02154296 0.03041183 0.02123785 0.03030699 0.02148687 0.02903199 0.02182799 0.02970182 0.02178198 0.02972197 0.02205985 0.02903199 0.02182799 0.02952086 0.02154296 0.02970182 0.02178198 0.02903199 0.02182799 0.02972197 0.02205985 0.02917885 0.022098 0.07588195 0.05866897 0.06851798 0.05294299 0.07343196 0.05180597 0.06443196 0.04263287 0.07343196 0.05180597 0.06851798 0.05294299 0.07936596 0.05821084 0.07588195 0.05866897 0.07343196 0.05180597 0.06806099 0.06008487 0.06424099 0.05405396 0.06851798 0.05294299 0.06093084 0.044227 0.06851798 0.05294299 0.06424099 0.05405396 0.07200396 0.05928587 0.06806099 0.06008487 0.06851798 0.05294299 0.07588195 0.05866897 0.07200396 0.05928587 0.06851798 0.05294299 0.06093084 0.044227 0.06443196 0.04263287 0.06851798 0.05294299 0.06491196 0.06092596 0.060669 0.05513983 0.06424099 0.05405396 0.05797499 0.04578596 0.06424099 0.05405396 0.060669 0.05513983 0.06806099 0.06008487 0.06491196 0.06092596 0.06424099 0.05405396 0.05797499 0.04578596 0.06093084 0.044227 0.06424099 0.05405396 0.06057095 0.06262499 0.05786883 0.05620098 0.060669 0.05513983 0.05562198 0.04731082 0.060669 0.05513983 0.05786883 0.05620098 0.06246685 0.06177687 0.06057095 0.06262499 0.060669 0.05513983 0.06491196 0.06092596 0.06246685 0.06177687 0.060669 0.05513983 0.05562198 0.04731082 0.05797499 0.04578596 0.060669 0.05513983 0.05803287 0.06434196 0.05590498 0.05723887 0.05786883 0.05620098 0.05393087 0.04880297 0.05786883 0.05620098 0.05590498 0.05723887 0.06057095 0.06262499 0.05803287 0.06434196 0.05786883 0.05620098 0.05393087 0.04880297 0.05562198 0.04731082 0.05786883 0.05620098 0.05495584 0.05864 0.05485385 0.05827397 0.05590498 0.05723887 0.05295795 0.05026286 0.05590498 0.05723887 0.05485385 0.05827397 0.05508697 0.05911797 0.05495584 0.05864 0.05590498 0.05723887 0.05651098 0.06550598 0.05508697 0.05911797 0.05590498 0.05723887 0.05803287 0.06434196 0.05651098 0.06550598 0.05590498 0.05723887 0.05295795 0.05026286 0.05393087 0.04880297 0.05590498 0.05723887 0.0551669 0.05945897 0.05485385 0.05827397 0.05495584 0.05864 0.05328083 0.05319899 0.05295795 0.05026286 0.05485385 0.05827397 0.0551669 0.05945897 0.05328083 0.05319899 0.05485385 0.05827397 0.0551669 0.05945897 0.05495584 0.05864 0.05508697 0.05911797 0.05646497 0.06571698 0.05508697 0.05911797 0.05651098 0.06550598 0.0551669 0.05945897 0.05508697 0.05911797 0.05646497 0.06571698 0.05675399 0.06744599 0.05651098 0.06550598 0.05803287 0.06434196 0.05646497 0.06571698 0.05651098 0.06550598 0.05675399 0.06744599 0.05868196 0.066733 0.05803287 0.06434196 0.06057095 0.06262499 0.05868196 0.066733 0.05675399 0.06744599 0.05803287 0.06434196 0.06158185 0.065889 0.06057095 0.06262499 0.06246685 0.06177687 0.06158185 0.065889 0.05868196 0.066733 0.06057095 0.06262499 0.06544798 0.065171 0.06246685 0.06177687 0.06491196 0.06092596 0.06544798 0.065171 0.06158185 0.065889 0.06246685 0.06177687 0.06544798 0.065171 0.06491196 0.06092596 0.06806099 0.06008487 0.07024496 0.064561 0.06806099 0.06008487 0.07200396 0.05928587 0.07024496 0.064561 0.06544798 0.065171 0.06806099 0.06008487 0.07592695 0.06405097 0.07200396 0.05928587 0.07588195 0.05866897 0.07592695 0.06405097 0.07024496 0.064561 0.07200396 0.05928587 0.07592695 0.06405097 0.07588195 0.05866897 0.07936596 0.05821084 0.08243596 0.06361895 0.07592695 0.06405097 0.07936596 0.05821084 0.05601096 0.035703 0.06443196 0.04263287 0.06093084 0.044227 0.05380195 0.03748399 0.06093084 0.044227 0.05797499 0.04578596 0.05380195 0.03748399 0.05601096 0.035703 0.06093084 0.044227 0.05204898 0.03922498 0.05797499 0.04578596 0.05562198 0.04731082 0.05204898 0.03922498 0.05380195 0.03748399 0.05797499 0.04578596 0.05080085 0.04092997 0.05562198 0.04731082 0.05393087 0.04880297 0.05080085 0.04092997 0.05204898 0.03922498 0.05562198 0.04731082 0.05010885 0.04259783 0.05393087 0.04880297 0.05295795 0.05026286 0.05010885 0.04259783 0.05080085 0.04092997 0.05393087 0.04880297 0.05328083 0.05319899 0.05276799 0.05169987 0.05295795 0.05026286 0.05001884 0.04422998 0.05295795 0.05026286 0.05276799 0.05169987 0.05001884 0.04422998 0.05010885 0.04259783 0.05295795 0.05026286 0.05349683 0.05359697 0.05276799 0.05169987 0.05328083 0.05319899 0.05134499 0.04779595 0.05001884 0.04422998 0.05276799 0.05169987 0.05349683 0.05359697 0.05134499 0.04779595 0.05276799 0.05169987 0.05349683 0.05359697 0.05328083 0.05319899 0.0551669 0.05945897 0.04871785 0.03077799 0.05601096 0.035703 0.05380195 0.03748399 0.04761683 0.03249299 0.05380195 0.03748399 0.05204898 0.03922498 0.04761683 0.03249299 0.04871785 0.03077799 0.05380195 0.03748399 0.046884 0.03417098 0.05204898 0.03922498 0.05080085 0.04092997 0.046884 0.03417098 0.04761683 0.03249299 0.05204898 0.03922498 0.04655796 0.03581297 0.05080085 0.04092997 0.05010885 0.04259783 0.04655796 0.03581297 0.046884 0.03417098 0.05080085 0.04092997 0.04667782 0.03741997 0.05010885 0.04259783 0.05001884 0.04422998 0.04667782 0.03741997 0.04655796 0.03581297 0.05010885 0.04259783 0.05134499 0.04779595 0.050601 0.04586786 0.05001884 0.04422998 0.04728299 0.038993 0.05001884 0.04422998 0.050601 0.04586786 0.04728299 0.038993 0.04667782 0.03741997 0.05001884 0.04422998 0.05166995 0.04823297 0.050601 0.04586786 0.05134499 0.04779595 0.05020797 0.04487395 0.04728299 0.038993 0.050601 0.04586786 0.05166995 0.04823297 0.05020797 0.04487395 0.050601 0.04586786 0.05166995 0.04823297 0.05134499 0.04779595 0.05349683 0.05359697 0.04254084 0.02724796 0.04871785 0.03077799 0.04761683 0.03249299 0.042364 0.02866798 0.04761683 0.03249299 0.046884 0.03417098 0.042364 0.02866798 0.04254084 0.02724796 0.04761683 0.03249299 0.04244399 0.03005695 0.046884 0.03417098 0.04655796 0.03581297 0.04244399 0.03005695 0.042364 0.02866798 0.046884 0.03417098 0.04280591 0.03141695 0.04655796 0.03581297 0.04667782 0.03741997 0.04280591 0.03141695 0.04244399 0.03005695 0.04655796 0.03581297 0.04347383 0.03274697 0.04667782 0.03741997 0.04728299 0.038993 0.04347383 0.03274697 0.04280591 0.03141695 0.04667782 0.03741997 0.04940187 0.04288583 0.04843795 0.04059284 0.04728299 0.038993 0.04447382 0.034051 0.04728299 0.038993 0.04843795 0.04059284 0.05020797 0.04487395 0.04940187 0.04288583 0.04728299 0.038993 0.04447382 0.034051 0.04347383 0.03274697 0.04728299 0.038993 0.04979497 0.043338 0.04843795 0.04059284 0.04940187 0.04288583 0.04587388 0.03537297 0.04447382 0.034051 0.04843795 0.04059284 0.04745882 0.03836095 0.04587388 0.03537297 0.04843795 0.04059284 0.04979497 0.043338 0.04745882 0.03836095 0.04843795 0.04059284 0.05166995 0.04823297 0.04940187 0.04288583 0.05020797 0.04487395 0.04979497 0.043338 0.04940187 0.04288583 0.05166995 0.04823297 0.03724282 0.024818 0.04254084 0.02724796 0.042364 0.02866798 0.03790485 0.02596497 0.042364 0.02866798 0.04244399 0.03005695 0.03790485 0.02596497 0.03724282 0.024818 0.042364 0.02866798 0.03876495 0.027085 0.04244399 0.03005695 0.04280591 0.03141695 0.03876495 0.027085 0.03790485 0.02596497 0.04244399 0.03005695 0.03983891 0.02817696 0.04280591 0.03141695 0.04347383 0.03274697 0.03983891 0.02817696 0.03876495 0.027085 0.04280591 0.03141695 0.04114699 0.02924299 0.04347383 0.03274697 0.04447382 0.034051 0.04114699 0.02924299 0.03983891 0.02817696 0.04347383 0.03274697 0.042732 0.03030186 0.04447382 0.034051 0.04587388 0.03537297 0.042732 0.03030186 0.04114699 0.02924299 0.04447382 0.034051 0.04669195 0.036484 0.04587388 0.03537297 0.04745882 0.03836095 0.04407882 0.03235596 0.042732 0.03030186 0.04587388 0.03537297 0.046148 0.034886 0.04407882 0.03235596 0.04587388 0.03537297 0.04617697 0.03498399 0.046148 0.034886 0.04587388 0.03537297 0.04669195 0.036484 0.04617697 0.03498399 0.04587388 0.03537297 0.04786199 0.03883183 0.04669195 0.036484 0.04745882 0.03836095 0.04786199 0.03883183 0.04745882 0.03836095 0.04979497 0.043338 0.04385387 0.03094995 0.042732 0.03030186 0.04407882 0.03235596 0.046148 0.034886 0.04385387 0.03094995 0.04407882 0.03235596 0.04613697 0.03484886 0.04385387 0.03094995 0.046148 0.034886 0.04574698 0.03220999 0.04429584 0.02967482 0.04385387 0.03094995 0.04613697 0.03484886 0.04574698 0.03220999 0.04385387 0.03094995 0.04693496 0.035613 0.046148 0.034886 0.04617697 0.03498399 0.04693496 0.035613 0.04613697 0.03484886 0.046148 0.034886 0.04786199 0.03883183 0.04617697 0.03498399 0.04669195 0.036484 0.04693496 0.035613 0.04617697 0.03498399 0.04786199 0.03883183 0.04582285 0.02977287 0.04429584 0.02967482 0.04574698 0.03220999 0.04693496 0.035613 0.04574698 0.03220999 0.04613697 0.03484886 0.04674082 0.03058797 0.04582285 0.02977287 0.04574698 0.03220999 0.04670995 0.03287386 0.04674082 0.03058797 0.04574698 0.03220999 0.04693496 0.035613 0.04670995 0.03287386 0.04574698 0.03220999 0.04674082 0.03058797 0.04733383 0.02870082 0.04582285 0.02977287 0.04783797 0.03100287 0.04733383 0.02870082 0.04674082 0.03058797 0.04783797 0.03100287 0.04845899 0.029127 0.04733383 0.02870082 0.04783797 0.03100287 0.04674082 0.03058797 0.04670995 0.03287386 0.04706895 0.03304886 0.04783797 0.03100287 0.04670995 0.03287386 0.04786884 0.03606283 0.04706895 0.03304886 0.04670995 0.03287386 0.04786884 0.03606283 0.04670995 0.03287386 0.04693496 0.035613 0.04984086 0.02909886 0.04963582 0.02770799 0.04845899 0.029127 0.04984086 0.02909886 0.05132198 0.02771699 0.04963582 0.02770799 0.04905086 0.03103399 0.04845899 0.029127 0.04783797 0.03100287 0.04905086 0.03103399 0.04984086 0.02909886 0.04845899 0.029127 0.04706895 0.03304886 0.04783797 0.03332787 0.04783797 0.03100287 0.04905086 0.03103399 0.04783797 0.03100287 0.04783797 0.03332787 0.04786884 0.03606283 0.04783797 0.03332787 0.04706895 0.03304886 0.04865199 0.03349983 0.04905086 0.03103399 0.04783797 0.03332787 0.04893589 0.03631585 0.04865199 0.03349983 0.04783797 0.03332787 0.04893589 0.03631585 0.04783797 0.03332787 0.04786884 0.03606283 0.05379384 0.02725595 0.05329185 0.026802 0.05132198 0.02771699 0.05517786 0.02681297 0.056728 0.02650797 0.05329185 0.026802 0.05379384 0.02725595 0.05517786 0.02681297 0.05329185 0.026802 0.05261182 0.02782785 0.05132198 0.02771699 0.04984086 0.02909886 0.05261182 0.02782785 0.05379384 0.02725595 0.05132198 0.02771699 0.05096298 0.02929699 0.04984086 0.02909886 0.04905086 0.03103399 0.05096298 0.02929699 0.05261182 0.02782785 0.04984086 0.02909886 0.04865199 0.03349983 0.04907184 0.03354597 0.04905086 0.03103399 0.05023497 0.03121984 0.04905086 0.03103399 0.04907184 0.03354597 0.05023497 0.03121984 0.05096298 0.02929699 0.04905086 0.03103399 0.05008482 0.03636085 0.04907184 0.03354597 0.04865199 0.03349983 0.05033987 0.03351998 0.05023497 0.03121984 0.04907184 0.03354597 0.05124396 0.03615397 0.05033987 0.03351998 0.04907184 0.03354597 0.05124396 0.03615397 0.04907184 0.03354597 0.05126297 0.03619498 0.05008482 0.03636085 0.05126297 0.03619498 0.04907184 0.03354597 0.05008482 0.03636085 0.04865199 0.03349983 0.04893589 0.03631585 0.06066387 0.026317 0.058025 0.02631998 0.05844783 0.02633899 0.07580399 0.02596497 0.05844783 0.02633899 0.056728 0.02650797 0.07613295 0.02600383 0.06066387 0.026317 0.05844783 0.02633899 0.07613295 0.02600383 0.05844783 0.02633899 0.07580399 0.02596497 0.07580399 0.02596497 0.056728 0.02650797 0.05517786 0.02681297 0.07580399 0.02596497 0.05517786 0.02681297 0.05379384 0.02725595 0.07504999 0.02688598 0.05379384 0.02725595 0.05261182 0.02782785 0.07580399 0.02596497 0.05379384 0.02725595 0.07504999 0.02688598 0.07504999 0.02688598 0.05261182 0.02782785 0.05096298 0.02929699 0.07431197 0.02931797 0.05096298 0.02929699 0.05023497 0.03121984 0.07504999 0.02688598 0.05096298 0.02929699 0.07431197 0.02931797 0.07431197 0.02931797 0.05023497 0.03121984 0.05033987 0.03351998 0.07431197 0.02931797 0.05033987 0.03351998 0.07362198 0.03322899 0.05124396 0.03615397 0.07362198 0.03322899 0.05033987 0.03351998 0.0385499 0.02709299 0.06295597 0.02648997 0.06356 0.02653586 0.0385499 0.02709299 0.03834682 0.02698493 0.06295597 0.02648997 0.07613295 0.02600383 0.06356 0.02653586 0.06066387 0.026317 0.077196 0.02783685 0.0385499 0.02709299 0.06356 0.02653586 0.07646 0.02626097 0.077196 0.02783685 0.06356 0.02653586 0.07613295 0.02600383 0.07646 0.02626097 0.06356 0.02653586 0.03731983 0.027278 0.03834682 0.02698493 0.0385499 0.02709299 0.03976684 0.02864187 0.03731983 0.027278 0.0385499 0.02709299 0.077196 0.02783685 0.03976684 0.02864187 0.0385499 0.02709299 0.03628695 0.02993798 0.034298 0.02943295 0.03448587 0.02917695 0.03628695 0.02993798 0.03542697 0.03084695 0.034298 0.02943295 0.03628695 0.02993798 0.03448587 0.02917695 0.035133 0.02848196 0.03733599 0.02924096 0.035133 0.02848196 0.03562682 0.02808499 0.03733599 0.02924096 0.03628695 0.02993798 0.035133 0.02848196 0.03733599 0.02924096 0.03562682 0.02808499 0.03615885 0.02774995 0.03851598 0.02879399 0.03615885 0.02774995 0.03702396 0.02736896 0.03851598 0.02879399 0.03733599 0.02924096 0.03615885 0.02774995 0.03851598 0.02879399 0.03702396 0.02736896 0.03731983 0.027278 0.03976684 0.02864187 0.03851598 0.02879399 0.03731983 0.027278 0.03628695 0.1089439 0.03542697 0.108035 0.03604996 0.10545 0.03693199 0.106301 0.03604996 0.10545 0.03625386 0.101817 0.03693199 0.106301 0.03628695 0.1089439 0.03604996 0.10545 0.03715497 0.102594 0.03625386 0.101817 0.03615885 0.09727197 0.03715497 0.102594 0.03693199 0.106301 0.03625386 0.101817 0.03707391 0.09795296 0.03615885 0.09727197 0.03588998 0.09195196 0.03707391 0.09795296 0.03715497 0.102594 0.03615885 0.09727197 0.03681486 0.09251695 0.03588998 0.09195196 0.03556984 0.08600097 0.03681486 0.09251695 0.03707391 0.09795296 0.03588998 0.09195196 0.03650099 0.08642596 0.03556984 0.08600097 0.03529298 0.07957696 0.03650099 0.08642596 0.03681486 0.09251695 0.03556984 0.08600097 0.036228 0.07984197 0.03529298 0.07957696 0.03513383 0.07285398 0.036228 0.07984197 0.03650099 0.08642596 0.03529298 0.07957696 0.036071 0.07294499 0.03513383 0.07285398 0.03513383 0.06602698 0.036071 0.07294499 0.036228 0.07984197 0.03513383 0.07285398 0.036071 0.06593596 0.03513383 0.06602698 0.03529298 0.05930387 0.036071 0.06593596 0.036071 0.07294499 0.03513383 0.06602698 0.036228 0.05903887 0.03529298 0.05930387 0.03556895 0.05287986 0.036228 0.05903887 0.036071 0.06593596 0.03529298 0.05930387 0.03650099 0.05245482 0.03556895 0.05287986 0.03588998 0.04692995 0.03650099 0.05245482 0.036228 0.05903887 0.03556895 0.05287986 0.036816 0.04636496 0.03588998 0.04692995 0.03615999 0.04161083 0.036816 0.04636496 0.03650099 0.05245482 0.03588998 0.04692995 0.03707498 0.04092997 0.03615999 0.04161083 0.03625386 0.03706485 0.03707498 0.04092997 0.036816 0.04636496 0.03615999 0.04161083 0.03715497 0.03628885 0.03625386 0.03706485 0.03604882 0.03343182 0.03715497 0.03628885 0.03707498 0.04092997 0.03625386 0.03706485 0.03693199 0.03258097 0.03604882 0.03343182 0.03542697 0.03084695 0.03693199 0.03258097 0.03715497 0.03628885 0.03604882 0.03343182 0.03628695 0.02993798 0.03693199 0.03258097 0.03542697 0.03084695 0.03733599 0.109641 0.03628695 0.1089439 0.03693199 0.106301 0.03801 0.106945 0.03693199 0.106301 0.03715497 0.102594 0.03801 0.106945 0.03733599 0.109641 0.03693199 0.106301 0.03826493 0.103168 0.03715497 0.102594 0.03707391 0.09795296 0.03826493 0.103168 0.03801 0.106945 0.03715497 0.102594 0.03821682 0.09844499 0.03707391 0.09795296 0.03681486 0.09251695 0.03821682 0.09844499 0.03826493 0.103168 0.03707391 0.09795296 0.03798896 0.09291398 0.03681486 0.09251695 0.03650099 0.08642596 0.03798896 0.09291398 0.03821682 0.09844499 0.03681486 0.09251695 0.03770196 0.086717 0.03650099 0.08642596 0.036228 0.07984197 0.03770196 0.086717 0.03798896 0.09291398 0.03650099 0.08642596 0.03744786 0.08002001 0.036228 0.07984197 0.036071 0.07294499 0.03744786 0.08002001 0.03770196 0.086717 0.036228 0.07984197 0.037301 0.07300496 0.036071 0.07294499 0.036071 0.06593596 0.037301 0.07300496 0.03744786 0.08002001 0.036071 0.07294499 0.037301 0.065876 0.036071 0.06593596 0.036228 0.05903887 0.037301 0.065876 0.037301 0.07300496 0.036071 0.06593596 0.03744786 0.05886083 0.036228 0.05903887 0.03650099 0.05245482 0.03744786 0.05886083 0.037301 0.065876 0.036228 0.05903887 0.03770196 0.052163 0.03650099 0.05245482 0.036816 0.04636496 0.03770196 0.052163 0.03744786 0.05886083 0.03650099 0.05245482 0.03798997 0.04596787 0.036816 0.04636496 0.03707498 0.04092997 0.03798997 0.04596787 0.03770196 0.052163 0.036816 0.04636496 0.03821682 0.04043895 0.03707498 0.04092997 0.03715497 0.03628885 0.03821682 0.04043895 0.03798997 0.04596787 0.03707498 0.04092997 0.03826493 0.03571397 0.03715497 0.03628885 0.03693199 0.03258097 0.03826493 0.03571397 0.03821682 0.04043895 0.03715497 0.03628885 0.03800886 0.031937 0.03693199 0.03258097 0.03628695 0.02993798 0.03800886 0.031937 0.03826493 0.03571397 0.03693199 0.03258097 0.03733599 0.02924096 0.03800886 0.031937 0.03628695 0.02993798 0.03851598 0.110088 0.03733599 0.109641 0.03801 0.106945 0.03921997 0.107345 0.03801 0.106945 0.03826493 0.103168 0.03921997 0.107345 0.03851598 0.110088 0.03801 0.106945 0.039514 0.103507 0.03826493 0.103168 0.03821682 0.09844499 0.039514 0.103507 0.03921997 0.107345 0.03826493 0.103168 0.03950995 0.09871399 0.03821682 0.09844499 0.03798896 0.09291398 0.03950995 0.09871399 0.039514 0.103507 0.03821682 0.09844499 0.03932684 0.093113 0.03798896 0.09291398 0.03770196 0.086717 0.03932684 0.093113 0.03950995 0.09871399 0.03798896 0.09291398 0.03907787 0.08685195 0.03770196 0.086717 0.03744786 0.08002001 0.03907787 0.08685195 0.03932684 0.093113 0.03770196 0.086717 0.038854 0.08009696 0.03744786 0.08002001 0.037301 0.07300496 0.038854 0.08009696 0.03907787 0.08685195 0.03744786 0.08002001 0.03872299 0.07302898 0.037301 0.07300496 0.037301 0.065876 0.03872299 0.07302898 0.038854 0.08009696 0.037301 0.07300496 0.03872299 0.06585198 0.037301 0.065876 0.03744786 0.05886083 0.03872299 0.06585198 0.03872299 0.07302898 0.037301 0.065876 0.038854 0.05878382 0.03744786 0.05886083 0.03770196 0.052163 0.038854 0.05878382 0.03872299 0.06585198 0.03744786 0.05886083 0.03907787 0.05202895 0.03770196 0.052163 0.03798997 0.04596787 0.03907787 0.05202895 0.038854 0.05878382 0.03770196 0.052163 0.03932684 0.04576885 0.03798997 0.04596787 0.03821682 0.04043895 0.03932684 0.04576885 0.03907787 0.05202895 0.03798997 0.04596787 0.03951096 0.040169 0.03821682 0.04043895 0.03826493 0.03571397 0.03951096 0.040169 0.03932684 0.04576885 0.03821682 0.04043895 0.039514 0.03537487 0.03826493 0.03571397 0.03800886 0.031937 0.039514 0.03537487 0.03951096 0.040169 0.03826493 0.03571397 0.03921896 0.03153687 0.03800886 0.031937 0.03733599 0.02924096 0.03921896 0.03153687 0.039514 0.03537487 0.03800886 0.031937 0.03851598 0.02879399 0.03921896 0.03153687 0.03733599 0.02924096 0.03977096 0.110232 0.03851598 0.110088 0.03921997 0.107345 0.04051697 0.107314 0.03921997 0.107345 0.039514 0.103507 0.04051697 0.107314 0.03977096 0.110232 0.03921997 0.107345 0.04084295 0.103132 0.039514 0.103507 0.03950995 0.09871399 0.04084295 0.103132 0.04051697 0.107314 0.039514 0.103507 0.04085499 0.09784299 0.03950995 0.09871399 0.03932684 0.093113 0.04085499 0.09784299 0.04084295 0.103132 0.03950995 0.09871399 0.04068398 0.091596 0.03932684 0.093113 0.03907787 0.08685195 0.04077982 0.094819 0.04085499 0.09784299 0.03932684 0.093113 0.04068398 0.091596 0.04077982 0.094819 0.03932684 0.093113 0.04045796 0.08466196 0.03907787 0.08685195 0.038854 0.08009696 0.04056799 0.08820199 0.04068398 0.091596 0.03907787 0.08685195 0.04045796 0.08466196 0.04056799 0.08820199 0.03907787 0.08685195 0.04027485 0.07725095 0.038854 0.08009696 0.03872299 0.07302898 0.04035395 0.08100301 0.04045796 0.08466196 0.038854 0.08009696 0.04027485 0.07725095 0.04035395 0.08100301 0.038854 0.08009696 0.040205 0.069588 0.03872299 0.07302898 0.03872299 0.06585198 0.04022186 0.07343596 0.04027485 0.07725095 0.03872299 0.07302898 0.040205 0.069588 0.04022186 0.07343596 0.03872299 0.07302898 0.04021996 0.06573498 0.03872299 0.06585198 0.038854 0.05878382 0.04021996 0.06573498 0.040205 0.069588 0.03872299 0.06585198 0.04034799 0.05813497 0.038854 0.05878382 0.03907787 0.05202895 0.04027098 0.06190699 0.04021996 0.06573498 0.038854 0.05878382 0.04034799 0.05813497 0.04027098 0.06190699 0.038854 0.05878382 0.04056096 0.05087482 0.03907787 0.05202895 0.03932684 0.04576885 0.04045099 0.05444782 0.04034799 0.05813497 0.03907787 0.05202895 0.04056096 0.05087482 0.04045099 0.05444782 0.03907787 0.05202895 0.04077684 0.04418796 0.03932684 0.04576885 0.03951096 0.040169 0.04067885 0.04744595 0.04056096 0.05087482 0.03932684 0.04576885 0.04077684 0.04418796 0.04067885 0.04744595 0.03932684 0.04576885 0.04087698 0.03832083 0.03951096 0.040169 0.039514 0.03537487 0.04085499 0.04112899 0.04077684 0.04418796 0.03951096 0.040169 0.04087698 0.03832083 0.04085499 0.04112899 0.03951096 0.040169 0.04051697 0.03156799 0.039514 0.03537487 0.03921896 0.03153687 0.04084396 0.03578299 0.04087698 0.03832083 0.039514 0.03537487 0.04051697 0.03156799 0.04084396 0.03578299 0.039514 0.03537487 0.03976684 0.02864187 0.03921896 0.03153687 0.03851598 0.02879399 0.03976684 0.02864187 0.04051697 0.03156799 0.03921896 0.03153687 0.07719296 0.111056 0.03977096 0.110232 0.04051697 0.107314 0.07719296 0.111056 0.07646 0.11262 0.03977096 0.110232 0.07788896 0.108097 0.04051697 0.107314 0.04084295 0.103132 0.07788896 0.108097 0.07719296 0.111056 0.04051697 0.107314 0.07851999 0.103852 0.04084295 0.103132 0.04085499 0.09784299 0.07851999 0.103852 0.07788896 0.108097 0.04084295 0.103132 0.07906496 0.09849798 0.04085499 0.09784299 0.04077982 0.094819 0.07906496 0.09849798 0.07851999 0.103852 0.04085499 0.09784299 0.07950896 0.09218698 0.04077982 0.094819 0.04068398 0.091596 0.07950896 0.09218698 0.07906496 0.09849798 0.04077982 0.094819 0.07969099 0.08870297 0.04068398 0.091596 0.04056799 0.08820199 0.07969099 0.08870297 0.07950896 0.09218698 0.04068398 0.091596 0.07984095 0.08507895 0.04056799 0.08820199 0.04045796 0.08466196 0.07984095 0.08507895 0.07969099 0.08870297 0.04056799 0.08820199 0.07995998 0.08132195 0.04045796 0.08466196 0.04035395 0.08100301 0.07995998 0.08132195 0.07984095 0.08507895 0.04045796 0.08466196 0.08004498 0.07748597 0.04035395 0.08100301 0.04027485 0.07725095 0.08004498 0.07748597 0.07995998 0.08132195 0.04035395 0.08100301 0.08009696 0.07358598 0.04027485 0.07725095 0.04022186 0.07343596 0.08009696 0.07358598 0.08004498 0.07748597 0.04027485 0.07725095 0.08011597 0.069669 0.04022186 0.07343596 0.040205 0.069588 0.08011597 0.069669 0.08009696 0.07358598 0.04022186 0.07343596 0.08010095 0.06574696 0.040205 0.069588 0.04021996 0.06573498 0.08010095 0.06574696 0.08011597 0.069669 0.040205 0.069588 0.08005297 0.06183499 0.04021996 0.06573498 0.04027098 0.06190699 0.08005297 0.06183499 0.08010095 0.06574696 0.04021996 0.06573498 0.07997095 0.05797696 0.04027098 0.06190699 0.04034799 0.05813497 0.07997095 0.05797696 0.08005297 0.06183499 0.04027098 0.06190699 0.07985496 0.05419099 0.04034799 0.05813497 0.04045099 0.05444782 0.07985496 0.05419099 0.07997095 0.05797696 0.04034799 0.05813497 0.07970798 0.05053097 0.04045099 0.05444782 0.04056096 0.05087482 0.07970798 0.05053097 0.07985496 0.05419099 0.04045099 0.05444782 0.07952696 0.04700398 0.04056096 0.05087482 0.04067885 0.04744595 0.07952696 0.04700398 0.07970798 0.05053097 0.04056096 0.05087482 0.079319 0.04368984 0.04067885 0.04744595 0.04077684 0.04418796 0.079319 0.04368984 0.07952696 0.04700398 0.04067885 0.04744595 0.07908296 0.04059797 0.04077684 0.04418796 0.04085499 0.04112899 0.07908296 0.04059797 0.079319 0.04368984 0.04077684 0.04418796 0.07908296 0.04059797 0.04085499 0.04112899 0.04087698 0.03832083 0.07853496 0.03515297 0.04087698 0.03832083 0.04084396 0.03578299 0.07853496 0.03515297 0.07908296 0.04059797 0.04087698 0.03832083 0.07789796 0.03083688 0.04084396 0.03578299 0.04051697 0.03156799 0.07789796 0.03083688 0.07853496 0.03515297 0.04084396 0.03578299 0.077196 0.02783685 0.04051697 0.03156799 0.03976684 0.02864187 0.077196 0.02783685 0.07789796 0.03083688 0.04051697 0.03156799 0.07687699 0.108488 0.07646 0.11262 0.07719296 0.111056 0.076137 0.109565 0.07613295 0.112878 0.07646 0.11262 0.07687699 0.108488 0.076137 0.109565 0.07646 0.11262 0.077578 0.1059589 0.07719296 0.111056 0.07788896 0.108097 0.077578 0.1059589 0.07687699 0.108488 0.07719296 0.111056 0.078215 0.102097 0.07788896 0.108097 0.07851999 0.103852 0.078215 0.102097 0.077578 0.1059589 0.07788896 0.108097 0.07876795 0.09705799 0.07851999 0.103852 0.07906496 0.09849798 0.07876795 0.09705799 0.078215 0.102097 0.07851999 0.103852 0.07921499 0.09107297 0.07906496 0.09849798 0.07950896 0.09218698 0.07921499 0.09107297 0.07876795 0.09705799 0.07906496 0.09849798 0.07954698 0.084315 0.07950896 0.09218698 0.07969099 0.08870297 0.07954698 0.084315 0.07921499 0.09107297 0.07950896 0.09218698 0.07975095 0.07700997 0.07969099 0.08870297 0.07984095 0.08507895 0.07975095 0.07700997 0.07954698 0.084315 0.07969099 0.08870297 0.07985496 0.05419099 0.07984095 0.08507895 0.07995998 0.08132195 0.07981997 0.06944096 0.07984095 0.08507895 0.07985496 0.05419099 0.07980197 0.07325595 0.07984095 0.08507895 0.07981997 0.06944096 0.07980197 0.07325595 0.07975095 0.07700997 0.07984095 0.08507895 0.07997095 0.05797696 0.07995998 0.08132195 0.08004498 0.07748597 0.07985496 0.05419099 0.07995998 0.08132195 0.07997095 0.05797696 0.08005297 0.06183499 0.08004498 0.07748597 0.08009696 0.07358598 0.07997095 0.05797696 0.08004498 0.07748597 0.08005297 0.06183499 0.08010095 0.06574696 0.08009696 0.07358598 0.08011597 0.069669 0.08005297 0.06183499 0.08009696 0.07358598 0.08010095 0.06574696 0.07981997 0.06944096 0.07985496 0.05419099 0.07970798 0.05053097 0.07954895 0.05462884 0.07970798 0.05053097 0.07952696 0.04700398 0.07975196 0.06191384 0.07981997 0.06944096 0.07970798 0.05053097 0.07954895 0.05462884 0.07975196 0.06191384 0.07970798 0.05053097 0.07954895 0.05462884 0.07952696 0.04700398 0.079319 0.04368984 0.07921898 0.04786795 0.079319 0.04368984 0.07908296 0.04059797 0.07921898 0.04786795 0.07954895 0.05462884 0.079319 0.04368984 0.07877099 0.04185998 0.07908296 0.04059797 0.07853496 0.03515297 0.07877099 0.04185998 0.07921898 0.04786795 0.07908296 0.04059797 0.07821595 0.03679198 0.07853496 0.03515297 0.07789796 0.03083688 0.07821595 0.03679198 0.07877099 0.04185998 0.07853496 0.03515297 0.07757496 0.03290885 0.07789796 0.03083688 0.077196 0.02783685 0.07757496 0.03290885 0.07821595 0.03679198 0.07789796 0.03083688 0.07687097 0.03037798 0.077196 0.02783685 0.07646 0.02626097 0.07687097 0.03037798 0.07757496 0.03290885 0.077196 0.02783685 0.07687097 0.03037798 0.07646 0.02626097 0.07613295 0.02600383 0.07538497 0.109113 0.07580399 0.112916 0.07613295 0.112878 0.05844783 0.112543 0.07613295 0.112878 0.07580399 0.112916 0.076137 0.109565 0.07538497 0.109113 0.07613295 0.112878 0.06104195 0.112551 0.07613295 0.112878 0.05844783 0.112543 0.07538497 0.109113 0.075046 0.111987 0.07580399 0.112916 0.05844783 0.112543 0.07580399 0.112916 0.075046 0.111987 0.074647 0.107104 0.074301 0.109518 0.075046 0.111987 0.052688 0.111099 0.075046 0.111987 0.074301 0.109518 0.07538497 0.109113 0.074647 0.107104 0.075046 0.111987 0.05676686 0.112379 0.05844783 0.112543 0.075046 0.111987 0.05524283 0.112085 0.05676686 0.112379 0.075046 0.111987 0.05387085 0.111656 0.05524283 0.112085 0.075046 0.111987 0.052688 0.111099 0.05387085 0.111656 0.075046 0.111987 0.07395595 0.1035709 0.07360595 0.105535 0.074301 0.109518 0.05024296 0.107718 0.074301 0.109518 0.07360595 0.105535 0.074647 0.107104 0.07395595 0.1035709 0.074301 0.109518 0.05100786 0.109647 0.052688 0.111099 0.074301 0.109518 0.05024296 0.107718 0.05100786 0.109647 0.074301 0.109518 0.07334196 0.09862595 0.07299095 0.100172 0.07360595 0.105535 0.05124199 0.102734 0.07360595 0.105535 0.07299095 0.100172 0.07395595 0.1035709 0.07334196 0.09862595 0.07360595 0.105535 0.05033987 0.105361 0.05024296 0.107718 0.07360595 0.105535 0.05124199 0.102734 0.05033987 0.105361 0.07360595 0.105535 0.07283598 0.09249699 0.072721 0.09702301 0.07299095 0.100172 0.05294895 0.099357 0.07299095 0.100172 0.072721 0.09702301 0.07334196 0.09862595 0.07283598 0.09249699 0.07299095 0.100172 0.05126386 0.102686 0.05124199 0.102734 0.07299095 0.100172 0.05294895 0.099357 0.05126386 0.102686 0.07299095 0.100172 0.072456 0.085388 0.07248097 0.09358596 0.072721 0.09702301 0.05513387 0.09507495 0.072721 0.09702301 0.07248097 0.09358596 0.07283598 0.09249699 0.072456 0.085388 0.072721 0.09702301 0.05513387 0.09507495 0.05294895 0.099357 0.072721 0.09702301 0.072456 0.085388 0.072272 0.08987295 0.07248097 0.09358596 0.05609995 0.09304195 0.07248097 0.09358596 0.072272 0.08987295 0.05609995 0.09304195 0.05513387 0.09507495 0.07248097 0.09358596 0.07213997 0.06944096 0.07209795 0.08597296 0.072272 0.08987295 0.05892282 0.08650696 0.072272 0.08987295 0.07209795 0.08597296 0.07221996 0.077582 0.07213997 0.06944096 0.072272 0.08987295 0.072456 0.085388 0.07221996 0.077582 0.072272 0.08987295 0.05731195 0.09037399 0.05609995 0.09304195 0.072272 0.08987295 0.05892282 0.08650696 0.05731195 0.09037399 0.072272 0.08987295 0.07197499 0.05652898 0.07196199 0.08190095 0.07209795 0.08597296 0.05939882 0.08528 0.07209795 0.08597296 0.07196199 0.08190095 0.072115 0.05249196 0.07197499 0.05652898 0.07209795 0.08597296 0.07213997 0.06944096 0.072115 0.05249196 0.07209795 0.08597296 0.05939882 0.08528 0.05892282 0.08650696 0.07209795 0.08597296 0.07187497 0.06068098 0.07186597 0.07772296 0.07196199 0.08190095 0.06121587 0.079966 0.07196199 0.08190095 0.07186597 0.07772296 0.07197499 0.05652898 0.07187497 0.06068098 0.07196199 0.08190095 0.06121587 0.079966 0.05939882 0.08528 0.07196199 0.08190095 0.07181298 0.06492197 0.07180798 0.07346695 0.07186597 0.07772296 0.06276297 0.07356196 0.07186597 0.07772296 0.07180798 0.07346695 0.07187497 0.06068098 0.07181298 0.06492197 0.07186597 0.07772296 0.06130594 0.079665 0.06121587 0.079966 0.07186597 0.07772296 0.06276297 0.07356196 0.06130594 0.079665 0.07186597 0.07772296 0.07181298 0.06492197 0.07178997 0.06919199 0.07180798 0.07346695 0.06312298 0.06944 0.07180798 0.07346695 0.07178997 0.06919199 0.06312298 0.06944 0.06276297 0.07356196 0.07180798 0.07346695 0.06276297 0.06531995 0.07178997 0.06919199 0.07181298 0.06492197 0.06276297 0.06531995 0.06312298 0.06944 0.07178997 0.06919199 0.06276297 0.06531995 0.07181298 0.06492197 0.07187497 0.06068098 0.06130594 0.05921489 0.07187497 0.06068098 0.07197499 0.05652898 0.06130594 0.05921489 0.06276297 0.06531995 0.07187497 0.06068098 0.05939882 0.05360198 0.07197499 0.05652898 0.072115 0.05249196 0.06121999 0.05892795 0.06130594 0.05921489 0.07197499 0.05652898 0.05939882 0.05360198 0.06121999 0.05892795 0.07197499 0.05652898 0.07222098 0.06125396 0.07229 0.04863482 0.072115 0.05249196 0.05892884 0.05238986 0.072115 0.05249196 0.07229 0.04863482 0.07216095 0.06531 0.07222098 0.06125396 0.072115 0.05249196 0.07213997 0.06944096 0.07216095 0.06531 0.072115 0.05249196 0.05892884 0.05238986 0.05939882 0.05360198 0.072115 0.05249196 0.07245898 0.05342698 0.07250195 0.04497283 0.07229 0.04863482 0.05731195 0.048509 0.07229 0.04863482 0.07250195 0.04497283 0.07222098 0.06125396 0.07245898 0.05342698 0.07229 0.04863482 0.05731195 0.048509 0.05892884 0.05238986 0.07229 0.04863482 0.07283997 0.04632395 0.07301098 0.03849285 0.07250195 0.04497283 0.05513495 0.04380697 0.07250195 0.04497283 0.07301098 0.03849285 0.07245898 0.05342698 0.07283997 0.04632395 0.07250195 0.04497283 0.05610483 0.04584985 0.05731195 0.048509 0.07250195 0.04497283 0.05513495 0.04380697 0.05610483 0.04584985 0.07250195 0.04497283 0.07334595 0.04021996 0.07362198 0.03322899 0.07301098 0.03849285 0.05126297 0.03619498 0.07301098 0.03849285 0.07362198 0.03322899 0.07283997 0.04632395 0.07334595 0.04021996 0.07301098 0.03849285 0.05294895 0.03952383 0.05513495 0.04380697 0.07301098 0.03849285 0.05126297 0.03619498 0.05294895 0.03952383 0.07301098 0.03849285 0.07395696 0.03530395 0.07431197 0.02931797 0.07362198 0.03322899 0.07334595 0.04021996 0.07395696 0.03530395 0.07362198 0.03322899 0.05124396 0.03615397 0.05126297 0.03619498 0.07362198 0.03322899 0.07464396 0.03178983 0.07504999 0.02688598 0.07431197 0.02931797 0.07395696 0.03530395 0.07464396 0.03178983 0.07431197 0.02931797 0.075378 0.02977883 0.07580399 0.02596497 0.07504999 0.02688598 0.07464396 0.03178983 0.075378 0.02977883 0.07504999 0.02688598 0.07612997 0.02931398 0.07613295 0.02600383 0.07580399 0.02596497 0.075378 0.02977883 0.07612997 0.02931398 0.07580399 0.02596497 0.07612997 0.02931398 0.07687097 0.03037798 0.07613295 0.02600383 0.05339694 0.06944096 0.07981997 0.06944096 0.07975196 0.06191384 0.05330985 0.07694697 0.07980197 0.07325595 0.07981997 0.06944096 0.05330985 0.07694697 0.07981997 0.06944096 0.05339694 0.06944096 0.05330896 0.06189286 0.07975196 0.06191384 0.07954895 0.05462884 0.05337482 0.06563699 0.05339694 0.06944096 0.07975196 0.06191384 0.05330896 0.06189286 0.05337482 0.06563699 0.07975196 0.06191384 0.053047 0.05460786 0.07954895 0.05462884 0.07921898 0.04786795 0.053047 0.05460786 0.05330896 0.06189286 0.07954895 0.05462884 0.05262196 0.04786998 0.07921898 0.04786795 0.07877099 0.04185998 0.05262196 0.04786998 0.053047 0.05460786 0.07921898 0.04786795 0.05204784 0.04190182 0.07877099 0.04185998 0.07821595 0.03679198 0.05204784 0.04190182 0.05262196 0.04786998 0.07877099 0.04185998 0.05133998 0.036879 0.07821595 0.03679198 0.07757496 0.03290885 0.05133998 0.036879 0.05204784 0.04190182 0.07821595 0.03679198 0.04962384 0.03050899 0.07757496 0.03290885 0.07687097 0.03037798 0.05052191 0.03302896 0.05133998 0.036879 0.07757496 0.03290885 0.04962384 0.03050899 0.05052191 0.03302896 0.07757496 0.03290885 0.048675 0.02943783 0.07687097 0.03037798 0.07612997 0.02931398 0.048675 0.02943783 0.04962384 0.03050899 0.07687097 0.03037798 0.04771 0.02989 0.07612997 0.02931398 0.075378 0.02977883 0.04771 0.02989 0.048675 0.02943783 0.07612997 0.02931398 0.04676598 0.03189498 0.075378 0.02977883 0.07464396 0.03178983 0.04676598 0.03189498 0.04771 0.02989 0.075378 0.02977883 0.04676598 0.03189498 0.07464396 0.03178983 0.07395696 0.03530395 0.04587996 0.03541797 0.07395696 0.03530395 0.07334595 0.04021996 0.04587996 0.03541797 0.04676598 0.03189498 0.07395696 0.03530395 0.04509294 0.04034882 0.07334595 0.04021996 0.07283997 0.04632395 0.04509294 0.04034882 0.04587996 0.03541797 0.07334595 0.04021996 0.04444396 0.04645884 0.07283997 0.04632395 0.07245898 0.05342698 0.04444396 0.04645884 0.04509294 0.04034882 0.07283997 0.04632395 0.04395699 0.05354487 0.07245898 0.05342698 0.07222098 0.06125396 0.04395699 0.05354487 0.04444396 0.04645884 0.07245898 0.05342698 0.04365485 0.06132584 0.07222098 0.06125396 0.07216095 0.06531 0.04365485 0.06132584 0.04395699 0.05354487 0.07222098 0.06125396 0.04365485 0.06132584 0.07216095 0.06531 0.07213997 0.06944096 0.04355299 0.06944096 0.07213997 0.06944096 0.07221996 0.077582 0.04355299 0.06944096 0.04365485 0.06132584 0.07213997 0.06944096 0.04365599 0.07760095 0.07221996 0.077582 0.072456 0.085388 0.04357898 0.07355797 0.04355299 0.06944096 0.07221996 0.077582 0.04365599 0.07760095 0.04357898 0.07355797 0.07221996 0.077582 0.04395997 0.08540195 0.072456 0.085388 0.07283598 0.09249699 0.04395997 0.08540195 0.04365599 0.07760095 0.072456 0.085388 0.04444897 0.09248298 0.07283598 0.09249699 0.07334196 0.09862595 0.04444897 0.09248298 0.04395997 0.08540195 0.07283598 0.09249699 0.04509699 0.09856897 0.07334196 0.09862595 0.07395595 0.1035709 0.04509699 0.09856897 0.04444897 0.09248298 0.07334196 0.09862595 0.04588097 0.10347 0.07395595 0.1035709 0.074647 0.107104 0.04588097 0.10347 0.04509699 0.09856897 0.07395595 0.1035709 0.04770195 0.108981 0.074647 0.107104 0.07538497 0.109113 0.04676085 0.106975 0.04588097 0.10347 0.074647 0.107104 0.04770195 0.108981 0.04676085 0.106975 0.074647 0.107104 0.048666 0.109447 0.07538497 0.109113 0.076137 0.109565 0.048666 0.109447 0.04770195 0.108981 0.07538497 0.109113 0.04961585 0.108388 0.076137 0.109565 0.07687699 0.108488 0.04961585 0.108388 0.048666 0.109447 0.076137 0.109565 0.05051785 0.105867 0.07687699 0.108488 0.077578 0.1059589 0.05051785 0.105867 0.04961585 0.108388 0.07687699 0.108488 0.05051785 0.105867 0.077578 0.1059589 0.078215 0.102097 0.05134087 0.101996 0.078215 0.102097 0.07876795 0.09705799 0.05134087 0.101996 0.05051785 0.105867 0.078215 0.102097 0.05205297 0.09694296 0.07876795 0.09705799 0.07921499 0.09107297 0.05205297 0.09694296 0.05134087 0.101996 0.07876795 0.09705799 0.05262684 0.09095299 0.07921499 0.09107297 0.07954698 0.084315 0.05262684 0.09095299 0.05205297 0.09694296 0.07921499 0.09107297 0.05304998 0.08421099 0.07954698 0.084315 0.07975095 0.07700997 0.05304998 0.08421099 0.05262684 0.09095299 0.07954698 0.084315 0.05330985 0.07694697 0.07975095 0.07700997 0.07980197 0.07325595 0.05330985 0.07694697 0.05304998 0.08421099 0.07975095 0.07700997 0.05802798 0.112562 0.05844783 0.112543 0.05676686 0.112379 0.05559796 0.112593 0.05676686 0.112379 0.05524283 0.112085 0.05329185 0.11208 0.05524283 0.112085 0.05387085 0.111656 0.05329185 0.11208 0.05559796 0.112593 0.05524283 0.112085 0.05329185 0.11208 0.05387085 0.111656 0.052688 0.111099 0.05132287 0.111165 0.052688 0.111099 0.05100786 0.109647 0.05132287 0.111165 0.05329185 0.11208 0.052688 0.111099 0.049842 0.109783 0.05100786 0.109647 0.05024296 0.107718 0.049842 0.109783 0.05132287 0.111165 0.05100786 0.109647 0.04905086 0.107848 0.05024296 0.107718 0.05033987 0.105361 0.04905086 0.107848 0.049842 0.109783 0.05024296 0.107718 0.05008482 0.10252 0.05033987 0.105361 0.05124199 0.102734 0.04907184 0.1053349 0.04905086 0.107848 0.05033987 0.105361 0.05008482 0.10252 0.04907184 0.1053349 0.05033987 0.105361 0.05008482 0.10252 0.05124199 0.102734 0.05126386 0.102686 0.052109 0.09915 0.05126386 0.102686 0.05294895 0.099357 0.05008482 0.10252 0.05126386 0.102686 0.052109 0.09915 0.05405586 0.09484797 0.05294895 0.099357 0.05513387 0.09507495 0.05405586 0.09484797 0.052109 0.09915 0.05294895 0.099357 0.05612397 0.09013897 0.05513387 0.09507495 0.05609995 0.09304195 0.05612397 0.09013897 0.05405586 0.09484797 0.05513387 0.09507495 0.05612397 0.09013897 0.05609995 0.09304195 0.05731195 0.09037399 0.05811887 0.08497697 0.05731195 0.09037399 0.05892282 0.08650696 0.05811887 0.08497697 0.05612397 0.09013897 0.05731195 0.09037399 0.05811887 0.08497697 0.05892282 0.08650696 0.05939882 0.08528 0.05991286 0.07934695 0.05939882 0.08528 0.06121587 0.079966 0.05991286 0.07934695 0.05811887 0.08497697 0.05939882 0.08528 0.05991286 0.07934695 0.06121587 0.079966 0.06130594 0.079665 0.06102395 0.07330197 0.06130594 0.079665 0.06276297 0.07356196 0.05991286 0.07934695 0.06130594 0.079665 0.06102395 0.07330197 0.06132495 0.06944 0.06276297 0.07356196 0.06312298 0.06944 0.06132495 0.06944 0.06102395 0.07330197 0.06276297 0.07356196 0.06102395 0.06558001 0.06312298 0.06944 0.06276297 0.06531995 0.06102395 0.06558001 0.06132495 0.06944 0.06312298 0.06944 0.05991286 0.05953484 0.06276297 0.06531995 0.06130594 0.05921489 0.05991286 0.05953484 0.06102395 0.06558001 0.06276297 0.06531995 0.05811887 0.05390387 0.06130594 0.05921489 0.06121999 0.05892795 0.05811887 0.05390387 0.05991286 0.05953484 0.06130594 0.05921489 0.05811887 0.05390387 0.06121999 0.05892795 0.05939882 0.05360198 0.05612283 0.04874289 0.05939882 0.05360198 0.05892884 0.05238986 0.05612283 0.04874289 0.05811887 0.05390387 0.05939882 0.05360198 0.05612283 0.04874289 0.05892884 0.05238986 0.05731195 0.048509 0.05405586 0.044034 0.05731195 0.048509 0.05610483 0.04584985 0.05405586 0.044034 0.05612283 0.04874289 0.05731195 0.048509 0.05405586 0.044034 0.05610483 0.04584985 0.05513495 0.04380697 0.05210983 0.03973084 0.05513495 0.04380697 0.05294895 0.03952383 0.05210983 0.03973084 0.05405586 0.044034 0.05513495 0.04380697 0.05008482 0.03636085 0.05294895 0.03952383 0.05126297 0.03619498 0.05008482 0.03636085 0.05210983 0.03973084 0.05294895 0.03952383 0.05511796 0.11257 0.05559796 0.112593 0.05329185 0.11208 0.05121886 0.112194 0.05329185 0.11208 0.05132287 0.111165 0.05287683 0.112397 0.05511796 0.11257 0.05329185 0.11208 0.05121886 0.112194 0.05287683 0.112397 0.05329185 0.11208 0.04963499 0.111173 0.05132287 0.111165 0.049842 0.109783 0.04963499 0.111173 0.05121886 0.112194 0.05132287 0.111165 0.04845899 0.109754 0.049842 0.109783 0.04905086 0.107848 0.04845899 0.109754 0.04963499 0.111173 0.049842 0.109783 0.04783797 0.107879 0.04905086 0.107848 0.04907184 0.1053349 0.04783797 0.107879 0.04845899 0.109754 0.04905086 0.107848 0.04865092 0.105381 0.04783797 0.107879 0.04907184 0.1053349 0.04893589 0.102565 0.04865092 0.105381 0.04907184 0.1053349 0.05008482 0.10252 0.04893589 0.102565 0.04907184 0.1053349 0.05463784 0.112746 0.05511796 0.11257 0.05287683 0.112397 0.05201596 0.112731 0.05287683 0.112397 0.05121886 0.112194 0.05201596 0.112731 0.05463784 0.112746 0.05287683 0.112397 0.05087399 0.112142 0.05121886 0.112194 0.04963499 0.111173 0.05201596 0.112731 0.05121886 0.112194 0.05087399 0.112142 0.04844594 0.111645 0.04963499 0.111173 0.04845899 0.109754 0.04914093 0.111816 0.05087399 0.112142 0.04963499 0.111173 0.04844594 0.111645 0.04914093 0.111816 0.04963499 0.111173 0.04734885 0.110209 0.04845899 0.109754 0.04783797 0.107879 0.04734885 0.110209 0.04844594 0.111645 0.04845899 0.109754 0.04865092 0.105381 0.04783797 0.105554 0.04783797 0.107879 0.046745 0.1083109 0.04783797 0.107879 0.04783797 0.105554 0.046745 0.1083109 0.04734885 0.110209 0.04783797 0.107879 0.04893589 0.102565 0.04783797 0.105554 0.04865092 0.105381 0.04706895 0.105832 0.046745 0.1083109 0.04783797 0.105554 0.04786884 0.102818 0.04706895 0.105832 0.04783797 0.105554 0.04893589 0.102565 0.04786884 0.102818 0.04783797 0.105554 0.049537 0.112655 0.05087399 0.112142 0.04914093 0.111816 0.049537 0.112655 0.05201596 0.112731 0.05087399 0.112142 0.049537 0.112655 0.04914093 0.111816 0.04844594 0.111645 0.04649198 0.111063 0.04844594 0.111645 0.04734885 0.110209 0.047279 0.112527 0.04844594 0.111645 0.04649198 0.111063 0.047279 0.112527 0.049537 0.112655 0.04844594 0.111645 0.04582399 0.109112 0.04734885 0.110209 0.046745 0.1083109 0.04582399 0.109112 0.04649198 0.111063 0.04734885 0.110209 0.04706895 0.105832 0.04670995 0.106007 0.046745 0.1083109 0.04582399 0.109112 0.046745 0.1083109 0.04670995 0.106007 0.04693496 0.103268 0.04670995 0.106007 0.04706895 0.105832 0.04574799 0.106671 0.04582399 0.109112 0.04670995 0.106007 0.046139 0.104028 0.04574799 0.106671 0.04670995 0.106007 0.046148 0.103996 0.046139 0.104028 0.04670995 0.106007 0.04617583 0.1039 0.046148 0.103996 0.04670995 0.106007 0.04693496 0.103268 0.04617583 0.1039 0.04670995 0.106007 0.04786884 0.102818 0.04693496 0.103268 0.04706895 0.105832 0.04452782 0.1113409 0.04649198 0.111063 0.04582399 0.109112 0.04537087 0.112363 0.047279 0.112527 0.04649198 0.111063 0.04159283 0.112743 0.04537087 0.112363 0.04649198 0.111063 0.04159283 0.112743 0.04649198 0.111063 0.04452782 0.1113409 0.04429394 0.109209 0.04582399 0.109112 0.04574799 0.106671 0.04452782 0.1113409 0.04582399 0.109112 0.04276198 0.111574 0.04429394 0.109209 0.04276198 0.111574 0.04582399 0.109112 0.04384785 0.107941 0.04574799 0.106671 0.046139 0.104028 0.04429394 0.109209 0.04574799 0.106671 0.04384785 0.107941 0.054223 0.112833 0.05463784 0.112746 0.05201596 0.112731 0.05141484 0.11292 0.05201596 0.112731 0.049537 0.112655 0.05141484 0.11292 0.054223 0.112833 0.05201596 0.112731 0.048702 0.112993 0.049537 0.112655 0.047279 0.112527 0.048702 0.112993 0.05141484 0.11292 0.049537 0.112655 0.04616385 0.1130599 0.047279 0.112527 0.04537087 0.112363 0.04616385 0.1130599 0.048702 0.112993 0.047279 0.112527 0.04616385 0.1130599 0.04537087 0.112363 0.04393386 0.113137 0.04159283 0.112743 0.04393386 0.113137 0.04537087 0.112363 0.04159283 0.112743 0.040151 0.113421 0.04393386 0.113137 0.04159283 0.112743 0.04452782 0.1113409 0.04276198 0.111574 0.03994786 0.1129299 0.04159283 0.112743 0.04276198 0.111574 0.03994786 0.1129299 0.04276198 0.111574 0.04120987 0.111787 0.04429394 0.109209 0.04120987 0.111787 0.04276198 0.111574 0.03840595 0.113586 0.040151 0.113421 0.04159283 0.112743 0.03840595 0.113586 0.04159283 0.112743 0.03994786 0.1129299 0.03888487 0.113146 0.04120987 0.111787 0.04021787 0.111993 0.04272699 0.108587 0.04021787 0.111993 0.04120987 0.111787 0.03643 0.114044 0.03888487 0.113146 0.04021787 0.111993 0.03891187 0.112553 0.03643 0.114044 0.04021787 0.111993 0.04114699 0.109639 0.03891187 0.112553 0.04021787 0.111993 0.04272699 0.108587 0.04114699 0.109639 0.04021787 0.111993 0.03888487 0.113146 0.03994786 0.1129299 0.04120987 0.111787 0.04384785 0.107941 0.04272699 0.108587 0.04120987 0.111787 0.04429394 0.109209 0.04384785 0.107941 0.04120987 0.111787 0.03725087 0.113807 0.03840595 0.113586 0.03994786 0.1129299 0.03888487 0.113146 0.03725087 0.113807 0.03994786 0.1129299 0.03531485 0.114535 0.03725087 0.113807 0.03888487 0.113146 0.03411698 0.114766 0.03725087 0.113807 0.03531485 0.114535 0.03531485 0.114535 0.03888487 0.113146 0.03643 0.114044 0.03356099 0.115424 0.03600084 0.114122 0.03443884 0.115022 0.03876584 0.111796 0.03443884 0.115022 0.03600084 0.114122 0.03790599 0.112915 0.03291589 0.115844 0.03443884 0.115022 0.03876584 0.111796 0.03790599 0.112915 0.03443884 0.115022 0.03356099 0.115424 0.03741395 0.113319 0.03600084 0.114122 0.03983998 0.110704 0.03600084 0.114122 0.03741395 0.113319 0.03983998 0.110704 0.03876584 0.111796 0.03600084 0.114122 0.03356099 0.115424 0.03643 0.114044 0.03741395 0.113319 0.03753983 0.11325 0.03741395 0.113319 0.03643 0.114044 0.03983998 0.110704 0.03741395 0.113319 0.03753983 0.11325 0.0326249 0.11567 0.03531485 0.114535 0.03643 0.114044 0.03356099 0.115424 0.0326249 0.11567 0.03643 0.114044 0.03891187 0.112553 0.03753983 0.11325 0.03643 0.114044 0.03165996 0.115751 0.03411698 0.114766 0.03531485 0.114535 0.0326249 0.11567 0.03165996 0.115751 0.03531485 0.114535 0.04114699 0.109639 0.03753983 0.11325 0.03891187 0.112553 0.04114699 0.109639 0.03983998 0.110704 0.03753983 0.11325 0.03790599 0.112915 0.03724396 0.114062 0.03291589 0.115844 0.04253995 0.111628 0.03674799 0.115243 0.03724396 0.114062 0.04295682 0.113082 0.03750598 0.115011 0.03674799 0.115243 0.04253995 0.111628 0.04295682 0.113082 0.03674799 0.115243 0.042364 0.110209 0.03724396 0.114062 0.03790599 0.112915 0.042364 0.110209 0.04253995 0.111628 0.03724396 0.114062 0.042445 0.108821 0.03790599 0.112915 0.03876584 0.111796 0.042445 0.108821 0.042364 0.110209 0.03790599 0.112915 0.04280698 0.107462 0.03876584 0.111796 0.03983998 0.110704 0.04280698 0.107462 0.042445 0.108821 0.03876584 0.111796 0.04347497 0.106133 0.03983998 0.110704 0.04114699 0.109639 0.04347497 0.106133 0.04280698 0.107462 0.03983998 0.110704 0.04447484 0.10483 0.04114699 0.109639 0.04272699 0.108587 0.04447484 0.10483 0.04347497 0.106133 0.04114699 0.109639 0.04407882 0.106527 0.04447484 0.10483 0.04272699 0.108587 0.04384785 0.107941 0.04407882 0.106527 0.04272699 0.108587 0.04871195 0.108095 0.04295682 0.113082 0.04253995 0.111628 0.05028986 0.109785 0.04488682 0.112295 0.04295682 0.113082 0.04355299 0.114816 0.04295682 0.113082 0.04488682 0.112295 0.04871195 0.108095 0.05028986 0.109785 0.04295682 0.113082 0.04761296 0.1063809 0.04253995 0.111628 0.042364 0.110209 0.04761296 0.1063809 0.04871195 0.108095 0.04253995 0.111628 0.04688197 0.104705 0.042364 0.110209 0.042445 0.108821 0.04688197 0.104705 0.04761296 0.1063809 0.042364 0.110209 0.04655796 0.103064 0.042445 0.108821 0.04280698 0.107462 0.04655796 0.103064 0.04688197 0.104705 0.042445 0.108821 0.04667896 0.101459 0.04280698 0.107462 0.04347497 0.106133 0.04667896 0.101459 0.04655796 0.103064 0.04280698 0.107462 0.04728299 0.09988796 0.04347497 0.106133 0.04447484 0.10483 0.04728299 0.09988796 0.04667896 0.101459 0.04347497 0.106133 0.04407882 0.106527 0.04587799 0.103501 0.04447484 0.10483 0.04843795 0.09828895 0.04447484 0.10483 0.04587799 0.103501 0.04843795 0.09828895 0.04728299 0.09988796 0.04447484 0.10483 0.04617583 0.1039 0.04587799 0.103501 0.04407882 0.106527 0.04745882 0.100521 0.04843795 0.09828895 0.04587799 0.103501 0.04617583 0.1039 0.04745882 0.100521 0.04587799 0.103501 0.04617583 0.1039 0.04407882 0.106527 0.046148 0.103996 0.04384785 0.107941 0.046148 0.103996 0.04407882 0.106527 0.04355299 0.114816 0.04488682 0.112295 0.05028986 0.109785 0.05600982 0.103178 0.05028986 0.109785 0.04871195 0.108095 0.05878984 0.104909 0.05348485 0.108092 0.05028986 0.109785 0.05176997 0.111195 0.05028986 0.109785 0.05348485 0.108092 0.05600982 0.103178 0.05878984 0.104909 0.05028986 0.109785 0.05176997 0.111195 0.04355299 0.114816 0.05028986 0.109785 0.053801 0.101398 0.04871195 0.108095 0.04761296 0.1063809 0.053801 0.101398 0.05600982 0.103178 0.04871195 0.108095 0.05204784 0.09965598 0.04761296 0.1063809 0.04688197 0.104705 0.05204784 0.09965598 0.053801 0.101398 0.04761296 0.1063809 0.05080085 0.09795099 0.04688197 0.104705 0.04655796 0.103064 0.05080085 0.09795099 0.05204784 0.09965598 0.04688197 0.104705 0.05010885 0.09628397 0.04655796 0.103064 0.04667896 0.101459 0.05010885 0.09628397 0.05080085 0.09795099 0.04655796 0.103064 0.05001884 0.09465098 0.04667896 0.101459 0.04728299 0.09988796 0.05001884 0.09465098 0.05010885 0.09628397 0.04667896 0.101459 0.05020886 0.094006 0.04728299 0.09988796 0.04843795 0.09828895 0.050601 0.093014 0.05001884 0.09465098 0.04728299 0.09988796 0.05020886 0.094006 0.050601 0.093014 0.04728299 0.09988796 0.04786282 0.100049 0.04843795 0.09828895 0.04745882 0.100521 0.04940187 0.095995 0.05020886 0.094006 0.04843795 0.09828895 0.04786282 0.100049 0.04940187 0.095995 0.04843795 0.09828895 0.04693496 0.103268 0.04786282 0.100049 0.04745882 0.100521 0.04693496 0.103268 0.04745882 0.100521 0.04617583 0.1039 0.05176997 0.111195 0.05348485 0.108092 0.05878984 0.104909 0.06442797 0.09624695 0.05878984 0.104909 0.05600982 0.103178 0.068448 0.09785395 0.06155097 0.103062 0.05878984 0.104909 0.06050688 0.106121 0.05878984 0.104909 0.06155097 0.103062 0.06442797 0.09624695 0.068448 0.09785395 0.05878984 0.104909 0.06050688 0.106121 0.05176997 0.111195 0.05878984 0.104909 0.060929 0.09465301 0.05600982 0.103178 0.053801 0.101398 0.060929 0.09465301 0.06442797 0.09624695 0.05600982 0.103178 0.05797284 0.09309399 0.053801 0.101398 0.05204784 0.09965598 0.05797284 0.09309399 0.060929 0.09465301 0.053801 0.101398 0.05562084 0.09156996 0.05204784 0.09965598 0.05080085 0.09795099 0.05562084 0.09156996 0.05797284 0.09309399 0.05204784 0.09965598 0.05392998 0.09007799 0.05080085 0.09795099 0.05010885 0.09628397 0.05392998 0.09007799 0.05562084 0.09156996 0.05080085 0.09795099 0.05295795 0.08861798 0.05010885 0.09628397 0.05001884 0.09465098 0.05295795 0.08861798 0.05392998 0.09007799 0.05010885 0.09628397 0.05276799 0.08718198 0.05001884 0.09465098 0.050601 0.093014 0.05276799 0.08718198 0.05295795 0.08861798 0.05001884 0.09465098 0.04979497 0.09554398 0.050601 0.093014 0.05020886 0.094006 0.051346 0.09108495 0.05276799 0.08718198 0.050601 0.093014 0.04979497 0.09554398 0.051346 0.09108495 0.050601 0.093014 0.04979497 0.09554398 0.05020886 0.094006 0.04940187 0.095995 0.04979497 0.09554398 0.04940187 0.095995 0.04786282 0.100049 0.06050688 0.106121 0.06155097 0.103062 0.068448 0.09785395 0.07343399 0.087076 0.068448 0.09785395 0.06442797 0.09624695 0.07894998 0.08821099 0.06952697 0.096964 0.068448 0.09785395 0.06940698 0.09959995 0.068448 0.09785395 0.06952697 0.096964 0.07343399 0.087076 0.07894998 0.08821099 0.068448 0.09785395 0.06940698 0.09959995 0.06050688 0.106121 0.068448 0.09785395 0.06851899 0.08593899 0.06442797 0.09624695 0.060929 0.09465301 0.06851899 0.08593899 0.07343399 0.087076 0.06442797 0.09624695 0.064242 0.08482795 0.060929 0.09465301 0.05797284 0.09309399 0.064242 0.08482795 0.06851899 0.08593899 0.060929 0.09465301 0.06066983 0.08374196 0.05797284 0.09309399 0.05562084 0.09156996 0.06066983 0.08374196 0.064242 0.08482795 0.05797284 0.09309399 0.05786883 0.082681 0.05562084 0.09156996 0.05392998 0.09007799 0.05786883 0.082681 0.06066983 0.08374196 0.05562084 0.09156996 0.05590498 0.08164298 0.05392998 0.09007799 0.05295795 0.08861798 0.05590498 0.08164298 0.05786883 0.082681 0.05392998 0.09007799 0.05485385 0.08060801 0.05295795 0.08861798 0.05276799 0.08718198 0.05485385 0.08060801 0.05590498 0.08164298 0.05295795 0.08861798 0.05167084 0.09064799 0.05276799 0.08718198 0.051346 0.09108495 0.05328083 0.08568298 0.05485385 0.08060801 0.05276799 0.08718198 0.05167084 0.09064799 0.05328083 0.08568298 0.05276799 0.08718198 0.05167084 0.09064799 0.051346 0.09108495 0.04979497 0.09554398 0.07894998 0.08821099 0.07744598 0.08973097 0.06952697 0.096964 0.078094 0.09183198 0.06952697 0.096964 0.07744598 0.08973097 0.078094 0.09183198 0.06940698 0.09959995 0.06952697 0.096964 0.078094 0.09183198 0.07744598 0.08973097 0.07894998 0.08821099 0.07936996 0.08067095 0.07894998 0.08821099 0.07343399 0.087076 0.07936996 0.08067095 0.08514297 0.08141195 0.07894998 0.08821099 0.078094 0.09183198 0.07894998 0.08821099 0.08514297 0.08141195 0.07589697 0.08021396 0.07343399 0.087076 0.06851899 0.08593899 0.07589697 0.08021396 0.07936996 0.08067095 0.07343399 0.087076 0.07203596 0.079602 0.06851899 0.08593899 0.064242 0.08482795 0.07203596 0.079602 0.07589697 0.08021396 0.06851899 0.08593899 0.06492596 0.07795995 0.064242 0.08482795 0.06066983 0.08374196 0.068084 0.07880198 0.07203596 0.079602 0.064242 0.08482795 0.06492596 0.07795995 0.068084 0.07880198 0.064242 0.08482795 0.06247484 0.07710796 0.06066983 0.08374196 0.05786883 0.082681 0.06247484 0.07710796 0.06492596 0.07795995 0.06066983 0.08374196 0.05803483 0.07454097 0.05786883 0.082681 0.05590498 0.08164298 0.06057596 0.07625895 0.06247484 0.07710796 0.05786883 0.082681 0.05803483 0.07454097 0.06057596 0.07625895 0.05786883 0.082681 0.05495584 0.08024197 0.05590498 0.08164298 0.05485385 0.08060801 0.05651098 0.07337498 0.05803483 0.07454097 0.05590498 0.08164298 0.05508798 0.07976299 0.05651098 0.07337498 0.05590498 0.08164298 0.05495584 0.08024197 0.05508798 0.07976299 0.05590498 0.08164298 0.05349683 0.085285 0.05485385 0.08060801 0.05328083 0.08568298 0.05349683 0.085285 0.05495584 0.08024197 0.05485385 0.08060801 0.05349683 0.085285 0.05328083 0.08568298 0.05167084 0.09064799 0.08243197 0.07525098 0.08514297 0.08141195 0.07936996 0.08067095 0.08636701 0.08296 0.078094 0.09183198 0.08514297 0.08141195 0.08686995 0.07958495 0.08636701 0.08296 0.08514297 0.08141195 0.08686995 0.07958495 0.08514297 0.08141195 0.08948296 0.07578295 0.08243197 0.07525098 0.08948296 0.07578295 0.08514297 0.08141195 0.08243197 0.07525098 0.07936996 0.08067095 0.07589697 0.08021396 0.07592499 0.07481998 0.07589697 0.08021396 0.07203596 0.079602 0.08243197 0.07525098 0.07589697 0.08021396 0.07592499 0.07481998 0.070243 0.07431095 0.07203596 0.079602 0.068084 0.07880198 0.07592499 0.07481998 0.07203596 0.079602 0.070243 0.07431095 0.070243 0.07431095 0.068084 0.07880198 0.06492596 0.07795995 0.06544798 0.07370197 0.06492596 0.07795995 0.06247484 0.07710796 0.070243 0.07431095 0.06492596 0.07795995 0.06544798 0.07370197 0.06158185 0.07298499 0.06247484 0.07710796 0.06057596 0.07625895 0.06544798 0.07370197 0.06247484 0.07710796 0.06158185 0.07298499 0.05868285 0.07214295 0.06057596 0.07625895 0.05803483 0.07454097 0.06158185 0.07298499 0.06057596 0.07625895 0.05868285 0.07214295 0.05675482 0.07143199 0.05803483 0.07454097 0.05651098 0.07337498 0.05868285 0.07214295 0.05803483 0.07454097 0.05675482 0.07143199 0.0551669 0.07942301 0.05651098 0.07337498 0.05508798 0.07976299 0.05646497 0.07316499 0.05675482 0.07143199 0.05651098 0.07337498 0.0551669 0.07942301 0.05646497 0.07316499 0.05651098 0.07337498 0.05349683 0.085285 0.05508798 0.07976299 0.05495584 0.08024197 0.0551669 0.07942301 0.05508798 0.07976299 0.05349683 0.085285 0.05231183 0.113795 0.05176997 0.111195 0.06050688 0.106121 0.06142199 0.108441 0.06050688 0.106121 0.06940698 0.09959995 0.06142199 0.108441 0.05231183 0.113795 0.06050688 0.106121 0.07057899 0.101668 0.06940698 0.09959995 0.078094 0.09183198 0.07057899 0.101668 0.06142199 0.108441 0.06940698 0.09959995 0.07944697 0.09367996 0.078094 0.09183198 0.08636701 0.08296 0.07944697 0.09367996 0.07057899 0.101668 0.078094 0.09183198 0.08783799 0.084625 0.07944697 0.09367996 0.08636701 0.08296 0.08686995 0.07958495 0.08783799 0.084625 0.08636701 0.08296 0.05827283 0.113912 0.05231183 0.113795 0.06142199 0.108441 0.06644898 0.108358 0.06142199 0.108441 0.07057899 0.101668 0.06644898 0.108358 0.05827283 0.113912 0.06142199 0.108441 0.07448697 0.101839 0.07057899 0.101668 0.07944697 0.09367996 0.07448697 0.101839 0.06644898 0.108358 0.07057899 0.101668 0.08221697 0.09447598 0.07944697 0.09367996 0.08783799 0.084625 0.08221697 0.09447598 0.07448697 0.101839 0.07944697 0.09367996 0.089531 0.08637595 0.08221697 0.09447598 0.08783799 0.084625 0.08997297 0.082116 0.089531 0.08637595 0.08783799 0.084625 0.08686995 0.07958495 0.08997297 0.082116 0.08783799 0.084625 0.08821898 0.077874 0.09183299 0.07932299 0.08997297 0.082116 0.08686995 0.07958495 0.08821898 0.077874 0.08997297 0.082116 0.089908 0.07491195 0.09331095 0.07624298 0.09183299 0.07932299 0.08948296 0.07578295 0.089908 0.07491195 0.09183299 0.07932299 0.08918398 0.07634097 0.08948296 0.07578295 0.09183299 0.07932299 0.08821898 0.077874 0.08918398 0.07634097 0.09183299 0.07932299 0.09082496 0.07203596 0.09427601 0.07291698 0.09331095 0.07624298 0.089908 0.07491195 0.09082496 0.07203596 0.09331095 0.07624298 0.09106695 0.07035696 0.09461396 0.06944096 0.09427601 0.07291698 0.09082496 0.07203596 0.09106695 0.07035696 0.09427601 0.07291698 0.091075 0.06870698 0.09427601 0.06596499 0.09461396 0.06944096 0.09109896 0.06943398 0.091075 0.06870698 0.09461396 0.06944096 0.09106695 0.07035696 0.09109896 0.06943398 0.09461396 0.06944096 0.09053599 0.06568098 0.09331095 0.06263697 0.09427601 0.06596499 0.091075 0.06870698 0.09053599 0.06568098 0.09427601 0.06596499 0.088786 0.06187099 0.09183299 0.05955797 0.09331095 0.06263697 0.08947598 0.063075 0.088786 0.06187099 0.09331095 0.06263697 0.08951699 0.06315398 0.08947598 0.063075 0.09331095 0.06263697 0.09053599 0.06568098 0.08951699 0.06315398 0.09331095 0.06263697 0.08785396 0.0605039 0.08997195 0.05676597 0.09183299 0.05955797 0.088786 0.06187099 0.08785396 0.0605039 0.09183299 0.05955797 0.08785396 0.0605039 0.08663898 0.05902493 0.08997195 0.05676597 0.08243596 0.06361895 0.08663898 0.05902493 0.08785396 0.0605039 0.08243596 0.06361895 0.08785396 0.0605039 0.088786 0.06187099 0.08243596 0.06361895 0.088786 0.06187099 0.08947598 0.063075 0.08382195 0.06943595 0.08947598 0.063075 0.08951699 0.06315398 0.08382195 0.06943595 0.08243596 0.06361895 0.08947598 0.063075 0.08382195 0.06943595 0.08951699 0.06315398 0.09053599 0.06568098 0.09109896 0.06943398 0.09053599 0.06568098 0.091075 0.06870698 0.08382195 0.06943595 0.09053599 0.06568098 0.09109896 0.06943398 0.09082496 0.07203596 0.09109896 0.06943398 0.09106695 0.07035696 0.089908 0.07491195 0.09109896 0.06943398 0.09082496 0.07203596 0.08948296 0.07578295 0.09109896 0.06943398 0.089908 0.07491195 0.08382195 0.06943595 0.09109896 0.06943398 0.08948296 0.07578295 0.08821898 0.077874 0.08948296 0.07578295 0.08918398 0.07634097 0.08686995 0.07958495 0.08948296 0.07578295 0.08821898 0.077874 0.08243197 0.07525098 0.08382195 0.06943595 0.08948296 0.07578295 0.05683785 0.06944 0.05675399 0.06744599 0.05868196 0.066733 0.05646497 0.06571698 0.05675399 0.06744599 0.05683785 0.06944 0.05890583 0.06944 0.05868196 0.066733 0.06158185 0.065889 0.05890583 0.06944 0.05683785 0.06944 0.05868196 0.066733 0.06198787 0.06943899 0.06158185 0.065889 0.06544798 0.065171 0.06198787 0.06943899 0.05890583 0.06944 0.06158185 0.065889 0.06606698 0.06943798 0.06544798 0.065171 0.07024496 0.064561 0.06606698 0.06943798 0.06198787 0.06943899 0.06544798 0.065171 0.07110297 0.06943696 0.07024496 0.064561 0.07592695 0.06405097 0.07110297 0.06943696 0.06606698 0.06943798 0.07024496 0.064561 0.07704198 0.06943696 0.07592695 0.06405097 0.08243596 0.06361895 0.07704198 0.06943696 0.07110297 0.06943696 0.07592695 0.06405097 0.08382195 0.06943595 0.07704198 0.06943696 0.08243596 0.06361895 0.05868285 0.07214295 0.05683785 0.06944 0.05890583 0.06944 0.05868285 0.07214295 0.05675482 0.07143199 0.05683785 0.06944 0.05646497 0.07316499 0.05683785 0.06944 0.05675482 0.07143199 0.05674499 0.06944 0.05683785 0.06944 0.05646497 0.07316499 0.05646497 0.06571698 0.05683785 0.06944 0.05674499 0.06944 0.06158185 0.07298499 0.05890583 0.06944 0.06198787 0.06943899 0.06158185 0.07298499 0.05868285 0.07214295 0.05890583 0.06944 0.06544798 0.07370197 0.06198787 0.06943899 0.06606698 0.06943798 0.06544798 0.07370197 0.06158185 0.07298499 0.06198787 0.06943899 0.070243 0.07431095 0.06606698 0.06943798 0.07110297 0.06943696 0.070243 0.07431095 0.06544798 0.07370197 0.06606698 0.06943798 0.07592499 0.07481998 0.07110297 0.06943696 0.07704198 0.06943696 0.07592499 0.07481998 0.070243 0.07431095 0.07110297 0.06943696 0.08243197 0.07525098 0.07704198 0.06943696 0.08382195 0.06943595 0.08243197 0.07525098 0.07592499 0.07481998 0.07704198 0.06943696 0.06132495 0.06944 0.05936795 0.07311695 0.06102395 0.07330197 0.05857098 0.07911396 0.06102395 0.07330197 0.05936795 0.07311695 0.05991286 0.07934695 0.06102395 0.07330197 0.05857098 0.07911396 0.058218 0.06944 0.05796498 0.07302695 0.05936795 0.07311695 0.05735486 0.07900196 0.05936795 0.07311695 0.05796498 0.07302695 0.05963397 0.06944 0.058218 0.06944 0.05936795 0.07311695 0.06132495 0.06944 0.05963397 0.06944 0.05936795 0.07311695 0.05857098 0.07911396 0.05936795 0.07311695 0.05735486 0.07900196 0.05722182 0.06944 0.05696398 0.073044 0.05796498 0.07302695 0.05634182 0.07901799 0.05796498 0.07302695 0.05696398 0.073044 0.058218 0.06944 0.05722182 0.06944 0.05796498 0.07302695 0.05735486 0.07900196 0.05796498 0.07302695 0.05634182 0.07901799 0.05674499 0.06944 0.05646497 0.07316499 0.05696398 0.073044 0.05559682 0.07916098 0.05696398 0.073044 0.05646497 0.07316499 0.05722182 0.06944 0.05674499 0.06944 0.05696398 0.073044 0.05634182 0.07901799 0.05696398 0.073044 0.05559682 0.07916098 0.05559682 0.07916098 0.05646497 0.07316499 0.0551669 0.07942301 0.05696398 0.06583797 0.05674499 0.06944 0.05722182 0.06944 0.05696398 0.06583797 0.05646497 0.06571698 0.05674499 0.06944 0.05796498 0.06585395 0.05722182 0.06944 0.058218 0.06944 0.05796498 0.06585395 0.05696398 0.06583797 0.05722182 0.06944 0.05796498 0.06585395 0.058218 0.06944 0.05963397 0.06944 0.05936795 0.06576496 0.05963397 0.06944 0.06132495 0.06944 0.05936795 0.06576496 0.05796498 0.06585395 0.05963397 0.06944 0.06102395 0.06558001 0.05936795 0.06576496 0.06132495 0.06944 0.05559682 0.05972099 0.05646497 0.06571698 0.05696398 0.06583797 0.05559682 0.05972099 0.0551669 0.05945897 0.05646497 0.06571698 0.05634182 0.05986398 0.05696398 0.06583797 0.05796498 0.06585395 0.05634182 0.05986398 0.05559682 0.05972099 0.05696398 0.06583797 0.05735486 0.05987983 0.05796498 0.06585395 0.05936795 0.06576496 0.05735486 0.05987983 0.05634182 0.05986398 0.05796498 0.06585395 0.05857098 0.05976796 0.05936795 0.06576496 0.06102395 0.06558001 0.05857098 0.05976796 0.05735486 0.05987983 0.05936795 0.06576496 0.05991286 0.05953484 0.05857098 0.05976796 0.06102395 0.06558001 0.05405586 0.09484797 0.05127286 0.09904396 0.052109 0.09915 0.05008482 0.10252 0.052109 0.09915 0.05127286 0.09904396 0.05302399 0.094702 0.05046099 0.09904199 0.05127286 0.09904396 0.05008482 0.10252 0.05127286 0.09904396 0.05046099 0.09904199 0.05405586 0.09484797 0.05302399 0.094702 0.05127286 0.09904396 0.052046 0.09470099 0.04969495 0.099146 0.05046099 0.09904199 0.04893589 0.102565 0.05046099 0.09904199 0.04969495 0.099146 0.05302399 0.094702 0.052046 0.09470099 0.05046099 0.09904199 0.05008482 0.10252 0.05046099 0.09904199 0.04893589 0.102565 0.05115985 0.09484601 0.04899483 0.099352 0.04969495 0.099146 0.04786884 0.102818 0.04969495 0.099146 0.04899483 0.099352 0.052046 0.09470099 0.05115985 0.09484601 0.04969495 0.099146 0.04893589 0.102565 0.04969495 0.099146 0.04786884 0.102818 0.050399 0.09512996 0.04837799 0.09965598 0.04899483 0.099352 0.04786884 0.102818 0.04899483 0.099352 0.04837799 0.09965598 0.05115985 0.09484601 0.050399 0.09512996 0.04899483 0.099352 0.04979497 0.09554398 0.04786282 0.100049 0.04837799 0.09965598 0.04693496 0.103268 0.04837799 0.09965598 0.04786282 0.100049 0.050399 0.09512996 0.04979497 0.09554398 0.04837799 0.09965598 0.04786884 0.102818 0.04837799 0.09965598 0.04693496 0.103268 0.05167084 0.09064799 0.04979497 0.09554398 0.050399 0.09512996 0.05224496 0.09025996 0.050399 0.09512996 0.05115985 0.09484601 0.05224496 0.09025996 0.05167084 0.09064799 0.050399 0.09512996 0.05301582 0.09000796 0.05115985 0.09484601 0.052046 0.09470099 0.05301582 0.09000796 0.05224496 0.09025996 0.05115985 0.09484601 0.05394887 0.08990198 0.052046 0.09470099 0.05302399 0.094702 0.05394887 0.08990198 0.05301582 0.09000796 0.052046 0.09470099 0.05500096 0.08994597 0.05302399 0.094702 0.05405586 0.09484797 0.05500096 0.08994597 0.05394887 0.08990198 0.05302399 0.094702 0.05612397 0.09013897 0.05500096 0.08994597 0.05405586 0.09484797 0.05349683 0.085285 0.05167084 0.09064799 0.05224496 0.09025996 0.05401295 0.08494096 0.05224496 0.09025996 0.05301582 0.09000796 0.05401295 0.08494096 0.05349683 0.085285 0.05224496 0.09025996 0.05478096 0.08473199 0.05301582 0.09000796 0.05394887 0.08990198 0.05478096 0.08473199 0.05401295 0.08494096 0.05301582 0.09000796 0.05575788 0.08466696 0.05394887 0.08990198 0.05500096 0.08994597 0.05575788 0.08466696 0.05478096 0.08473199 0.05394887 0.08990198 0.05689096 0.08474999 0.05500096 0.08994597 0.05612397 0.09013897 0.05689096 0.08474999 0.05575788 0.08466696 0.05500096 0.08994597 0.05811887 0.08497697 0.05689096 0.08474999 0.05612397 0.09013897 0.0551669 0.07942301 0.05349683 0.085285 0.05401295 0.08494096 0.05559682 0.07916098 0.05401295 0.08494096 0.05478096 0.08473199 0.05559682 0.07916098 0.0551669 0.07942301 0.05401295 0.08494096 0.05634182 0.07901799 0.05478096 0.08473199 0.05575788 0.08466696 0.05634182 0.07901799 0.05559682 0.07916098 0.05478096 0.08473199 0.05735486 0.07900196 0.05575788 0.08466696 0.05689096 0.08474999 0.05735486 0.07900196 0.05634182 0.07901799 0.05575788 0.08466696 0.05857098 0.07911396 0.05689096 0.08474999 0.05811887 0.08497697 0.05857098 0.07911396 0.05735486 0.07900196 0.05689096 0.08474999 0.05991286 0.07934695 0.05857098 0.07911396 0.05811887 0.08497697 0.04384785 0.107941 0.046139 0.104028 0.046148 0.103996 0.05349683 0.05359697 0.0551669 0.05945897 0.05559682 0.05972099 0.05401295 0.05393987 0.05559682 0.05972099 0.05634182 0.05986398 0.05401295 0.05393987 0.05349683 0.05359697 0.05559682 0.05972099 0.05478096 0.05414897 0.05634182 0.05986398 0.05735486 0.05987983 0.05478096 0.05414897 0.05401295 0.05393987 0.05634182 0.05986398 0.05575788 0.054214 0.05735486 0.05987983 0.05857098 0.05976796 0.05575788 0.054214 0.05478096 0.05414897 0.05735486 0.05987983 0.05689096 0.05413097 0.05857098 0.05976796 0.05991286 0.05953484 0.05689096 0.05413097 0.05575788 0.054214 0.05857098 0.05976796 0.05811887 0.05390387 0.05689096 0.05413097 0.05991286 0.05953484 0.05166995 0.04823297 0.05349683 0.05359697 0.05401295 0.05393987 0.05224382 0.04862087 0.05401295 0.05393987 0.05478096 0.05414897 0.05224382 0.04862087 0.05166995 0.04823297 0.05401295 0.05393987 0.05301499 0.04887282 0.05478096 0.05414897 0.05575788 0.054214 0.05301499 0.04887282 0.05224382 0.04862087 0.05478096 0.05414897 0.05394798 0.04897898 0.05575788 0.054214 0.05689096 0.05413097 0.05394798 0.04897898 0.05301499 0.04887282 0.05575788 0.054214 0.05499982 0.04893487 0.05689096 0.05413097 0.05811887 0.05390387 0.05499982 0.04893487 0.05394798 0.04897898 0.05689096 0.05413097 0.05612283 0.04874289 0.05499982 0.04893487 0.05811887 0.05390387 0.04979497 0.043338 0.05166995 0.04823297 0.05224382 0.04862087 0.050399 0.043751 0.05224382 0.04862087 0.05301499 0.04887282 0.050399 0.043751 0.04979497 0.043338 0.05224382 0.04862087 0.05115985 0.04403597 0.05301499 0.04887282 0.05394798 0.04897898 0.05115985 0.04403597 0.050399 0.043751 0.05301499 0.04887282 0.052046 0.04417985 0.05394798 0.04897898 0.05499982 0.04893487 0.052046 0.04417985 0.05115985 0.04403597 0.05394798 0.04897898 0.05302399 0.04417896 0.05499982 0.04893487 0.05612283 0.04874289 0.05302399 0.04417896 0.052046 0.04417985 0.05499982 0.04893487 0.05405586 0.044034 0.05302399 0.04417896 0.05612283 0.04874289 0.04837799 0.03922498 0.04979497 0.043338 0.050399 0.043751 0.04837799 0.03922498 0.04786199 0.03883183 0.04979497 0.043338 0.04899483 0.03952884 0.050399 0.043751 0.05115985 0.04403597 0.04899483 0.03952884 0.04837799 0.03922498 0.050399 0.043751 0.04969495 0.03973484 0.05115985 0.04403597 0.052046 0.04417985 0.04969495 0.03973484 0.04899483 0.03952884 0.05115985 0.04403597 0.05046182 0.03983891 0.052046 0.04417985 0.05302399 0.04417896 0.05046182 0.03983891 0.04969495 0.03973484 0.052046 0.04417985 0.051274 0.039837 0.05302399 0.04417896 0.05405586 0.044034 0.051274 0.039837 0.05046182 0.03983891 0.05302399 0.04417896 0.05210983 0.03973084 0.051274 0.039837 0.05405586 0.044034 0.04693496 0.035613 0.04786199 0.03883183 0.04837799 0.03922498 0.04693496 0.035613 0.04837799 0.03922498 0.04899483 0.03952884 0.04786884 0.03606283 0.04899483 0.03952884 0.04969495 0.03973484 0.04786884 0.03606283 0.04693496 0.035613 0.04899483 0.03952884 0.04893589 0.03631585 0.04969495 0.03973484 0.05046182 0.03983891 0.04893589 0.03631585 0.04786884 0.03606283 0.04969495 0.03973484 0.04893589 0.03631585 0.05046182 0.03983891 0.051274 0.039837 0.05008482 0.03636085 0.051274 0.039837 0.05210983 0.03973084 0.05008482 0.03636085 0.04893589 0.03631585 0.051274 0.039837 0.05330985 0.07694697 0.05339694 0.06944096 0.05337482 0.06563699 0.05330985 0.07694697 0.05337482 0.06563699 0.05330896 0.06189286 0.05304998 0.08421099 0.05330896 0.06189286 0.053047 0.05460786 0.05330985 0.07694697 0.05330896 0.06189286 0.05304998 0.08421099 0.05262684 0.09095299 0.053047 0.05460786 0.05262196 0.04786998 0.05304998 0.08421099 0.053047 0.05460786 0.05262684 0.09095299 0.05205297 0.09694296 0.05262196 0.04786998 0.05204784 0.04190182 0.05262684 0.09095299 0.05262196 0.04786998 0.05205297 0.09694296 0.05134087 0.101996 0.05204784 0.04190182 0.05133998 0.036879 0.05205297 0.09694296 0.05204784 0.04190182 0.05134087 0.101996 0.05134087 0.101996 0.05133998 0.036879 0.05052191 0.03302896 0.05051785 0.105867 0.05052191 0.03302896 0.04962384 0.03050899 0.05134087 0.101996 0.05052191 0.03302896 0.05051785 0.105867 0.04961585 0.108388 0.04962384 0.03050899 0.048675 0.02943783 0.05051785 0.105867 0.04962384 0.03050899 0.04961585 0.108388 0.048666 0.109447 0.048675 0.02943783 0.04771 0.02989 0.04961585 0.108388 0.048675 0.02943783 0.048666 0.109447 0.04770195 0.108981 0.04771 0.02989 0.04676598 0.03189498 0.048666 0.109447 0.04771 0.02989 0.04770195 0.108981 0.04676085 0.106975 0.04676598 0.03189498 0.04587996 0.03541797 0.04770195 0.108981 0.04676598 0.03189498 0.04676085 0.106975 0.04509699 0.09856897 0.04587996 0.03541797 0.04509294 0.04034882 0.04588097 0.10347 0.04587996 0.03541797 0.04509699 0.09856897 0.04676085 0.106975 0.04587996 0.03541797 0.04588097 0.10347 0.04444897 0.09248298 0.04509294 0.04034882 0.04444396 0.04645884 0.04509699 0.09856897 0.04509294 0.04034882 0.04444897 0.09248298 0.04395997 0.08540195 0.04444396 0.04645884 0.04395699 0.05354487 0.04444897 0.09248298 0.04444396 0.04645884 0.04395997 0.08540195 0.04365599 0.07760095 0.04395699 0.05354487 0.04365485 0.06132584 0.04395997 0.08540195 0.04395699 0.05354487 0.04365599 0.07760095 0.04357898 0.07355797 0.04365485 0.06132584 0.04355299 0.06944096 0.04365599 0.07760095 0.04365485 0.06132584 0.04357898 0.07355797 0.100099 0.08592897 0.100099 0.052953 0.121172 0.02304196 0.09730899 0.08089399 0.09730899 0.05798786 0.100099 0.052953 0.100099 0.08592897 0.09730899 0.08089399 0.100099 0.052953 0.121172 0.11584 0.121172 0.02304196 0.126107 0.01738697 0.121172 0.11584 0.100099 0.08592897 0.121172 0.02304196 0.132001 0.125881 0.126107 0.01738697 0.132001 0.01300096 0.126107 0.121494 0.121172 0.11584 0.126107 0.01738697 0.132001 0.125881 0.126107 0.121494 0.126107 0.01738697 0.1386 0.128798 0.132001 0.01300096 0.1386 0.01008397 0.1386 0.128798 0.132001 0.125881 0.132001 0.01300096 0.145617 0.130102 0.1386 0.01008397 0.145617 0.008779942 0.145617 0.130102 0.1386 0.128798 0.1386 0.01008397 0.145617 0.130102 0.145617 0.008779942 0.152739 0.009168982 0.152739 0.129712 0.145617 0.130102 0.152739 0.009168982 0.182384 0.01441782 0.152739 0.129712 0.152739 0.009168982 0.09558796 0.07530695 0.09558796 0.06357496 0.09730899 0.05798786 0.09730899 0.08089399 0.09558796 0.07530695 0.09730899 0.05798786 0.09558796 0.07530695 0.095007 0.06944096 0.09558796 0.06357496 0.182384 0.01441782 0.182384 0.124464 0.152739 0.129712 0.191529 0.01702797 0.191493 0.121868 0.182384 0.124464 0.182384 0.01441782 0.191529 0.01702797 0.182384 0.124464 0.195917 0.01903897 0.2000499 0.117433 0.191493 0.121868 0.191529 0.01702797 0.195917 0.01903897 0.191493 0.121868 0.200112 0.02148896 0.207723 0.111308 0.2000499 0.117433 0.195917 0.01903897 0.200112 0.02148896 0.2000499 0.117433 0.207791 0.02763897 0.214224 0.103709 0.207723 0.111308 0.200112 0.02148896 0.207791 0.02763897 0.207723 0.111308 0.214277 0.03524684 0.2193599 0.09483295 0.214224 0.103709 0.207791 0.02763897 0.214277 0.03524684 0.214224 0.103709 0.2193869 0.04410582 0.222891 0.08504098 0.2193599 0.09483295 0.214277 0.03524684 0.2193869 0.04410582 0.2193599 0.09483295 0.222898 0.05386698 0.224686 0.07470095 0.222891 0.08504098 0.2193869 0.04410582 0.222898 0.05386698 0.222891 0.08504098 0.222898 0.05386698 0.224686 0.06418597 0.224686 0.07470095 0.112896 0.133623 0.09255999 0.132042 0.101733 0.134754 0.120984 0.135851 0.112896 0.133623 0.101733 0.134754 0.104899 0.130779 0.083485 0.128686 0.09255999 0.132042 0.112896 0.133623 0.104899 0.130779 0.09255999 0.132042 0.09709697 0.127344 0.074651 0.124715 0.083485 0.128686 0.104899 0.130779 0.09709697 0.127344 0.083485 0.128686 0.08959698 0.123346 0.06620496 0.1201699 0.074651 0.124715 0.05321484 0.122155 0.074651 0.124715 0.06620496 0.1201699 0.09709697 0.127344 0.08959698 0.123346 0.074651 0.124715 0.08250796 0.118822 0.05829495 0.115095 0.06620496 0.1201699 0.04467797 0.11759 0.06620496 0.1201699 0.05829495 0.115095 0.08959698 0.123346 0.08250796 0.118822 0.06620496 0.1201699 0.04467797 0.11759 0.05321484 0.122155 0.06620496 0.1201699 0.075935 0.113813 0.05106699 0.109542 0.05829495 0.115095 0.03670299 0.112589 0.05829495 0.115095 0.05106699 0.109542 0.08250796 0.118822 0.075935 0.113813 0.05829495 0.115095 0.03670299 0.112589 0.04467797 0.11759 0.05829495 0.115095 0.06998199 0.1083649 0.04466187 0.103566 0.05106699 0.109542 0.02943295 0.1071979 0.05106699 0.109542 0.04466187 0.103566 0.075935 0.113813 0.06998199 0.1083649 0.05106699 0.109542 0.02943295 0.1071979 0.03670299 0.112589 0.05106699 0.109542 0.064745 0.102529 0.03920799 0.09722399 0.04466187 0.103566 0.02300482 0.101464 0.04466187 0.103566 0.03920799 0.09722399 0.06998199 0.1083649 0.064745 0.102529 0.04466187 0.103566 0.02300482 0.101464 0.02943295 0.1071979 0.04466187 0.103566 0.06031286 0.09635698 0.03482395 0.09057897 0.03920799 0.09722399 0.01754283 0.095438 0.03920799 0.09722399 0.03482395 0.09057897 0.064745 0.102529 0.06031286 0.09635698 0.03920799 0.09722399 0.01754283 0.095438 0.02300482 0.101464 0.03920799 0.09722399 0.05676686 0.08990496 0.03160583 0.08369195 0.03482395 0.09057897 0.01316183 0.08917099 0.03482395 0.09057897 0.03160583 0.08369195 0.06031286 0.09635698 0.05676686 0.08990496 0.03482395 0.09057897 0.01316183 0.08917099 0.01754283 0.095438 0.03482395 0.09057897 0.05417382 0.08322995 0.02963685 0.07662498 0.03160583 0.08369195 0.009952962 0.08271497 0.03160583 0.08369195 0.02963685 0.07662498 0.05676686 0.08990496 0.05417382 0.08322995 0.03160583 0.08369195 0.009952962 0.08271497 0.01316183 0.08917099 0.03160583 0.08369195 0.05417382 0.08322995 0.05259186 0.07638996 0.02963685 0.07662498 0.007994949 0.07612097 0.009952962 0.08271497 0.02963685 0.07662498 0.07710999 0.07632195 0.05259186 0.07638996 0.05417382 0.08322995 0.07840895 0.08310997 0.05417382 0.08322995 0.05676686 0.08990496 0.07710999 0.07632195 0.05417382 0.08322995 0.07840895 0.08310997 0.08054399 0.08974397 0.05676686 0.08990496 0.06031286 0.09635698 0.07840895 0.08310997 0.05676686 0.08990496 0.08054399 0.08974397 0.08347696 0.096165 0.06031286 0.09635698 0.064745 0.102529 0.08054399 0.08974397 0.06031286 0.09635698 0.08347696 0.096165 0.08716398 0.102313 0.064745 0.102529 0.06998199 0.1083649 0.08347696 0.096165 0.064745 0.102529 0.08716398 0.102313 0.09154695 0.108133 0.06998199 0.1083649 0.075935 0.113813 0.08716398 0.102313 0.06998199 0.1083649 0.09154695 0.108133 0.09656697 0.11357 0.075935 0.113813 0.08250796 0.118822 0.09154695 0.108133 0.075935 0.113813 0.09656697 0.11357 0.102154 0.118574 0.08250796 0.118822 0.08959698 0.123346 0.09656697 0.11357 0.08250796 0.118822 0.102154 0.118574 0.108235 0.123097 0.08959698 0.123346 0.09709697 0.127344 0.102154 0.118574 0.08959698 0.123346 0.108235 0.123097 0.114733 0.127099 0.09709697 0.127344 0.104899 0.130779 0.108235 0.123097 0.09709697 0.127344 0.114733 0.127099 0.1215659 0.130541 0.104899 0.130779 0.112896 0.133623 0.114733 0.127099 0.104899 0.130779 0.1215659 0.130541 0.128653 0.133394 0.112896 0.133623 0.120984 0.135851 0.1215659 0.130541 0.112896 0.133623 0.128653 0.133394 0.135911 0.135633 0.120984 0.135851 0.129067 0.1374509 0.128653 0.133394 0.120984 0.135851 0.135911 0.135633 0.14326 0.137242 0.129067 0.1374509 0.1370519 0.138414 0.135911 0.135633 0.129067 0.1374509 0.14326 0.137242 0.14326 0.137242 0.1370519 0.138414 0.15062 0.1382099 0.01087695 0.03235197 0.01019597 0.03325897 0.007694959 0.03767496 0.01325899 0.02906197 0.01019597 0.03325897 0.01087695 0.03235197 0.01325899 0.02906197 0.01243084 0.030101 0.01019597 0.03325897 0.008298993 0.03681695 0.007694959 0.03767496 0.005343973 0.04270899 0.008298993 0.03681695 0.01087695 0.03235197 0.007694959 0.03767496 0.005862951 0.04193097 0.005343973 0.04270899 0.003242969 0.04843199 0.005862951 0.04193097 0.008298993 0.03681695 0.005343973 0.04270899 0.003672957 0.04777598 0.003242969 0.04843199 0.001536965 0.05487185 0.003672957 0.04777598 0.005862951 0.04193097 0.003242969 0.04843199 0.001884937 0.05438894 0.001536965 0.05487185 4.02e-4 0.06195282 0.001884937 0.05438894 0.003672957 0.04777598 0.001536965 0.05487185 6.89e-4 0.06169492 0.001884937 0.05438894 4.02e-4 0.06195282 0.01960796 0.02508985 0.01820397 0.02633798 0.01651698 0.02667587 0.01771098 0.02546799 0.01651698 0.02667587 0.01457285 0.02790898 0.01771098 0.02546799 0.01960796 0.02508985 0.01651698 0.02667587 0.01557284 0.02677083 0.01457285 0.02790898 0.01243084 0.030101 0.01557284 0.02677083 0.01771098 0.02546799 0.01457285 0.02790898 0.01325899 0.02906197 0.01557284 0.02677083 0.01243084 0.030101 0.234316 0.06944096 0.109213 0.06944096 0.109455 0.074934 0.234073 0.06394797 0.109213 0.06944096 0.234316 0.06944096 0.110158 0.05860096 0.109213 0.06944096 0.234073 0.06394797 0.23337 0.08028095 0.109455 0.074934 0.110169 0.08034497 0.234316 0.06944096 0.109455 0.074934 0.23337 0.08028095 0.230554 0.09081798 0.110169 0.08034497 0.113007 0.09090799 0.23337 0.08028095 0.110169 0.08034497 0.230554 0.09081798 0.2259539 0.100701 0.113007 0.09090799 0.117619 0.1007789 0.230554 0.09081798 0.113007 0.09090799 0.2259539 0.100701 0.2197279 0.109606 0.117619 0.1007789 0.123836 0.109648 0.2259539 0.100701 0.117619 0.1007789 0.2197279 0.109606 0.21602 0.11366 0.123836 0.109648 0.131543 0.117358 0.2197279 0.109606 0.123836 0.109648 0.21602 0.11366 0.2119809 0.117362 0.131543 0.117358 0.1404629 0.123606 0.21602 0.11366 0.131543 0.117358 0.2119809 0.117362 0.202996 0.123645 0.1404629 0.123606 0.1503199 0.128205 0.207617 0.120707 0.1404629 0.123606 0.202996 0.123645 0.2119809 0.117362 0.1404629 0.123606 0.207617 0.120707 0.193072 0.128255 0.1503199 0.128205 0.160822 0.1310279 0.202996 0.123645 0.1503199 0.128205 0.193072 0.128255 0.182519 0.131061 0.160822 0.1310279 0.171662 0.131991 0.193072 0.128255 0.160822 0.1310279 0.182519 0.131061 0.110158 0.05860096 0.234073 0.06394797 0.233359 0.05853599 0.112975 0.04806298 0.233359 0.05853599 0.230521 0.04797399 0.110158 0.05860096 0.233359 0.05853599 0.112975 0.04806298 0.117574 0.03818082 0.230521 0.04797399 0.2259089 0.03810298 0.112975 0.04806298 0.230521 0.04797399 0.117574 0.03818082 0.123801 0.02927595 0.2259089 0.03810298 0.219693 0.02923399 0.117574 0.03818082 0.2259089 0.03810298 0.123801 0.02927595 0.1275089 0.025222 0.219693 0.02923399 0.211986 0.02152395 0.123801 0.02927595 0.219693 0.02923399 0.1275089 0.025222 0.131547 0.02151983 0.211986 0.02152395 0.203065 0.01527583 0.1275089 0.025222 0.211986 0.02152395 0.131547 0.02151983 0.140532 0.01523697 0.203065 0.01527583 0.193208 0.01067584 0.135911 0.01817399 0.203065 0.01527583 0.140532 0.01523697 0.131547 0.02151983 0.203065 0.01527583 0.135911 0.01817399 0.150457 0.01062697 0.193208 0.01067584 0.1827059 0.007853984 0.140532 0.01523697 0.193208 0.01067584 0.150457 0.01062697 0.161009 0.007820963 0.1827059 0.007853984 0.1718659 0.006889939 0.150457 0.01062697 0.1827059 0.007853984 0.161009 0.007820963 0.02431398 0.080388 0.02431398 0.05849283 0.02708399 0.041619 0.02380895 0.07630795 0.02380895 0.06257295 0.02431398 0.05849283 0.02431398 0.080388 0.02380895 0.07630795 0.02431398 0.05849283 0.02708399 0.09726297 0.02708399 0.041619 0.02787399 0.037705 0.02708399 0.09726297 0.02431398 0.080388 0.02708399 0.041619 0.02787399 0.101176 0.02787399 0.037705 0.02881598 0.03461796 0.02787399 0.101176 0.02708399 0.09726297 0.02787399 0.037705 0.02881598 0.104264 0.02881598 0.03461796 0.02986997 0.03246986 0.02881598 0.104264 0.02787399 0.101176 0.02881598 0.03461796 0.02986997 0.106412 0.02986997 0.03246986 0.03099083 0.03133487 0.02986997 0.106412 0.02881598 0.104264 0.02986997 0.03246986 0.03099083 0.107547 0.03099083 0.03133487 0.03213596 0.03124094 0.03099083 0.107547 0.02986997 0.106412 0.03099083 0.03133487 0.03213596 0.10764 0.03099083 0.107547 0.03213596 0.03124094 0.03534787 0.03244096 0.03213596 0.10764 0.03213596 0.03124094 0.02354699 0.07178097 0.02354699 0.067101 0.02380895 0.06257295 0.02380895 0.07630795 0.02354699 0.07178097 0.02380895 0.06257295 0.03534787 0.03244096 0.03534787 0.10644 0.03213596 0.10764 0.03693085 0.03379899 0.036924 0.105093 0.03534787 0.10644 0.03534787 0.03244096 0.03693085 0.03379899 0.03534787 0.10644 0.03693085 0.03379899 0.03840196 0.102314 0.036924 0.105093 0.038414 0.03659784 0.03972095 0.09825199 0.03840196 0.102314 0.03693085 0.03379899 0.038414 0.03659784 0.03840196 0.102314 0.03973299 0.04067498 0.04083585 0.09307998 0.03972095 0.09825199 0.038414 0.03659784 0.03973299 0.04067498 0.03972095 0.09825199 0.04084396 0.04584795 0.04171186 0.08697497 0.04083585 0.09307998 0.03973299 0.04067498 0.04084396 0.04584795 0.04083585 0.09307998 0.04231095 0.05866396 0.04231184 0.08021199 0.04171186 0.08697497 0.04171484 0.05193096 0.04231095 0.05866396 0.04171186 0.08697497 0.04084396 0.04584795 0.04171484 0.05193096 0.04171186 0.08697497 0.04261487 0.06579297 0.04261487 0.073062 0.04231184 0.08021199 0.04231095 0.05866396 0.04261487 0.06579297 0.04231184 0.08021199 0.228379 0.09271395 0.22584 0.09732198 0.225933 0.09715098 0.2258239 0.09735 0.225933 0.09715098 0.22584 0.09732198 0.226243 0.09651398 0.225933 0.09715098 0.225948 0.09706795 0.2258239 0.09735 0.225948 0.09706795 0.225933 0.09715098 0.226624 0.09579396 0.225933 0.09715098 0.226243 0.09651398 0.2271029 0.09486895 0.225933 0.09715098 0.226624 0.09579396 0.227697 0.09369099 0.225933 0.09715098 0.2271029 0.09486895 0.228227 0.09265297 0.225933 0.09715098 0.227697 0.09369099 0.228227 0.09265297 0.228379 0.09271395 0.225933 0.09715098 0.228379 0.09271395 0.225731 0.09748399 0.22584 0.09732198 0.2258239 0.09735 0.22584 0.09732198 0.225731 0.09748399 0.228379 0.09271395 0.225948 0.09706795 0.225731 0.09748399 0.2258239 0.09735 0.225731 0.09748399 0.225948 0.09706795 0.225709 0.09752196 0.225731 0.09748399 0.225702 0.09753799 0.2258239 0.09735 0.225702 0.09753799 0.225731 0.09748399 0.2258239 0.09735 0.225731 0.09748399 0.225709 0.09752196 0.228379 0.09271395 0.226243 0.09651398 0.225948 0.09706795 0.228379 0.09271395 0.226624 0.09579396 0.226243 0.09651398 0.228379 0.09271395 0.2271029 0.09486895 0.226624 0.09579396 0.228217 0.09262299 0.227697 0.09369099 0.2271029 0.09486895 0.228379 0.09271395 0.228217 0.09262299 0.2271029 0.09486895 0.228227 0.09265297 0.227697 0.09369099 0.228217 0.09262299 0.230357 0.08782398 0.228217 0.09262299 0.228379 0.09271395 0.2284229 0.09219199 0.228217 0.09262299 0.230357 0.08782398 0.228227 0.09265297 0.228217 0.09262299 0.2284229 0.09219199 0.228227 0.09265297 0.230357 0.08782398 0.228379 0.09271395 0.03625899 0.02369898 0.02054995 0.03229397 0.028503 0.01845395 0.02401095 0.01833397 0.028503 0.01845395 0.02054995 0.03229397 0.02960985 0.01642799 0.03625899 0.02369898 0.028503 0.01845395 0.02590584 0.01408886 0.02960985 0.01642799 0.028503 0.01845395 0.02590584 0.01408886 0.028503 0.01845395 0.02401095 0.01833397 0.03769385 0.03813886 0.01323199 0.04411482 0.02054995 0.03229397 0.01154887 0.03460294 0.02054995 0.03229397 0.01323199 0.04411482 0.03625899 0.02369898 0.03769385 0.03813886 0.02054995 0.03229397 0.02174896 0.02156597 0.02401095 0.01833397 0.02054995 0.03229397 0.019499 0.02477997 0.02174896 0.02156597 0.02054995 0.03229397 0.01845997 0.02473396 0.019499 0.02477997 0.02054995 0.03229397 0.01154887 0.03460294 0.01845997 0.02473396 0.02054995 0.03229397 0.03841286 0.05271798 0.01079487 0.048985 0.01323199 0.04411482 0.004917979 0.044061 0.01323199 0.04411482 0.01079487 0.048985 0.03769385 0.03813886 0.03841286 0.05271798 0.01323199 0.04411482 0.004917979 0.044061 0.01154887 0.03460294 0.01323199 0.04411482 0.03841286 0.05271798 0.009306967 0.05439299 0.01079487 0.048985 0.001809895 0.04997897 0.01079487 0.048985 0.009306967 0.05439299 0.001809895 0.04997897 0.004917979 0.044061 0.01079487 0.048985 0.03841286 0.067344 0.008809983 0.06002998 0.009306967 0.05439299 2.04e-4 0.05659782 0.009306967 0.05439299 0.008809983 0.06002998 0.03841286 0.05271798 0.03841286 0.067344 0.009306967 0.05439299 0.001809895 0.04997897 0.009306967 0.05439299 2.04e-4 0.05659782 0.03841286 0.067344 0.009306967 0.06566798 0.008809983 0.06002998 2.04e-4 0.06346195 0.008809983 0.06002998 0.009306967 0.06566798 0 0.06002998 0.008809983 0.06002998 2.04e-4 0.06346195 2.04e-4 0.05659782 0.008809983 0.06002998 0 0.06002998 0.03841286 0.067344 0.01079487 0.07107597 0.009306967 0.06566798 0.001809895 0.07008099 0.009306967 0.06566798 0.01079487 0.07107597 2.04e-4 0.06346195 0.009306967 0.06566798 0.001809895 0.07008099 0.03769385 0.081923 0.01323199 0.07594597 0.01079487 0.07107597 0.001809895 0.07008099 0.01079487 0.07107597 0.01323199 0.07594597 0.03841286 0.067344 0.03769385 0.081923 0.01079487 0.07107597 0.03769385 0.081923 0.01878386 0.08484095 0.01323199 0.07594597 0.004917979 0.07599997 0.01323199 0.07594597 0.01878386 0.08484095 0.001809895 0.07008099 0.01323199 0.07594597 0.004917979 0.07599997 0.03625899 0.096363 0.02472382 0.09488397 0.01878386 0.08484095 0.01155185 0.08546096 0.01878386 0.08484095 0.02472382 0.09488397 0.03769385 0.081923 0.03625899 0.096363 0.01878386 0.08484095 0.004917979 0.07599997 0.01878386 0.08484095 0.01155185 0.08546096 0.03625899 0.096363 0.02777397 0.100288 0.02472382 0.09488397 0.019499 0.095281 0.02472382 0.09488397 0.02777397 0.100288 0.019499 0.095281 0.01155185 0.08546096 0.02472382 0.09488397 0.03403699 0.110661 0.03069984 0.105654 0.02777397 0.100288 0.02401 0.101726 0.02777397 0.100288 0.03069984 0.105654 0.03625899 0.096363 0.03403699 0.110661 0.02777397 0.100288 0.02175796 0.098508 0.019499 0.095281 0.02777397 0.100288 0.02401 0.101726 0.02175796 0.098508 0.02777397 0.100288 0.02590584 0.105971 0.03069984 0.105654 0.03403699 0.110661 0.02297782 0.101785 0.03069984 0.105654 0.02590584 0.105971 0.02401 0.101726 0.03069984 0.105654 0.02297782 0.101785 0.06579399 0.104374 0.03403699 0.110661 0.03625899 0.096363 0.06330299 0.118712 0.03471595 0.111454 0.03403699 0.110661 0.03073799 0.111557 0.03403699 0.110661 0.03471595 0.111454 0.06579399 0.104374 0.06330299 0.118712 0.03403699 0.110661 0.02819395 0.108912 0.03403699 0.110661 0.03073799 0.111557 0.02590584 0.105971 0.03403699 0.110661 0.02819395 0.108912 0.06757897 0.08974897 0.03625899 0.096363 0.03769385 0.081923 0.06757897 0.08974897 0.06579399 0.104374 0.03625899 0.096363 0.06865197 0.07493698 0.03769385 0.081923 0.03841286 0.067344 0.06865197 0.07493698 0.06757897 0.08974897 0.03769385 0.081923 0.06900995 0.06002998 0.03841286 0.067344 0.03841286 0.05271798 0.06900995 0.06002998 0.06865197 0.07493698 0.03841286 0.067344 0.06865197 0.04512399 0.03841286 0.05271798 0.03769385 0.03813886 0.06865197 0.04512399 0.06900995 0.06002998 0.03841286 0.05271798 0.06757897 0.03031086 0.03769385 0.03813886 0.03625899 0.02369898 0.06757897 0.03031086 0.06865197 0.04512399 0.03769385 0.03813886 0.03069984 0.01440685 0.03403896 0.009397983 0.03625899 0.02369898 0.06579399 0.01568686 0.03625899 0.02369898 0.03403896 0.009397983 0.02960985 0.01642799 0.03069984 0.01440685 0.03625899 0.02369898 0.06579399 0.01568686 0.06757897 0.03031086 0.03625899 0.02369898 0.02819395 0.01114886 0.03403896 0.009397983 0.03069984 0.01440685 0.03472495 0.008595943 0.06579399 0.01568686 0.03403896 0.009397983 0.03073799 0.00850296 0.03472495 0.008595943 0.03403896 0.009397983 0.03073799 0.00850296 0.03403896 0.009397983 0.02819395 0.01114886 0.02590584 0.01408886 0.03069984 0.01440685 0.02960985 0.01642799 0.02819395 0.01114886 0.03069984 0.01440685 0.02590584 0.01408886 0.06330299 0.118712 0.03710198 0.1138229 0.03471595 0.111454 0.03352296 0.113892 0.03471595 0.111454 0.03710198 0.1138229 0.03073799 0.111557 0.03471595 0.111454 0.03352296 0.113892 0.06330299 0.118712 0.03973895 0.115841 0.03710198 0.1138229 0.03651696 0.115889 0.03710198 0.1138229 0.03973895 0.115841 0.03352296 0.113892 0.03710198 0.1138229 0.03651696 0.115889 0.06330299 0.118712 0.04557496 0.118694 0.03973895 0.115841 0.04298496 0.118768 0.03973895 0.115841 0.04557496 0.118694 0.03651696 0.115889 0.03973895 0.115841 0.04298496 0.118768 0.058631 0.119536 0.05197685 0.119924 0.04557496 0.118694 0.049878 0.12006 0.04557496 0.118694 0.05197685 0.119924 0.06330299 0.118712 0.058631 0.119536 0.04557496 0.118694 0.04298496 0.118768 0.04557496 0.118694 0.049878 0.12006 0.049878 0.12006 0.05197685 0.119924 0.058631 0.119536 0.05688196 0.119681 0.058631 0.119536 0.06330299 0.118712 0.049878 0.12006 0.058631 0.119536 0.05688196 0.119681 0.07335597 0.116934 0.06330299 0.118712 0.06579399 0.104374 0.07155597 0.1170819 0.06330299 0.118712 0.07335597 0.116934 0.05688196 0.119681 0.06330299 0.118712 0.07155597 0.1170819 0.09814399 0.09747195 0.06579399 0.104374 0.06757897 0.08974897 0.09545201 0.112389 0.08819198 0.114294 0.06579399 0.104374 0.07335597 0.116934 0.06579399 0.104374 0.08819198 0.114294 0.09607297 0.112168 0.09545201 0.112389 0.06579399 0.104374 0.09814399 0.09747195 0.09607297 0.112168 0.06579399 0.104374 0.099536 0.08258795 0.06757897 0.08974897 0.06865197 0.07493698 0.099536 0.08258795 0.09814399 0.09747195 0.06757897 0.08974897 0.100233 0.06756496 0.06865197 0.07493698 0.06900995 0.06002998 0.100233 0.06756496 0.099536 0.08258795 0.06865197 0.07493698 0.100233 0.05249583 0.06900995 0.06002998 0.06865197 0.04512399 0.100233 0.05249583 0.100233 0.06756496 0.06900995 0.06002998 0.099536 0.03747296 0.06865197 0.04512399 0.06757897 0.03031086 0.099536 0.03747296 0.100233 0.05249583 0.06865197 0.04512399 0.09814399 0.02258795 0.06757897 0.03031086 0.06579399 0.01568686 0.09814399 0.02258795 0.099536 0.03747296 0.06757897 0.03031086 0.03973084 0.004223883 0.06330299 0.001347959 0.06579399 0.01568686 0.09607297 0.007891952 0.06579399 0.01568686 0.06330299 0.001347959 0.03710496 0.006234884 0.03973084 0.004223883 0.06579399 0.01568686 0.03472495 0.008595943 0.03710496 0.006234884 0.06579399 0.01568686 0.09607297 0.007891952 0.09814399 0.02258795 0.06579399 0.01568686 0.04553896 0.001378953 0.058631 5.24e-4 0.06330299 0.001347959 0.07155597 0.002977967 0.06330299 0.001347959 0.058631 5.24e-4 0.03973084 0.004223883 0.04553896 0.001378953 0.06330299 0.001347959 0.09545099 0.007671952 0.09607297 0.007891952 0.06330299 0.001347959 0.07335597 0.003126919 0.09545099 0.007671952 0.06330299 0.001347959 0.07155597 0.002977967 0.07335597 0.003126919 0.06330299 0.001347959 0.04553896 0.001378953 0.05192995 1.39e-4 0.058631 5.24e-4 0.05688196 3.8e-4 0.058631 5.24e-4 0.05192995 1.39e-4 0.07155597 0.002977967 0.058631 5.24e-4 0.05688196 3.8e-4 0.049878 0 0.05192995 1.39e-4 0.04553896 0.001378953 0.05688196 3.8e-4 0.05192995 1.39e-4 0.049878 0 0.04298496 0.00129199 0.04553896 0.001378953 0.03973084 0.004223883 0.049878 0 0.04553896 0.001378953 0.04298496 0.00129199 0.03651696 0.004171967 0.03973084 0.004223883 0.03710496 0.006234884 0.04298496 0.00129199 0.03973084 0.004223883 0.03651696 0.004171967 0.03352296 0.006167948 0.03710496 0.006234884 0.03472495 0.008595943 0.03651696 0.004171967 0.03710496 0.006234884 0.03352296 0.006167948 0.03352296 0.006167948 0.03472495 0.008595943 0.03073799 0.00850296 0.08650499 0.114426 0.08819198 0.114294 0.09545201 0.112389 0.07155597 0.1170819 0.07335597 0.116934 0.08819198 0.114294 0.07155597 0.1170819 0.08819198 0.114294 0.08650499 0.114426 0.09373199 0.112521 0.09545201 0.112389 0.09607297 0.112168 0.08650499 0.114426 0.09545201 0.112389 0.09373199 0.112521 0.1026239 0.109264 0.09607297 0.112168 0.09814399 0.09747195 0.101593 0.109372 0.09607297 0.112168 0.1026239 0.109264 0.101593 0.109372 0.09373199 0.112521 0.09607297 0.112168 0.123644 0.089742 0.09814399 0.09747195 0.099536 0.08258795 0.109521 0.104918 0.1026239 0.109264 0.09814399 0.09747195 0.113526 0.101658 0.109521 0.104918 0.09814399 0.09747195 0.117242 0.09802097 0.113526 0.101658 0.09814399 0.09747195 0.123644 0.089742 0.117242 0.09802097 0.09814399 0.09747195 0.128418 0.08042097 0.099536 0.08258795 0.100233 0.06756496 0.128418 0.08042097 0.123644 0.089742 0.099536 0.08258795 0.132355 0.06002998 0.100233 0.06756496 0.100233 0.05249583 0.1313689 0.07034999 0.128418 0.08042097 0.100233 0.06756496 0.132355 0.06002998 0.1313689 0.07034999 0.100233 0.06756496 0.1313689 0.04970699 0.100233 0.05249583 0.099536 0.03747296 0.1313689 0.04970699 0.132355 0.06002998 0.100233 0.05249583 0.123642 0.03031384 0.099536 0.03747296 0.09814399 0.02258795 0.128416 0.039635 0.1313689 0.04970699 0.099536 0.03747296 0.123642 0.03031384 0.128416 0.039635 0.099536 0.03747296 0.11724 0.02203691 0.09814399 0.02258795 0.09607297 0.007891952 0.11724 0.02203691 0.123642 0.03031384 0.09814399 0.02258795 0.09373199 0.007539987 0.09607297 0.007891952 0.09545099 0.007671952 0.109521 0.01514196 0.11724 0.02203691 0.09607297 0.007891952 0.102622 0.01079595 0.109521 0.01514196 0.09607297 0.007891952 0.101593 0.01068782 0.102622 0.01079595 0.09607297 0.007891952 0.09373199 0.007539987 0.100643 0.01061987 0.09607297 0.007891952 0.101593 0.01068782 0.09607297 0.007891952 0.100643 0.01061987 0.07335597 0.003126919 0.08819097 0.005765974 0.09545099 0.007671952 0.09373199 0.007539987 0.09545099 0.007671952 0.08819097 0.005765974 0.08650499 0.005634963 0.08819097 0.005765974 0.07335597 0.003126919 0.09373199 0.007539987 0.08819097 0.005765974 0.08650499 0.005634963 0.08650499 0.005634963 0.07335597 0.003126919 0.07155597 0.002977967 0.105243 0.10717 0.1026239 0.109264 0.109521 0.104918 0.105243 0.10717 0.101593 0.109372 0.1026239 0.109264 0.107286 0.105086 0.109521 0.104918 0.113526 0.101658 0.108876 0.104974 0.109521 0.104918 0.107286 0.105086 0.108219 0.10503 0.109521 0.104918 0.108876 0.104974 0.105243 0.10717 0.109521 0.104918 0.108219 0.10503 0.114473 0.09828197 0.113526 0.101658 0.117242 0.09802097 0.107286 0.105086 0.113526 0.101658 0.114473 0.09828197 0.120406 0.09003698 0.117242 0.09802097 0.123644 0.089742 0.114473 0.09828197 0.117242 0.09802097 0.120406 0.09003698 0.122815 0.08547198 0.123644 0.089742 0.128418 0.08042097 0.120406 0.09003698 0.123644 0.089742 0.122815 0.08547198 0.127528 0.07056397 0.128418 0.08042097 0.1313689 0.07034999 0.124823 0.08065497 0.128418 0.08042097 0.127528 0.07056397 0.122815 0.08547198 0.128418 0.08042097 0.124823 0.08065497 0.128216 0.065333 0.1313689 0.07034999 0.132355 0.06002998 0.127528 0.07056397 0.1313689 0.07034999 0.128216 0.065333 0.128219 0.05475884 0.132355 0.06002998 0.1313689 0.04970699 0.1284469 0.06004887 0.132355 0.06002998 0.128219 0.05475884 0.128216 0.065333 0.132355 0.06002998 0.1284469 0.06004887 0.127529 0.04950284 0.1313689 0.04970699 0.128416 0.039635 0.128219 0.05475884 0.1313689 0.04970699 0.127529 0.04950284 0.124807 0.03935986 0.128416 0.039635 0.123642 0.03031384 0.126388 0.044357 0.128416 0.039635 0.124807 0.03935986 0.127529 0.04950284 0.128416 0.039635 0.126388 0.044357 0.120404 0.03002095 0.123642 0.03031384 0.11724 0.02203691 0.124807 0.03935986 0.123642 0.03031384 0.120404 0.03002095 0.114485 0.02179199 0.11724 0.02203691 0.109521 0.01514196 0.120404 0.03002095 0.11724 0.02203691 0.114485 0.02179199 0.108875 0.01508796 0.109521 0.01514196 0.102622 0.01079595 0.108875 0.01508796 0.114485 0.02179199 0.109521 0.01514196 0.108219 0.01502984 0.108875 0.01508796 0.102622 0.01079595 0.106863 0.01399987 0.108219 0.01502984 0.102622 0.01079595 0.104364 0.01232296 0.106863 0.01399987 0.102622 0.01079595 0.101593 0.01068782 0.104364 0.01232296 0.102622 0.01079595 0.02297782 0.01827496 0.02590584 0.01408886 0.02401095 0.01833397 0.02174896 0.02156597 0.02297782 0.01827496 0.02401095 0.01833397 0.02590584 0.105971 0.02590584 0.01408886 0.02297782 0.01827496 0.02590584 0.105971 0.02819395 0.108912 0.02590584 0.01408886 0.02819395 0.01114886 0.02590584 0.01408886 0.02819395 0.108912 0.019499 0.02477997 0.02297782 0.01827496 0.02174896 0.02156597 0.01845997 0.02473396 0.02297782 0.01827496 0.019499 0.02477997 0.02297782 0.101785 0.02297782 0.01827496 0.01845997 0.02473396 0.02297782 0.101785 0.02590584 0.105971 0.02297782 0.01827496 0.01845997 0.09532696 0.01845997 0.02473396 0.01154887 0.03460294 0.01845997 0.09532696 0.02297782 0.101785 0.01845997 0.02473396 0.01155185 0.08546096 0.01154887 0.03460294 0.004917979 0.044061 0.01155185 0.08546096 0.01845997 0.09532696 0.01154887 0.03460294 0.004917979 0.07599997 0.01155185 0.08546096 0.004917979 0.044061 0.001809895 0.04997897 0.004917979 0.07599997 0.004917979 0.044061 0.10403 0.107412 0.10403 0.01264894 0.100643 0.01061987 0.104364 0.01232296 0.100643 0.01061987 0.10403 0.01264894 0.100643 0.109441 0.10403 0.107412 0.100643 0.01061987 0.09373199 0.007539987 0.100643 0.109441 0.100643 0.01061987 0.101593 0.01068782 0.100643 0.01061987 0.104364 0.01232296 0.107286 0.105086 0.107286 0.01497387 0.10403 0.01264894 0.106863 0.01399987 0.10403 0.01264894 0.107286 0.01497387 0.10403 0.107412 0.107286 0.105086 0.10403 0.01264894 0.104364 0.01232296 0.10403 0.01264894 0.106863 0.01399987 0.114473 0.09828197 0.114485 0.02179199 0.107286 0.01497387 0.108219 0.01502984 0.107286 0.01497387 0.114485 0.02179199 0.107286 0.105086 0.114473 0.09828197 0.107286 0.01497387 0.106863 0.01399987 0.107286 0.01497387 0.108219 0.01502984 0.120406 0.09003698 0.120404 0.03002095 0.114485 0.02179199 0.114473 0.09828197 0.120406 0.09003698 0.114485 0.02179199 0.108219 0.01502984 0.114485 0.02179199 0.108875 0.01508796 0.122815 0.08547198 0.124807 0.03935986 0.120404 0.03002095 0.120406 0.09003698 0.122815 0.08547198 0.120404 0.03002095 0.124823 0.08065497 0.126388 0.044357 0.124807 0.03935986 0.122815 0.08547198 0.124823 0.08065497 0.124807 0.03935986 0.127528 0.07056397 0.127529 0.04950284 0.126388 0.044357 0.124823 0.08065497 0.127528 0.07056397 0.126388 0.044357 0.128216 0.065333 0.128219 0.05475884 0.127529 0.04950284 0.127528 0.07056397 0.128216 0.065333 0.127529 0.04950284 0.128216 0.065333 0.1284469 0.06004887 0.128219 0.05475884 0.105243 0.10717 0.107286 0.105086 0.10403 0.107412 0.108219 0.10503 0.108876 0.104974 0.107286 0.105086 0.105243 0.10717 0.108219 0.10503 0.107286 0.105086 0.105243 0.10717 0.10403 0.107412 0.100643 0.109441 0.09373199 0.007539987 0.09373199 0.112521 0.100643 0.109441 0.101593 0.109372 0.100643 0.109441 0.09373199 0.112521 0.105243 0.10717 0.100643 0.109441 0.101593 0.109372 0.08650499 0.005634963 0.08650499 0.114426 0.09373199 0.112521 0.09373199 0.007539987 0.08650499 0.005634963 0.09373199 0.112521 0.07155597 0.002977967 0.07155597 0.1170819 0.08650499 0.114426 0.08650499 0.005634963 0.07155597 0.002977967 0.08650499 0.114426 0.05688196 3.8e-4 0.05688196 0.119681 0.07155597 0.1170819 0.07155597 0.002977967 0.05688196 3.8e-4 0.07155597 0.1170819 0.049878 0 0.049878 0.12006 0.05688196 0.119681 0.05688196 3.8e-4 0.049878 0 0.05688196 0.119681 0.04298496 0.00129199 0.04298496 0.118768 0.049878 0.12006 0.049878 0 0.04298496 0.00129199 0.049878 0.12006 0.03651696 0.004171967 0.03651696 0.115889 0.04298496 0.118768 0.04298496 0.00129199 0.03651696 0.004171967 0.04298496 0.118768 0.03352296 0.006167948 0.03352296 0.113892 0.03651696 0.115889 0.03651696 0.004171967 0.03352296 0.006167948 0.03651696 0.115889 0.03073799 0.00850296 0.03073799 0.111557 0.03352296 0.113892 0.03352296 0.006167948 0.03073799 0.00850296 0.03352296 0.113892 0.02819395 0.01114886 0.02819395 0.108912 0.03073799 0.111557 0.03073799 0.00850296 0.02819395 0.01114886 0.03073799 0.111557 0.02401 0.101726 0.02297782 0.101785 0.01845997 0.09532696 0.019499 0.095281 0.01845997 0.09532696 0.01155185 0.08546096 0.02175796 0.098508 0.01845997 0.09532696 0.019499 0.095281 0.02401 0.101726 0.01845997 0.09532696 0.02175796 0.098508 0.001809895 0.04997897 0.001809895 0.07008099 0.004917979 0.07599997 2.04e-4 0.05659782 2.04e-4 0.06346195 0.001809895 0.07008099 0.001809895 0.04997897 2.04e-4 0.05659782 0.001809895 0.07008099 2.04e-4 0.05659782 0 0.06002998 2.04e-4 0.06346195 0.01736187 0.07500696 0.009876966 0.07033598 0.007442951 0.06569999 0.01171886 0.06567996 0.007442951 0.06569999 0.009876966 0.07033598 0.01426297 0.064619 0.01736187 0.07500696 0.007442951 0.06569999 0.004074931 0.05714684 0.01426297 0.064619 0.007442951 0.06569999 0.01163697 0.06518501 0.004074931 0.05714684 0.007442951 0.06569999 0.01167798 0.06543296 0.01163697 0.06518501 0.007442951 0.06569999 0.01171886 0.06567996 0.01167798 0.06543296 0.007442951 0.06569999 0.01736187 0.07500696 0.01222884 0.07350897 0.009876966 0.07033598 0.01581192 0.07328897 0.009876966 0.07033598 0.01222884 0.07350897 0.01411098 0.06785398 0.01171886 0.06567996 0.009876966 0.07033598 0.01464498 0.07004797 0.01411098 0.06785398 0.009876966 0.07033598 0.01581192 0.07328897 0.01464498 0.07004797 0.009876966 0.07033598 0.01736187 0.07500696 0.01434898 0.07526397 0.01222884 0.07350897 0.01646596 0.07441598 0.01222884 0.07350897 0.01434898 0.07526397 0.01646596 0.07441598 0.01581192 0.07328897 0.01222884 0.07350897 0.01736187 0.07500696 0.015989 0.07550299 0.01434898 0.07526397 0.01786983 0.07553499 0.01434898 0.07526397 0.015989 0.07550299 0.01716095 0.075181 0.01646596 0.07441598 0.01434898 0.07526397 0.01786983 0.07553499 0.01716095 0.075181 0.01434898 0.07526397 0.01858484 0.075477 0.015989 0.07550299 0.01736187 0.07500696 0.01858484 0.075477 0.01786983 0.07553499 0.015989 0.07550299 0.01764595 0.07490497 0.01736187 0.07500696 0.01426297 0.064619 0.01858484 0.075477 0.01736187 0.07500696 0.01764595 0.07490497 0.004074931 0.05714684 0.01218187 0.05397886 0.01426297 0.064619 0.02180182 0.06143587 0.01426297 0.064619 0.01218187 0.05397886 0.02049398 0.073237 0.01928496 0.07431197 0.01426297 0.064619 0.01764595 0.07490497 0.01426297 0.064619 0.01928496 0.07431197 0.02093786 0.07229 0.02049398 0.073237 0.01426297 0.064619 0.02128183 0.07107597 0.02093786 0.07229 0.01426297 0.064619 0.02169698 0.06791597 0.02128183 0.07107597 0.01426297 0.064619 0.02182096 0.06382399 0.02169698 0.06791597 0.01426297 0.064619 0.02180182 0.06143587 0.02182096 0.06382399 0.01426297 0.064619 7.79e-4 0.04598885 0.01113796 0.04318785 0.01218187 0.05397886 0.0215469 0.05218982 0.01218187 0.05397886 0.01113796 0.04318785 0.001342952 0.04841798 7.79e-4 0.04598885 0.01218187 0.05397886 0.004074931 0.05714684 0.001342952 0.04841798 0.01218187 0.05397886 0.02174592 0.05882591 0.02180182 0.06143587 0.01218187 0.05397886 0.02165091 0.05556082 0.02174592 0.05882591 0.01218187 0.05397886 0.0215469 0.05218982 0.02165091 0.05556082 0.01218187 0.05397886 3.53e-4 0.03217583 0.01113796 0.03234696 0.01113796 0.04318785 0.02129983 0.03776592 0.01113796 0.04318785 0.01113796 0.03234696 8.9e-5 0.03493696 3.53e-4 0.03217583 0.01113796 0.04318785 0 0.03776997 8.9e-5 0.03493696 0.01113796 0.04318785 9e-5 0.04060184 0 0.03776997 0.01113796 0.04318785 3.54e-4 0.04336297 9e-5 0.04060184 0.01113796 0.04318785 7.79e-4 0.04598885 3.54e-4 0.04336297 0.01113796 0.04318785 0.02136898 0.04510897 0.0215469 0.05218982 0.01113796 0.04318785 0.02129983 0.03776592 0.02136898 0.04510897 0.01113796 0.04318785 0.001342952 0.027116 0.01218187 0.02155596 0.01113796 0.03234696 0.02136898 0.03042 0.01113796 0.03234696 0.01218187 0.02155596 7.79e-4 0.02954697 0.001342952 0.027116 0.01113796 0.03234696 3.53e-4 0.03217583 7.79e-4 0.02954697 0.01113796 0.03234696 0.02136898 0.03042 0.02129983 0.03776592 0.01113796 0.03234696 0.004075944 0.01838696 0.01426297 0.01091599 0.01218187 0.02155596 0.02165091 0.01996392 0.01218187 0.02155596 0.01426297 0.01091599 0.001342952 0.027116 0.004075944 0.01838696 0.01218187 0.02155596 0.02154797 0.02333599 0.02136898 0.03042 0.01218187 0.02155596 0.02165091 0.01996392 0.02154797 0.02333599 0.01218187 0.02155596 0.01434797 2.71e-4 0.01736187 5.28e-4 0.01426297 0.01091599 0.02182096 0.011702 0.01426297 0.01091599 0.01736187 5.28e-4 0.01222687 0.002026975 0.01434797 2.71e-4 0.01426297 0.01091599 0.009874999 0.005200982 0.01222687 0.002026975 0.01426297 0.01091599 0.007442951 0.009832978 0.009874999 0.005200982 0.01426297 0.01091599 0.004075944 0.01838696 0.007442951 0.009832978 0.01426297 0.01091599 0.02174699 0.016698 0.02165091 0.01996392 0.01426297 0.01091599 0.02180182 0.01408886 0.02174699 0.016698 0.01426297 0.01091599 0.02182096 0.011702 0.02180182 0.01408886 0.01426297 0.01091599 0.01434797 2.71e-4 0.015989 3.2e-5 0.01736187 5.28e-4 0.02180695 0.001248896 0.01736187 5.28e-4 0.015989 3.2e-5 0.02169698 0.007612943 0.02182096 0.011702 0.01736187 5.28e-4 0.021281 0.00445497 0.02169698 0.007612943 0.01736187 5.28e-4 0.02093696 0.003242969 0.021281 0.00445497 0.01736187 5.28e-4 0.02049297 0.002295911 0.02093696 0.003242969 0.01736187 5.28e-4 0.02049297 0.002295911 0.01736187 5.28e-4 0.01764595 6.3e-4 0.01764595 6.3e-4 0.01928496 0.001222968 0.02049297 0.002295911 0.02180695 0.001248896 0.01764595 6.3e-4 0.01736187 5.28e-4 0.01858484 5.7e-5 0.015989 3.2e-5 0.01434797 2.71e-4 0.02180695 0.001248896 0.015989 3.2e-5 0.01858484 5.7e-5 0.01715987 3.54e-4 0.01434797 2.71e-4 0.01222687 0.002026975 0.01786983 0 0.01434797 2.71e-4 0.01715987 3.54e-4 0.01858484 5.7e-5 0.01434797 2.71e-4 0.01786983 0 0.01581096 0.002246916 0.01222687 0.002026975 0.009874999 0.005200982 0.01646482 0.001119971 0.01222687 0.002026975 0.01581096 0.002246916 0.01715987 3.54e-4 0.01222687 0.002026975 0.01646482 0.001119971 0.01464498 0.005486965 0.009874999 0.005200982 0.007442951 0.009832978 0.01581096 0.002246916 0.009874999 0.005200982 0.01464498 0.005486965 0.01171886 0.009852945 0.007442951 0.009832978 0.004075944 0.01838696 0.01464498 0.005486965 0.007442951 0.009832978 0.01411098 0.007680952 0.01171886 0.009852945 0.01411098 0.007680952 0.007442951 0.009832978 0.01225286 0.01866495 0.004075944 0.01838696 0.001342952 0.027116 0.01361083 0.01035785 0.004075944 0.01838696 0.01225286 0.01866495 0.01163697 0.010351 0.004075944 0.01838696 0.01361083 0.01035785 0.01167798 0.01010197 0.004075944 0.01838696 0.01163697 0.010351 0.01171886 0.009852945 0.004075944 0.01838696 0.01167798 0.01010197 0.01052397 0.02959299 0.001342952 0.027116 7.79e-4 0.02954697 0.01085597 0.02719396 0.001342952 0.027116 0.01052397 0.02959299 0.01225286 0.01866495 0.001342952 0.027116 0.01085597 0.02719396 0.01028198 0.03219985 7.79e-4 0.02954697 3.53e-4 0.03217583 0.01052397 0.02959299 7.79e-4 0.02954697 0.01028198 0.03219985 0.01013284 0.03494799 3.53e-4 0.03217583 8.9e-5 0.03493696 0.01028198 0.03219985 3.53e-4 0.03217583 0.01013284 0.03494799 0.01008296 0.03776699 8.9e-5 0.03493696 0 0.03776997 0.01013284 0.03494799 8.9e-5 0.03493696 0.01008296 0.03776699 0.01008296 0.03776699 0 0.03776997 9e-5 0.04060184 0.01013284 0.04058682 9e-5 0.04060184 3.54e-4 0.04336297 0.01008296 0.03776699 9e-5 0.04060184 0.01013284 0.04058682 0.01028198 0.04333496 3.54e-4 0.04336297 7.79e-4 0.04598885 0.01013284 0.04058682 3.54e-4 0.04336297 0.01028198 0.04333496 0.01052397 0.04594182 7.79e-4 0.04598885 0.001342952 0.04841798 0.01028198 0.04333496 7.79e-4 0.04598885 0.01052397 0.04594182 0.01085597 0.04834085 0.001342952 0.04841798 0.004074931 0.05714684 0.01052397 0.04594182 0.001342952 0.04841798 0.01085597 0.04834085 0.01225286 0.05686998 0.004074931 0.05714684 0.01163697 0.06518501 0.01225286 0.05686998 0.01085597 0.04834085 0.004074931 0.05714684 0.02180695 0.07428598 0.01928496 0.07431197 0.02049398 0.073237 0.01858484 0.075477 0.01764595 0.07490497 0.01928496 0.07431197 0.02180695 0.07428598 0.01858484 0.075477 0.01928496 0.07431197 0.02318698 0.07318896 0.02049398 0.073237 0.02093786 0.07229 0.02250397 0.07387995 0.02049398 0.073237 0.02318698 0.07318896 0.02180695 0.07428598 0.02049398 0.073237 0.02250397 0.07387995 0.023853 0.072218 0.02093786 0.07229 0.02128183 0.07107597 0.02318698 0.07318896 0.02093786 0.07229 0.023853 0.072218 0.02449697 0.07097697 0.02128183 0.07107597 0.02169698 0.06791597 0.023853 0.072218 0.02128183 0.07107597 0.02449697 0.07097697 0.02569586 0.06773597 0.02169698 0.06791597 0.02182096 0.06382399 0.02511286 0.06947797 0.02169698 0.06791597 0.02569586 0.06773597 0.02449697 0.07097697 0.02169698 0.06791597 0.02511286 0.06947797 0.02489387 0.06359601 0.02182096 0.06382399 0.02180182 0.06143587 0.02569586 0.06773597 0.02182096 0.06382399 0.02624297 0.06576496 0.02489387 0.06359601 0.02624297 0.06576496 0.02182096 0.06382399 0.02528399 0.06164383 0.02180182 0.06143587 0.02174592 0.05882591 0.02528399 0.06164383 0.02489387 0.06359601 0.02180182 0.06143587 0.02576082 0.05880099 0.02174592 0.05882591 0.02165091 0.05556082 0.02528399 0.06164383 0.02174592 0.05882591 0.02576082 0.05880099 0.02767992 0.05829596 0.02165091 0.05556082 0.0215469 0.05218982 0.02583485 0.05830097 0.02165091 0.05556082 0.02767992 0.05829596 0.02579796 0.05855184 0.02576082 0.05880099 0.02165091 0.05556082 0.02583485 0.05830097 0.02579796 0.05855184 0.02165091 0.05556082 0.02841699 0.05192583 0.0215469 0.05218982 0.02136898 0.04510897 0.02767992 0.05829596 0.0215469 0.05218982 0.02841699 0.05192583 0.02887094 0.04499 0.02136898 0.04510897 0.02129983 0.03776592 0.02841699 0.05192583 0.02136898 0.04510897 0.02887094 0.04499 0.02887094 0.03054195 0.02129983 0.03776592 0.02136898 0.03042 0.02902483 0.03776592 0.02129983 0.03776592 0.02887094 0.03054195 0.02887094 0.04499 0.02129983 0.03776592 0.02902483 0.03776592 0.02841585 0.02360785 0.02136898 0.03042 0.02154797 0.02333599 0.02887094 0.03054195 0.02136898 0.03042 0.02841585 0.02360785 0.02841585 0.02360785 0.02154797 0.02333599 0.02165091 0.01996392 0.02583485 0.01723384 0.02165091 0.01996392 0.02174699 0.016698 0.02583485 0.01723384 0.02841585 0.02360785 0.02165091 0.01996392 0.025451 0.01499086 0.02174699 0.016698 0.02180182 0.01408886 0.025451 0.01499086 0.02575898 0.01672285 0.02174699 0.016698 0.02579897 0.01698696 0.02174699 0.016698 0.02575898 0.01672285 0.02579897 0.01698696 0.02583485 0.01723384 0.02174699 0.016698 0.02523899 0.01347297 0.02180182 0.01408886 0.02182096 0.011702 0.02523899 0.01347297 0.025451 0.01499086 0.02180182 0.01408886 0.02624297 0.009769976 0.02182096 0.011702 0.02169698 0.007612943 0.02624297 0.009769976 0.02674984 0.01195585 0.02182096 0.011702 0.02489387 0.01193886 0.02182096 0.011702 0.02674984 0.01195585 0.02507787 0.012546 0.02523899 0.01347297 0.02182096 0.011702 0.02489387 0.01193886 0.02507787 0.012546 0.02182096 0.011702 0.02511286 0.006056964 0.02169698 0.007612943 0.021281 0.00445497 0.02569586 0.00779891 0.02169698 0.007612943 0.02511286 0.006056964 0.02624297 0.009769976 0.02169698 0.007612943 0.02569586 0.00779891 0.023853 0.003316998 0.021281 0.00445497 0.02093696 0.003242969 0.02449697 0.004557967 0.021281 0.00445497 0.023853 0.003316998 0.02511286 0.006056964 0.021281 0.00445497 0.02449697 0.004557967 0.02318698 0.002345979 0.02093696 0.003242969 0.02049297 0.002295911 0.023853 0.003316998 0.02093696 0.003242969 0.02318698 0.002345979 0.02250397 0.001654863 0.02049297 0.002295911 0.01928496 0.001222968 0.02318698 0.002345979 0.02049297 0.002295911 0.02250397 0.001654863 0.02180695 0.001248896 0.01928496 0.001222968 0.01764595 6.3e-4 0.02250397 0.001654863 0.01928496 0.001222968 0.02180695 0.001248896 0.01167798 0.06543296 0.01361083 0.06517696 0.01163697 0.06518501 0.01225286 0.05686998 0.01163697 0.06518501 0.01361083 0.06517696 0.01171886 0.06567996 0.01361083 0.06517696 0.01167798 0.06543296 0.01411098 0.06785398 0.01361083 0.06517696 0.01171886 0.06567996 0.01361083 0.01035785 0.01225286 0.05686998 0.01361083 0.06517696 0.01411098 0.007680952 0.01361083 0.06517696 0.01411098 0.06785398 0.01411098 0.007680952 0.01361083 0.01035785 0.01361083 0.06517696 0.01085597 0.02719396 0.01085597 0.04834085 0.01225286 0.05686998 0.01052397 0.02959299 0.01052397 0.04594182 0.01085597 0.04834085 0.01085597 0.02719396 0.01052397 0.02959299 0.01085597 0.04834085 0.01225286 0.01866495 0.01085597 0.02719396 0.01225286 0.05686998 0.01361083 0.01035785 0.01225286 0.01866495 0.01225286 0.05686998 0.01464498 0.005486965 0.01411098 0.06785398 0.01464498 0.07004797 0.01464498 0.005486965 0.01411098 0.007680952 0.01411098 0.06785398 0.01581096 0.002246916 0.01464498 0.07004797 0.01581192 0.07328897 0.01581096 0.002246916 0.01464498 0.005486965 0.01464498 0.07004797 0.01646482 0.001119971 0.01581192 0.07328897 0.01646596 0.07441598 0.01646482 0.001119971 0.01581096 0.002246916 0.01581192 0.07328897 0.01715987 3.54e-4 0.01646596 0.07441598 0.01716095 0.075181 0.01715987 3.54e-4 0.01646482 0.001119971 0.01646596 0.07441598 0.01786983 0 0.01716095 0.075181 0.01786983 0.07553499 0.01786983 0 0.01715987 3.54e-4 0.01716095 0.075181 0.01786983 0 0.01786983 0.07553499 0.01858484 0.075477 0.01858484 5.7e-5 0.01858484 0.075477 0.02180695 0.07428598 0.01858484 5.7e-5 0.01786983 0 0.01858484 0.075477 0.02722597 0.06112384 0.02722787 0.0144189 0.02674984 0.01195585 0.02581495 0.01194983 0.02674984 0.01195585 0.02722787 0.0144189 0.02674984 0.06357896 0.02722597 0.06112384 0.02674984 0.01195585 0.02624297 0.009769976 0.02674984 0.06357896 0.02674984 0.01195585 0.02581495 0.01194983 0.02489387 0.01193886 0.02674984 0.01195585 0.02752298 0.05933797 0.02752399 0.0162 0.02722787 0.0144189 0.025451 0.01499086 0.02722787 0.0144189 0.02752399 0.0162 0.02722597 0.06112384 0.02752298 0.05933797 0.02722787 0.0144189 0.02523899 0.01347297 0.02722787 0.0144189 0.025451 0.01499086 0.02507787 0.012546 0.02722787 0.0144189 0.02523899 0.01347297 0.02581495 0.01194983 0.02722787 0.0144189 0.02507787 0.012546 0.02767992 0.05829596 0.02767992 0.01723897 0.02752399 0.0162 0.02575898 0.01672285 0.02752399 0.0162 0.02767992 0.01723897 0.02752298 0.05933797 0.02767992 0.05829596 0.02752399 0.0162 0.025451 0.01499086 0.02752399 0.0162 0.02575898 0.01672285 0.02841699 0.05192583 0.02841585 0.02360785 0.02767992 0.01723897 0.02583485 0.01723384 0.02767992 0.01723897 0.02841585 0.02360785 0.02767992 0.05829596 0.02841699 0.05192583 0.02767992 0.01723897 0.02579897 0.01698696 0.02575898 0.01672285 0.02767992 0.01723897 0.02583485 0.01723384 0.026748 0.01723295 0.02767992 0.01723897 0.02579897 0.01698696 0.02767992 0.01723897 0.026748 0.01723295 0.02841699 0.05192583 0.02887094 0.03054195 0.02841585 0.02360785 0.02887094 0.04499 0.02902483 0.03776592 0.02887094 0.03054195 0.02841699 0.05192583 0.02887094 0.04499 0.02887094 0.03054195 0.026748 0.05830198 0.02767992 0.05829596 0.02752298 0.05933797 0.026748 0.05830198 0.02583485 0.05830097 0.02767992 0.05829596 0.02576082 0.05880099 0.02752298 0.05933797 0.02722597 0.06112384 0.02579796 0.05855184 0.02752298 0.05933797 0.02576082 0.05880099 0.026748 0.05830198 0.02752298 0.05933797 0.02579796 0.05855184 0.02528399 0.06164383 0.02722597 0.06112384 0.02674984 0.06357896 0.02528399 0.06164383 0.02576082 0.05880099 0.02722597 0.06112384 0.02624297 0.009769976 0.02624297 0.06576496 0.02674984 0.06357896 0.02489387 0.06359601 0.02674984 0.06357896 0.02624297 0.06576496 0.02581596 0.06358498 0.02674984 0.06357896 0.02489387 0.06359601 0.02581596 0.06358498 0.02528399 0.06164383 0.02674984 0.06357896 0.02569586 0.00779891 0.02569586 0.06773597 0.02624297 0.06576496 0.02624297 0.009769976 0.02569586 0.00779891 0.02624297 0.06576496 0.02511286 0.006056964 0.02511286 0.06947797 0.02569586 0.06773597 0.02569586 0.00779891 0.02511286 0.006056964 0.02569586 0.06773597 0.02449697 0.004557967 0.02449697 0.07097697 0.02511286 0.06947797 0.02511286 0.006056964 0.02449697 0.004557967 0.02511286 0.06947797 0.023853 0.003316998 0.023853 0.072218 0.02449697 0.07097697 0.02449697 0.004557967 0.023853 0.003316998 0.02449697 0.07097697 0.02318698 0.002345979 0.02318698 0.07318896 0.023853 0.072218 0.023853 0.003316998 0.02318698 0.002345979 0.023853 0.072218 0.02250397 0.001654863 0.02250397 0.07387995 0.02318698 0.07318896 0.02318698 0.002345979 0.02250397 0.001654863 0.02318698 0.07318896 0.02180695 0.001248896 0.02180695 0.07428598 0.02250397 0.07387995 0.02250397 0.001654863 0.02180695 0.001248896 0.02250397 0.07387995 0.02180695 0.001248896 0.01858484 5.7e-5 0.02180695 0.07428598 0.01028198 0.03219985 0.01028198 0.04333496 0.01052397 0.04594182 0.01052397 0.02959299 0.01028198 0.03219985 0.01052397 0.04594182 0.01013284 0.03494799 0.01013284 0.04058682 0.01028198 0.04333496 0.01028198 0.03219985 0.01013284 0.03494799 0.01028198 0.04333496 0.01013284 0.03494799 0.01008296 0.03776699 0.01013284 0.04058682 0.01167798 0.01010197 0.01361083 0.01035785 0.01411098 0.007680952 0.01167798 0.01010197 0.01163697 0.010351 0.01361083 0.01035785 0.01171886 0.009852945 0.01167798 0.01010197 0.01411098 0.007680952 0.02581495 0.01194983 0.02507787 0.012546 0.02489387 0.01193886 0.026748 0.05830198 0.02579796 0.05855184 0.02583485 0.05830097 0.02579897 0.01698696 0.026748 0.01723295 0.02583485 0.01723384 0.02581596 0.06358498 0.02489387 0.06359601 0.02528399 0.06164383 - - - - - - - - - - - - - - -

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 8 7 10 9 7 11 10 8 12 9 9 13 8 10 14 10 8 15 8 10 16 11 11 17 3 3 18 12 12 19 4 4 20 13 13 21 14 14 22 1 1 23 15 15 24 5 5 25 16 16 26 0 0 27 13 13 28 1 1 29 3 3 30 5 5 31 15 15 32 17 17 33 18 18 34 14 14 35 19 19 36 16 16 37 20 20 38 13 13 39 17 17 40 14 14 41 15 15 42 16 16 43 19 19 44 21 21 45 22 22 46 18 18 47 23 23 48 20 20 49 24 24 50 17 17 51 21 21 52 18 18 53 19 19 54 20 20 55 23 23 56 25 25 57 26 26 58 22 22 59 27 27 60 24 24 61 28 28 62 29 29 63 25 25 64 22 22 65 21 21 66 29 29 67 22 22 68 23 23 69 24 24 70 27 27 71 30 30 72 31 31 73 32 32 74 33 33 75 31 31 76 30 30 77 34 34 78 35 35 79 36 36 80 34 34 81 37 37 82 35 35 83 30 30 84 32 32 85 38 38 86 39 39 87 40 40 88 41 41 89 42 42 90 40 40 91 39 39 92 30 30 93 38 38 94 43 43 95 44 44 96 41 41 97 45 45 98 39 39 99 41 41 100 44 44 101 46 46 102 45 45 103 47 47 104 44 44 105 45 45 106 46 46 107 48 48 108 47 47 109 49 49 110 46 46 111 47 47 112 48 48 113 6 6 114 50 50 115 0 0 116 51 51 117 49 49 118 52 52 119 53 53 120 49 49 121 51 51 122 48 48 123 49 49 124 53 53 125 54 54 126 55 55 127 56 56 128 57 57 129 55 55 130 54 54 131 58 58 132 59 59 133 60 60 134 61 61 135 62 62 136 63 63 137 64 64 138 58 58 139 60 60 140 65 65 141 66 66 142 67 67 143 68 68 144 69 69 145 70 70 146 71 71 147 72 72 148 62 62 149 73 73 150 71 71 151 62 62 152 61 61 153 73 73 154 62 62 155 58 58 156 74 74 157 59 59 158 61 61 159 63 63 160 75 75 161 58 58 162 76 76 163 74 74 164 77 77 165 78 78 166 79 79 167 58 58 168 80 80 169 76 76 170 81 81 171 79 79 172 82 82 173 81 81 174 77 77 175 79 79 176 58 58 177 83 83 178 80 80 179 81 81 180 82 82 181 84 84 182 58 58 183 85 85 184 83 83 185 86 86 186 84 84 187 87 87 188 81 81 189 84 84 190 86 86 191 58 58 192 88 88 193 85 85 194 89 89 195 87 87 196 90 90 197 86 86 198 87 87 199 89 89 200 91 91 201 88 88 202 58 58 203 91 91 204 92 92 205 88 88 206 89 89 207 90 90 208 93 93 209 64 64 210 94 94 211 58 58 212 95 95 213 58 58 214 94 94 215 96 96 216 91 91 217 58 58 218 95 95 219 96 96 220 58 58 221 64 64 222 97 97 223 94 94 224 98 98 225 99 99 226 100 100 227 98 98 228 101 101 229 99 99 230 64 64 231 102 102 232 97 97 233 103 103 234 100 100 235 104 104 236 98 98 237 100 100 238 103 103 239 64 64 240 105 105 241 102 102 242 103 103 243 104 104 244 106 106 245 65 65 246 107 107 247 66 66 248 108 108 249 107 107 250 65 65 251 109 109 252 110 110 253 111 111 254 112 112 255 110 110 256 109 109 257 113 113 258 110 110 259 112 112 260 103 103 261 106 106 262 114 114 263 91 91 264 115 115 265 92 92 266 116 116 267 93 93 268 117 117 269 89 89 270 93 93 271 116 116 272 91 91 273 118 118 274 115 115 275 119 119 276 117 117 277 120 120 278 116 116 279 117 117 280 119 119 281 91 91 282 121 121 283 118 118 284 119 119 285 120 120 286 122 122 287 91 91 288 123 123 289 121 121 290 124 124 291 122 122 292 125 125 293 119 119 294 122 122 295 124 124 296 91 91 297 126 126 298 123 123 299 127 127 300 125 125 301 128 128 302 124 124 303 125 125 304 127 127 305 129 129 306 126 126 307 91 91 308 130 130 309 131 131 310 126 126 311 127 127 312 128 128 313 132 132 314 129 129 315 130 130 316 126 126 317 133 133 318 91 91 319 96 96 320 133 133 321 129 129 322 91 91 323 134 134 324 135 135 325 101 101 326 136 136 327 133 133 328 96 96 329 134 134 330 137 137 331 135 135 332 134 134 333 101 101 334 98 98 335 138 138 336 139 139 337 131 131 338 140 140 339 132 132 340 141 141 341 130 130 342 138 138 343 131 131 344 127 127 345 132 132 346 140 140 347 138 138 348 142 142 349 139 139 350 143 143 351 141 141 352 144 144 353 140 140 354 141 141 355 143 143 356 138 138 357 145 145 358 142 142 359 146 146 360 144 144 361 147 147 362 143 143 363 144 144 364 146 146 365 10 8 366 148 148 367 145 145 368 149 149 369 147 147 370 150 150 371 138 138 372 10 8 373 145 145 374 146 146 375 147 147 376 149 149 377 10 8 378 11 11 379 148 148 380 3 3 381 150 150 382 12 12 383 149 149 384 150 150 385 3 3 386 54 54 387 56 56 388 151 151 389 152 152 390 151 151 391 153 153 392 54 54 393 151 151 394 152 152 395 152 152 396 153 153 397 154 154 398 155 155 399 154 154 400 156 156 401 152 152 402 154 154 403 155 155 404 136 136 405 157 157 406 133 133 407 155 155 408 156 156 409 158 158 410 159 159 411 160 160 412 137 137 413 155 155 414 158 158 415 161 161 416 162 162 417 161 161 418 158 158 419 163 163 420 164 164 421 165 165 422 163 163 423 165 165 424 166 166 425 134 134 426 159 159 427 137 137 428 108 108 429 65 65 430 167 167 431 68 68 432 168 168 433 69 69 434 169 169 435 108 108 436 167 167 437 170 170 438 171 171 439 172 172 440 173 173 441 168 168 442 68 68 443 174 174 444 175 175 445 176 176 446 109 109 447 111 111 448 177 177 449 178 178 450 171 171 451 170 170 452 179 179 453 171 171 454 178 178 455 180 180 456 181 181 457 182 182 458 183 183 459 181 181 460 180 180 461 184 184 462 185 185 463 186 186 464 187 187 465 188 188 466 189 189 467 190 190 468 191 191 469 192 192 470 193 193 471 190 190 472 192 192 473 194 194 474 195 195 475 188 188 476 194 194 477 188 188 478 187 187 479 184 184 480 196 196 481 185 185 482 197 197 483 189 189 484 198 198 485 187 187 486 189 189 487 197 197 488 199 199 489 68 68 490 196 196 491 200 200 492 201 201 493 72 72 494 184 184 495 199 199 496 196 196 497 197 197 498 198 198 499 202 202 500 199 199 501 173 173 502 68 68 503 203 203 504 204 204 505 72 72 506 200 200 507 72 72 508 204 204 509 205 205 510 203 203 511 72 72 512 71 71 513 205 205 514 72 72 515 206 206 516 176 176 517 207 207 518 174 174 519 176 176 520 206 206 521 208 208 522 207 207 523 191 191 524 206 206 525 207 207 526 208 208 527 208 208 528 191 191 529 190 190 530 209 209 531 210 210 532 211 211 533 212 212 534 213 213 535 214 214 536 215 215 537 216 216 538 217 217 539 215 215 540 217 217 541 218 218 542 219 219 543 220 220 544 221 221 545 209 209 546 222 222 547 210 210 548 223 223 549 214 214 550 224 224 551 212 212 552 214 214 553 223 223 554 209 209 555 225 225 556 222 222 557 223 223 558 224 224 559 226 226 560 209 209 561 190 190 562 225 225 563 193 193 564 225 225 565 190 190 566 227 227 567 226 226 568 195 195 569 223 223 570 226 226 571 227 227 572 209 209 573 208 208 574 190 190 575 228 228 576 206 206 577 208 208 578 209 209 579 228 228 580 208 208 581 229 229 582 174 174 583 206 206 584 230 230 585 229 229 586 206 206 587 228 228 588 230 230 589 206 206 590 179 179 591 178 178 592 231 231 593 232 232 594 233 233 595 234 234 596 235 235 597 231 231 598 236 236 599 235 235 600 179 179 601 231 231 602 237 237 603 234 234 604 216 216 605 232 232 606 234 234 607 237 237 608 238 238 609 239 238 610 240 238 611 237 237 612 216 216 613 215 215 614 227 227 615 195 195 616 194 194 617 241 239 618 218 218 619 242 240 620 243 241 621 244 242 622 220 220 623 245 243 624 246 244 625 247 245 626 248 246 627 249 247 628 250 248 629 251 249 630 250 248 631 249 247 632 245 243 633 247 245 634 252 250 635 253 251 636 244 242 637 243 241 638 251 249 639 249 247 640 254 252 641 241 239 642 215 215 643 218 218 644 243 241 645 220 220 646 219 219 647 255 253 648 237 237 649 215 215 650 241 239 651 255 253 652 215 215 653 255 253 654 232 232 655 237 237 656 255 253 657 256 254 658 232 232 659 235 235 660 236 236 661 257 255 662 258 256 663 259 257 664 260 258 665 261 259 666 262 260 667 263 261 668 235 235 669 257 255 670 264 262 671 265 263 672 263 261 673 246 244 674 266 264 675 261 259 676 263 261 677 265 263 678 266 264 679 263 261 680 245 243 681 265 263 682 246 244 683 245 243 684 252 250 685 267 265 686 268 266 687 269 267 688 270 268 689 271 269 690 272 270 691 273 271 692 271 269 693 273 271 694 274 272 695 235 235 696 264 262 697 275 273 698 276 274 699 277 275 700 278 276 701 279 277 702 277 275 703 276 274 704 235 235 705 275 273 706 280 278 707 281 279 708 278 276 709 269 267 710 276 274 711 278 276 712 281 279 713 268 266 714 282 280 715 269 267 716 281 279 717 269 267 718 282 280 719 283 281 720 284 282 721 285 283 722 286 284 723 287 285 724 288 286 725 289 287 726 283 281 727 285 283 728 290 288 729 291 289 730 292 290 731 293 291 732 294 292 733 295 293 734 293 291 735 295 293 736 296 294 737 283 281 738 297 295 739 284 282 740 298 296 741 288 286 742 299 297 743 300 298 744 288 286 745 298 296 746 301 299 747 286 284 748 288 286 749 300 298 750 301 299 751 288 286 752 283 281 753 302 300 754 297 295 755 298 296 756 299 297 757 303 301 758 304 302 759 305 303 760 302 300 761 298 296 762 303 301 763 306 304 764 283 281 765 304 302 766 302 300 767 281 279 768 307 305 769 305 303 770 308 306 771 306 304 772 309 307 773 304 302 774 281 279 775 305 303 776 310 308 777 306 304 778 308 306 779 310 308 780 298 296 781 306 304 782 281 279 783 311 309 784 307 305 785 308 306 786 309 307 787 312 310 788 281 279 789 282 280 790 311 309 791 308 306 792 312 310 793 313 311 794 271 269 795 313 311 796 272 270 797 314 312 798 313 311 799 271 269 800 314 312 801 308 306 802 313 311 803 276 274 804 281 279 805 304 302 806 315 313 807 304 302 808 283 281 809 315 313 810 276 274 811 304 302 812 316 314 813 283 281 814 289 287 815 316 314 816 315 313 817 283 281 818 316 314 819 289 287 820 317 315 821 290 288 822 318 316 823 291 289 824 319 317 825 316 314 826 317 315 827 290 288 828 320 318 829 318 316 830 321 319 831 276 274 832 315 313 833 321 319 834 279 277 835 276 274 836 322 320 837 315 313 838 316 314 839 323 321 840 321 319 841 315 313 842 322 320 843 323 321 844 315 313 845 324 322 846 316 314 847 319 317 848 324 322 849 322 320 850 316 314 851 324 322 852 319 317 853 325 323 854 290 288 855 326 324 856 320 318 857 327 325 858 328 326 859 329 327 860 330 328 861 326 324 862 290 288 863 327 325 864 329 327 865 331 329 866 327 325 867 280 278 868 332 330 869 327 325 870 235 235 871 280 278 872 327 325 873 332 330 874 333 331 875 327 325 876 333 331 877 334 332 878 327 325 879 334 332 880 328 326 881 335 333 882 336 334 883 337 335 884 338 336 885 339 336 886 340 336 887 341 337 888 335 333 889 337 335 890 327 325 891 342 338 892 343 339 893 344 340 894 327 325 895 343 339 896 345 341 897 346 342 898 336 334 899 347 343 900 340 343 901 348 343 902 335 333 903 345 341 904 336 334 905 338 344 906 340 344 907 347 344 908 345 341 909 349 345 910 346 342 911 347 346 912 348 346 913 350 346 914 347 347 915 350 348 916 351 349 917 352 350 918 353 351 919 354 352 920 355 353 921 347 353 922 351 353 923 355 354 924 351 354 925 356 354 926 341 337 927 357 355 928 335 333 929 293 291 930 354 352 931 358 356 932 359 357 933 352 350 934 354 352 935 293 291 936 359 357 937 354 352 938 330 328 939 290 288 940 357 355 941 293 291 942 358 356 943 294 292 944 341 337 945 330 328 946 357 355 947 327 325 948 331 329 949 342 338 950 180 180 951 182 182 952 360 358 953 180 180 954 360 358 955 361 359 956 344 340 957 362 340 958 327 325 959 180 180 960 361 359 961 363 360 962 364 361 963 365 362 964 366 363 965 367 364 966 366 363 967 368 365 968 367 364 969 364 361 970 366 363 971 369 366 972 370 367 973 371 368 974 372 369 975 373 370 976 374 371 977 375 372 978 369 366 979 371 368 980 376 373 981 377 373 982 378 373 983 379 374 984 380 375 985 370 367 986 381 376 987 374 371 988 382 377 989 369 366 990 379 374 991 370 367 992 372 369 993 374 371 994 383 378 995 384 379 996 383 378 997 374 371 998 385 380 999 384 379 1000 374 371 1001 381 376 1002 385 380 1003 374 371 1004 386 381 1005 180 180 1006 380 375 1007 387 382 1008 382 377 1009 365 362 1010 388 383 1011 386 381 1012 380 375 1013 379 374 1014 388 383 1015 380 375 1016 389 384 1017 381 376 1018 382 377 1019 387 382 1020 389 384 1021 382 377 1022 386 381 1023 183 183 1024 180 180 1025 364 361 1026 387 382 1027 365 362 1028 113 113 1029 112 112 1030 390 385 1031 113 113 1032 390 385 1033 391 386 1034 392 387 1035 391 386 1036 393 388 1037 113 113 1038 391 386 1039 392 387 1040 394 389 1041 395 390 1042 369 366 1043 392 387 1044 393 388 1045 396 391 1046 397 392 1047 394 389 1048 369 366 1049 375 372 1050 397 392 1051 369 366 1052 398 393 1053 399 394 1054 400 395 1055 401 396 1056 399 394 1057 398 393 1058 392 387 1059 396 391 1060 402 397 1061 403 398 1062 400 395 1063 404 399 1064 405 400 1065 398 393 1066 400 395 1067 406 401 1068 405 400 1069 400 395 1070 407 402 1071 406 401 1072 400 395 1073 408 403 1074 407 402 1075 400 395 1076 409 404 1077 408 403 1078 400 395 1079 410 405 1080 409 404 1081 400 395 1082 403 398 1083 410 405 1084 400 395 1085 411 406 1086 404 399 1087 377 407 1088 412 408 1089 404 399 1090 411 406 1091 412 408 1092 403 398 1093 404 399 1094 413 409 1095 414 410 1096 377 407 1097 411 406 1098 377 407 1099 414 410 1100 376 411 1101 413 411 1102 377 411 1103 415 412 1104 416 413 1105 417 414 1106 418 415 1107 419 416 1108 420 417 1109 421 418 1110 415 412 1111 417 414 1112 422 419 1113 421 418 1114 417 414 1115 423 420 1116 422 419 1117 417 414 1118 424 421 1119 425 422 1120 426 423 1121 424 421 1122 426 423 1123 427 424 1124 428 425 1125 429 426 1126 416 413 1127 430 427 1128 420 417 1129 431 428 1130 415 412 1131 428 425 1132 416 413 1133 430 427 1134 418 415 1135 420 417 1136 428 425 1137 432 429 1138 429 426 1139 433 430 1140 431 428 1141 434 431 1142 433 430 1143 430 427 1144 431 428 1145 428 425 1146 435 432 1147 432 429 1148 433 430 1149 434 431 1150 436 433 1151 437 434 1152 438 435 1153 435 432 1154 439 436 1155 436 433 1156 440 437 1157 428 425 1158 437 434 1159 435 432 1160 439 436 1161 433 430 1162 436 433 1163 437 434 1164 441 438 1165 438 435 1166 439 436 1167 440 437 1168 442 439 1169 437 434 1170 443 440 1171 441 438 1172 444 441 1173 442 439 1174 445 442 1175 444 441 1176 439 436 1177 442 439 1178 437 434 1179 446 443 1180 443 440 1181 447 444 1182 445 442 1183 448 445 1184 447 444 1185 444 441 1186 445 442 1187 449 446 1188 450 447 1189 446 443 1190 447 444 1191 448 445 1192 451 448 1193 437 434 1194 449 446 1195 446 443 1196 449 446 1197 452 449 1198 450 447 1199 453 450 1200 454 451 1201 455 452 1202 456 453 1203 447 444 1204 451 448 1205 449 446 1206 457 454 1207 452 449 1208 458 455 1209 455 452 1210 459 456 1211 458 455 1212 453 450 1213 455 452 1214 449 446 1215 460 457 1216 457 454 1217 461 458 1218 459 456 1219 462 459 1220 461 458 1221 458 455 1222 459 456 1223 449 446 1224 463 460 1225 460 457 1226 461 458 1227 462 459 1228 464 461 1229 449 446 1230 465 462 1231 463 460 1232 466 463 1233 464 461 1234 467 464 1235 466 463 1236 461 458 1237 464 461 1238 465 465 1239 449 465 1240 468 465 1241 466 463 1242 467 464 1243 469 466 1244 468 467 1245 470 467 1246 465 467 1247 471 468 1248 472 469 1249 473 470 1250 474 471 1251 466 463 1252 469 466 1253 471 468 1254 475 472 1255 472 469 1256 449 473 1257 476 473 1258 468 473 1259 471 468 1260 473 470 1261 477 474 1262 478 475 1263 479 476 1264 480 477 1265 478 475 1266 481 478 1267 479 476 1268 482 479 1269 449 446 1270 437 434 1271 483 480 1272 484 481 1273 449 446 1274 478 475 1275 480 477 1276 485 482 1277 486 483 1278 483 480 1279 449 446 1280 487 484 1281 486 483 1282 449 446 1283 482 479 1284 487 484 1285 449 446 1286 488 485 1287 437 434 1288 428 425 1289 489 486 1290 482 479 1291 437 434 1292 490 487 1293 489 486 1294 437 434 1295 491 488 1296 490 487 1297 437 434 1298 492 489 1299 491 488 1300 437 434 1301 488 485 1302 492 489 1303 437 434 1304 493 490 1305 428 425 1306 415 412 1307 494 491 1308 488 485 1309 428 425 1310 495 492 1311 494 491 1312 428 425 1313 493 490 1314 495 492 1315 428 425 1316 496 493 1317 497 494 1318 498 495 1319 499 496 1320 500 497 1321 497 494 1322 499 496 1323 497 494 1324 496 493 1325 501 498 1326 498 495 1327 502 499 1328 496 493 1329 498 495 1330 501 498 1331 423 420 1332 503 500 1333 422 419 1334 501 498 1335 502 499 1336 504 501 1337 505 502 1338 506 503 1339 503 500 1340 507 504 1341 503 500 1342 506 503 1343 508 505 1344 505 502 1345 503 500 1346 423 420 1347 508 505 1348 503 500 1349 501 498 1350 504 501 1351 509 506 1352 510 507 1353 398 393 1354 506 503 1355 511 508 1356 506 503 1357 398 393 1358 512 509 1359 510 507 1360 506 503 1361 513 510 1362 512 509 1363 506 503 1364 514 511 1365 513 510 1366 506 503 1367 505 502 1368 514 511 1369 506 503 1370 515 512 1371 507 504 1372 506 503 1373 511 508 1374 515 512 1375 506 503 1376 516 513 1377 401 396 1378 398 393 1379 517 514 1380 516 513 1381 398 393 1382 518 515 1383 517 514 1384 398 393 1385 519 516 1386 518 515 1387 398 393 1388 520 517 1389 519 516 1390 398 393 1391 521 518 1392 520 517 1393 398 393 1394 522 519 1395 521 518 1396 398 393 1397 523 520 1398 522 519 1399 398 393 1400 510 507 1401 523 520 1402 398 393 1403 524 521 1404 511 508 1405 398 393 1406 405 400 1407 524 521 1408 398 393 1409 392 387 1410 402 397 1411 525 397 1412 526 522 1413 527 523 1414 528 524 1415 529 525 1416 528 524 1417 530 526 1418 529 525 1419 526 522 1420 528 524 1421 529 525 1422 530 526 1423 531 527 1424 532 528 1425 531 527 1426 533 529 1427 532 528 1428 529 525 1429 531 527 1430 534 530 1431 533 529 1432 535 531 1433 534 530 1434 532 528 1435 533 529 1436 534 530 1437 535 531 1438 536 532 1439 537 533 1440 538 534 1441 539 535 1442 534 530 1443 536 532 1444 540 536 1445 541 537 1446 539 535 1447 542 538 1448 541 537 1449 537 533 1450 539 535 1451 543 539 1452 542 538 1453 544 540 1454 543 539 1455 541 537 1456 542 538 1457 543 539 1458 544 540 1459 545 541 1460 546 542 1461 545 541 1462 547 543 1463 546 542 1464 543 539 1465 545 541 1466 546 542 1467 547 543 1468 548 544 1469 549 545 1470 548 544 1471 550 546 1472 549 545 1473 546 542 1474 548 544 1475 424 421 1476 550 546 1477 425 422 1478 424 421 1479 549 545 1480 550 546 1481 478 475 1482 485 482 1483 551 547 1484 552 548 1485 553 548 1486 483 548 1487 554 549 1488 483 549 1489 553 549 1490 486 483 1491 552 550 1492 483 480 1493 554 551 1494 555 551 1495 483 551 1496 478 475 1497 551 547 1498 556 552 1499 557 553 1500 558 553 1501 559 553 1502 560 554 1503 554 554 1504 553 554 1505 561 555 1506 560 556 1507 553 557 1508 562 558 1509 561 558 1510 553 558 1511 557 559 1512 563 559 1513 558 559 1514 557 560 1515 559 560 1516 564 560 1517 565 561 1518 566 562 1519 567 563 1520 557 564 1521 564 564 1522 568 564 1523 569 565 1524 567 563 1525 570 566 1526 565 561 1527 567 563 1528 569 565 1529 571 567 1530 570 566 1531 572 568 1532 569 565 1533 570 566 1534 571 567 1535 573 569 1536 572 568 1537 574 570 1538 571 567 1539 572 568 1540 573 569 1541 573 569 1542 574 570 1543 575 571 1544 576 572 1545 575 571 1546 577 573 1547 573 569 1548 575 571 1549 576 572 1550 576 572 1551 577 573 1552 578 574 1553 579 575 1554 580 575 1555 581 575 1556 576 572 1557 578 574 1558 582 576 1559 579 577 1560 581 577 1561 583 577 1562 584 578 1563 585 579 1564 500 497 1565 579 580 1566 583 580 1567 586 580 1568 584 578 1569 500 497 1570 499 496 1571 587 581 1572 588 582 1573 589 583 1574 587 581 1575 590 584 1576 588 582 1577 587 581 1578 589 583 1579 591 585 1580 592 586 1581 593 587 1582 594 588 1583 595 589 1584 596 590 1585 561 555 1586 597 591 1587 594 588 1588 598 592 1589 562 593 1590 595 593 1591 561 593 1592 597 591 1593 592 586 1594 594 588 1595 599 594 1596 600 595 1597 596 590 1598 601 596 1599 598 592 1600 602 597 1601 603 598 1602 599 594 1603 596 590 1604 595 589 1605 603 598 1606 596 590 1607 601 596 1608 597 591 1609 598 592 1610 604 599 1611 605 600 1612 600 595 1613 606 601 1614 602 597 1615 607 602 1616 608 603 1617 604 599 1618 600 595 1619 599 594 1620 608 603 1621 600 595 1622 609 604 1623 601 596 1624 602 597 1625 606 601 1626 609 604 1627 602 597 1628 610 605 1629 611 606 1630 605 600 1631 606 601 1632 607 602 1633 612 607 1634 604 599 1635 610 605 1636 605 600 1637 613 608 1638 614 609 1639 611 606 1640 615 610 1641 612 607 1642 616 611 1643 610 605 1644 613 608 1645 611 606 1646 615 610 1647 606 601 1648 612 607 1649 617 612 1650 618 613 1651 614 609 1652 615 610 1653 616 611 1654 619 614 1655 613 608 1656 617 612 1657 614 609 1658 617 612 1659 620 615 1660 618 613 1661 621 616 1662 619 614 1663 622 617 1664 621 616 1665 615 610 1666 619 614 1667 623 618 1668 624 619 1669 620 615 1670 621 616 1671 622 617 1672 625 620 1673 617 612 1674 623 618 1675 620 615 1676 623 618 1677 626 621 1678 624 619 1679 627 622 1680 625 620 1681 628 623 1682 627 622 1683 621 616 1684 625 620 1685 629 624 1686 630 625 1687 626 621 1688 627 622 1689 628 623 1690 631 626 1691 623 618 1692 629 624 1693 626 621 1694 629 624 1695 632 627 1696 630 625 1697 633 628 1698 631 626 1699 634 629 1700 633 628 1701 627 622 1702 631 626 1703 635 630 1704 636 631 1705 632 627 1706 637 632 1707 634 629 1708 638 633 1709 629 624 1710 635 630 1711 632 627 1712 637 632 1713 633 628 1714 634 629 1715 635 630 1716 639 634 1717 636 631 1718 637 632 1719 638 633 1720 640 635 1721 641 636 1722 642 637 1723 639 634 1724 643 638 1725 640 635 1726 644 639 1727 635 630 1728 641 636 1729 639 634 1730 643 638 1731 637 632 1732 640 635 1733 645 640 1734 646 641 1735 642 637 1736 643 638 1737 644 639 1738 647 642 1739 641 636 1740 645 640 1741 642 637 1742 648 643 1743 649 644 1744 646 641 1745 650 645 1746 647 642 1747 651 646 1748 645 640 1749 648 643 1750 646 641 1751 650 645 1752 643 638 1753 647 642 1754 652 647 1755 653 648 1756 649 644 1757 650 645 1758 651 646 1759 654 649 1760 648 643 1761 652 647 1762 649 644 1763 655 650 1764 656 651 1765 653 648 1766 657 652 1767 654 649 1768 658 653 1769 652 647 1770 655 650 1771 653 648 1772 657 652 1773 650 645 1774 654 649 1775 659 654 1776 660 655 1777 656 651 1778 657 652 1779 658 653 1780 661 656 1781 655 650 1782 659 654 1783 656 651 1784 662 657 1785 663 658 1786 660 655 1787 664 659 1788 661 656 1789 665 660 1790 666 661 1791 662 657 1792 660 655 1793 659 654 1794 666 661 1795 660 655 1796 664 659 1797 657 652 1798 661 656 1799 667 662 1800 668 663 1801 663 658 1802 664 659 1803 665 660 1804 669 664 1805 662 657 1806 667 662 1807 663 658 1808 667 662 1809 670 665 1810 668 663 1811 671 666 1812 669 664 1813 672 667 1814 671 666 1815 664 659 1816 669 664 1817 673 668 1818 414 410 1819 670 665 1820 674 669 1821 672 667 1822 675 670 1823 676 671 1824 673 668 1825 670 665 1826 667 662 1827 676 671 1828 670 665 1829 674 669 1830 671 666 1831 672 667 1832 677 672 1833 675 670 1834 678 673 1835 673 668 1836 411 406 1837 414 410 1838 677 672 1839 674 669 1840 675 670 1841 677 672 1842 678 673 1843 679 674 1844 680 675 1845 681 675 1846 682 675 1847 680 676 1848 683 676 1849 681 676 1850 684 677 1851 685 678 1852 686 679 1853 687 680 1854 680 680 1855 682 680 1856 688 681 1857 686 679 1858 689 682 1859 684 677 1860 686 679 1861 688 681 1862 690 683 1863 689 682 1864 691 684 1865 688 681 1866 689 682 1867 690 683 1868 692 685 1869 691 684 1870 693 686 1871 690 683 1872 691 684 1873 692 685 1874 692 685 1875 693 686 1876 694 687 1877 695 688 1878 694 687 1879 696 689 1880 692 685 1881 694 687 1882 695 688 1883 695 688 1884 696 689 1885 697 690 1886 698 691 1887 697 690 1888 699 692 1889 695 688 1890 697 690 1891 698 691 1892 700 693 1893 699 692 1894 701 694 1895 698 691 1896 699 692 1897 700 693 1898 700 693 1899 701 694 1900 702 695 1901 703 696 1902 702 695 1903 704 697 1904 700 693 1905 702 695 1906 703 696 1907 705 698 1908 704 697 1909 706 699 1910 703 696 1911 704 697 1912 705 698 1913 705 698 1914 706 699 1915 707 700 1916 708 701 1917 707 700 1918 709 702 1919 705 698 1920 707 700 1921 708 701 1922 710 703 1923 709 702 1924 711 704 1925 708 701 1926 709 702 1927 710 703 1928 712 705 1929 711 704 1930 713 706 1931 710 703 1932 711 704 1933 712 705 1934 712 705 1935 713 706 1936 714 707 1937 715 708 1938 714 707 1939 716 709 1940 712 705 1941 714 707 1942 715 708 1943 717 710 1944 716 709 1945 718 711 1946 715 708 1947 716 709 1948 717 710 1949 717 710 1950 718 711 1951 719 712 1952 720 713 1953 719 712 1954 721 714 1955 717 710 1956 719 712 1957 720 713 1958 720 713 1959 721 714 1960 722 715 1961 720 713 1962 722 715 1963 723 716 1964 724 717 1965 509 506 1966 725 718 1967 501 498 1968 509 506 1969 724 717 1970 726 719 1971 727 719 1972 728 719 1973 724 717 1974 725 718 1975 729 720 1976 726 721 1977 728 721 1978 730 721 1979 731 722 1980 732 723 1981 733 724 1982 734 725 1983 726 725 1984 730 725 1985 735 726 1986 733 724 1987 736 727 1988 735 726 1989 731 722 1990 733 724 1991 735 726 1992 736 727 1993 737 728 1994 738 729 1995 737 728 1996 739 730 1997 738 729 1998 735 726 1999 737 728 2000 740 731 2001 739 730 2002 741 732 2003 740 731 2004 738 729 2005 739 730 2006 742 733 2007 741 732 2008 743 734 2009 742 733 2010 740 731 2011 741 732 2012 742 733 2013 743 734 2014 744 735 2015 680 736 2016 745 736 2017 683 736 2018 746 737 2019 742 733 2020 744 735 2021 747 738 2022 418 415 2023 430 427 2024 748 739 2025 427 424 2026 749 740 2027 748 739 2028 424 421 2029 427 424 2030 750 741 2031 430 427 2032 433 430 2033 750 741 2034 747 738 2035 430 427 2036 751 742 2037 433 430 2038 439 436 2039 751 742 2040 750 741 2041 433 430 2042 752 743 2043 439 436 2044 444 441 2045 752 743 2046 751 742 2047 439 436 2048 753 744 2049 444 441 2050 447 444 2051 753 744 2052 752 743 2053 444 441 2054 754 745 2055 447 444 2056 456 453 2057 754 745 2058 753 744 2059 447 444 2060 754 745 2061 456 453 2062 755 746 2063 756 747 2064 757 748 2065 453 450 2066 756 747 2067 453 450 2068 458 455 2069 758 749 2070 754 745 2071 755 746 2072 758 749 2073 755 746 2074 759 750 2075 760 751 2076 761 752 2077 757 748 2078 760 751 2079 757 748 2080 756 747 2081 762 753 2082 747 738 2083 750 741 2084 763 754 2085 749 740 2086 764 755 2087 748 739 2088 749 740 2089 763 754 2090 765 756 2091 750 741 2092 751 742 2093 766 757 2094 762 753 2095 750 741 2096 765 756 2097 766 757 2098 750 741 2099 767 758 2100 751 742 2101 752 743 2102 768 759 2103 765 756 2104 751 742 2105 767 758 2106 768 759 2107 751 742 2108 769 760 2109 752 743 2110 753 744 2111 769 760 2112 767 758 2113 752 743 2114 770 761 2115 753 744 2116 754 745 2117 771 762 2118 769 760 2119 753 744 2120 770 761 2121 771 762 2122 753 744 2123 758 749 2124 770 761 2125 754 745 2126 772 763 2127 773 764 2128 774 765 2129 775 766 2130 776 767 2131 777 768 2132 778 769 2133 776 767 2134 775 766 2135 772 763 2136 774 765 2137 779 770 2138 780 771 2139 781 772 2140 782 773 2141 783 774 2142 784 775 2143 785 776 2144 786 777 2145 784 775 2146 783 774 2147 787 778 2148 782 773 2149 788 779 2150 787 778 2151 780 771 2152 782 773 2153 789 780 2154 788 779 2155 790 781 2156 787 778 2157 788 779 2158 789 780 2159 789 780 2160 790 781 2161 791 782 2162 792 783 2163 791 782 2164 793 784 2165 789 780 2166 791 782 2167 792 783 2168 794 785 2169 793 784 2170 795 786 2171 792 783 2172 793 784 2173 794 785 2174 794 785 2175 795 786 2176 796 787 2177 797 788 2178 796 787 2179 773 764 2180 794 785 2181 796 787 2182 797 788 2183 797 788 2184 773 764 2185 772 763 2186 756 747 2187 458 455 2188 461 458 2189 798 789 2190 461 458 2191 466 463 2192 798 789 2193 756 747 2194 461 458 2195 799 790 2196 466 463 2197 474 471 2198 799 790 2199 798 789 2200 466 463 2201 799 790 2202 474 471 2203 800 791 2204 801 792 2205 802 793 2206 475 472 2207 803 794 2208 801 792 2209 475 472 2210 471 468 2211 803 794 2212 475 472 2213 804 795 2214 799 790 2215 800 791 2216 804 795 2217 800 791 2218 805 796 2219 806 797 2220 807 798 2221 802 793 2222 808 799 2223 806 797 2224 802 793 2225 801 792 2226 808 799 2227 802 793 2228 809 800 2229 756 747 2230 798 789 2231 809 800 2232 760 751 2233 756 747 2234 810 801 2235 798 789 2236 799 790 2237 811 802 2238 809 800 2239 798 789 2240 810 801 2241 811 802 2242 798 789 2243 812 803 2244 810 801 2245 799 790 2246 813 804 2247 812 803 2248 799 790 2249 804 795 2250 813 804 2251 799 790 2252 814 805 2253 815 806 2254 816 807 2255 806 797 2256 817 808 2257 807 798 2258 818 809 2259 819 810 2260 820 811 2261 821 812 2262 822 813 2263 819 810 2264 818 809 2265 821 812 2266 819 810 2267 775 766 2268 777 768 2269 823 814 2270 824 815 2271 823 814 2272 825 816 2273 826 817 2274 823 814 2275 824 815 2276 775 766 2277 823 814 2278 826 817 2279 824 815 2280 825 816 2281 827 818 2282 824 815 2283 827 818 2284 828 819 2285 814 805 2286 828 819 2287 829 820 2288 830 821 2289 828 819 2290 814 805 2291 831 822 2292 828 819 2293 830 821 2294 831 822 2295 832 823 2296 828 819 2297 824 815 2298 828 819 2299 832 823 2300 814 805 2301 829 820 2302 815 806 2303 806 797 2304 833 824 2305 817 808 2306 818 809 2307 820 811 2308 834 825 2309 835 826 2310 836 827 2311 837 828 2312 838 829 2313 839 830 2314 840 831 2315 818 809 2316 834 825 2317 841 832 2318 842 833 2319 837 828 2320 843 834 2321 842 833 2322 844 835 2323 837 828 2324 845 836 2325 837 828 2326 844 835 2327 846 837 2328 835 826 2329 837 828 2330 845 836 2331 846 837 2332 837 828 2333 842 833 2334 843 834 2335 847 838 2336 848 839 2337 847 838 2338 849 840 2339 848 839 2340 842 833 2341 847 838 2342 478 475 2343 849 840 2344 481 478 2345 478 475 2346 848 839 2347 849 840 2348 850 841 2349 851 842 2350 852 843 2351 853 844 2352 854 845 2353 855 846 2354 856 847 2355 857 848 2356 858 849 2357 856 850 2358 859 850 2359 860 850 2360 860 851 2361 857 851 2362 856 851 2363 861 852 2364 855 846 2365 862 853 2366 863 854 2367 855 846 2368 861 852 2369 864 855 2370 855 846 2371 863 854 2372 865 856 2373 855 846 2374 864 855 2375 866 857 2376 855 846 2377 865 856 2378 867 858 2379 853 844 2380 855 846 2381 868 859 2382 867 858 2383 855 846 2384 866 857 2385 868 859 2386 855 846 2387 869 860 2388 852 843 2389 870 861 2390 871 862 2391 850 841 2392 852 843 2393 872 863 2394 871 862 2395 852 843 2396 869 860 2397 872 863 2398 852 843 2399 873 864 2400 870 861 2401 590 584 2402 874 865 2403 869 860 2404 870 861 2405 875 866 2406 874 865 2407 870 861 2408 873 864 2409 875 866 2410 870 861 2411 876 867 2412 873 864 2413 590 584 2414 587 581 2415 876 867 2416 590 584 2417 877 868 2418 840 831 2419 878 869 2420 879 870 2421 838 829 2422 840 831 2423 880 871 2424 879 870 2425 840 831 2426 877 868 2427 880 871 2428 840 831 2429 881 872 2430 878 869 2431 854 845 2432 881 872 2433 877 868 2434 878 869 2435 258 256 2436 260 258 2437 882 873 2438 883 874 2439 881 872 2440 854 845 2441 884 875 2442 883 874 2443 854 845 2444 885 876 2445 884 875 2446 854 845 2447 886 877 2448 885 876 2449 854 845 2450 853 844 2451 886 877 2452 854 845 2453 887 878 2454 858 878 2455 888 878 2456 889 879 2457 856 847 2458 858 849 2459 890 880 2460 889 880 2461 858 880 2462 891 881 2463 890 881 2464 858 881 2465 887 882 2466 891 882 2467 858 882 2468 892 883 2469 893 884 2470 894 885 2471 895 886 2472 887 886 2473 888 886 2474 896 887 2475 897 888 2476 898 889 2477 899 890 2478 893 884 2479 892 883 2480 900 891 2481 894 885 2482 901 892 2483 892 883 2484 894 885 2485 900 891 2486 900 891 2487 901 892 2488 902 893 2489 903 894 2490 902 893 2491 904 895 2492 900 891 2493 902 893 2494 903 894 2495 903 894 2496 904 895 2497 905 896 2498 597 591 2499 905 896 2500 906 897 2501 903 894 2502 905 896 2503 597 591 2504 597 591 2505 906 897 2506 592 586 2507 907 898 2508 908 899 2509 909 900 2510 861 901 2511 862 901 2512 910 901 2513 907 898 2514 911 902 2515 908 899 2516 907 898 2517 909 900 2518 912 903 2519 907 898 2520 912 903 2521 913 904 2522 907 898 2523 913 904 2524 914 905 2525 915 906 2526 916 907 2527 917 908 2528 915 906 2529 918 909 2530 916 907 2531 915 906 2532 917 908 2533 919 910 2534 920 911 2535 897 888 2536 896 887 2537 921 912 2538 922 913 2539 923 914 2540 924 915 2541 922 913 2542 921 912 2543 925 916 2544 926 917 2545 911 902 2546 907 898 2547 925 916 2548 911 902 2549 927 918 2550 928 919 2551 926 917 2552 925 916 2553 927 918 2554 926 917 2555 929 920 2556 930 921 2557 928 919 2558 931 922 2559 929 920 2560 928 919 2561 932 923 2562 931 922 2563 928 919 2564 933 924 2565 932 923 2566 928 919 2567 927 918 2568 933 924 2569 928 919 2570 934 925 2571 935 926 2572 936 927 2573 934 925 2574 937 928 2575 935 926 2576 938 929 2577 936 927 2578 939 930 2579 934 925 2580 936 927 2581 938 929 2582 938 929 2583 939 930 2584 940 931 2585 941 932 2586 940 931 2587 942 933 2588 943 934 2589 940 931 2590 941 932 2591 938 929 2592 940 931 2593 943 934 2594 944 935 2595 945 936 2596 946 937 2597 947 938 2598 948 939 2599 949 940 2600 950 941 2601 949 940 2602 948 939 2603 951 942 2604 946 937 2605 952 943 2606 944 935 2607 946 937 2608 951 942 2609 915 906 2610 952 943 2611 918 909 2612 915 906 2613 951 942 2614 952 943 2615 953 944 2616 954 945 2617 955 946 2618 956 947 2619 957 948 2620 958 949 2621 959 950 2622 954 945 2623 953 944 2624 960 951 2625 955 946 2626 961 952 2627 953 944 2628 955 946 2629 960 951 2630 960 951 2631 961 952 2632 962 953 2633 963 954 2634 964 955 2635 965 956 2636 966 957 2637 967 958 2638 968 959 2639 963 954 2640 965 956 2641 969 960 2642 970 961 2643 965 956 2644 971 962 2645 969 960 2646 965 956 2647 970 961 2648 972 963 2649 973 964 2650 974 965 2651 975 966 2652 973 964 2653 972 963 2654 972 963 2655 974 965 2656 976 967 2657 977 968 2658 978 969 2659 979 970 2660 980 971 2661 979 970 2662 981 972 2663 980 971 2664 977 968 2665 979 970 2666 982 973 2667 981 972 2668 983 974 2669 980 971 2670 981 972 2671 982 973 2672 984 975 2673 983 974 2674 985 976 2675 982 973 2676 983 974 2677 984 975 2678 984 975 2679 985 976 2680 937 928 2681 984 975 2682 937 928 2683 934 925 2684 956 947 2685 986 977 2686 957 948 2687 987 978 2688 988 979 2689 989 980 2690 956 947 2691 990 981 2692 986 977 2693 987 978 2694 991 982 2695 988 979 2696 992 983 2697 824 815 2698 832 823 2699 993 984 2700 994 985 2701 995 986 2702 996 987 2703 991 982 2704 987 978 2705 993 984 2706 995 986 2707 997 988 2708 998 989 2709 826 817 2710 824 815 2711 999 990 2712 998 989 2713 824 815 2714 1000 991 2715 999 990 2716 824 815 2717 992 983 2718 1000 991 2719 824 815 2720 1001 992 2721 1002 993 2722 1003 994 2723 1004 995 2724 775 766 2725 826 817 2726 1005 996 2727 1006 997 2728 1002 993 2729 1005 996 2730 1002 993 2731 1001 992 2732 1007 998 2733 1003 994 2734 1008 999 2735 1001 992 2736 1003 994 2737 1007 998 2738 1007 998 2739 1008 999 2740 1009 1000 2741 993 984 2742 1009 1000 2743 994 985 2744 1007 998 2745 1009 1000 2746 993 984 2747 1010 1001 2748 1011 1002 2749 775 766 2750 1012 1003 2751 775 766 2752 1011 1002 2753 1013 1004 2754 1010 1001 2755 775 766 2756 1014 1005 2757 1013 1004 2758 775 766 2759 1015 1006 2760 1014 1005 2761 775 766 2762 1004 995 2763 1015 1006 2764 775 766 2765 1012 1003 2766 778 769 2767 775 766 2768 1016 1007 2769 1017 1008 2770 1018 1009 2771 1019 1010 2772 1012 1003 2773 1011 1002 2774 1020 1011 2775 1019 1010 2776 1011 1002 2777 1016 1007 2778 1021 1012 2779 1017 1008 2780 1022 1013 2781 1018 1009 2782 1023 1014 2783 1016 1007 2784 1018 1009 2785 1022 1013 2786 1024 1015 2787 1023 1014 2788 1025 1016 2789 1022 1013 2790 1023 1014 2791 1024 1015 2792 1026 1017 2793 1025 1016 2794 1027 1018 2795 1024 1015 2796 1025 1016 2797 1026 1017 2798 1005 996 2799 1027 1018 2800 1006 997 2801 1026 1017 2802 1027 1018 2803 1005 996 2804 1028 1019 2805 779 770 2806 1029 1020 2807 772 763 2808 779 770 2809 1028 1019 2810 1028 1019 2811 1029 1020 2812 1030 1021 2813 1031 1022 2814 1032 1023 2815 1019 1010 2816 1033 1024 2817 1030 1021 2818 1034 1025 2819 1035 1026 2820 1031 1022 2821 1019 1010 2822 1036 1027 2823 1035 1026 2824 1019 1010 2825 1020 1011 2826 1036 1027 2827 1019 1010 2828 1028 1019 2829 1030 1021 2830 1033 1024 2831 1037 1028 2832 1038 1029 2833 1032 1023 2834 1033 1024 2835 1034 1025 2836 1039 1030 2837 1040 1031 2838 1037 1028 2839 1032 1023 2840 1031 1022 2841 1040 1031 2842 1032 1023 2843 1041 1032 2844 1042 1033 2845 1038 1029 2846 1043 1034 2847 1039 1030 2848 1044 1035 2849 1045 1036 2850 1041 1032 2851 1038 1029 2852 1046 1037 2853 1045 1036 2854 1038 1029 2855 1037 1028 2856 1046 1037 2857 1038 1029 2858 1033 1024 2859 1039 1030 2860 1043 1034 2861 1047 1038 2862 1048 1039 2863 1049 1040 2864 1050 1041 2865 1048 1039 2866 1047 1038 2867 1051 1042 2868 1052 1043 2869 1053 1044 2870 1054 1045 2871 1052 1043 2872 1051 1042 2873 1043 1034 2874 1044 1035 2875 1055 1046 2876 1047 1038 2877 1049 1040 2878 1056 1047 2879 1057 1048 2880 1058 1049 2881 1059 1050 2882 1060 1051 2883 1059 1050 2884 1061 1052 2885 1060 1051 2886 1057 1048 2887 1059 1050 2888 1062 1053 2889 1061 1052 2890 1063 1054 2891 1060 1051 2892 1061 1052 2893 1062 1053 2894 1064 1055 2895 1063 1054 2896 1065 1056 2897 1062 1053 2898 1063 1054 2899 1064 1055 2900 1064 1055 2901 1065 1056 2902 1066 1057 2903 1067 1058 2904 1066 1057 2905 1068 1059 2906 1064 1055 2907 1066 1057 2908 1067 1058 2909 1069 1060 2910 1068 1059 2911 1021 1012 2912 1067 1058 2913 1068 1059 2914 1069 1060 2915 1069 1060 2916 1021 1012 2917 1016 1007 2918 1070 1061 2919 1071 1062 2920 1072 1063 2921 1073 1064 2922 1074 1065 2923 1075 1066 2924 1076 1067 2925 1070 1061 2926 1072 1063 2927 1077 1068 2928 1078 1069 2929 1079 1070 2930 1080 1071 2931 1081 1072 2932 1082 1073 2933 1073 1064 2934 1075 1066 2935 1083 1074 2936 1084 1075 2937 987 978 2938 1070 1061 2939 1085 1076 2940 1086 1077 2941 990 981 2942 1076 1067 2943 1084 1075 2944 1070 1061 2945 1087 1078 2946 1083 1074 2947 1088 1079 2948 1087 1078 2949 1073 1064 2950 1083 1074 2951 1089 1080 2952 996 987 2953 987 978 2954 1090 1081 2955 1089 1080 2956 987 978 2957 1084 1075 2958 1090 1081 2959 987 978 2960 1091 1082 2961 1092 1083 2962 990 981 2963 1085 1076 2964 990 981 2965 1092 1083 2966 1093 1084 2967 990 981 2968 956 947 2969 1091 1082 2970 990 981 2971 1093 1084 2972 1094 1085 2973 997 988 2974 1095 1086 2975 993 984 2976 997 988 2977 1094 1085 2978 1096 1087 2979 1095 1086 2980 1097 1088 2981 1094 1085 2982 1095 1086 2983 1096 1087 2984 1096 1087 2985 1097 1088 2986 1098 1089 2987 1099 1090 2988 1098 1089 2989 1078 1069 2990 1096 1087 2991 1098 1089 2992 1099 1090 2993 1099 1090 2994 1078 1069 2995 1077 1068 2996 1100 1091 2997 1101 1092 2998 1102 1093 2999 1103 1094 3000 1104 1095 3001 1105 1096 3002 1106 1097 3003 1100 1091 3004 1102 1093 3005 1107 1098 3006 1108 1099 3007 1109 1100 3008 1107 1098 3009 1109 1100 3010 1110 1101 3011 1111 1102 3012 1112 1103 3013 1113 1104 3014 1114 1105 3015 1111 1102 3016 1113 1104 3017 1103 1094 3018 1115 1106 3019 1104 1095 3020 1100 1091 3021 1116 1107 3022 1101 1092 3023 1103 1094 3024 1105 1096 3025 1117 1108 3026 1118 1109 3027 1119 1110 3028 1116 1107 3029 1103 1094 3030 1117 1108 3031 1120 1111 3032 1100 1091 3033 1118 1109 3034 1116 1107 3035 1121 1112 3036 1122 1113 3037 1119 1110 3038 1123 1114 3039 1120 1111 3040 1124 1115 3041 1118 1109 3042 1121 1112 3043 1119 1110 3044 1103 1094 3045 1120 1111 3046 1123 1114 3047 1121 1112 3048 1125 1116 3049 1122 1113 3050 1123 1114 3051 1124 1115 3052 1126 1117 3053 1127 1118 3054 1128 1119 3055 1125 1116 3056 1123 1114 3057 1126 1117 3058 1129 1120 3059 1121 1112 3060 1127 1118 3061 1125 1116 3062 1130 1121 3063 1131 1122 3064 1128 1119 3065 1123 1114 3066 1129 1120 3067 1132 1123 3068 1127 1118 3069 1130 1121 3070 1128 1119 3071 1133 1124 3072 1134 1125 3073 1131 1122 3074 1135 1126 3075 1132 1123 3076 1136 1127 3077 1130 1121 3078 1133 1124 3079 1131 1122 3080 1137 1128 3081 1132 1123 3082 1135 1126 3083 1123 1114 3084 1132 1123 3085 1137 1128 3086 1133 1124 3087 1138 1129 3088 1134 1125 3089 1135 1126 3090 1136 1127 3091 1139 1130 3092 1140 1131 3093 1141 1132 3094 1138 1129 3095 1135 1126 3096 1139 1130 3097 1142 1133 3098 1133 1124 3099 1140 1131 3100 1138 1129 3101 1143 1134 3102 1144 1135 3103 1141 1132 3104 1135 1126 3105 1142 1133 3106 1145 1136 3107 1140 1131 3108 1143 1134 3109 1141 1132 3110 1143 1134 3111 1146 1137 3112 1144 1135 3113 1135 1126 3114 1145 1136 3115 1147 1138 3116 1148 1139 3117 1149 1140 3118 1146 1137 3119 1135 1126 3120 1147 1138 3121 1150 1141 3122 1143 1134 3123 1148 1139 3124 1146 1137 3125 1151 1142 3126 1152 1143 3127 1149 1140 3128 1153 1144 3129 1150 1141 3130 1154 1145 3131 1148 1139 3132 1151 1142 3133 1149 1140 3134 1155 1146 3135 1150 1141 3136 1153 1144 3137 1135 1126 3138 1150 1141 3139 1155 1146 3140 1151 1142 3141 1156 1147 3142 1152 1143 3143 1080 1071 3144 1154 1145 3145 1157 1148 3146 1153 1144 3147 1154 1145 3148 1080 1071 3149 1158 1149 3150 1159 1150 3151 1156 1147 3152 1080 1071 3153 1157 1148 3154 1160 1151 3155 1151 1142 3156 1158 1149 3157 1156 1147 3158 1158 1149 3159 1161 1152 3160 1159 1150 3161 1080 1071 3162 1160 1151 3163 1162 1153 3164 1163 1154 3165 1164 1155 3166 1161 1152 3167 1080 1071 3168 1162 1153 3169 1165 1156 3170 1158 1149 3171 1163 1154 3172 1161 1152 3173 1163 1154 3174 1166 1157 3175 1164 1155 3176 1080 1071 3177 1165 1156 3178 1167 1158 3179 1099 1090 3180 1077 1068 3181 1166 1157 3182 1080 1071 3183 1167 1158 3184 1081 1072 3185 1163 1154 3186 1099 1090 3187 1166 1157 3188 1096 1087 3189 1099 1090 3190 1163 1154 3191 1168 1159 3192 1163 1154 3193 1158 1149 3194 1168 1159 3195 1096 1087 3196 1163 1154 3197 1169 1160 3198 1158 1149 3199 1151 1142 3200 1169 1160 3201 1168 1159 3202 1158 1149 3203 1170 1161 3204 1151 1142 3205 1148 1139 3206 1170 1161 3207 1169 1160 3208 1151 1142 3209 1171 1162 3210 1148 1139 3211 1143 1134 3212 1171 1162 3213 1170 1161 3214 1148 1139 3215 1172 1163 3216 1143 1134 3217 1140 1131 3218 1172 1163 3219 1171 1162 3220 1143 1134 3221 1173 1164 3222 1140 1131 3223 1133 1124 3224 1173 1164 3225 1172 1163 3226 1140 1131 3227 1174 1165 3228 1133 1124 3229 1130 1121 3230 1174 1165 3231 1173 1164 3232 1133 1124 3233 1175 1166 3234 1130 1121 3235 1127 1118 3236 1175 1166 3237 1174 1165 3238 1130 1121 3239 1176 1167 3240 1127 1118 3241 1121 1112 3242 1176 1167 3243 1175 1166 3244 1127 1118 3245 1177 1168 3246 1121 1112 3247 1118 1109 3248 1177 1168 3249 1176 1167 3250 1121 1112 3251 1178 1169 3252 1118 1109 3253 1100 1091 3254 1178 1169 3255 1177 1168 3256 1118 1109 3257 1179 1170 3258 1100 1091 3259 1106 1097 3260 1179 1170 3261 1178 1169 3262 1100 1091 3263 1179 1170 3264 1106 1097 3265 1180 1171 3266 1181 1172 3267 1182 1173 3268 1108 1099 3269 1107 1098 3270 1181 1172 3271 1108 1099 3272 1183 1174 3273 1179 1170 3274 1180 1171 3275 1183 1174 3276 1180 1171 3277 1184 1175 3278 1185 1176 3279 1186 1177 3280 1182 1173 3281 1181 1172 3282 1185 1176 3283 1182 1173 3284 1094 1085 3285 1096 1087 3286 1168 1159 3287 1187 1178 3288 1168 1159 3289 1169 1160 3290 1187 1178 3291 1094 1085 3292 1168 1159 3293 1188 1179 3294 1169 1160 3295 1170 1161 3296 1188 1179 3297 1187 1178 3298 1169 1160 3299 1189 1180 3300 1170 1161 3301 1171 1162 3302 1189 1180 3303 1188 1179 3304 1170 1161 3305 1190 1181 3306 1171 1162 3307 1172 1163 3308 1190 1181 3309 1189 1180 3310 1171 1162 3311 1191 1182 3312 1172 1163 3313 1173 1164 3314 1191 1182 3315 1190 1181 3316 1172 1163 3317 1192 1183 3318 1173 1164 3319 1174 1165 3320 1192 1183 3321 1191 1182 3322 1173 1164 3323 1193 1184 3324 1174 1165 3325 1175 1166 3326 1193 1184 3327 1192 1183 3328 1174 1165 3329 1194 1185 3330 1175 1166 3331 1176 1167 3332 1194 1185 3333 1193 1184 3334 1175 1166 3335 1195 1186 3336 1176 1167 3337 1177 1168 3338 1195 1186 3339 1194 1185 3340 1176 1167 3341 1196 1187 3342 1177 1168 3343 1178 1169 3344 1196 1187 3345 1195 1186 3346 1177 1168 3347 1197 1188 3348 1178 1169 3349 1179 1170 3350 1197 1188 3351 1196 1187 3352 1178 1169 3353 1183 1174 3354 1197 1188 3355 1179 1170 3356 1060 1051 3357 1183 1174 3358 1184 1175 3359 1060 1051 3360 1184 1175 3361 1057 1048 3362 1050 1041 3363 1047 1038 3364 1186 1177 3365 1185 1176 3366 1050 1041 3367 1186 1177 3368 993 984 3369 1094 1085 3370 1187 1178 3371 1007 998 3372 1187 1178 3373 1188 1179 3374 1007 998 3375 993 984 3376 1187 1178 3377 1001 992 3378 1188 1179 3379 1189 1180 3380 1001 992 3381 1007 998 3382 1188 1179 3383 1005 996 3384 1189 1180 3385 1190 1181 3386 1005 996 3387 1001 992 3388 1189 1180 3389 1026 1017 3390 1190 1181 3391 1191 1182 3392 1026 1017 3393 1005 996 3394 1190 1181 3395 1024 1015 3396 1191 1182 3397 1192 1183 3398 1024 1015 3399 1026 1017 3400 1191 1182 3401 1022 1013 3402 1192 1183 3403 1193 1184 3404 1022 1013 3405 1024 1015 3406 1192 1183 3407 1016 1007 3408 1193 1184 3409 1194 1185 3410 1016 1007 3411 1022 1013 3412 1193 1184 3413 1069 1060 3414 1194 1185 3415 1195 1186 3416 1069 1060 3417 1016 1007 3418 1194 1185 3419 1067 1058 3420 1195 1186 3421 1196 1187 3422 1067 1058 3423 1069 1060 3424 1195 1186 3425 1064 1055 3426 1196 1187 3427 1197 1188 3428 1064 1055 3429 1067 1058 3430 1196 1187 3431 1062 1053 3432 1197 1188 3433 1183 1174 3434 1062 1053 3435 1064 1055 3436 1197 1188 3437 1060 1051 3438 1062 1053 3439 1183 1174 3440 1107 1098 3441 1110 1101 3442 1198 1189 3443 1111 1102 3444 1199 1190 3445 1112 1103 3446 1200 1191 3447 1201 1192 3448 1202 1193 3449 1203 1194 3450 1199 1190 3451 1111 1102 3452 1204 1195 3453 1053 1044 3454 1205 1196 3455 1051 1042 3456 1053 1044 3457 1204 1195 3458 1206 1197 3459 1205 1196 3460 1207 1198 3461 1204 1195 3462 1205 1196 3463 1206 1197 3464 1208 1199 3465 1207 1198 3466 1201 1192 3467 1206 1197 3468 1207 1198 3469 1208 1199 3470 1208 1199 3471 1201 1192 3472 1200 1191 3473 1209 1200 3474 1210 1201 3475 1211 1202 3476 1212 1203 3477 1213 1204 3478 1214 1205 3479 1215 1206 3480 1210 1201 3481 1209 1200 3482 1216 1207 3483 1212 1203 3484 1214 1205 3485 1217 1208 3486 1218 1209 3487 1219 1210 3488 1212 1203 3489 1220 1211 3490 1213 1204 3491 1221 1212 3492 1222 1213 3493 1220 1211 3494 1215 1206 3495 1209 1200 3496 1223 1214 3497 1212 1203 3498 1221 1212 3499 1220 1211 3500 1224 1215 3501 1223 1214 3502 1225 1216 3503 1221 1212 3504 1226 1217 3505 1222 1213 3506 1227 1218 3507 1223 1214 3508 1224 1215 3509 1111 1102 3510 1223 1214 3511 1227 1218 3512 1228 1219 3513 1223 1214 3514 1111 1102 3515 1215 1206 3516 1223 1214 3517 1229 1220 3518 1228 1219 3519 1229 1220 3520 1223 1214 3521 1221 1212 3522 1230 1221 3523 1226 1217 3524 1231 1222 3525 1232 1223 3526 1230 1221 3527 1221 1212 3528 1231 1222 3529 1230 1221 3530 1233 1224 3531 1234 1225 3532 1232 1223 3533 1231 1222 3534 1233 1224 3535 1232 1223 3536 1203 1194 3537 1111 1102 3538 1235 1226 3539 1233 1224 3540 1236 1227 3541 1234 1225 3542 1228 1219 3543 1111 1102 3544 1237 1228 3545 1114 1105 3546 1237 1228 3547 1111 1102 3548 1208 1199 3549 1200 1191 3550 1236 1227 3551 1233 1224 3552 1208 1199 3553 1236 1227 3554 1206 1197 3555 1208 1199 3556 1233 1224 3557 1238 1229 3558 1233 1224 3559 1231 1222 3560 1238 1229 3561 1206 1197 3562 1233 1224 3563 1239 1230 3564 1231 1222 3565 1221 1212 3566 1239 1230 3567 1238 1229 3568 1231 1222 3569 1240 1231 3570 1221 1212 3571 1212 1203 3572 1240 1231 3573 1239 1230 3574 1221 1212 3575 1241 1232 3576 1212 1203 3577 1216 1207 3578 1241 1232 3579 1240 1231 3580 1212 1203 3581 1241 1232 3582 1216 1207 3583 1242 1233 3584 1217 1208 3585 1243 1234 3586 1218 1209 3587 1244 1235 3588 1241 1232 3589 1242 1233 3590 1245 1236 3591 1246 1237 3592 1243 1234 3593 1217 1208 3594 1245 1236 3595 1243 1234 3596 1204 1195 3597 1206 1197 3598 1238 1229 3599 1247 1238 3600 1238 1229 3601 1239 1230 3602 1247 1238 3603 1204 1195 3604 1238 1229 3605 1248 1239 3606 1239 1230 3607 1240 1231 3608 1248 1239 3609 1247 1238 3610 1239 1230 3611 1249 1240 3612 1240 1231 3613 1241 1232 3614 1249 1240 3615 1248 1239 3616 1240 1231 3617 1250 1241 3618 1241 1232 3619 1244 1235 3620 1250 1241 3621 1249 1240 3622 1241 1232 3623 1250 1241 3624 1244 1235 3625 1251 1242 3626 1245 1236 3627 1252 1243 3628 1246 1237 3629 1253 1244 3630 1250 1241 3631 1251 1242 3632 1254 1245 3633 1255 1246 3634 1252 1243 3635 1254 1245 3636 1252 1243 3637 1245 1236 3638 1051 1042 3639 1204 1195 3640 1247 1238 3641 1256 1247 3642 1247 1238 3643 1248 1239 3644 1256 1247 3645 1051 1042 3646 1247 1238 3647 1257 1248 3648 1248 1239 3649 1249 1240 3650 1257 1248 3651 1256 1247 3652 1248 1239 3653 1258 1249 3654 1249 1240 3655 1250 1241 3656 1258 1249 3657 1257 1248 3658 1249 1240 3659 1259 1250 3660 1250 1241 3661 1253 1244 3662 1259 1250 3663 1258 1249 3664 1250 1241 3665 1259 1250 3666 1253 1244 3667 1260 1251 3668 1254 1245 3669 1261 1252 3670 1255 1246 3671 1262 1253 3672 1259 1250 3673 1260 1251 3674 1263 1254 3675 1264 1255 3676 1261 1252 3677 1263 1254 3678 1261 1252 3679 1254 1245 3680 1265 1256 3681 1051 1042 3682 1256 1247 3683 1266 1257 3684 1054 1045 3685 1051 1042 3686 1265 1256 3687 1266 1257 3688 1051 1042 3689 1267 1258 3690 1256 1247 3691 1257 1248 3692 1267 1258 3693 1265 1256 3694 1256 1247 3695 1268 1259 3696 1257 1248 3697 1258 1249 3698 1269 1260 3699 1267 1258 3700 1257 1248 3701 1268 1259 3702 1269 1260 3703 1257 1248 3704 1270 1261 3705 1258 1249 3706 1259 1250 3707 1271 1262 3708 1268 1259 3709 1258 1249 3710 1270 1261 3711 1271 1262 3712 1258 1249 3713 1272 1263 3714 1259 1250 3715 1262 1253 3716 1273 1264 3717 1270 1261 3718 1259 1250 3719 1274 1265 3720 1273 1264 3721 1259 1250 3722 1272 1263 3723 1274 1265 3724 1259 1250 3725 1272 1263 3726 1262 1253 3727 1275 1266 3728 1263 1254 3729 1276 1267 3730 1264 1255 3731 1277 1268 3732 1278 1269 3733 1279 1270 3734 1280 1271 3735 1276 1267 3736 1263 1254 3737 1281 1272 3738 1282 1272 3739 1283 1273 3740 1277 1268 3741 1279 1270 3742 1284 1274 3743 1285 1275 3744 1055 1046 3745 1286 1276 3746 1043 1034 3747 1055 1046 3748 1285 1275 3749 1287 1277 3750 1286 1276 3751 1288 1278 3752 1285 1275 3753 1286 1276 3754 1287 1277 3755 1287 1277 3756 1288 1278 3757 1289 1279 3758 1290 1280 3759 1289 1279 3760 1291 1281 3761 1287 1277 3762 1289 1279 3763 1290 1280 3764 1290 1280 3765 1291 1281 3766 1292 1282 3767 1293 1283 3768 1292 1282 3769 1294 1284 3770 1290 1280 3771 1292 1282 3772 1293 1283 3773 1293 1283 3774 1294 1284 3775 1295 1285 3776 1296 1286 3777 1295 1285 3778 1297 1287 3779 1296 1286 3780 1293 1283 3781 1295 1285 3782 1298 1288 3783 1297 1287 3784 1299 1289 3785 1298 1288 3786 1296 1286 3787 1297 1287 3788 1277 1268 3789 1299 1289 3790 1278 1269 3791 1277 1268 3792 1298 1288 3793 1299 1289 3794 1300 1290 3795 1301 1291 3796 1245 1236 3797 1254 1245 3798 1245 1236 3799 1301 1291 3800 1302 1292 3801 1300 1290 3802 1245 1236 3803 1303 1293 3804 1302 1292 3805 1245 1236 3806 1217 1208 3807 1303 1293 3808 1245 1236 3809 1304 1294 3810 1305 1295 3811 1301 1291 3812 1306 1296 3813 1301 1291 3814 1305 1295 3815 1300 1290 3816 1304 1294 3817 1301 1291 3818 1306 1296 3819 1254 1245 3820 1301 1291 3821 1307 1297 3822 1308 1298 3823 1305 1295 3824 1309 1299 3825 1305 1295 3826 1308 1298 3827 1310 1300 3828 1307 1297 3829 1305 1295 3830 1304 1294 3831 1310 1300 3832 1305 1295 3833 1309 1299 3834 1306 1296 3835 1305 1295 3836 1311 1301 3837 1312 1302 3838 1308 1298 3839 1313 1303 3840 1308 1298 3841 1312 1302 3842 1314 1304 3843 1311 1301 3844 1308 1298 3845 1307 1297 3846 1314 1304 3847 1308 1298 3848 1313 1303 3849 1309 1299 3850 1308 1298 3851 1315 1305 3852 1316 1306 3853 1312 1302 3854 1317 1307 3855 1312 1302 3856 1316 1306 3857 1318 1308 3858 1315 1305 3859 1312 1302 3860 1311 1301 3861 1318 1308 3862 1312 1302 3863 1317 1307 3864 1313 1303 3865 1312 1302 3866 1319 1309 3867 1320 1310 3868 1316 1306 3869 1321 1311 3870 1316 1306 3871 1320 1310 3872 1322 1312 3873 1319 1309 3874 1316 1306 3875 1315 1305 3876 1322 1312 3877 1316 1306 3878 1321 1311 3879 1317 1307 3880 1316 1306 3881 1323 1313 3882 1324 1314 3883 1320 1310 3884 1325 1315 3885 1320 1310 3886 1324 1314 3887 1319 1309 3888 1323 1313 3889 1320 1310 3890 1325 1315 3891 1321 1311 3892 1320 1310 3893 1326 1316 3894 1327 1317 3895 1324 1314 3896 1328 1318 3897 1324 1314 3898 1327 1317 3899 1329 1319 3900 1326 1316 3901 1324 1314 3902 1323 1313 3903 1329 1319 3904 1324 1314 3905 1328 1318 3906 1325 1315 3907 1324 1314 3908 1330 1320 3909 1331 1321 3910 1327 1317 3911 1332 1322 3912 1327 1317 3913 1331 1321 3914 1333 1323 3915 1330 1320 3916 1327 1317 3917 1326 1316 3918 1333 1323 3919 1327 1317 3920 1332 1322 3921 1328 1318 3922 1327 1317 3923 1334 1324 3924 1335 1325 3925 1331 1321 3926 1336 1326 3927 1331 1321 3928 1335 1325 3929 1330 1320 3930 1334 1324 3931 1331 1321 3932 1336 1326 3933 1332 1322 3934 1331 1321 3935 1337 1327 3936 1338 1328 3937 1335 1325 3938 1339 1329 3939 1335 1325 3940 1338 1328 3941 1340 1330 3942 1337 1327 3943 1335 1325 3944 1334 1324 3945 1340 1330 3946 1335 1325 3947 1339 1329 3948 1336 1326 3949 1335 1325 3950 1341 1331 3951 1342 1332 3952 1338 1328 3953 1343 1333 3954 1338 1328 3955 1342 1332 3956 1337 1327 3957 1341 1331 3958 1338 1328 3959 1343 1333 3960 1339 1329 3961 1338 1328 3962 1344 1334 3963 1345 1335 3964 1342 1332 3965 1346 1336 3966 1342 1332 3967 1345 1335 3968 1347 1337 3969 1344 1334 3970 1342 1332 3971 1341 1331 3972 1347 1337 3973 1342 1332 3974 1346 1336 3975 1343 1333 3976 1342 1332 3977 1348 1338 3978 1349 1339 3979 1350 1340 3980 1351 1341 3981 1346 1336 3982 1345 1335 3983 1352 1342 3984 1353 1343 3985 1349 1339 3986 1348 1338 3987 1352 1342 3988 1349 1339 3989 1354 1344 3990 1355 1345 3991 1356 1346 3992 1357 1347 3993 1358 1348 3994 1355 1345 3995 1354 1344 3996 1357 1347 3997 1355 1345 3998 1359 1349 3999 1356 1346 4000 1360 1350 4001 1359 1349 4002 1354 1344 4003 1356 1346 4004 1359 1349 4005 1360 1350 4006 1361 1351 4007 1362 1352 4008 1361 1351 4009 1363 1353 4010 1362 1352 4011 1359 1349 4012 1361 1351 4013 1362 1352 4014 1363 1353 4015 1364 1354 4016 1365 1355 4017 1364 1354 4018 1366 1356 4019 1365 1355 4020 1362 1352 4021 1364 1354 4022 1365 1355 4023 1366 1356 4024 1367 1357 4025 1368 1358 4026 1367 1357 4027 1369 1359 4028 1368 1358 4029 1365 1355 4030 1367 1357 4031 1368 1358 4032 1369 1359 4033 1370 1360 4034 1371 1361 4035 1370 1360 4036 1372 1362 4037 1371 1361 4038 1368 1358 4039 1370 1360 4040 1373 1363 4041 1372 1362 4042 1374 1364 4043 1373 1363 4044 1371 1361 4045 1372 1362 4046 1375 1365 4047 1374 1364 4048 1376 1366 4049 1375 1365 4050 1373 1363 4051 1374 1364 4052 1375 1365 4053 1376 1366 4054 1377 1367 4055 1378 1368 4056 1377 1367 4057 1379 1369 4058 1380 1370 4059 1375 1365 4060 1377 1367 4061 1378 1368 4062 1380 1370 4063 1377 1367 4064 1378 1368 4065 1379 1369 4066 1381 1371 4067 1382 1372 4068 1381 1371 4069 1383 1373 4070 1382 1372 4071 1378 1368 4072 1381 1371 4073 1384 1374 4074 1383 1373 4075 1385 1375 4076 1382 1372 4077 1383 1373 4078 1384 1374 4079 1384 1374 4080 1385 1375 4081 1386 1376 4082 1384 1374 4083 1386 1376 4084 1387 1377 4085 1384 1374 4086 1387 1377 4087 1388 1378 4088 1384 1374 4089 1388 1378 4090 1389 1379 4091 1228 1219 4092 1389 1379 4093 1229 1220 4094 1390 1380 4095 1389 1379 4096 1228 1219 4097 1391 1381 4098 1384 1381 4099 1389 1381 4100 1392 1382 4101 1391 1383 4102 1389 1379 4103 1390 1380 4104 1392 1382 4105 1389 1379 4106 1263 1254 4107 1254 1245 4108 1306 1296 4109 1393 1384 4110 1306 1296 4111 1309 1299 4112 1393 1384 4113 1263 1254 4114 1306 1296 4115 1394 1385 4116 1309 1299 4117 1313 1303 4118 1394 1385 4119 1393 1384 4120 1309 1299 4121 1395 1386 4122 1313 1303 4123 1317 1307 4124 1395 1386 4125 1394 1385 4126 1313 1303 4127 1396 1387 4128 1317 1307 4129 1321 1311 4130 1396 1387 4131 1395 1386 4132 1317 1307 4133 1397 1388 4134 1321 1311 4135 1325 1315 4136 1397 1388 4137 1396 1387 4138 1321 1311 4139 1398 1389 4140 1325 1315 4141 1328 1318 4142 1398 1389 4143 1397 1388 4144 1325 1315 4145 1399 1390 4146 1328 1318 4147 1332 1322 4148 1399 1390 4149 1398 1389 4150 1328 1318 4151 1400 1391 4152 1332 1322 4153 1336 1326 4154 1400 1391 4155 1399 1390 4156 1332 1322 4157 1401 1392 4158 1336 1326 4159 1339 1329 4160 1401 1392 4161 1400 1391 4162 1336 1326 4163 1402 1393 4164 1339 1329 4165 1343 1333 4166 1402 1393 4167 1401 1392 4168 1339 1329 4169 1403 1394 4170 1343 1333 4171 1346 1336 4172 1403 1394 4173 1402 1393 4174 1343 1333 4175 1404 1395 4176 1346 1336 4177 1351 1341 4178 1404 1395 4179 1403 1394 4180 1346 1336 4181 1405 1396 4182 1404 1395 4183 1351 1341 4184 1406 1397 4185 1407 1398 4186 1353 1343 4187 1352 1342 4188 1406 1397 4189 1353 1343 4190 1408 1399 4191 1263 1254 4192 1393 1384 4193 1408 1399 4194 1280 1271 4195 1263 1254 4196 1409 1400 4197 1393 1384 4198 1394 1385 4199 1409 1400 4200 1408 1399 4201 1393 1384 4202 1410 1401 4203 1394 1385 4204 1395 1386 4205 1410 1401 4206 1409 1400 4207 1394 1385 4208 1411 1402 4209 1395 1386 4210 1396 1387 4211 1411 1402 4212 1410 1401 4213 1395 1386 4214 1412 1403 4215 1396 1387 4216 1397 1388 4217 1413 1404 4218 1411 1402 4219 1396 1387 4220 1412 1403 4221 1413 1404 4222 1396 1387 4223 1414 1405 4224 1397 1388 4225 1398 1389 4226 1414 1405 4227 1412 1403 4228 1397 1388 4229 1415 1406 4230 1398 1389 4231 1399 1390 4232 1416 1407 4233 1414 1405 4234 1398 1389 4235 1417 1408 4236 1416 1407 4237 1398 1389 4238 1415 1406 4239 1417 1408 4240 1398 1389 4241 1418 1409 4242 1399 1390 4243 1400 1391 4244 1419 1410 4245 1415 1406 4246 1399 1390 4247 1418 1409 4248 1419 1410 4249 1399 1390 4250 1420 1411 4251 1400 1391 4252 1401 1392 4253 1420 1411 4254 1418 1409 4255 1400 1391 4256 1421 1412 4257 1401 1392 4258 1402 1393 4259 1421 1412 4260 1420 1411 4261 1401 1392 4262 1422 1413 4263 1402 1393 4264 1403 1394 4265 1422 1413 4266 1421 1412 4267 1402 1393 4268 1423 1414 4269 1403 1394 4270 1404 1395 4271 1423 1414 4272 1422 1413 4273 1403 1394 4274 1424 1415 4275 1404 1395 4276 1405 1396 4277 1424 1415 4278 1423 1414 4279 1404 1395 4280 1425 1416 4281 1424 1415 4282 1405 1396 4283 1426 1417 4284 1427 1418 4285 1407 1398 4286 1406 1397 4287 1426 1417 4288 1407 1398 4289 1428 1419 4290 1283 1273 4291 1429 1420 4292 1430 1421 4293 1283 1273 4294 1428 1419 4295 1281 1272 4296 1283 1273 4297 1430 1421 4298 1431 1422 4299 1429 1420 4300 1432 1423 4301 1428 1419 4302 1429 1420 4303 1431 1422 4304 1431 1422 4305 1432 1423 4306 1433 1424 4307 1434 1425 4308 1433 1424 4309 1435 1426 4310 1431 1422 4311 1433 1424 4312 1434 1425 4313 1436 1427 4314 1435 1426 4315 1437 1428 4316 1434 1425 4317 1435 1426 4318 1436 1427 4319 1436 1427 4320 1437 1428 4321 1438 1429 4322 1439 1430 4323 1438 1429 4324 1440 1431 4325 1436 1427 4326 1438 1429 4327 1439 1430 4328 1439 1430 4329 1440 1431 4330 1441 1432 4331 1442 1433 4332 1441 1432 4333 1443 1434 4334 1439 1430 4335 1441 1432 4336 1442 1433 4337 1444 1435 4338 1443 1434 4339 1445 1436 4340 1442 1433 4341 1443 1434 4342 1444 1435 4343 1444 1435 4344 1445 1436 4345 1446 1437 4346 1447 1438 4347 1446 1437 4348 1448 1439 4349 1444 1435 4350 1446 1437 4351 1447 1438 4352 1449 1440 4353 1448 1439 4354 1450 1441 4355 1447 1438 4356 1448 1439 4357 1449 1440 4358 1451 1442 4359 1450 1441 4360 1452 1443 4361 1449 1440 4362 1450 1441 4363 1451 1442 4364 1453 1444 4365 1452 1443 4366 1454 1445 4367 1451 1442 4368 1452 1443 4369 1453 1444 4370 1455 1446 4371 1454 1445 4372 1456 1447 4373 1453 1444 4374 1454 1445 4375 1455 1446 4376 1457 1448 4377 1456 1447 4378 1458 1449 4379 1455 1446 4380 1456 1447 4381 1457 1448 4382 1457 1448 4383 1458 1449 4384 1459 1450 4385 1457 1448 4386 1459 1450 4387 1460 1451 4388 1461 1452 4389 1462 1453 4390 1463 1454 4391 1426 1417 4392 1464 1455 4393 1427 1418 4394 1465 1456 4395 1460 1451 4396 1466 1457 4397 1467 1458 4398 1468 1459 4399 1462 1453 4400 1469 1460 4401 1470 1461 4402 1471 1462 4403 1467 1458 4404 1472 1463 4405 1468 1459 4406 1473 1464 4407 1471 1462 4408 1474 1465 4409 1469 1460 4410 1471 1462 4411 1473 1464 4412 1465 1456 4413 1457 1448 4414 1460 1451 4415 1461 1452 4416 1467 1458 4417 1462 1453 4418 1475 1466 4419 1455 1446 4420 1457 1448 4421 1465 1456 4422 1475 1466 4423 1457 1448 4424 1476 1467 4425 1453 1444 4426 1455 1446 4427 1477 1468 4428 1476 1467 4429 1455 1446 4430 1475 1466 4431 1477 1468 4432 1455 1446 4433 1478 1469 4434 1451 1442 4435 1453 1444 4436 1476 1467 4437 1478 1469 4438 1453 1444 4439 1479 1470 4440 1449 1440 4441 1451 1442 4442 1478 1469 4443 1479 1470 4444 1451 1442 4445 1480 1471 4446 1447 1438 4447 1449 1440 4448 1481 1472 4449 1480 1471 4450 1449 1440 4451 1479 1470 4452 1481 1472 4453 1449 1440 4454 1482 1473 4455 1444 1435 4456 1447 1438 4457 1480 1471 4458 1482 1473 4459 1447 1438 4460 1483 1474 4461 1442 1433 4462 1444 1435 4463 1484 1475 4464 1483 1474 4465 1444 1435 4466 1482 1473 4467 1484 1475 4468 1444 1435 4469 1485 1476 4470 1486 1477 4471 1442 1433 4472 1439 1430 4473 1442 1433 4474 1486 1477 4475 1483 1474 4476 1485 1476 4477 1442 1433 4478 1487 1478 4479 1488 1479 4480 1486 1477 4481 1436 1427 4482 1486 1477 4483 1488 1479 4484 1485 1476 4485 1487 1478 4486 1486 1477 4487 1436 1427 4488 1439 1430 4489 1486 1477 4490 1489 1480 4491 1490 1481 4492 1488 1479 4493 1434 1425 4494 1488 1479 4495 1490 1481 4496 1491 1482 4497 1489 1480 4498 1488 1479 4499 1487 1478 4500 1491 1482 4501 1488 1479 4502 1434 1425 4503 1436 1427 4504 1488 1479 4505 1492 1483 4506 1493 1484 4507 1490 1481 4508 1431 1422 4509 1490 1481 4510 1493 1484 4511 1489 1480 4512 1492 1483 4513 1490 1481 4514 1431 1422 4515 1434 1425 4516 1490 1481 4517 1494 1485 4518 1495 1486 4519 1493 1484 4520 1428 1419 4521 1493 1484 4522 1495 1486 4523 1496 1487 4524 1494 1485 4525 1493 1484 4526 1492 1483 4527 1496 1487 4528 1493 1484 4529 1428 1419 4530 1431 1422 4531 1493 1484 4532 1497 1488 4533 1498 1489 4534 1499 1489 4535 1500 1490 4536 1428 1419 4537 1495 1486 4538 1497 1488 4539 1501 1491 4540 1498 1489 4541 1502 1492 4542 1503 1493 4543 1504 1494 4544 1502 1492 4545 1505 1495 4546 1503 1493 4547 1506 1496 4548 1504 1494 4549 1507 1497 4550 1506 1496 4551 1502 1492 4552 1504 1494 4553 1506 1496 4554 1507 1497 4555 1508 1498 4556 1509 1499 4557 1508 1498 4558 1510 1500 4559 1509 1499 4560 1506 1496 4561 1508 1498 4562 1509 1499 4563 1510 1500 4564 1511 1501 4565 1512 1502 4566 1511 1501 4567 1513 1503 4568 1512 1502 4569 1509 1499 4570 1511 1501 4571 1514 1504 4572 1513 1503 4573 1515 1505 4574 1514 1504 4575 1512 1502 4576 1513 1503 4577 1516 1506 4578 1515 1505 4579 1517 1507 4580 1516 1506 4581 1514 1504 4582 1515 1505 4583 1518 1508 4584 1517 1507 4585 1519 1509 4586 1518 1508 4587 1516 1506 4588 1517 1507 4589 1518 1508 4590 1519 1509 4591 1520 1510 4592 1521 1511 4593 1520 1510 4594 1522 1512 4595 1521 1511 4596 1518 1508 4597 1520 1510 4598 1523 1513 4599 1522 1512 4600 1524 1514 4601 1523 1513 4602 1521 1511 4603 1522 1512 4604 1523 1513 4605 1524 1514 4606 1525 1515 4607 1526 1516 4608 1525 1515 4609 1527 1517 4610 1526 1516 4611 1523 1513 4612 1525 1515 4613 1526 1516 4614 1527 1517 4615 1528 1518 4616 1526 1516 4617 1528 1518 4618 1529 1519 4619 1469 1460 4620 1529 1519 4621 1470 1461 4622 1469 1460 4623 1526 1516 4624 1529 1519 4625 1500 1490 4626 1430 1421 4627 1428 1419 4628 1530 1520 4629 1531 1521 4630 1501 1491 4631 1530 1520 4632 1284 1274 4633 1531 1521 4634 1530 1520 4635 1501 1491 4636 1497 1488 4637 1530 1520 4638 1277 1268 4639 1284 1274 4640 1467 1458 4641 1532 1522 4642 1472 1463 4643 1473 1464 4644 1474 1465 4645 1533 1523 4646 1534 1524 4647 1535 1525 4648 1532 1522 4649 1536 1526 4650 1533 1523 4651 1537 1527 4652 1467 1458 4653 1534 1524 4654 1532 1522 4655 1536 1526 4656 1473 1464 4657 1533 1523 4658 1538 1528 4659 1539 1529 4660 1535 1525 4661 1536 1526 4662 1537 1527 4663 1540 1530 4664 1534 1524 4665 1538 1528 4666 1535 1525 4667 1538 1528 4668 1541 1531 4669 1539 1529 4670 1542 1532 4671 1540 1530 4672 1543 1533 4673 1542 1532 4674 1536 1526 4675 1540 1530 4676 1544 1534 4677 1545 1535 4678 1541 1531 4679 1542 1532 4680 1543 1533 4681 1546 1536 4682 1538 1528 4683 1544 1534 4684 1541 1531 4685 1547 1537 4686 1548 1538 4687 1545 1535 4688 1549 1539 4689 1546 1536 4690 1550 1540 4691 1544 1534 4692 1547 1537 4693 1545 1535 4694 1549 1539 4695 1542 1532 4696 1546 1536 4697 1551 1541 4698 1552 1542 4699 1548 1538 4700 1549 1539 4701 1550 1540 4702 1553 1543 4703 1547 1537 4704 1551 1541 4705 1548 1538 4706 1551 1541 4707 1554 1544 4708 1552 1542 4709 1555 1545 4710 1553 1543 4711 1556 1546 4712 1555 1545 4713 1549 1539 4714 1553 1543 4715 1557 1547 4716 1558 1548 4717 1554 1544 4718 1559 1549 4719 1556 1546 4720 1560 1550 4721 1551 1541 4722 1557 1547 4723 1554 1544 4724 1559 1549 4725 1555 1545 4726 1556 1546 4727 1561 1551 4728 1562 1552 4729 1558 1548 4730 1559 1549 4731 1560 1550 4732 1563 1553 4733 1557 1547 4734 1561 1551 4735 1558 1548 4736 1561 1551 4737 1564 1554 4738 1562 1552 4739 1565 1555 4740 1563 1553 4741 1566 1556 4742 1565 1555 4743 1559 1549 4744 1563 1553 4745 1567 1557 4746 1568 1558 4747 1564 1554 4748 1565 1555 4749 1566 1556 4750 1569 1559 4751 1561 1551 4752 1567 1557 4753 1564 1554 4754 1570 1560 4755 1571 1561 4756 1568 1558 4757 1572 1562 4758 1569 1559 4759 1573 1563 4760 1567 1557 4761 1570 1560 4762 1568 1558 4763 1572 1562 4764 1565 1555 4765 1569 1559 4766 1574 1564 4767 1575 1565 4768 1571 1561 4769 1572 1562 4770 1573 1563 4771 1576 1566 4772 1570 1560 4773 1574 1564 4774 1571 1561 4775 1574 1564 4776 1577 1567 4777 1575 1565 4778 1578 1568 4779 1576 1566 4780 1579 1569 4781 1578 1568 4782 1572 1562 4783 1576 1566 4784 1580 1570 4785 1581 1571 4786 1577 1567 4787 1578 1568 4788 1579 1569 4789 1582 1572 4790 1574 1564 4791 1580 1570 4792 1577 1567 4793 1583 1573 4794 1584 1574 4795 1581 1571 4796 1578 1568 4797 1582 1572 4798 1585 1575 4799 1580 1570 4800 1583 1573 4801 1581 1571 4802 1586 1576 4803 1587 1577 4804 1588 1578 4805 1589 1579 4806 1578 1568 4807 1585 1575 4808 1590 1580 4809 1591 1581 4810 1592 1582 4811 1586 1576 4812 1593 1583 4813 1587 1577 4814 1594 1584 4815 1583 1573 4816 1580 1570 4817 1586 1576 4818 1588 1578 4819 1595 1585 4820 1596 1586 4821 1580 1570 4822 1574 1564 4823 1597 1587 4824 1594 1584 4825 1580 1570 4826 1598 1588 4827 1597 1587 4828 1580 1570 4829 1596 1586 4830 1598 1588 4831 1580 1570 4832 1599 1589 4833 1574 1564 4834 1570 1560 4835 1599 1589 4836 1596 1586 4837 1574 1564 4838 1600 1590 4839 1570 1560 4840 1567 1557 4841 1600 1590 4842 1599 1589 4843 1570 1560 4844 1601 1591 4845 1567 1557 4846 1561 1551 4847 1601 1591 4848 1600 1590 4849 1567 1557 4850 1602 1592 4851 1561 1551 4852 1557 1547 4853 1602 1592 4854 1601 1591 4855 1561 1551 4856 1603 1593 4857 1557 1547 4858 1551 1541 4859 1603 1593 4860 1602 1592 4861 1557 1547 4862 1604 1594 4863 1551 1541 4864 1547 1537 4865 1605 1595 4866 1603 1593 4867 1551 1541 4868 1604 1594 4869 1605 1595 4870 1551 1541 4871 1606 1596 4872 1547 1537 4873 1544 1534 4874 1606 1596 4875 1604 1594 4876 1547 1537 4877 1607 1597 4878 1544 1534 4879 1538 1528 4880 1607 1597 4881 1606 1596 4882 1544 1534 4883 1608 1598 4884 1538 1528 4885 1534 1524 4886 1608 1598 4887 1607 1597 4888 1538 1528 4889 1609 1599 4890 1534 1524 4891 1467 1458 4892 1609 1599 4893 1608 1598 4894 1534 1524 4895 1461 1452 4896 1609 1599 4897 1467 1458 4898 1610 1600 4899 1595 1585 4900 1611 1601 4901 1586 1576 4902 1595 1585 4903 1610 1600 4904 1612 1602 4905 1597 1587 4906 1598 1588 4907 1610 1600 4908 1611 1601 4909 1613 1603 4910 1614 1604 4911 1598 1588 4912 1596 1586 4913 1615 1605 4914 1612 1602 4915 1598 1588 4916 1616 1606 4917 1615 1605 4918 1598 1588 4919 1614 1604 4920 1616 1606 4921 1598 1588 4922 1617 1607 4923 1596 1586 4924 1599 1589 4925 1617 1607 4926 1614 1604 4927 1596 1586 4928 1618 1608 4929 1599 1589 4930 1600 1590 4931 1619 1609 4932 1617 1607 4933 1599 1589 4934 1618 1608 4935 1619 1609 4936 1599 1589 4937 1620 1610 4938 1600 1590 4939 1601 1591 4940 1620 1610 4941 1618 1608 4942 1600 1590 4943 1621 1611 4944 1601 1591 4945 1602 1592 4946 1622 1612 4947 1620 1610 4948 1601 1591 4949 1621 1611 4950 1622 1612 4951 1601 1591 4952 1623 1613 4953 1624 1614 4954 1625 1615 4955 1626 1616 4956 1627 1617 4957 1624 1614 4958 1623 1613 4959 1626 1616 4960 1624 1614 4961 1628 1618 4962 1625 1615 4963 1629 1619 4964 1628 1618 4965 1623 1613 4966 1625 1615 4967 1628 1618 4968 1629 1619 4969 1630 1620 4970 1631 1621 4971 1630 1620 4972 1632 1622 4973 1631 1621 4974 1628 1618 4975 1630 1620 4976 1633 1623 4977 1632 1622 4978 1634 1624 4979 1633 1623 4980 1631 1621 4981 1632 1622 4982 1635 1625 4983 1634 1624 4984 1636 1626 4985 1635 1625 4986 1633 1623 4987 1634 1624 4988 1637 1627 4989 1636 1626 4990 1638 1628 4991 1637 1627 4992 1635 1625 4993 1636 1626 4994 1426 1417 4995 1638 1628 4996 1464 1455 4997 1426 1417 4998 1637 1627 4999 1638 1628 5000 1639 1629 5001 1613 1603 5002 1640 1630 5003 1639 1629 5004 1610 1600 5005 1613 1603 5006 1641 1631 5007 1642 1632 5008 1643 1633 5009 1644 1634 5010 1639 1629 5011 1640 1630 5012 1641 1631 5013 1645 1635 5014 1642 1632 5015 1646 1636 5016 1643 1633 5017 1647 1637 5018 1646 1636 5019 1641 1631 5020 1643 1633 5021 1648 1638 5022 1647 1637 5023 1649 1639 5024 1648 1638 5025 1646 1636 5026 1647 1637 5027 1648 1638 5028 1649 1639 5029 1650 1640 5030 1651 1641 5031 1650 1640 5032 1652 1642 5033 1651 1641 5034 1648 1638 5035 1650 1640 5036 1653 1643 5037 1652 1642 5038 1654 1644 5039 1653 1643 5040 1651 1641 5041 1652 1642 5042 1653 1643 5043 1654 1644 5044 1655 1645 5045 1626 1616 5046 1655 1645 5047 1627 1617 5048 1626 1616 5049 1653 1643 5050 1655 1645 5051 1656 1646 5052 1657 1646 5053 1658 1646 5054 1659 1647 5055 1660 1647 5056 1657 1647 5057 1661 1648 5058 1659 1648 5059 1657 1648 5060 1656 1648 5061 1661 1648 5062 1657 1648 5063 1662 1649 5064 1658 1649 5065 1663 1649 5066 1664 1650 5067 1656 1650 5068 1658 1650 5069 1662 1648 5070 1664 1648 5071 1658 1648 5072 1665 1648 5073 1663 1648 5074 1666 1648 5075 1665 1651 5076 1662 1651 5077 1663 1651 5078 1667 1652 5079 1666 1652 5080 1668 1652 5081 1667 1653 5082 1665 1653 5083 1666 1653 5084 1669 1648 5085 1668 1648 5086 1670 1648 5087 1669 1648 5088 1667 1648 5089 1668 1648 5090 1671 1648 5091 1670 1648 5092 1672 1648 5093 1673 1648 5094 1669 1648 5095 1670 1648 5096 1671 1648 5097 1673 1648 5098 1670 1648 5099 1674 1648 5100 1672 1648 5101 1675 1648 5102 1676 1648 5103 1671 1648 5104 1672 1648 5105 1674 1654 5106 1676 1654 5107 1672 1654 5108 1677 1648 5109 1675 1648 5110 1678 1648 5111 1679 1655 5112 1674 1655 5113 1675 1655 5114 1677 1648 5115 1679 1648 5116 1675 1648 5117 1680 1648 5118 1678 1648 5119 1681 1648 5120 1680 1648 5121 1682 1648 5122 1678 1648 5123 1677 1648 5124 1678 1648 5125 1682 1648 5126 1590 1580 5127 1683 1656 5128 1591 1581 5129 1684 1657 5130 1685 1658 5131 1505 1495 5132 1530 1520 5133 1497 1488 5134 1686 1659 5135 1502 1492 5136 1684 1657 5137 1505 1495 5138 1684 1657 5139 1687 1660 5140 1685 1658 5141 1688 1661 5142 1686 1659 5143 1689 1662 5144 1688 1661 5145 1530 1520 5146 1686 1659 5147 1690 1663 5148 1691 1664 5149 1687 1660 5150 1692 1665 5151 1689 1662 5152 1693 1666 5153 1684 1657 5154 1690 1663 5155 1687 1660 5156 1692 1665 5157 1688 1661 5158 1689 1662 5159 1690 1663 5160 1694 1667 5161 1691 1664 5162 1695 1668 5163 1693 1666 5164 1696 1669 5165 1695 1668 5166 1692 1665 5167 1693 1666 5168 1697 1670 5169 1698 1671 5170 1694 1667 5171 1699 1672 5172 1696 1669 5173 1700 1673 5174 1690 1663 5175 1697 1670 5176 1694 1667 5177 1699 1672 5178 1695 1668 5179 1696 1669 5180 1697 1670 5181 1701 1674 5182 1698 1671 5183 1702 1675 5184 1700 1673 5185 1703 1676 5186 1702 1675 5187 1699 1672 5188 1700 1673 5189 1704 1677 5190 1705 1678 5191 1701 1674 5192 1706 1679 5193 1703 1676 5194 1707 1680 5195 1697 1670 5196 1704 1677 5197 1701 1674 5198 1706 1679 5199 1702 1675 5200 1703 1676 5201 1708 1681 5202 1709 1682 5203 1705 1678 5204 1706 1679 5205 1707 1680 5206 1710 1683 5207 1704 1677 5208 1708 1681 5209 1705 1678 5210 1708 1681 5211 1711 1684 5212 1709 1682 5213 1712 1685 5214 1710 1683 5215 1713 1686 5216 1712 1685 5217 1706 1679 5218 1710 1683 5219 1714 1687 5220 1715 1688 5221 1711 1684 5222 1716 1689 5223 1713 1686 5224 1717 1690 5225 1708 1681 5226 1714 1687 5227 1711 1684 5228 1716 1689 5229 1712 1685 5230 1713 1686 5231 1714 1687 5232 1718 1691 5233 1715 1688 5234 1719 1692 5235 1717 1690 5236 1720 1693 5237 1719 1692 5238 1716 1689 5239 1717 1690 5240 1721 1694 5241 1722 1695 5242 1718 1691 5243 1723 1696 5244 1720 1693 5245 1724 1697 5246 1714 1687 5247 1721 1694 5248 1718 1691 5249 1723 1696 5250 1719 1692 5251 1720 1693 5252 1721 1694 5253 1725 1698 5254 1722 1695 5255 1726 1699 5256 1724 1697 5257 1727 1700 5258 1726 1699 5259 1723 1696 5260 1724 1697 5261 1728 1701 5262 1729 1702 5263 1725 1698 5264 1730 1703 5265 1727 1700 5266 1731 1704 5267 1721 1694 5268 1728 1701 5269 1725 1698 5270 1730 1703 5271 1726 1699 5272 1727 1700 5273 1728 1701 5274 1732 1705 5275 1729 1702 5276 1733 1706 5277 1731 1704 5278 1734 1707 5279 1733 1706 5280 1730 1703 5281 1731 1704 5282 1735 1708 5283 1736 1709 5284 1732 1705 5285 1737 1710 5286 1734 1707 5287 1738 1711 5288 1728 1701 5289 1735 1708 5290 1732 1705 5291 1737 1710 5292 1733 1706 5293 1734 1707 5294 1739 1712 5295 1740 1713 5296 1736 1709 5297 1737 1710 5298 1738 1711 5299 1741 1714 5300 1735 1708 5301 1739 1712 5302 1736 1709 5303 1742 1715 5304 1743 1716 5305 1744 1717 5306 1745 1718 5307 1743 1716 5308 1742 1715 5309 1746 1719 5310 1747 1720 5311 1748 1721 5312 1737 1710 5313 1741 1714 5314 1749 1722 5315 1750 1723 5316 1751 1723 5317 1752 1723 5318 1753 1724 5319 1754 1724 5320 1751 1724 5321 1755 1648 5322 1751 1648 5323 1750 1648 5324 1755 1648 5325 1753 1648 5326 1751 1648 5327 1756 1725 5328 1752 1725 5329 1757 1725 5330 1756 1648 5331 1750 1648 5332 1752 1648 5333 1758 1648 5334 1757 1648 5335 1759 1648 5336 1758 1648 5337 1756 1648 5338 1757 1648 5339 1760 1726 5340 1759 1726 5341 1761 1726 5342 1760 1727 5343 1758 1727 5344 1759 1727 5345 1762 1648 5346 1761 1648 5347 1763 1648 5348 1762 1728 5349 1760 1728 5350 1761 1728 5351 1764 1648 5352 1763 1648 5353 1765 1648 5354 1764 1648 5355 1762 1648 5356 1763 1648 5357 1766 1648 5358 1765 1648 5359 1767 1648 5360 1768 1729 5361 1764 1729 5362 1765 1729 5363 1766 1648 5364 1768 1648 5365 1765 1648 5366 1769 1730 5367 1767 1730 5368 1770 1730 5369 1771 1731 5370 1766 1731 5371 1767 1731 5372 1769 1732 5373 1771 1732 5374 1767 1732 5375 1772 1733 5376 1770 1733 5377 1773 1733 5378 1774 1734 5379 1769 1734 5380 1770 1734 5381 1772 1735 5382 1774 1735 5383 1770 1735 5384 1775 1736 5385 1773 1736 5386 1776 1736 5387 1777 1737 5388 1773 1737 5389 1775 1737 5390 1772 1648 5391 1773 1648 5392 1777 1648 5393 1778 1648 5394 1777 1648 5395 1779 1648 5396 1778 1648 5397 1772 1648 5398 1777 1648 5399 1780 1738 5400 1779 1738 5401 1781 1738 5402 1780 1648 5403 1778 1648 5404 1779 1648 5405 1782 1739 5406 1781 1739 5407 1783 1739 5408 1782 1648 5409 1780 1648 5410 1781 1648 5411 1784 1648 5412 1783 1648 5413 1785 1648 5414 1784 1740 5415 1782 1740 5416 1783 1740 5417 1784 1741 5418 1785 1741 5419 1786 1741 5420 1787 1742 5421 1786 1742 5422 1788 1742 5423 1787 1648 5424 1784 1648 5425 1786 1648 5426 1789 1743 5427 1788 1743 5428 1790 1743 5429 1789 1648 5430 1787 1648 5431 1788 1648 5432 1791 1744 5433 1790 1744 5434 1660 1744 5435 1791 1648 5436 1789 1648 5437 1790 1648 5438 1659 1745 5439 1791 1745 5440 1660 1745 5441 1792 1648 5442 1793 1648 5443 1754 1648 5444 1794 1746 5445 1742 1715 5446 1795 1747 5447 1753 1748 5448 1792 1748 5449 1754 1748 5450 1796 1749 5451 1745 1718 5452 1742 1715 5453 1794 1746 5454 1796 1749 5455 1742 1715 5456 1797 1648 5457 1798 1648 5458 1793 1648 5459 1799 1750 5460 1795 1747 5461 1800 1751 5462 1792 1648 5463 1797 1648 5464 1793 1648 5465 1801 1752 5466 1794 1746 5467 1795 1747 5468 1799 1750 5469 1801 1752 5470 1795 1747 5471 1802 1648 5472 1803 1648 5473 1798 1648 5474 1804 1753 5475 1800 1751 5476 1805 1754 5477 1797 1648 5478 1802 1648 5479 1798 1648 5480 1806 1755 5481 1799 1750 5482 1800 1751 5483 1804 1753 5484 1806 1755 5485 1800 1751 5486 1807 1756 5487 1808 1756 5488 1803 1756 5489 1809 1757 5490 1805 1754 5491 1810 1758 5492 1802 1648 5493 1807 1648 5494 1803 1648 5495 1811 1759 5496 1804 1753 5497 1805 1754 5498 1809 1757 5499 1811 1759 5500 1805 1754 5501 1812 1648 5502 1813 1648 5503 1808 1648 5504 1814 1760 5505 1810 1758 5506 1815 1761 5507 1807 1648 5508 1812 1648 5509 1808 1648 5510 1816 1762 5511 1809 1757 5512 1810 1758 5513 1814 1760 5514 1816 1762 5515 1810 1758 5516 1817 1763 5517 1682 1763 5518 1813 1763 5519 1818 1764 5520 1815 1761 5521 1819 1765 5522 1820 1648 5523 1817 1648 5524 1813 1648 5525 1812 1766 5526 1820 1766 5527 1813 1766 5528 1821 1767 5529 1814 1760 5530 1815 1761 5531 1818 1764 5532 1821 1767 5533 1815 1761 5534 1822 1768 5535 1819 1765 5536 1683 1656 5537 1817 1648 5538 1677 1648 5539 1682 1648 5540 1823 1769 5541 1818 1764 5542 1819 1765 5543 1822 1768 5544 1823 1769 5545 1819 1765 5546 1824 1770 5547 1822 1768 5548 1683 1656 5549 1590 1580 5550 1824 1770 5551 1683 1656 5552 1825 1771 5553 1826 1772 5554 1827 1773 5555 1828 1774 5556 1829 1775 5557 1830 1776 5558 1828 1774 5559 1830 1776 5560 1831 1777 5561 1832 1778 5562 1827 1773 5563 1833 1779 5564 1834 1780 5565 1825 1771 5566 1827 1773 5567 1832 1778 5568 1834 1780 5569 1827 1773 5570 1835 1781 5571 1833 1779 5572 1836 1782 5573 1835 1781 5574 1832 1778 5575 1833 1779 5576 1837 1783 5577 1836 1782 5578 1838 1784 5579 1837 1783 5580 1835 1781 5581 1836 1782 5582 1839 1785 5583 1838 1784 5584 1840 1786 5585 1839 1785 5586 1837 1783 5587 1838 1784 5588 1841 1787 5589 1840 1786 5590 1842 1788 5591 1841 1787 5592 1839 1785 5593 1840 1786 5594 1841 1787 5595 1842 1788 5596 1843 1789 5597 1844 1790 5598 1843 1789 5599 1845 1791 5600 1844 1790 5601 1841 1787 5602 1843 1789 5603 1846 1792 5604 1845 1791 5605 1847 1793 5606 1846 1792 5607 1844 1790 5608 1845 1791 5609 1848 1794 5610 1847 1793 5611 1849 1795 5612 1848 1794 5613 1846 1792 5614 1847 1793 5615 1850 1796 5616 1849 1795 5617 1851 1797 5618 1850 1796 5619 1848 1794 5620 1849 1795 5621 1852 1798 5622 1851 1797 5623 1853 1799 5624 1852 1798 5625 1850 1796 5626 1851 1797 5627 1854 1800 5628 1853 1799 5629 1855 1801 5630 1854 1800 5631 1852 1798 5632 1853 1799 5633 1856 1802 5634 1855 1801 5635 1857 1803 5636 1856 1802 5637 1854 1800 5638 1855 1801 5639 1858 1804 5640 1857 1803 5641 1859 1805 5642 1858 1804 5643 1856 1802 5644 1857 1803 5645 1860 1806 5646 1859 1805 5647 1861 1807 5648 1862 1808 5649 1858 1804 5650 1859 1805 5651 1860 1806 5652 1862 1808 5653 1859 1805 5654 1863 1809 5655 1861 1807 5656 1864 1810 5657 1863 1809 5658 1860 1806 5659 1861 1807 5660 1865 1811 5661 1864 1810 5662 1866 1812 5663 1865 1811 5664 1863 1809 5665 1864 1810 5666 1867 1813 5667 1866 1812 5668 1868 1814 5669 1867 1813 5670 1865 1811 5671 1866 1812 5672 1869 1815 5673 1868 1814 5674 1870 1816 5675 1869 1815 5676 1867 1813 5677 1868 1814 5678 1869 1815 5679 1870 1816 5680 1871 1817 5681 1872 1818 5682 1873 1819 5683 1874 1820 5684 1875 1821 5685 1869 1815 5686 1871 1817 5687 1876 1822 5688 1874 1820 5689 1877 1823 5690 1878 1824 5691 1872 1818 5692 1874 1820 5693 1876 1822 5694 1878 1824 5695 1874 1820 5696 1879 1825 5697 1877 1823 5698 1880 1826 5699 1879 1825 5700 1876 1822 5701 1877 1823 5702 1881 1827 5703 1880 1826 5704 1882 1828 5705 1881 1827 5706 1879 1825 5707 1880 1826 5708 1883 1829 5709 1882 1828 5710 1884 1830 5711 1883 1829 5712 1881 1827 5713 1882 1828 5714 1885 1831 5715 1884 1830 5716 1886 1832 5717 1885 1831 5718 1883 1829 5719 1884 1830 5720 1885 1831 5721 1886 1832 5722 1887 1833 5723 1888 1834 5724 1887 1833 5725 1889 1835 5726 1888 1834 5727 1885 1831 5728 1887 1833 5729 1890 1836 5730 1889 1835 5731 1891 1837 5732 1890 1836 5733 1888 1834 5734 1889 1835 5735 1892 1838 5736 1891 1837 5737 1893 1839 5738 1892 1838 5739 1890 1836 5740 1891 1837 5741 1894 1840 5742 1893 1839 5743 1895 1841 5744 1894 1840 5745 1892 1838 5746 1893 1839 5747 1896 1842 5748 1895 1841 5749 1897 1843 5750 1896 1842 5751 1894 1840 5752 1895 1841 5753 1898 1844 5754 1897 1843 5755 1899 1845 5756 1898 1844 5757 1896 1842 5758 1897 1843 5759 1900 1846 5760 1899 1845 5761 1901 1847 5762 1900 1846 5763 1898 1844 5764 1899 1845 5765 1902 1848 5766 1901 1847 5767 1903 1849 5768 1902 1848 5769 1900 1846 5770 1901 1847 5771 1904 1850 5772 1903 1849 5773 1905 1851 5774 1906 1852 5775 1902 1848 5776 1903 1849 5777 1904 1850 5778 1906 1852 5779 1903 1849 5780 1907 1853 5781 1905 1851 5782 1908 1854 5783 1907 1853 5784 1904 1850 5785 1905 1851 5786 1909 1855 5787 1908 1854 5788 1910 1856 5789 1909 1855 5790 1907 1853 5791 1908 1854 5792 1911 1857 5793 1910 1856 5794 1912 1858 5795 1911 1857 5796 1909 1855 5797 1910 1856 5798 1828 1774 5799 1912 1858 5800 1829 1775 5801 1828 1774 5802 1911 1857 5803 1912 1858 5804 1913 1859 5805 1748 1721 5806 1914 1860 5807 1913 1859 5808 1746 1719 5809 1748 1721 5810 1915 1861 5811 1914 1860 5812 1916 1862 5813 1915 1861 5814 1913 1859 5815 1914 1860 5816 1917 1863 5817 1916 1862 5818 1918 1864 5819 1917 1863 5820 1915 1861 5821 1916 1862 5822 1919 1865 5823 1918 1864 5824 1920 1866 5825 1919 1865 5826 1917 1863 5827 1918 1864 5828 1919 1865 5829 1920 1866 5830 1921 1867 5831 1922 1868 5832 1921 1867 5833 1923 1869 5834 1922 1868 5835 1919 1865 5836 1921 1867 5837 1924 1870 5838 1923 1869 5839 1925 1871 5840 1924 1870 5841 1922 1868 5842 1923 1869 5843 1926 1872 5844 1925 1871 5845 1927 1873 5846 1926 1872 5847 1924 1870 5848 1925 1871 5849 1928 1874 5850 1927 1873 5851 1929 1875 5852 1928 1874 5853 1926 1872 5854 1927 1873 5855 1930 1876 5856 1929 1875 5857 1931 1877 5858 1930 1876 5859 1928 1874 5860 1929 1875 5861 1930 1876 5862 1931 1877 5863 1932 1878 5864 1933 1879 5865 1932 1878 5866 1934 1880 5867 1933 1879 5868 1930 1876 5869 1932 1878 5870 1935 1881 5871 1934 1880 5872 1936 1882 5873 1935 1881 5874 1933 1879 5875 1934 1880 5876 1937 1883 5877 1936 1882 5878 1938 1884 5879 1937 1883 5880 1935 1881 5881 1936 1882 5882 1939 1885 5883 1938 1884 5884 1940 1886 5885 1939 1885 5886 1937 1883 5887 1938 1884 5888 1586 1576 5889 1940 1886 5890 1593 1583 5891 1586 1576 5892 1939 1885 5893 1940 1886 5894 1941 1887 5895 1942 1888 5896 1610 1600 5897 1586 1576 5898 1610 1600 5899 1942 1888 5900 1639 1629 5901 1941 1887 5902 1610 1600 5903 1943 1889 5904 1944 1890 5905 1942 1888 5906 1939 1885 5907 1942 1888 5908 1944 1890 5909 1941 1887 5910 1943 1889 5911 1942 1888 5912 1586 1576 5913 1942 1888 5914 1939 1885 5915 1945 1891 5916 1946 1892 5917 1944 1890 5918 1937 1883 5919 1944 1890 5920 1946 1892 5921 1943 1889 5922 1945 1891 5923 1944 1890 5924 1939 1885 5925 1944 1890 5926 1937 1883 5927 1947 1893 5928 1948 1894 5929 1946 1892 5930 1935 1881 5931 1946 1892 5932 1948 1894 5933 1945 1891 5934 1947 1893 5935 1946 1892 5936 1937 1883 5937 1946 1892 5938 1935 1881 5939 1949 1895 5940 1950 1896 5941 1948 1894 5942 1933 1879 5943 1948 1894 5944 1950 1896 5945 1947 1893 5946 1949 1895 5947 1948 1894 5948 1935 1881 5949 1948 1894 5950 1933 1879 5951 1951 1897 5952 1952 1898 5953 1950 1896 5954 1930 1876 5955 1950 1896 5956 1952 1898 5957 1949 1895 5958 1951 1897 5959 1950 1896 5960 1933 1879 5961 1950 1896 5962 1930 1876 5963 1953 1899 5964 1954 1900 5965 1952 1898 5966 1928 1874 5967 1952 1898 5968 1954 1900 5969 1951 1897 5970 1953 1899 5971 1952 1898 5972 1930 1876 5973 1952 1898 5974 1928 1874 5975 1955 1901 5976 1956 1902 5977 1954 1900 5978 1926 1872 5979 1954 1900 5980 1956 1902 5981 1953 1899 5982 1955 1901 5983 1954 1900 5984 1928 1874 5985 1954 1900 5986 1926 1872 5987 1957 1903 5988 1958 1904 5989 1956 1902 5990 1924 1870 5991 1956 1902 5992 1958 1904 5993 1955 1901 5994 1957 1903 5995 1956 1902 5996 1926 1872 5997 1956 1902 5998 1924 1870 5999 1959 1905 6000 1960 1906 6001 1958 1904 6002 1922 1868 6003 1958 1904 6004 1960 1906 6005 1957 1903 6006 1959 1905 6007 1958 1904 6008 1924 1870 6009 1958 1904 6010 1922 1868 6011 1961 1907 6012 1962 1908 6013 1960 1906 6014 1919 1865 6015 1960 1906 6016 1962 1908 6017 1959 1905 6018 1961 1907 6019 1960 1906 6020 1922 1868 6021 1960 1906 6022 1919 1865 6023 1963 1909 6024 1964 1910 6025 1962 1908 6026 1917 1863 6027 1962 1908 6028 1964 1910 6029 1961 1907 6030 1963 1909 6031 1962 1908 6032 1919 1865 6033 1962 1908 6034 1917 1863 6035 1965 1911 6036 1966 1912 6037 1964 1910 6038 1915 1861 6039 1964 1910 6040 1966 1912 6041 1963 1909 6042 1965 1911 6043 1964 1910 6044 1917 1863 6045 1964 1910 6046 1915 1861 6047 1967 1913 6048 1968 1914 6049 1966 1912 6050 1913 1859 6051 1966 1912 6052 1968 1914 6053 1969 1915 6054 1967 1913 6055 1966 1912 6056 1965 1911 6057 1969 1915 6058 1966 1912 6059 1915 1861 6060 1966 1912 6061 1913 1859 6062 1970 1916 6063 1971 1917 6064 1972 1918 6065 1913 1859 6066 1968 1914 6067 1746 1719 6068 1973 1919 6069 1749 1722 6070 1971 1917 6071 1973 1919 6072 1971 1917 6073 1970 1916 6074 785 776 6075 1967 1913 6076 1969 1915 6077 787 778 6078 1972 1918 6079 780 771 6080 787 778 6081 1970 1916 6082 1972 1918 6083 1974 1920 6084 1969 1915 6085 1965 1911 6086 783 774 6087 785 776 6088 1969 1915 6089 1974 1920 6090 783 774 6091 1969 1915 6092 1975 1921 6093 1965 1911 6094 1963 1909 6095 1975 1921 6096 1974 1920 6097 1965 1911 6098 1976 1922 6099 1963 1909 6100 1961 1907 6101 1976 1922 6102 1975 1921 6103 1963 1909 6104 1977 1923 6105 1961 1907 6106 1959 1905 6107 1977 1923 6108 1976 1922 6109 1961 1907 6110 161 161 6111 1959 1905 6112 1957 1903 6113 161 161 6114 1977 1923 6115 1959 1905 6116 155 155 6117 1957 1903 6118 1955 1901 6119 155 155 6120 161 161 6121 1957 1903 6122 152 152 6123 1955 1901 6124 1953 1899 6125 152 152 6126 155 155 6127 1955 1901 6128 54 54 6129 1953 1899 6130 1951 1897 6131 54 54 6132 152 152 6133 1953 1899 6134 57 57 6135 1951 1897 6136 1949 1895 6137 57 57 6138 54 54 6139 1951 1897 6140 1978 1924 6141 1949 1895 6142 1947 1893 6143 1979 1925 6144 57 57 6145 1949 1895 6146 1978 1924 6147 1979 1925 6148 1949 1895 6149 1980 1926 6150 1947 1893 6151 1945 1891 6152 1980 1926 6153 1978 1924 6154 1947 1893 6155 1981 1927 6156 1945 1891 6157 1943 1889 6158 1982 1928 6159 1980 1926 6160 1945 1891 6161 1981 1927 6162 1982 1928 6163 1945 1891 6164 1983 1929 6165 1984 1930 6166 1985 1931 6167 1983 1929 6168 1986 1932 6169 1984 1930 6170 1987 1933 6171 1985 1931 6172 1988 1934 6173 1987 1933 6174 1983 1929 6175 1985 1931 6176 1644 1634 6177 1989 1935 6178 1639 1629 6179 1987 1933 6180 1988 1934 6181 1990 1936 6182 1991 1937 6183 1992 1938 6184 1645 1635 6185 1987 1933 6186 1990 1936 6187 1993 1939 6188 1641 1631 6189 1991 1937 6190 1645 1635 6191 1737 1710 6192 1749 1722 6193 1973 1919 6194 1994 1940 6195 783 774 6196 1974 1920 6197 1994 1940 6198 786 777 6199 783 774 6200 1995 1941 6201 1974 1920 6202 1975 1921 6203 1995 1941 6204 1994 1940 6205 1974 1920 6206 1996 1942 6207 1975 1921 6208 1976 1922 6209 1996 1942 6210 1995 1941 6211 1975 1921 6212 1997 1943 6213 1976 1922 6214 1977 1923 6215 1998 1944 6216 1996 1942 6217 1976 1922 6218 1997 1943 6219 1998 1944 6220 1976 1922 6221 162 162 6222 1977 1923 6223 161 161 6224 1999 1945 6225 1997 1943 6226 1977 1923 6227 162 162 6228 1999 1945 6229 1977 1923 6230 48 48 6231 53 53 6232 2000 1946 6233 2001 1947 6234 2000 1946 6235 2002 1948 6236 2001 1947 6237 48 48 6238 2000 1946 6239 2003 1949 6240 2002 1948 6241 2004 1950 6242 2003 1949 6243 2001 1947 6244 2002 1948 6245 1983 1929 6246 2004 1950 6247 1986 1932 6248 1983 1929 6249 2003 1949 6250 2004 1950 6251 748 739 6252 763 754 6253 2005 1951 6254 2006 1952 6255 2005 1951 6256 2007 1953 6257 748 739 6258 2005 1951 6259 2006 1952 6260 2006 1952 6261 2007 1953 6262 2008 1954 6263 2009 1955 6264 2008 1954 6265 2010 1956 6266 2006 1952 6267 2008 1954 6268 2009 1955 6269 2011 1957 6270 2010 1956 6271 2012 1958 6272 2009 1955 6273 2010 1956 6274 2011 1957 6275 2011 1957 6276 2012 1958 6277 2013 1959 6278 163 163 6279 2013 1959 6280 164 164 6281 2011 1957 6282 2013 1959 6283 163 163 6284 2014 1960 6285 1993 1939 6286 2015 1961 6287 2014 1960 6288 1987 1933 6289 1993 1939 6290 2016 1962 6291 1641 1631 6292 1646 1636 6293 2016 1962 6294 2017 1963 6295 1641 1631 6296 2014 1960 6297 2015 1961 6298 2018 1964 6299 2019 1965 6300 1646 1636 6301 1648 1638 6302 2019 1965 6303 2016 1962 6304 1646 1636 6305 2020 1966 6306 1648 1638 6307 1651 1641 6308 2020 1966 6309 2019 1965 6310 1648 1638 6311 2021 1967 6312 1651 1641 6313 1653 1643 6314 2021 1967 6315 2020 1966 6316 1651 1641 6317 2022 1968 6318 1653 1643 6319 1626 1616 6320 2022 1968 6321 2021 1967 6322 1653 1643 6323 2023 1969 6324 1626 1616 6325 1623 1613 6326 2023 1969 6327 2022 1968 6328 1626 1616 6329 2024 1970 6330 1623 1613 6331 1628 1618 6332 2024 1970 6333 2023 1969 6334 1623 1613 6335 2025 1971 6336 1628 1618 6337 1631 1621 6338 2025 1971 6339 2024 1970 6340 1628 1618 6341 2026 1972 6342 1631 1621 6343 1633 1623 6344 2026 1972 6345 2025 1971 6346 1631 1621 6347 2027 1973 6348 1633 1623 6349 1635 1625 6350 2027 1973 6351 2026 1972 6352 1633 1623 6353 2028 1974 6354 1635 1625 6355 1637 1627 6356 2028 1974 6357 2027 1973 6358 1635 1625 6359 1406 1397 6360 1637 1627 6361 1426 1417 6362 1406 1397 6363 2028 1974 6364 1637 1627 6365 2016 1962 6366 2029 1975 6367 2017 1963 6368 2014 1960 6369 2018 1964 6370 2030 1976 6371 2016 1962 6372 2031 1977 6373 2029 1975 6374 2032 1978 6375 2030 1976 6376 2033 1979 6377 2032 1978 6378 2014 1960 6379 2030 1976 6380 2034 1980 6381 2031 1977 6382 2016 1962 6383 2034 1980 6384 2035 1981 6385 2031 1977 6386 2032 1978 6387 2033 1979 6388 2036 1982 6389 2037 1983 6390 2016 1962 6391 2019 1965 6392 2037 1983 6393 2034 1980 6394 2016 1962 6395 2038 1984 6396 2019 1965 6397 2020 1966 6398 2038 1984 6399 2037 1983 6400 2019 1965 6401 2039 1985 6402 2020 1966 6403 2021 1967 6404 2039 1985 6405 2038 1984 6406 2020 1966 6407 2040 1986 6408 2021 1967 6409 2022 1968 6410 2040 1986 6411 2039 1985 6412 2021 1967 6413 2041 1987 6414 2022 1968 6415 2023 1969 6416 2041 1987 6417 2040 1986 6418 2022 1968 6419 2042 1988 6420 2023 1969 6421 2024 1970 6422 2042 1988 6423 2041 1987 6424 2023 1969 6425 2043 1989 6426 2024 1970 6427 2025 1971 6428 2043 1989 6429 2042 1988 6430 2024 1970 6431 2044 1990 6432 2025 1971 6433 2026 1972 6434 2044 1990 6435 2043 1989 6436 2025 1971 6437 2045 1991 6438 2026 1972 6439 2027 1973 6440 2045 1991 6441 2044 1990 6442 2026 1972 6443 2046 1992 6444 2027 1973 6445 2028 1974 6446 2046 1992 6447 2045 1991 6448 2027 1973 6449 1352 1342 6450 2028 1974 6451 1406 1397 6452 1352 1342 6453 2046 1992 6454 2028 1974 6455 2034 1980 6456 2047 1993 6457 2035 1981 6458 2032 1978 6459 2036 1982 6460 2048 1994 6461 2034 1980 6462 2049 1995 6463 2047 1993 6464 2050 1996 6465 2048 1994 6466 2051 1997 6467 2050 1996 6468 2032 1978 6469 2048 1994 6470 2052 1998 6471 2049 1995 6472 2034 1980 6473 2052 1998 6474 2053 1999 6475 2049 1995 6476 2050 1996 6477 2051 1997 6478 2054 2000 6479 2055 2001 6480 2034 1980 6481 2037 1983 6482 2055 2001 6483 2052 1998 6484 2034 1980 6485 2056 2002 6486 2037 1983 6487 2038 1984 6488 2057 2003 6489 2055 2001 6490 2037 1983 6491 2056 2002 6492 2057 2003 6493 2037 1983 6494 2058 2004 6495 2038 1984 6496 2039 1985 6497 2059 2005 6498 2056 2002 6499 2038 1984 6500 2058 2004 6501 2059 2005 6502 2038 1984 6503 2060 2006 6504 2039 1985 6505 2040 1986 6506 2060 2006 6507 2058 2004 6508 2039 1985 6509 2061 2007 6510 2040 1986 6511 2041 1987 6512 2062 2008 6513 2060 2006 6514 2040 1986 6515 2061 2007 6516 2062 2008 6517 2040 1986 6518 2063 2009 6519 2041 1987 6520 2042 1988 6521 2064 2010 6522 2061 2007 6523 2041 1987 6524 2063 2009 6525 2064 2010 6526 2041 1987 6527 2065 2011 6528 2042 1988 6529 2043 1989 6530 2066 2012 6531 2063 2009 6532 2042 1988 6533 2065 2011 6534 2066 2012 6535 2042 1988 6536 2067 2013 6537 2043 1989 6538 2044 1990 6539 2068 2014 6540 2065 2011 6541 2043 1989 6542 2067 2013 6543 2068 2014 6544 2043 1989 6545 2069 2015 6546 2044 1990 6547 2045 1991 6548 2069 2015 6549 2067 2013 6550 2044 1990 6551 2070 2016 6552 2045 1991 6553 2046 1992 6554 2070 2016 6555 2069 2015 6556 2045 1991 6557 2071 2017 6558 2046 1992 6559 1352 1342 6560 2072 2018 6561 2070 2016 6562 2046 1992 6563 2071 2017 6564 2072 2018 6565 2046 1992 6566 2073 2019 6567 2071 2017 6568 1352 1342 6569 1348 1338 6570 2073 2019 6571 1352 1342 6572 2052 1998 6573 2074 2020 6574 2053 1999 6575 2050 1996 6576 2054 2000 6577 2075 2021 6578 2052 1998 6579 2076 2022 6580 2074 2020 6581 2077 2023 6582 2075 2021 6583 2078 2024 6584 2077 2023 6585 2050 1996 6586 2075 2021 6587 2079 2025 6588 2080 2026 6589 2081 2027 6590 2082 2028 6591 2080 2026 6592 2079 2025 6593 2083 2029 6594 2081 2027 6595 2084 2030 6596 2079 2025 6597 2081 2027 6598 2083 2029 6599 2085 2031 6600 2084 2030 6601 2086 2032 6602 2087 2033 6603 2084 2030 6604 2085 2031 6605 2088 2034 6606 2084 2030 6607 2087 2033 6608 2089 2035 6609 2084 2030 6610 2088 2034 6611 2090 2036 6612 2083 2029 6613 2084 2030 6614 2091 2037 6615 2084 2037 6616 2089 2037 6617 2091 2038 6618 2090 2036 6619 2084 2030 6620 2089 2035 6621 2088 2034 6622 2092 2039 6623 2093 2040 6624 2092 2039 6625 2094 2041 6626 2093 2040 6627 2089 2035 6628 2092 2039 6629 2093 2040 6630 2094 2041 6631 2095 2042 6632 2096 2043 6633 2095 2042 6634 2097 2044 6635 2098 2045 6636 2095 2042 6637 2096 2043 6638 2099 2046 6639 2093 2040 6640 2095 2042 6641 2098 2045 6642 2099 2046 6643 2095 2042 6644 2096 2043 6645 2097 2044 6646 2100 2047 6647 2101 2048 6648 2100 2047 6649 2102 2049 6650 2101 2048 6651 2096 2043 6652 2100 2047 6653 2101 2048 6654 2102 2049 6655 2103 2050 6656 2104 2051 6657 2103 2050 6658 2105 2052 6659 2104 2051 6660 2101 2048 6661 2103 2050 6662 2106 2053 6663 2105 2052 6664 2107 2054 6665 2106 2053 6666 2104 2051 6667 2105 2052 6668 2108 2055 6669 2107 2054 6670 2109 2056 6671 2108 2055 6672 2106 2053 6673 2107 2054 6674 2108 2055 6675 2109 2056 6676 2110 2057 6677 2111 2058 6678 2110 2057 6679 2112 2059 6680 2111 2058 6681 2108 2055 6682 2110 2057 6683 2111 2058 6684 2112 2059 6685 2113 2060 6686 1357 1347 6687 2113 2060 6688 2114 2061 6689 1357 1347 6690 2111 2058 6691 2113 2060 6692 1357 1347 6693 2114 2061 6694 1358 1348 6695 46 46 6696 48 48 6697 2001 1947 6698 2115 2062 6699 2001 1947 6700 2003 1949 6701 2115 2062 6702 46 46 6703 2001 1947 6704 2116 2063 6705 2003 1949 6706 1983 1929 6707 2116 2063 6708 2115 2062 6709 2003 1949 6710 2117 2064 6711 1983 1929 6712 1987 1933 6713 2117 2064 6714 2116 2063 6715 1983 1929 6716 2014 1960 6717 2117 2064 6718 1987 1933 6719 44 44 6720 46 46 6721 2115 2062 6722 2118 2065 6723 2115 2062 6724 2116 2063 6725 2118 2065 6726 44 44 6727 2115 2062 6728 2119 2066 6729 2116 2063 6730 2117 2064 6731 2119 2066 6732 2118 2065 6733 2116 2063 6734 2120 2067 6735 2117 2064 6736 2014 1960 6737 2120 2067 6738 2119 2066 6739 2117 2064 6740 2032 1978 6741 2120 2067 6742 2014 1960 6743 39 39 6744 44 44 6745 2118 2065 6746 2121 2068 6747 2118 2065 6748 2119 2066 6749 2121 2068 6750 39 39 6751 2118 2065 6752 2122 2069 6753 2119 2066 6754 2120 2067 6755 2122 2069 6756 2121 2068 6757 2119 2066 6758 2123 2070 6759 2120 2067 6760 2032 1978 6761 2123 2070 6762 2122 2069 6763 2120 2067 6764 2050 1996 6765 2123 2070 6766 2032 1978 6767 2124 2071 6768 39 39 6769 2121 2068 6770 2124 2071 6771 42 42 6772 39 39 6773 2125 2072 6774 2121 2068 6775 2122 2069 6776 2125 2072 6777 2124 2071 6778 2121 2068 6779 2126 2073 6780 2122 2069 6781 2123 2070 6782 2127 2074 6783 2125 2072 6784 2122 2069 6785 2126 2073 6786 2127 2074 6787 2122 2069 6788 2128 2075 6789 2123 2070 6790 2050 1996 6791 2128 2075 6792 2126 2073 6793 2123 2070 6794 2129 2076 6795 2128 2075 6796 2050 1996 6797 2130 2077 6798 2129 2076 6799 2050 1996 6800 2077 2023 6801 2130 2077 6802 2050 1996 6803 30 30 6804 43 43 6805 2131 2078 6806 30 30 6807 2131 2078 6808 2132 2079 6809 2133 2080 6810 2132 2079 6811 2134 2081 6812 30 30 6813 2132 2079 6814 2133 2080 6815 2133 2080 6816 2134 2081 6817 2135 2082 6818 2133 2080 6819 2135 2082 6820 2136 2083 6821 2133 2080 6822 2136 2083 6823 2083 2029 6824 2137 2084 6825 2133 2080 6826 2083 2029 6827 2138 2085 6828 2137 2084 6829 2083 2029 6830 2139 2086 6831 2138 2085 6832 2083 2029 6833 2090 2036 6834 2139 2086 6835 2083 2029 6836 2140 2087 6837 2141 2088 6838 2142 2089 6839 2143 2090 6840 2144 2091 6841 2141 2088 6842 2143 2090 6843 2141 2088 6844 2140 2087 6845 2145 2092 6846 2142 2089 6847 2146 2093 6848 2140 2087 6849 2142 2089 6850 2145 2092 6851 2147 2094 6852 2146 2093 6853 2148 2095 6854 2145 2092 6855 2146 2093 6856 2147 2094 6857 2149 2096 6858 2148 2095 6859 2150 2097 6860 2147 2094 6861 2148 2095 6862 2149 2096 6863 2151 2098 6864 2150 2097 6865 2152 2099 6866 2149 2096 6867 2150 2097 6868 2151 2098 6869 2153 2100 6870 2152 2099 6871 2154 2101 6872 2151 2098 6873 2152 2099 6874 2153 2100 6875 2155 2102 6876 2154 2101 6877 2156 2103 6878 2153 2100 6879 2154 2101 6880 2155 2102 6881 2157 2104 6882 2156 2103 6883 2158 2105 6884 2155 2102 6885 2156 2103 6886 2157 2104 6887 2159 2106 6888 2158 2105 6889 2160 2107 6890 2157 2104 6891 2158 2105 6892 2159 2106 6893 2161 2108 6894 2160 2107 6895 2162 2109 6896 2159 2106 6897 2160 2107 6898 2161 2108 6899 2163 2110 6900 2162 2109 6901 2164 2111 6902 2161 2108 6903 2162 2109 6904 2163 2110 6905 2165 2112 6906 2164 2111 6907 2166 2113 6908 2163 2110 6909 2164 2111 6910 2165 2112 6911 2167 2114 6912 2166 2113 6913 2168 2115 6914 2165 2112 6915 2166 2113 6916 2167 2114 6917 2167 2114 6918 2168 2115 6919 2169 2116 6920 2170 2117 6921 2169 2116 6922 2171 2118 6923 2167 2114 6924 2169 2116 6925 2170 2117 6926 2172 2119 6927 2173 2119 6928 2174 2119 6929 2172 2120 6930 2175 2120 6931 2173 2120 6932 2172 2121 6933 2174 2121 6934 2176 2121 6935 2177 2122 6936 2178 2123 6937 2144 2091 6938 2179 2124 6939 2172 2124 6940 2176 2124 6941 2177 2122 6942 2144 2091 6943 2143 2090 6944 2180 2125 6945 2181 2126 6946 2133 2080 6947 30 30 6948 2133 2080 6949 2181 2126 6950 2182 2127 6951 2180 2125 6952 2133 2080 6953 2137 2084 6954 2182 2127 6955 2133 2080 6956 2183 2128 6957 2184 2128 6958 2185 2128 6959 2186 2129 6960 30 30 6961 2181 2126 6962 2187 2130 6963 2186 2129 6964 2181 2126 6965 2183 2131 6966 2188 2131 6967 2184 2131 6968 2189 2132 6969 2190 2133 6970 2191 2134 6971 2192 2135 6972 2183 2135 6973 2185 2135 6974 2193 2136 6975 2191 2134 6976 2194 2137 6977 2193 2136 6978 2189 2132 6979 2191 2134 6980 2195 2138 6981 2194 2137 6982 2196 2139 6983 2195 2138 6984 2193 2136 6985 2194 2137 6986 2197 2140 6987 2196 2139 6988 2198 2141 6989 2197 2140 6990 2195 2138 6991 2196 2139 6992 2199 2142 6993 2198 2141 6994 2200 2143 6995 2199 2142 6996 2197 2140 6997 2198 2141 6998 2199 2142 6999 2200 2143 7000 2201 2144 7001 2202 2145 7002 2199 2142 7003 2201 2144 7004 2203 2146 7005 30 30 7006 2186 2129 7007 2203 2146 7008 33 33 7009 30 30 7010 2187 2130 7011 2204 2147 7012 2186 2129 7013 2205 2148 7014 2186 2129 7015 2204 2147 7016 2206 2149 7017 2203 2146 7018 2186 2129 7019 2207 2150 7020 2206 2149 7021 2186 2129 7022 2208 2151 7023 2207 2150 7024 2186 2129 7025 2205 2148 7026 2208 2151 7027 2186 2129 7028 2209 2152 7029 2210 2153 7030 2204 2147 7031 2211 2154 7032 2212 2155 7033 2213 2156 7034 2187 2130 7035 2209 2152 7036 2204 2147 7037 2214 2157 7038 2215 2158 7039 2212 2155 7040 2216 2159 7041 2214 2157 7042 2212 2155 7043 2211 2154 7044 2216 2159 7045 2212 2155 7046 2217 2160 7047 2218 2161 7048 2210 2153 7049 2219 2162 7050 2213 2156 7051 2220 2163 7052 2209 2152 7053 2217 2160 7054 2210 2153 7055 2211 2154 7056 2213 2156 7057 2219 2162 7058 2217 2160 7059 2221 2164 7060 2218 2161 7061 2219 2162 7062 2220 2163 7063 2222 2165 7064 2223 2166 7065 2224 2167 7066 2221 2164 7067 2225 2168 7068 2222 2165 7069 2226 2169 7070 2217 2160 7071 2223 2166 7072 2221 2164 7073 2219 2162 7074 2222 2165 7075 2225 2168 7076 2223 2166 7077 2227 2170 7078 2224 2167 7079 2225 2168 7080 2226 2169 7081 2228 2171 7082 2229 2172 7083 2230 2173 7084 2227 2170 7085 2231 2174 7086 2228 2171 7087 2232 2175 7088 2223 2166 7089 2229 2172 7090 2227 2170 7091 2225 2168 7092 2228 2171 7093 2231 2174 7094 2233 2176 7095 2234 2177 7096 2230 2173 7097 2235 2178 7098 2232 2175 7099 2236 2179 7100 2229 2172 7101 2233 2176 7102 2230 2173 7103 2231 2174 7104 2232 2175 7105 2235 2178 7106 2233 2176 7107 2237 2180 7108 2234 2177 7109 2238 2181 7110 2236 2179 7111 2239 2182 7112 2235 2178 7113 2236 2179 7114 2238 2181 7115 2240 2183 7116 2241 2184 7117 2237 2180 7118 2242 2185 7119 2239 2182 7120 2243 2186 7121 2233 2176 7122 2240 2183 7123 2237 2180 7124 2238 2181 7125 2239 2182 7126 2242 2185 7127 2240 2183 7128 2244 2187 7129 2241 2184 7130 2242 2185 7131 2243 2186 7132 2245 2188 7133 2246 2189 7134 2247 2190 7135 2244 2187 7136 2248 2191 7137 2245 2188 7138 2249 2192 7139 2240 2183 7140 2246 2189 7141 2244 2187 7142 2242 2185 7143 2245 2188 7144 2248 2191 7145 2246 2189 7146 2250 2193 7147 2247 2190 7148 2251 2194 7149 2249 2192 7150 2252 2195 7151 2248 2191 7152 2249 2192 7153 2251 2194 7154 2253 2196 7155 2254 2197 7156 2250 2193 7157 2255 2198 7158 2250 2193 7159 2254 2197 7160 2246 2189 7161 2253 2196 7162 2250 2193 7163 2251 2194 7164 2252 2195 7165 2256 2199 7166 2257 2200 7167 1237 1228 7168 2254 2197 7169 2258 2201 7170 2254 2197 7171 1237 1228 7172 2253 2196 7173 2257 2200 7174 2254 2197 7175 2259 2202 7176 2255 2198 7177 2254 2197 7178 2258 2201 7179 2259 2202 7180 2254 2197 7181 2257 2200 7182 1228 1219 7183 1237 1228 7184 2260 2203 7185 2258 2201 7186 1237 1228 7187 2261 2204 7188 2260 2203 7189 1237 1228 7190 1114 1105 7191 2261 2204 7192 1237 1228 7193 2262 2205 7194 1228 1219 7195 2257 2200 7196 2263 2206 7197 1390 1380 7198 1228 1219 7199 2264 2207 7200 2263 2206 7201 1228 1219 7202 2265 2208 7203 2264 2207 7204 1228 1219 7205 2262 2205 7206 2265 2208 7207 1228 1219 7208 2266 2209 7209 2267 2209 7210 2268 2209 7211 2266 2210 7212 2269 2210 7213 2267 2210 7214 2266 2211 7215 2268 2211 7216 2270 2211 7217 2271 2212 7218 2272 2213 7219 2273 2214 7220 2266 2215 7221 2270 2215 7222 2274 2215 7223 2275 2216 7224 2273 2214 7225 2276 2217 7226 2277 2218 7227 2273 2214 7228 2275 2216 7229 2271 2212 7230 2273 2214 7231 2277 2218 7232 2275 2216 7233 2276 2217 7234 2278 2219 7235 2279 2219 7236 2278 2219 7237 2280 2220 7238 2275 2216 7239 2278 2219 7240 2279 2219 7241 2281 2221 7242 2280 2220 7243 2282 2222 7244 2279 2219 7245 2280 2220 7246 2281 2221 7247 2283 2223 7248 2282 2222 7249 2284 2224 7250 2281 2221 7251 2282 2222 7252 2283 2223 7253 2183 2225 7254 2285 2225 7255 2188 2225 7256 2283 2223 7257 2284 2224 7258 2286 2226 7259 2287 2227 7260 36 36 7261 2288 2228 7262 2287 2227 7263 34 34 7264 36 36 7265 2287 2227 7266 2288 2228 7267 2289 2229 7268 2290 2230 7269 2289 2229 7270 2291 2231 7271 2290 2230 7272 2287 2227 7273 2289 2229 7274 2292 2232 7275 2291 2231 7276 2293 2233 7277 2292 2232 7278 2290 2230 7279 2291 2231 7280 2292 2232 7281 2293 2233 7282 2294 2234 7283 2295 2235 7284 2292 2232 7285 2294 2234 7286 2296 2236 7287 2297 2237 7288 2298 2238 7289 2251 2194 7290 2256 2199 7291 2299 2239 7292 2300 2240 7293 2298 2238 7294 2301 2241 7295 2296 2236 7296 2298 2238 7297 2300 2240 7298 2302 2242 7299 2301 2241 7300 2303 2243 7301 2300 2240 7302 2301 2241 7303 2302 2242 7304 2302 2242 7305 2303 2243 7306 2304 2244 7307 2305 2245 7308 2304 2244 7309 1115 1106 7310 2302 2242 7311 2304 2244 7312 2305 2245 7313 2305 2245 7314 1115 1106 7315 1103 1094 7316 2306 2246 7317 2307 2246 7318 2308 2246 7319 2306 2247 7320 2309 2247 7321 2307 2247 7322 2310 2248 7323 2311 2249 7324 2312 2250 7325 2306 2251 7326 2308 2251 7327 2313 2251 7328 2314 2252 7329 2312 2250 7330 2315 2253 7331 2310 2248 7332 2312 2250 7333 2314 2252 7334 2316 2254 7335 2315 2253 7336 2317 2255 7337 2314 2252 7338 2315 2253 7339 2316 2254 7340 2318 2256 7341 2317 2255 7342 2319 2257 7343 2316 2254 7344 2317 2255 7345 2318 2256 7346 2320 2258 7347 2319 2257 7348 2321 2259 7349 2318 2256 7350 2319 2257 7351 2320 2258 7352 2320 2258 7353 2321 2259 7354 2322 2260 7355 2320 2258 7356 2322 2260 7357 2323 2261 7358 2170 2117 7359 2171 2118 7360 2324 2262 7361 2306 2263 7362 2325 2263 7363 2309 2263 7364 2170 2117 7365 2324 2262 7366 2326 2264 7367 34 34 7368 2327 2265 7369 37 37 7370 2328 2266 7371 27 27 7372 2329 2267 7373 2328 2266 7374 23 23 7375 27 27 7376 2330 2268 7377 2327 2265 7378 34 34 7379 2330 2268 7380 2331 2269 7381 2327 2265 7382 2332 2270 7383 2329 2267 7384 2333 2271 7385 2332 2270 7386 2328 2266 7387 2329 2267 7388 2334 2272 7389 34 34 7390 2287 2227 7391 2334 2272 7392 2330 2268 7393 34 34 7394 2335 2273 7395 2287 2227 7396 2290 2230 7397 2335 2273 7398 2334 2272 7399 2287 2227 7400 2336 2274 7401 2290 2230 7402 2292 2232 7403 2336 2274 7404 2335 2273 7405 2290 2230 7406 2336 2274 7407 2292 2232 7408 2295 2235 7409 2337 2275 7410 2336 2274 7411 2295 2235 7412 2330 2268 7413 2338 2276 7414 2331 2269 7415 2339 2277 7416 2333 2271 7417 2340 2278 7418 2339 2277 7419 2332 2270 7420 2333 2271 7421 2330 2268 7422 2341 2279 7423 2338 2276 7424 2339 2277 7425 2340 2278 7426 2342 2280 7427 2343 2281 7428 2341 2279 7429 2330 2268 7430 2343 2281 7431 2344 2282 7432 2341 2279 7433 2345 2283 7434 2342 2280 7435 2346 2284 7436 2345 2283 7437 2339 2277 7438 2342 2280 7439 2347 2285 7440 2330 2268 7441 2334 2272 7442 2347 2285 7443 2343 2281 7444 2330 2268 7445 2348 2286 7446 2334 2272 7447 2335 2273 7448 2348 2286 7449 2347 2285 7450 2334 2272 7451 2349 2287 7452 2335 2273 7453 2336 2274 7454 2349 2287 7455 2348 2286 7456 2335 2273 7457 2350 2288 7458 2336 2274 7459 2337 2275 7460 2350 2288 7461 2349 2287 7462 2336 2274 7463 2351 2289 7464 2350 2288 7465 2337 2275 7466 2211 2154 7467 2352 2290 7468 2216 2159 7469 2343 2281 7470 2353 2291 7471 2344 2282 7472 2354 2292 7473 2346 2284 7474 2355 2293 7475 2354 2292 7476 2345 2283 7477 2346 2284 7478 2343 2281 7479 2356 2294 7480 2353 2291 7481 2357 2295 7482 2355 2293 7483 2358 2296 7484 2357 2295 7485 2354 2292 7486 2355 2293 7487 2343 2281 7488 2359 2297 7489 2356 2294 7490 2357 2295 7491 2358 2296 7492 2360 2298 7493 2343 2281 7494 2361 2299 7495 2359 2297 7496 2362 2300 7497 2360 2298 7498 2363 2301 7499 2362 2300 7500 2357 2295 7501 2360 2298 7502 2364 2302 7503 2361 2299 7504 2343 2281 7505 2365 2303 7506 2366 2304 7507 2361 2299 7508 2367 2305 7509 2363 2301 7510 2368 2306 7511 2369 2307 7512 2365 2303 7513 2361 2299 7514 2364 2302 7515 2369 2307 7516 2361 2299 7517 2367 2305 7518 2362 2300 7519 2363 2301 7520 2370 2308 7521 2343 2281 7522 2347 2285 7523 2371 2309 7524 2364 2302 7525 2343 2281 7526 2370 2308 7527 2371 2309 7528 2343 2281 7529 2372 2310 7530 2347 2285 7531 2348 2286 7532 2373 2311 7533 2370 2308 7534 2347 2285 7535 2374 2312 7536 2373 2311 7537 2347 2285 7538 2372 2310 7539 2374 2312 7540 2347 2285 7541 2375 2313 7542 2348 2286 7543 2349 2287 7544 2376 2314 7545 2372 2310 7546 2348 2286 7547 2375 2313 7548 2376 2314 7549 2348 2286 7550 2377 2315 7551 2349 2287 7552 2350 2288 7553 2378 2316 7554 2375 2313 7555 2349 2287 7556 2377 2315 7557 2378 2316 7558 2349 2287 7559 2379 2317 7560 2350 2288 7561 2351 2289 7562 2379 2317 7563 2377 2315 7564 2350 2288 7565 2380 2318 7566 2379 2317 7567 2351 2289 7568 2381 2319 7569 2380 2318 7570 2351 2289 7571 2211 2154 7572 2382 2320 7573 2352 2290 7574 2383 2321 7575 2384 2322 7576 2366 2304 7577 2367 2305 7578 2368 2306 7579 2385 2323 7580 2365 2303 7581 2383 2321 7582 2366 2304 7583 2383 2321 7584 2386 2324 7585 2384 2322 7586 2387 2325 7587 2385 2323 7588 2388 2326 7589 2387 2325 7590 2367 2305 7591 2385 2323 7592 2383 2321 7593 2389 2327 7594 2386 2324 7595 2390 2328 7596 2388 2326 7597 2391 2329 7598 2390 2328 7599 2387 2325 7600 2388 2326 7601 2392 2330 7602 2393 2331 7603 2389 2327 7604 2394 2332 7605 2391 2329 7606 2395 2333 7607 2383 2321 7608 2392 2330 7609 2389 2327 7610 2394 2332 7611 2390 2328 7612 2391 2329 7613 2394 2332 7614 2395 2333 7615 2396 2334 7616 197 197 7617 2397 2335 7618 2398 2336 7619 2399 2337 7620 2394 2332 7621 2396 2334 7622 197 197 7623 202 202 7624 2397 2335 7625 197 197 7626 2398 2336 7627 2400 2338 7628 2401 2339 7629 2400 2338 7630 2402 2340 7631 197 197 7632 2400 2338 7633 2401 2339 7634 2401 2339 7635 2402 2340 7636 2403 2341 7637 2401 2339 7638 2403 2341 7639 2404 2342 7640 2405 2343 7641 2404 2342 7642 2406 2344 7643 2401 2339 7644 2404 2342 7645 2405 2343 7646 2405 2343 7647 2406 2344 7648 2407 2345 7649 2405 2343 7650 2407 2345 7651 2408 2346 7652 2409 2347 7653 2408 2346 7654 2410 2348 7655 2405 2343 7656 2408 2346 7657 2409 2347 7658 2409 2347 7659 2410 2348 7660 2411 2349 7661 2412 2350 7662 2411 2349 7663 2413 2351 7664 2409 2347 7665 2411 2349 7666 2412 2350 7667 2412 2350 7668 2413 2351 7669 2414 2352 7670 2415 2353 7671 2414 2352 7672 2416 2354 7673 2412 2350 7674 2414 2352 7675 2415 2353 7676 2415 2353 7677 2416 2354 7678 2417 2355 7679 2415 2353 7680 2417 2355 7681 2418 2356 7682 2419 2357 7683 2418 2356 7684 2420 2358 7685 2419 2357 7686 2415 2353 7687 2418 2356 7688 2421 2359 7689 2422 2360 7690 2423 2361 7691 2424 2362 7692 2382 2320 7693 2211 2154 7694 2421 2359 7695 2423 2361 7696 2425 2363 7697 19 19 7698 23 23 7699 2328 2266 7700 2426 2364 7701 2328 2266 7702 2332 2270 7703 2426 2364 7704 19 19 7705 2328 2266 7706 2427 2365 7707 2332 2270 7708 2339 2277 7709 2427 2365 7710 2426 2364 7711 2332 2270 7712 2428 2366 7713 2339 2277 7714 2345 2283 7715 2428 2366 7716 2427 2365 7717 2339 2277 7718 2429 2367 7719 2345 2283 7720 2354 2292 7721 2429 2367 7722 2428 2366 7723 2345 2283 7724 2430 2368 7725 2354 2292 7726 2357 2295 7727 2430 2368 7728 2429 2367 7729 2354 2292 7730 2431 2369 7731 2357 2295 7732 2362 2300 7733 2431 2369 7734 2430 2368 7735 2357 2295 7736 2432 2370 7737 2362 2300 7738 2367 2305 7739 2432 2370 7740 2431 2369 7741 2362 2300 7742 2433 2371 7743 2367 2305 7744 2387 2325 7745 2433 2371 7746 2432 2370 7747 2367 2305 7748 2434 2372 7749 2387 2325 7750 2390 2328 7751 2434 2372 7752 2433 2371 7753 2387 2325 7754 2435 2373 7755 2390 2328 7756 2394 2332 7757 2435 2373 7758 2434 2372 7759 2390 2328 7760 2436 2374 7761 2394 2332 7762 2399 2337 7763 2436 2374 7764 2435 2373 7765 2394 2332 7766 2436 2374 7767 2399 2337 7768 2437 2375 7769 2438 2376 7770 2436 2374 7771 2437 2375 7772 2438 2376 7773 2437 2375 7774 2439 2377 7775 15 15 7776 19 19 7777 2426 2364 7778 2440 2378 7779 2426 2364 7780 2427 2365 7781 2440 2378 7782 15 15 7783 2426 2364 7784 2441 2379 7785 2427 2365 7786 2428 2366 7787 2441 2379 7788 2440 2378 7789 2427 2365 7790 2442 2380 7791 2428 2366 7792 2429 2367 7793 2442 2380 7794 2441 2379 7795 2428 2366 7796 2443 2381 7797 2429 2367 7798 2430 2368 7799 2443 2381 7800 2442 2380 7801 2429 2367 7802 2444 2382 7803 2430 2368 7804 2431 2369 7805 2444 2382 7806 2443 2381 7807 2430 2368 7808 2445 2383 7809 2431 2369 7810 2432 2370 7811 2445 2383 7812 2444 2382 7813 2431 2369 7814 2446 2384 7815 2432 2370 7816 2433 2371 7817 2446 2384 7818 2445 2383 7819 2432 2370 7820 2447 2385 7821 2433 2371 7822 2434 2372 7823 2447 2385 7824 2446 2384 7825 2433 2371 7826 2448 2386 7827 2434 2372 7828 2435 2373 7829 2448 2386 7830 2447 2385 7831 2434 2372 7832 2449 2387 7833 2435 2373 7834 2436 2374 7835 2449 2387 7836 2448 2386 7837 2435 2373 7838 2438 2376 7839 2449 2387 7840 2436 2374 7841 2450 2388 7842 2438 2376 7843 2439 2377 7844 3 3 7845 15 15 7846 2440 2378 7847 149 149 7848 2440 2378 7849 2441 2379 7850 149 149 7851 3 3 7852 2440 2378 7853 146 146 7854 2441 2379 7855 2442 2380 7856 146 146 7857 149 149 7858 2441 2379 7859 143 143 7860 2442 2380 7861 2443 2381 7862 143 143 7863 146 146 7864 2442 2380 7865 140 140 7866 2443 2381 7867 2444 2382 7868 140 140 7869 143 143 7870 2443 2381 7871 127 127 7872 2444 2382 7873 2445 2383 7874 127 127 7875 140 140 7876 2444 2382 7877 124 124 7878 2445 2383 7879 2446 2384 7880 124 124 7881 127 127 7882 2445 2383 7883 119 119 7884 2446 2384 7885 2447 2385 7886 119 119 7887 124 124 7888 2446 2384 7889 116 116 7890 2447 2385 7891 2448 2386 7892 116 116 7893 119 119 7894 2447 2385 7895 89 89 7896 2448 2386 7897 2449 2387 7898 89 89 7899 116 116 7900 2448 2386 7901 86 86 7902 2449 2387 7903 2438 2376 7904 86 86 7905 89 89 7906 2449 2387 7907 81 81 7908 2438 2376 7909 2450 2388 7910 81 81 7911 86 86 7912 2438 2376 7913 81 81 7914 2450 2388 7915 77 77 7916 2451 2389 7917 2452 2390 7918 2415 2353 7919 2412 2350 7920 2415 2353 7921 2452 2390 7922 2419 2357 7923 2451 2389 7924 2415 2353 7925 2453 2391 7926 2454 2392 7927 2452 2390 7928 2455 2393 7929 2452 2390 7930 2454 2392 7931 2456 2394 7932 2453 2391 7933 2452 2390 7934 2451 2389 7935 2456 2394 7936 2452 2390 7937 2455 2393 7938 2412 2350 7939 2452 2390 7940 2457 2395 7941 2458 2396 7942 2454 2392 7943 2459 2397 7944 2454 2392 7945 2458 2396 7946 2453 2391 7947 2457 2395 7948 2454 2392 7949 2459 2397 7950 2455 2393 7951 2454 2392 7952 2460 2398 7953 2461 2399 7954 2458 2396 7955 2462 2400 7956 2458 2396 7957 2461 2399 7958 2463 2401 7959 2460 2398 7960 2458 2396 7961 2457 2395 7962 2463 2401 7963 2458 2396 7964 2462 2400 7965 2459 2397 7966 2458 2396 7967 2464 2402 7968 2465 2403 7969 2461 2399 7970 2466 2404 7971 2461 2399 7972 2465 2403 7973 2460 2398 7974 2464 2402 7975 2461 2399 7976 2466 2404 7977 2462 2400 7978 2461 2399 7979 2467 2405 7980 2468 2406 7981 2465 2403 7982 2469 2407 7983 2465 2403 7984 2468 2406 7985 2470 2408 7986 2467 2405 7987 2465 2403 7988 2471 2409 7989 2470 2408 7990 2465 2403 7991 2464 2402 7992 2471 2409 7993 2465 2403 7994 2469 2407 7995 2466 2404 7996 2465 2403 7997 2472 2410 7998 2473 2411 7999 2474 2412 8000 2475 2413 8001 2469 2407 8002 2468 2406 8003 2472 2410 8004 2476 2414 8005 2473 2411 8006 2472 2410 8007 2474 2412 8008 2477 2415 8009 2478 2416 8010 2477 2415 8011 2479 2417 8012 2472 2410 8013 2477 2415 8014 2478 2416 8015 2480 2418 8016 2481 2419 8017 2482 2420 8018 2483 2421 8019 2484 2422 8020 2485 2423 8021 2486 2424 8022 2482 2420 8023 2487 2425 8024 2486 2424 8025 2480 2418 8026 2482 2420 8027 2488 2426 8028 2487 2425 8029 2489 2427 8030 2488 2426 8031 2486 2424 8032 2487 2425 8033 2490 2428 8034 2489 2427 8035 2491 2429 8036 2490 2428 8037 2488 2426 8038 2489 2427 8039 2490 2428 8040 2491 2429 8041 2492 2430 8042 2493 2431 8043 2492 2430 8044 2494 2432 8045 2493 2431 8046 2490 2428 8047 2492 2430 8048 2495 2433 8049 2494 2432 8050 2496 2434 8051 2495 2433 8052 2493 2431 8053 2494 2432 8054 2495 2433 8055 2496 2434 8056 2422 2360 8057 2421 2359 8058 2495 2433 8059 2422 2360 8060 2409 2347 8061 2412 2350 8062 2455 2393 8063 2497 2435 8064 2455 2393 8065 2459 2397 8066 2497 2435 8067 2409 2347 8068 2455 2393 8069 2498 2436 8070 2459 2397 8071 2462 2400 8072 2498 2436 8073 2497 2435 8074 2459 2397 8075 2499 2437 8076 2462 2400 8077 2466 2404 8078 2499 2437 8079 2498 2436 8080 2462 2400 8081 2500 2438 8082 2466 2404 8083 2469 2407 8084 2500 2438 8085 2499 2437 8086 2466 2404 8087 2475 2413 8088 2501 2439 8089 2469 2407 8090 2502 2440 8091 2469 2407 8092 2501 2439 8093 2502 2440 8094 2500 2438 8095 2469 2407 8096 2503 2441 8097 2504 2442 8098 2476 2414 8099 2505 2443 8100 2502 2440 8101 2501 2439 8102 2503 2441 8103 2506 2444 8104 2504 2442 8105 2503 2441 8106 2476 2414 8107 2472 2410 8108 2405 2343 8109 2409 2347 8110 2497 2435 8111 2507 2445 8112 2497 2435 8113 2498 2436 8114 2507 2445 8115 2405 2343 8116 2497 2435 8117 2508 2446 8118 2498 2436 8119 2499 2437 8120 2508 2446 8121 2507 2445 8122 2498 2436 8123 2509 2447 8124 2499 2437 8125 2500 2438 8126 2509 2447 8127 2508 2446 8128 2499 2437 8129 2510 2448 8130 2500 2438 8131 2502 2440 8132 2510 2448 8133 2509 2447 8134 2500 2438 8135 2505 2443 8136 2511 2449 8137 2502 2440 8138 2512 2450 8139 2502 2440 8140 2511 2449 8141 2512 2450 8142 2510 2448 8143 2502 2440 8144 2513 2451 8145 2514 2452 8146 2506 2444 8147 2515 2453 8148 2512 2450 8149 2511 2449 8150 2513 2451 8151 2516 2454 8152 2514 2452 8153 2513 2451 8154 2506 2444 8155 2503 2441 8156 2401 2339 8157 2405 2343 8158 2507 2445 8159 2517 2455 8160 2507 2445 8161 2508 2446 8162 2517 2455 8163 2401 2339 8164 2507 2445 8165 2518 2456 8166 2508 2446 8167 2509 2447 8168 2518 2456 8169 2517 2455 8170 2508 2446 8171 2519 2457 8172 2509 2447 8173 2510 2448 8174 2519 2457 8175 2518 2456 8176 2509 2447 8177 2520 2458 8178 2510 2448 8179 2512 2450 8180 2520 2458 8181 2519 2457 8182 2510 2448 8183 2521 2459 8184 2522 2460 8185 2512 2450 8186 2523 2461 8187 2512 2450 8188 2522 2460 8189 2515 2453 8190 2521 2459 8191 2512 2450 8192 2523 2461 8193 2520 2458 8194 2512 2450 8195 2524 2462 8196 2525 2463 8197 2526 2464 8198 2527 2465 8199 2523 2461 8200 2522 2460 8201 2528 2466 8202 2527 2465 8203 2522 2460 8204 2524 2462 8205 2529 2467 8206 2525 2463 8207 2513 2451 8208 2526 2464 8209 2516 2454 8210 2524 2462 8211 2526 2464 8212 2513 2451 8213 197 197 8214 2401 2339 8215 2517 2455 8216 187 187 8217 2517 2455 8218 2518 2456 8219 187 187 8220 197 197 8221 2517 2455 8222 194 194 8223 2518 2456 8224 2519 2457 8225 194 194 8226 187 187 8227 2518 2456 8228 227 227 8229 2519 2457 8230 2520 2458 8231 227 227 8232 194 194 8233 2519 2457 8234 223 223 8235 2520 2458 8236 2523 2461 8237 223 223 8238 227 227 8239 2520 2458 8240 212 212 8241 2523 2461 8242 2527 2465 8243 212 212 8244 223 223 8245 2523 2461 8246 2530 2468 8247 2531 2469 8248 2532 2470 8249 2533 2471 8250 212 212 8251 2527 2465 8252 2534 2472 8253 2535 2473 8254 2531 2469 8255 2536 2474 8256 2534 2472 8257 2531 2469 8258 2530 2468 8259 2536 2474 8260 2531 2469 8261 2537 2475 8262 2538 2476 8263 2539 2477 8264 2540 2478 8265 2529 2467 8266 2524 2462 8267 243 241 8268 219 219 8269 2535 2473 8270 2534 2472 8271 243 241 8272 2535 2473 8273 2541 2479 8274 243 241 8275 2534 2472 8276 2542 2480 8277 253 251 8278 243 241 8279 2541 2479 8280 2542 2480 8281 243 241 8282 2543 2481 8283 2544 2482 8284 2545 2483 8285 2543 2481 8286 2546 2484 8287 2544 2482 8288 2537 2475 8289 2545 2483 8290 2538 2476 8291 2543 2481 8292 2545 2483 8293 2537 2475 8294 251 249 8295 254 252 8296 2547 2485 8297 2543 2481 8298 2548 2486 8299 2546 2484 8300 2549 2487 8301 274 272 8302 2550 2488 8303 2551 2489 8304 2549 2487 8305 2550 2488 8306 2543 2481 8307 2552 2490 8308 2548 2486 8309 2549 2487 8310 271 269 8311 274 272 8312 2553 2491 8313 271 269 8314 2549 2487 8315 2553 2491 8316 314 312 8317 271 269 8318 2553 2491 8319 2549 2487 8320 2551 2489 8321 2554 2492 8322 2553 2491 8323 2551 2489 8324 2555 2493 8325 2556 2494 8326 2552 2490 8327 2555 2493 8328 2552 2490 8329 2543 2481 8330 2557 2495 8331 308 306 8332 314 312 8333 2557 2495 8334 310 308 8335 308 306 8336 2558 2496 8337 314 312 8338 2553 2491 8339 2558 2496 8340 2557 2495 8341 314 312 8342 2554 2492 8343 2559 2497 8344 2553 2491 8345 2558 2496 8346 2553 2491 8347 2559 2497 8348 2555 2493 8349 2560 2498 8350 2556 2494 8351 2561 2499 8352 2558 2496 8353 2559 2497 8354 2562 2500 8355 2563 2501 8356 2560 2498 8357 2562 2500 8358 2560 2498 8359 2555 2493 8360 2564 2502 8361 298 296 8362 310 308 8363 2565 2503 8364 300 298 8365 298 296 8366 2564 2502 8367 2565 2503 8368 298 296 8369 2566 2504 8370 310 308 8371 2557 2495 8372 2566 2504 8373 2564 2502 8374 310 308 8375 2567 2505 8376 2557 2495 8377 2558 2496 8378 2567 2505 8379 2566 2504 8380 2557 2495 8381 2561 2499 8382 2568 2506 8383 2558 2496 8384 2569 2507 8385 2558 2496 8386 2568 2506 8387 2569 2507 8388 2567 2505 8389 2558 2496 8390 2570 2508 8391 2571 2509 8392 2563 2501 8393 2572 2510 8394 2569 2507 8395 2568 2506 8396 2573 2511 8397 2574 2512 8398 2571 2509 8399 2573 2511 8400 2571 2509 8401 2575 2513 8402 2570 2508 8403 2575 2513 8404 2571 2509 8405 2570 2508 8406 2563 2501 8407 2562 2500 8408 293 291 8409 296 294 8410 2576 2514 8411 2577 2515 8412 2578 2516 8413 2579 2517 8414 2580 2518 8415 2581 2519 8416 2582 2520 8417 2580 2518 8418 2582 2520 8419 2583 2521 8420 2577 2515 8421 2579 2517 8422 2584 2522 8423 2577 2515 8424 2584 2522 8425 2585 2523 8426 2586 2524 8427 2585 2523 8428 2587 2525 8429 2577 2515 8430 2585 2523 8431 2586 2524 8432 2586 2524 8433 2587 2525 8434 2588 2526 8435 2589 2527 8436 2588 2526 8437 2590 2528 8438 2586 2524 8439 2588 2526 8440 2589 2527 8441 2589 2527 8442 2590 2528 8443 2591 2529 8444 2589 2527 8445 2591 2529 8446 2592 2530 8447 2593 2531 8448 2592 2530 8449 2591 2529 8450 2594 2532 8451 356 2532 8452 2595 2532 8453 2594 2533 8454 355 2533 8455 356 2533 8456 2580 2518 8457 2596 2534 8458 2581 2519 8459 2597 2535 8460 2598 2536 8461 2599 2537 8462 2600 2538 8463 2597 2535 8464 2599 2537 8465 2580 2518 8466 2601 2539 8467 2596 2534 8468 367 364 8469 368 365 8470 2602 2540 8471 2603 2541 8472 2604 2542 8473 2605 2543 8474 2597 2535 8475 2606 2544 8476 2598 2536 8477 2607 2545 8478 679 674 8479 2608 2546 8480 2607 2545 8481 677 672 8482 679 674 8483 2607 2545 8484 2608 2546 8485 2609 2547 8486 2610 2548 8487 2609 2547 8488 2611 2549 8489 2610 2548 8490 2607 2545 8491 2609 2547 8492 2610 2548 8493 2611 2549 8494 2612 2550 8495 2613 2551 8496 2612 2550 8497 2614 2552 8498 2613 2551 8499 2610 2548 8500 2612 2550 8501 2613 2551 8502 2614 2552 8503 2604 2542 8504 2603 2541 8505 2613 2551 8506 2604 2542 8507 903 894 8508 597 591 8509 601 596 8510 2615 2553 8511 601 596 8512 609 604 8513 2615 2553 8514 903 894 8515 601 596 8516 2616 2554 8517 609 604 8518 606 601 8519 2616 2554 8520 2615 2553 8521 609 604 8522 2617 2555 8523 606 601 8524 615 610 8525 2617 2555 8526 2616 2554 8527 606 601 8528 2618 2556 8529 615 610 8530 621 616 8531 2618 2556 8532 2617 2555 8533 615 610 8534 2619 2557 8535 621 616 8536 627 622 8537 2619 2557 8538 2618 2556 8539 621 616 8540 2620 2558 8541 627 622 8542 633 628 8543 2620 2558 8544 2619 2557 8545 627 622 8546 2621 2559 8547 633 628 8548 637 632 8549 2621 2559 8550 2620 2558 8551 633 628 8552 2622 2560 8553 637 632 8554 643 638 8555 2622 2560 8556 2621 2559 8557 637 632 8558 2623 2561 8559 643 638 8560 650 645 8561 2623 2561 8562 2622 2560 8563 643 638 8564 2624 2562 8565 650 645 8566 657 652 8567 2624 2562 8568 2623 2561 8569 650 645 8570 2625 2563 8571 657 652 8572 664 659 8573 2625 2563 8574 2624 2562 8575 657 652 8576 2626 2564 8577 664 659 8578 671 666 8579 2626 2564 8580 2625 2563 8581 664 659 8582 2627 2565 8583 671 666 8584 674 669 8585 2627 2565 8586 2626 2564 8587 671 666 8588 2628 2566 8589 674 669 8590 677 672 8591 2628 2566 8592 2627 2565 8593 674 669 8594 2607 2545 8595 2628 2566 8596 677 672 8597 900 891 8598 903 894 8599 2615 2553 8600 2629 2567 8601 2615 2553 8602 2616 2554 8603 2629 2567 8604 900 891 8605 2615 2553 8606 2630 2568 8607 2616 2554 8608 2617 2555 8609 2630 2568 8610 2629 2567 8611 2616 2554 8612 2631 2569 8613 2617 2555 8614 2618 2556 8615 2631 2569 8616 2630 2568 8617 2617 2555 8618 2632 2570 8619 2618 2556 8620 2619 2557 8621 2632 2570 8622 2631 2569 8623 2618 2556 8624 2633 2571 8625 2619 2557 8626 2620 2558 8627 2633 2571 8628 2632 2570 8629 2619 2557 8630 2634 2572 8631 2620 2558 8632 2621 2559 8633 2634 2572 8634 2633 2571 8635 2620 2558 8636 2635 2573 8637 2621 2559 8638 2622 2560 8639 2635 2573 8640 2634 2572 8641 2621 2559 8642 2636 2574 8643 2622 2560 8644 2623 2561 8645 2636 2574 8646 2635 2573 8647 2622 2560 8648 2637 2575 8649 2623 2561 8650 2624 2562 8651 2637 2575 8652 2636 2574 8653 2623 2561 8654 2638 2576 8655 2624 2562 8656 2625 2563 8657 2638 2576 8658 2637 2575 8659 2624 2562 8660 2639 2577 8661 2625 2563 8662 2626 2564 8663 2639 2577 8664 2638 2576 8665 2625 2563 8666 2640 2578 8667 2626 2564 8668 2627 2565 8669 2640 2578 8670 2639 2577 8671 2626 2564 8672 2641 2579 8673 2627 2565 8674 2628 2566 8675 2641 2579 8676 2640 2578 8677 2627 2565 8678 2642 2580 8679 2628 2566 8680 2607 2545 8681 2642 2580 8682 2641 2579 8683 2628 2566 8684 2610 2548 8685 2642 2580 8686 2607 2545 8687 892 883 8688 900 891 8689 2629 2567 8690 2643 2581 8691 2629 2567 8692 2630 2568 8693 2643 2581 8694 892 883 8695 2629 2567 8696 2644 2582 8697 2630 2568 8698 2631 2569 8699 2644 2582 8700 2643 2581 8701 2630 2568 8702 2645 2583 8703 2631 2569 8704 2632 2570 8705 2645 2583 8706 2644 2582 8707 2631 2569 8708 2646 2584 8709 2632 2570 8710 2633 2571 8711 2646 2584 8712 2645 2583 8713 2632 2570 8714 2647 2585 8715 2633 2571 8716 2634 2572 8717 2647 2585 8718 2646 2584 8719 2633 2571 8720 2648 2586 8721 2634 2572 8722 2635 2573 8723 2648 2586 8724 2647 2585 8725 2634 2572 8726 2649 2587 8727 2635 2573 8728 2636 2574 8729 2649 2587 8730 2648 2586 8731 2635 2573 8732 2650 2588 8733 2636 2574 8734 2637 2575 8735 2650 2588 8736 2649 2587 8737 2636 2574 8738 2651 2589 8739 2637 2575 8740 2638 2576 8741 2651 2589 8742 2650 2588 8743 2637 2575 8744 2652 2590 8745 2638 2576 8746 2639 2577 8747 2652 2590 8748 2651 2589 8749 2638 2576 8750 2653 2591 8751 2639 2577 8752 2640 2578 8753 2653 2591 8754 2652 2590 8755 2639 2577 8756 2654 2592 8757 2640 2578 8758 2641 2579 8759 2654 2592 8760 2653 2591 8761 2640 2578 8762 2655 2593 8763 2641 2579 8764 2642 2580 8765 2655 2593 8766 2654 2592 8767 2641 2579 8768 2656 2594 8769 2642 2580 8770 2610 2548 8771 2656 2594 8772 2655 2593 8773 2642 2580 8774 2613 2551 8775 2656 2594 8776 2610 2548 8777 899 890 8778 892 883 8779 2643 2581 8780 2657 2595 8781 2643 2581 8782 2644 2582 8783 2657 2595 8784 899 890 8785 2643 2581 8786 2658 2596 8787 2644 2582 8788 2645 2583 8789 2658 2596 8790 2657 2595 8791 2644 2582 8792 2659 2597 8793 2645 2583 8794 2646 2584 8795 2659 2597 8796 2658 2596 8797 2645 2583 8798 2660 2598 8799 2646 2584 8800 2647 2585 8801 2661 2599 8802 2659 2597 8803 2646 2584 8804 2660 2598 8805 2661 2599 8806 2646 2584 8807 2662 2600 8808 2647 2585 8809 2648 2586 8810 2663 2601 8811 2660 2598 8812 2647 2585 8813 2662 2600 8814 2663 2601 8815 2647 2585 8816 2664 2602 8817 2648 2586 8818 2649 2587 8819 2665 2603 8820 2662 2600 8821 2648 2586 8822 2664 2602 8823 2665 2603 8824 2648 2586 8825 2666 2604 8826 2649 2587 8827 2650 2588 8828 2667 2605 8829 2664 2602 8830 2649 2587 8831 2666 2604 8832 2667 2605 8833 2649 2587 8834 2668 2606 8835 2650 2588 8836 2651 2589 8837 2668 2606 8838 2666 2604 8839 2650 2588 8840 2669 2607 8841 2651 2589 8842 2652 2590 8843 2670 2608 8844 2668 2606 8845 2651 2589 8846 2669 2607 8847 2670 2608 8848 2651 2589 8849 2671 2609 8850 2652 2590 8851 2653 2591 8852 2672 2610 8853 2669 2607 8854 2652 2590 8855 2671 2609 8856 2672 2610 8857 2652 2590 8858 2673 2611 8859 2653 2591 8860 2654 2592 8861 2674 2612 8862 2671 2609 8863 2653 2591 8864 2673 2611 8865 2674 2612 8866 2653 2591 8867 2675 2613 8868 2654 2592 8869 2655 2593 8870 2676 2614 8871 2673 2611 8872 2654 2592 8873 2675 2613 8874 2676 2614 8875 2654 2592 8876 2677 2615 8877 2655 2593 8878 2656 2594 8879 2678 2616 8880 2675 2613 8881 2655 2593 8882 2677 2615 8883 2678 2616 8884 2655 2593 8885 2603 2541 8886 2656 2594 8887 2613 2551 8888 2603 2541 8889 2677 2615 8890 2656 2594 8891 2679 2617 8892 896 887 8893 2680 2618 8894 2679 2617 8895 920 911 8896 896 887 8897 2681 2619 8898 2680 2618 8899 2682 2620 8900 2681 2619 8901 2679 2617 8902 2680 2618 8903 2683 2621 8904 2682 2620 8905 2684 2622 8906 2683 2621 8907 2681 2619 8908 2682 2620 8909 2685 2623 8910 2684 2622 8911 2686 2624 8912 2685 2623 8913 2683 2621 8914 2684 2622 8915 2687 2625 8916 2686 2624 8917 2688 2626 8918 2687 2625 8919 2685 2623 8920 2686 2624 8921 2689 2627 8922 2688 2626 8923 2690 2628 8924 2689 2627 8925 2687 2625 8926 2688 2626 8927 2691 2629 8928 2690 2628 8929 2692 2630 8930 2691 2629 8931 2689 2627 8932 2690 2628 8933 2693 2631 8934 2692 2630 8935 2694 2632 8936 2693 2631 8937 2691 2629 8938 2692 2630 8939 2695 2633 8940 2694 2632 8941 2696 2634 8942 2695 2633 8943 2693 2631 8944 2694 2632 8945 2697 2635 8946 2696 2634 8947 2698 2636 8948 2697 2635 8949 2695 2633 8950 2696 2634 8951 2699 2637 8952 2698 2636 8953 2700 2638 8954 2699 2637 8955 2697 2635 8956 2698 2636 8957 2701 2639 8958 2700 2638 8959 2702 2640 8960 2701 2639 8961 2699 2637 8962 2700 2638 8963 2703 2641 8964 2702 2640 8965 2704 2642 8966 2703 2641 8967 2701 2639 8968 2702 2640 8969 2705 2643 8970 2704 2642 8971 2706 2644 8972 2705 2643 8973 2703 2641 8974 2704 2642 8975 2707 2645 8976 2706 2644 8977 2708 2646 8978 2707 2645 8979 2705 2643 8980 2706 2644 8981 2709 2647 8982 2708 2646 8983 2710 2648 8984 2709 2647 8985 2707 2645 8986 2708 2646 8987 2711 2649 8988 2710 2648 8989 2712 2650 8990 2711 2649 8991 2709 2647 8992 2710 2648 8993 2713 2651 8994 2712 2650 8995 2714 2652 8996 2713 2651 8997 2711 2649 8998 2712 2650 8999 2715 2653 9000 2714 2652 9001 2716 2654 9002 2715 2653 9003 2713 2651 9004 2714 2652 9005 2715 2653 9006 2716 2654 9007 2717 2655 9008 2718 2656 9009 2717 2655 9010 2719 2657 9011 2718 2656 9012 2715 2653 9013 2717 2655 9014 2720 2658 9015 2719 2657 9016 2721 2659 9017 2720 2658 9018 2718 2656 9019 2719 2657 9020 2597 2535 9021 2721 2659 9022 2606 2544 9023 2597 2535 9024 2720 2658 9025 2721 2659 9026 2722 2660 9027 2723 2660 9028 2724 2660 9029 2725 2660 9030 2726 2660 9031 2723 2660 9032 2722 2660 9033 2725 2660 9034 2723 2660 9035 2727 2660 9036 2724 2660 9037 2728 2660 9038 2727 2660 9039 2722 2660 9040 2724 2660 9041 2729 2660 9042 2728 2660 9043 2730 2660 9044 2729 2660 9045 2727 2660 9046 2728 2660 9047 2731 2661 9048 2730 2661 9049 2732 2661 9050 2731 2662 9051 2729 2662 9052 2730 2662 9053 2733 2663 9054 2732 2663 9055 2734 2663 9056 2733 2664 9057 2731 2664 9058 2732 2664 9059 2735 2660 9060 2734 2660 9061 2736 2660 9062 2735 2665 9063 2733 2665 9064 2734 2665 9065 2737 2660 9066 2736 2660 9067 2738 2660 9068 2737 2660 9069 2735 2660 9070 2736 2660 9071 2739 2666 9072 2738 2666 9073 2740 2666 9074 2741 2660 9075 2738 2660 9076 2739 2660 9077 2742 2667 9078 2738 2667 9079 2741 2667 9080 2742 2668 9081 2737 2668 9082 2738 2668 9083 2743 2669 9084 2740 2669 9085 2744 2669 9086 2739 2670 9087 2740 2670 9088 2743 2670 9089 2745 2671 9090 2744 2671 9091 2746 2671 9092 2743 2672 9093 2744 2672 9094 2745 2672 9095 2747 2660 9096 2746 2660 9097 2748 2660 9098 2745 2660 9099 2746 2660 9100 2747 2660 9101 2741 2673 9102 2739 2673 9103 2749 2673 9104 2750 2674 9105 2749 2674 9106 2751 2674 9107 2752 2675 9108 2741 2675 9109 2749 2675 9110 2750 2676 9111 2752 2676 9112 2749 2676 9113 2750 2660 9114 2751 2660 9115 2753 2660 9116 2754 2677 9117 2753 2677 9118 2755 2677 9119 2754 2660 9120 2750 2660 9121 2753 2660 9122 2756 2678 9123 2755 2678 9124 2757 2678 9125 2756 2660 9126 2754 2660 9127 2755 2660 9128 2758 2679 9129 2757 2679 9130 2759 2679 9131 2758 2660 9132 2756 2660 9133 2757 2660 9134 2760 2660 9135 2759 2660 9136 2761 2660 9137 2760 2660 9138 2758 2660 9139 2759 2660 9140 2762 2660 9141 2761 2660 9142 2763 2660 9143 2762 2660 9144 2760 2660 9145 2761 2660 9146 2762 2660 9147 2763 2660 9148 2764 2660 9149 2765 2660 9150 2766 2660 9151 2726 2660 9152 2767 2680 9153 921 912 9154 2768 2681 9155 2725 2660 9156 2765 2660 9157 2726 2660 9158 924 915 9159 921 912 9160 2767 2680 9161 2765 2660 9162 2769 2660 9163 2766 2660 9164 2770 2682 9165 2771 2683 9166 2772 2684 9167 2773 2660 9168 2774 2660 9169 2769 2660 9170 2775 2685 9171 2772 2684 9172 2776 2686 9173 2765 2660 9174 2773 2660 9175 2769 2660 9176 2777 2687 9177 2770 2682 9178 2772 2684 9179 2778 2688 9180 2777 2687 9181 2772 2684 9182 2779 2689 9183 2778 2688 9184 2772 2684 9185 2775 2685 9186 2779 2689 9187 2772 2684 9188 2780 2660 9189 2781 2660 9190 2774 2660 9191 2782 2690 9192 2776 2686 9193 2783 2691 9194 2773 2692 9195 2780 2692 9196 2774 2692 9197 2784 2693 9198 2775 2685 9199 2776 2686 9200 2782 2690 9201 2784 2693 9202 2776 2686 9203 2785 2660 9204 2786 2660 9205 2781 2660 9206 2787 2694 9207 2783 2691 9208 2788 2695 9209 2780 2660 9210 2785 2660 9211 2781 2660 9212 2789 2696 9213 2782 2690 9214 2783 2691 9215 2787 2694 9216 2789 2696 9217 2783 2691 9218 2790 2697 9219 2791 2697 9220 2786 2697 9221 2792 2698 9222 2788 2695 9223 2793 2699 9224 2785 2660 9225 2790 2660 9226 2786 2660 9227 2794 2700 9228 2787 2694 9229 2788 2695 9230 2792 2698 9231 2794 2700 9232 2788 2695 9233 2795 2660 9234 2796 2660 9235 2791 2660 9236 2797 2701 9237 2793 2699 9238 2798 2702 9239 2790 2660 9240 2795 2660 9241 2791 2660 9242 2797 2701 9243 2792 2698 9244 2793 2699 9245 2795 2703 9246 2799 2703 9247 2796 2703 9248 2800 2704 9249 2798 2702 9250 2801 2705 9251 2800 2704 9252 2797 2701 9253 2798 2702 9254 2802 2706 9255 2803 2706 9256 2799 2706 9257 2804 2707 9258 2801 2705 9259 2805 2708 9260 2806 2709 9261 2802 2709 9262 2799 2709 9263 2795 2710 9264 2806 2710 9265 2799 2710 9266 2807 2711 9267 2800 2704 9268 2801 2705 9269 2804 2707 9270 2807 2711 9271 2801 2705 9272 2808 2712 9273 2809 2712 9274 2803 2712 9275 2810 2713 9276 2805 2708 9277 2811 2714 9278 2812 2660 9279 2808 2660 9280 2803 2660 9281 2802 2660 9282 2812 2660 9283 2803 2660 9284 2810 2713 9285 2804 2707 9286 2805 2708 9287 2813 2715 9288 2814 2715 9289 2809 2715 9290 2815 2716 9291 2811 2714 9292 2816 2717 9293 2808 2718 9294 2813 2718 9295 2809 2718 9296 2815 2716 9297 2810 2713 9298 2811 2714 9299 2817 2719 9300 2818 2719 9301 2814 2719 9302 2819 2720 9303 2816 2717 9304 2820 2721 9305 2813 2722 9306 2817 2722 9307 2814 2722 9308 2821 2723 9309 2815 2716 9310 2816 2717 9311 2819 2720 9312 2821 2723 9313 2816 2717 9314 2817 2660 9315 2822 2660 9316 2818 2660 9317 2823 2724 9318 2820 2721 9319 2824 2725 9320 2823 2724 9321 2819 2720 9322 2820 2721 9323 2825 2726 9324 2824 2725 9325 2826 2727 9326 2825 2726 9327 2823 2724 9328 2824 2725 9329 2825 2726 9330 2826 2727 9331 2827 2728 9332 2828 2729 9333 2827 2728 9334 2829 2730 9335 2828 2729 9336 2825 2726 9337 2827 2728 9338 2830 2731 9339 2829 2730 9340 2831 2732 9341 2832 2733 9342 2828 2729 9343 2829 2730 9344 2830 2731 9345 2832 2733 9346 2829 2730 9347 2833 2660 9348 2834 2660 9349 2812 2660 9350 2835 2734 9351 2831 2732 9352 2836 2735 9353 2837 2736 9354 2833 2736 9355 2812 2736 9356 2802 2737 9357 2837 2737 9358 2812 2737 9359 2835 2734 9360 2830 2731 9361 2831 2732 9362 2838 2660 9363 2839 2660 9364 2834 2660 9365 2840 2738 9366 2836 2735 9367 2841 2739 9368 2833 2740 9369 2838 2740 9370 2834 2740 9371 2840 2738 9372 2835 2734 9373 2836 2735 9374 2842 2660 9375 2843 2660 9376 2839 2660 9377 2844 2741 9378 2841 2739 9379 2845 2742 9380 2838 2743 9381 2842 2743 9382 2839 2743 9383 2846 2744 9384 2840 2738 9385 2841 2739 9386 2844 2741 9387 2846 2744 9388 2841 2739 9389 2847 2745 9390 2848 2745 9391 2843 2745 9392 2849 2746 9393 2845 2742 9394 2592 2530 9395 2842 2747 9396 2847 2747 9397 2843 2747 9398 2850 2748 9399 2844 2741 9400 2845 2742 9401 2849 2746 9402 2850 2748 9403 2845 2742 9404 2851 2660 9405 2852 2660 9406 2848 2660 9407 2847 2749 9408 2851 2749 9409 2848 2749 9410 2593 2531 9411 2849 2746 9412 2592 2530 9413 2853 2660 9414 2854 2660 9415 2852 2660 9416 2851 2660 9417 2853 2660 9418 2852 2660 9419 2855 2660 9420 2856 2660 9421 2854 2660 9422 2853 2660 9423 2855 2660 9424 2854 2660 9425 2857 2660 9426 2764 2660 9427 2856 2660 9428 2855 2660 9429 2857 2660 9430 2856 2660 9431 2857 2660 9432 2762 2660 9433 2764 2660 9434 2858 2750 9435 2859 2751 9436 2860 2752 9437 2861 2753 9438 2862 2754 9439 2863 2755 9440 2861 2753 9441 2863 2755 9442 2864 2756 9443 2865 2757 9444 2860 2752 9445 2866 2758 9446 2867 2759 9447 2858 2750 9448 2860 2752 9449 2865 2757 9450 2867 2759 9451 2860 2752 9452 2868 2760 9453 2866 2758 9454 2869 2761 9455 2868 2760 9456 2865 2757 9457 2866 2758 9458 2870 2762 9459 2869 2761 9460 2871 2763 9461 2870 2762 9462 2868 2760 9463 2869 2761 9464 2872 2764 9465 2871 2763 9466 2873 2765 9467 2872 2764 9468 2870 2762 9469 2871 2763 9470 2874 2766 9471 2873 2765 9472 2875 2767 9473 2874 2766 9474 2872 2764 9475 2873 2765 9476 2876 2768 9477 2875 2767 9478 2877 2769 9479 2878 2770 9480 2874 2766 9481 2875 2767 9482 2876 2768 9483 2878 2770 9484 2875 2767 9485 2879 2771 9486 2877 2769 9487 2880 2772 9488 2879 2771 9489 2876 2768 9490 2877 2769 9491 2881 2773 9492 2880 2772 9493 2882 2774 9494 2881 2773 9495 2879 2771 9496 2880 2772 9497 2883 2775 9498 2882 2774 9499 2884 2776 9500 2883 2775 9501 2881 2773 9502 2882 2774 9503 2883 2775 9504 2884 2776 9505 2885 2777 9506 2886 2778 9507 2885 2777 9508 2887 2779 9509 2886 2778 9510 2883 2775 9511 2885 2777 9512 2888 2780 9513 2887 2779 9514 2889 2781 9515 2888 2780 9516 2886 2778 9517 2887 2779 9518 2890 2782 9519 2889 2781 9520 2891 2783 9521 2890 2782 9522 2888 2780 9523 2889 2781 9524 2892 2784 9525 2891 2783 9526 2893 2785 9527 2892 2784 9528 2890 2782 9529 2891 2783 9530 2894 2786 9531 2893 2785 9532 2895 2787 9533 2894 2786 9534 2892 2784 9535 2893 2785 9536 2894 2786 9537 2895 2787 9538 2896 2788 9539 2897 2789 9540 2898 2790 9541 2899 2791 9542 2900 2792 9543 2894 2786 9544 2896 2788 9545 2901 2793 9546 2899 2791 9547 2902 2794 9548 2903 2795 9549 2897 2789 9550 2899 2791 9551 2901 2793 9552 2903 2795 9553 2899 2791 9554 2904 2796 9555 2902 2794 9556 2905 2797 9557 2904 2796 9558 2901 2793 9559 2902 2794 9560 2906 2798 9561 2905 2797 9562 2907 2799 9563 2906 2798 9564 2904 2796 9565 2905 2797 9566 2908 2800 9567 2907 2799 9568 2909 2801 9569 2908 2800 9570 2906 2798 9571 2907 2799 9572 2910 2802 9573 2909 2801 9574 2911 2803 9575 2910 2802 9576 2908 2800 9577 2909 2801 9578 2912 2804 9579 2911 2803 9580 2913 2805 9581 2914 2806 9582 2910 2802 9583 2911 2803 9584 2912 2804 9585 2914 2806 9586 2911 2803 9587 2915 2807 9588 2913 2805 9589 2916 2808 9590 2915 2807 9591 2912 2804 9592 2913 2805 9593 2917 2809 9594 2916 2808 9595 2918 2810 9596 2917 2809 9597 2915 2807 9598 2916 2808 9599 2919 2811 9600 2918 2810 9601 2920 2812 9602 2919 2811 9603 2917 2809 9604 2918 2810 9605 2919 2811 9606 2920 2812 9607 2921 2813 9608 2922 2814 9609 2921 2813 9610 2923 2815 9611 2922 2814 9612 2919 2811 9613 2921 2813 9614 2924 2816 9615 2923 2815 9616 2925 2817 9617 2924 2816 9618 2922 2814 9619 2923 2815 9620 2926 2818 9621 2925 2817 9622 2927 2819 9623 2926 2818 9624 2924 2816 9625 2925 2817 9626 2928 2820 9627 2927 2819 9628 2929 2821 9629 2928 2820 9630 2926 2818 9631 2927 2819 9632 2861 2753 9633 2929 2821 9634 2862 2754 9635 2861 2753 9636 2928 2820 9637 2929 2821 9638 947 938 9639 2930 2822 9640 948 939 9641 950 941 9642 948 939 9643 2931 2823 9644 2932 2824 9645 2931 2823 9646 2933 2825 9647 2932 2824 9648 950 941 9649 2931 2823 9650 2932 2824 9651 2933 2825 9652 2934 2826 9653 2935 2827 9654 2934 2826 9655 2936 2828 9656 2935 2827 9657 2932 2824 9658 2934 2826 9659 2937 2829 9660 2936 2828 9661 2938 2830 9662 2937 2829 9663 2935 2827 9664 2936 2828 9665 2939 2831 9666 2938 2830 9667 2940 2832 9668 2939 2831 9669 2937 2829 9670 2938 2830 9671 2941 2833 9672 2942 2834 9673 2943 2835 9674 2944 2836 9675 2939 2831 9676 2940 2832 9677 2941 2833 9678 2945 2837 9679 2942 2834 9680 2941 2833 9681 2943 2835 9682 2946 2838 9683 2947 2839 9684 2946 2838 9685 2948 2840 9686 2941 2833 9687 2946 2838 9688 2947 2839 9689 2949 2841 9690 2950 2842 9691 2951 2843 9692 2949 2841 9693 2952 2844 9694 2950 2842 9695 2953 2845 9696 2951 2843 9697 2954 2846 9698 2953 2845 9699 2949 2841 9700 2951 2843 9701 2953 2845 9702 2954 2846 9703 2955 2847 9704 2956 2848 9705 2955 2847 9706 2957 2849 9707 2956 2848 9708 2953 2845 9709 2955 2847 9710 2956 2848 9711 2957 2849 9712 2958 2850 9713 2959 2851 9714 2958 2850 9715 2960 2852 9716 2959 2851 9717 2956 2848 9718 2958 2850 9719 2959 2851 9720 2960 2852 9721 2961 2853 9722 2962 2854 9723 2961 2853 9724 2963 2855 9725 2959 2851 9726 2961 2853 9727 2962 2854 9728 2964 2856 9729 2965 2857 9730 2966 2858 9731 2964 2856 9732 2967 2859 9733 2965 2857 9734 2968 2860 9735 2966 2858 9736 2969 2861 9737 2968 2860 9738 2964 2856 9739 2966 2858 9740 2970 2862 9741 2971 2863 9742 2972 2864 9743 2970 2862 9744 2973 2865 9745 2971 2863 9746 2974 2866 9747 2972 2864 9748 2975 2867 9749 2974 2866 9750 2970 2862 9751 2972 2864 9752 2974 2866 9753 2975 2867 9754 2976 2868 9755 2977 2869 9756 2976 2868 9757 2978 2870 9758 2977 2869 9759 2974 2866 9760 2976 2868 9761 2977 2869 9762 2978 2870 9763 2979 2871 9764 2980 2872 9765 2979 2871 9766 2981 2873 9767 2980 2872 9768 2977 2869 9769 2979 2871 9770 2980 2872 9771 2981 2873 9772 2982 2874 9773 2983 2875 9774 2982 2874 9775 2984 2876 9776 2983 2875 9777 2980 2872 9778 2982 2874 9779 2570 2508 9780 2985 2877 9781 2575 2513 9782 2570 2508 9783 2986 2878 9784 2985 2877 9785 2987 2879 9786 950 941 9787 2932 2824 9788 2988 2880 9789 2932 2824 9790 2935 2827 9791 2989 2881 9792 2987 2879 9793 2932 2824 9794 2988 2880 9795 2989 2881 9796 2932 2824 9797 2990 2882 9798 2935 2827 9799 2937 2829 9800 2990 2882 9801 2988 2880 9802 2935 2827 9803 2991 2883 9804 2937 2829 9805 2939 2831 9806 2991 2883 9807 2990 2882 9808 2937 2829 9809 2992 2884 9810 2939 2831 9811 2944 2836 9812 2992 2884 9813 2991 2883 9814 2939 2831 9815 2993 2885 9816 2992 2884 9817 2944 2836 9818 2994 2886 9819 2995 2887 9820 2945 2837 9821 2941 2833 9822 2994 2886 9823 2945 2837 9824 938 929 9825 943 934 9826 2996 2888 9827 2997 2889 9828 2996 2888 9829 2998 2890 9830 2997 2889 9831 938 929 9832 2996 2888 9833 2999 2891 9834 2988 2880 9835 2990 2882 9836 2997 2889 9837 2998 2890 9838 3000 2892 9839 3001 2893 9840 2990 2882 9841 2991 2883 9842 3002 2894 9843 2999 2891 9844 2990 2882 9845 3001 2893 9846 3002 2894 9847 2990 2882 9848 3003 2895 9849 2991 2883 9850 2992 2884 9851 3003 2895 9852 3001 2893 9853 2991 2883 9854 2993 2885 9855 3004 2896 9856 2992 2884 9857 3005 2897 9858 2992 2884 9859 3004 2896 9860 3005 2897 9861 3003 2895 9862 2992 2884 9863 2994 2886 9864 3006 2898 9865 2995 2887 9866 3007 2899 9867 3005 2897 9868 3004 2896 9869 3008 2900 9870 3009 2901 9871 3006 2898 9872 2994 2886 9873 3008 2900 9874 3006 2898 9875 3010 2902 9876 3000 2892 9877 3011 2903 9878 3010 2902 9879 2997 2889 9880 3000 2892 9881 3010 2902 9882 3011 2903 9883 3012 2904 9884 3013 2905 9885 3001 2893 9886 3003 2895 9887 3014 2906 9888 3012 2904 9889 3015 2907 9890 3014 2906 9891 3010 2902 9892 3012 2904 9893 3016 2908 9894 3003 2895 9895 3005 2897 9896 3016 2908 9897 3013 2905 9898 3003 2895 9899 3007 2899 9900 3017 2909 9901 3005 2897 9902 3016 2908 9903 3005 2897 9904 3017 2909 9905 3018 2910 9906 3019 2911 9907 3009 2901 9908 3020 2912 9909 3016 2908 9910 3017 2909 9911 3021 2913 9912 3022 2914 9913 3019 2911 9914 3023 2915 9915 3021 2913 9916 3019 2911 9917 3024 2916 9918 3023 2915 9919 3019 2911 9920 3018 2910 9921 3024 2916 9922 3019 2911 9923 3008 2900 9924 3018 2910 9925 3009 2901 9926 3025 2917 9927 3026 2918 9928 3027 2919 9929 3028 2920 9930 3014 2906 9931 3015 2907 9932 3029 2921 9933 3030 2922 9934 3031 2923 9935 3029 2921 9936 3031 2923 9937 3032 2924 9938 3033 2925 9939 3027 2919 9940 3034 2926 9941 3025 2917 9942 3027 2919 9943 3035 2927 9944 3033 2925 9945 3035 2927 9946 3027 2919 9947 3036 2928 9948 3037 2929 9949 3038 2930 9950 3039 2931 9951 3037 2929 9952 3036 2928 9953 934 925 9954 938 929 9955 2997 2889 9956 984 975 9957 2997 2889 9958 3010 2902 9959 984 975 9960 934 925 9961 2997 2889 9962 982 973 9963 3010 2902 9964 3014 2906 9965 982 973 9966 984 975 9967 3010 2902 9968 980 971 9969 3014 2906 9970 3028 2920 9971 980 971 9972 982 973 9973 3014 2906 9974 980 971 9975 3028 2920 9976 977 968 9977 3029 2921 9978 972 963 9979 3030 2922 9980 3029 2921 9981 975 966 9982 972 963 9983 3029 2921 9984 3032 2924 9985 3040 2932 9986 3041 2933 9987 3042 2934 9988 3043 2935 9989 3041 2933 9990 3043 2935 9991 3044 2936 9992 3039 2931 9993 3045 2937 9994 3046 2938 9995 969 960 9996 970 961 9997 3042 2934 9998 969 960 9999 3042 2934 10000 3041 2933 10001 3047 2939 10002 3044 2936 10003 3048 2940 10004 3049 2941 10005 3050 2942 10006 3045 2937 10007 3051 2943 10008 3052 2944 10009 3053 2945 10010 3054 2946 10011 3051 2943 10012 3053 2945 10013 3055 2947 10014 3056 2948 10015 3057 2949 10016 3058 2950 10017 3055 2947 10018 3057 2949 10019 3047 2939 10020 3041 2933 10021 3044 2936 10022 3036 2928 10023 3049 2941 10024 3045 2937 10025 3039 2931 10026 3036 2928 10027 3045 2937 10028 963 954 10029 969 960 10030 3041 2933 10031 3047 2939 10032 963 954 10033 3041 2933 10034 3059 2951 10035 960 951 10036 3052 2944 10037 953 944 10038 960 951 10039 3059 2951 10040 3059 2951 10041 3052 2944 10042 3051 2943 10043 3060 2952 10044 3061 2953 10045 3062 2954 10046 3063 2955 10047 3064 2956 10048 3065 2957 10049 3066 2958 10050 1088 1079 10051 3064 2956 10052 3063 2955 10053 3066 2958 10054 3064 2956 10055 3060 2952 10056 3067 2959 10057 3061 2953 10058 3068 2960 10059 3065 2957 10060 3069 2961 10061 3068 2960 10062 3063 2955 10063 3065 2957 10064 3060 2952 10065 3051 2943 10066 3067 2959 10067 3070 2962 10068 3067 2959 10069 3051 2943 10070 3068 2960 10071 3069 2961 10072 3071 2963 10073 3072 2964 10074 3059 2951 10075 3051 2943 10076 3060 2952 10077 3072 2964 10078 3051 2943 10079 3054 2946 10080 3070 2962 10081 3051 2943 10082 959 950 10083 953 944 10084 3059 2951 10085 3072 2964 10086 959 950 10087 3059 2951 10088 3055 2947 10089 3071 2963 10090 3056 2948 10091 3055 2947 10092 3068 2960 10093 3071 2963 10094 3066 2958 10095 1087 1078 10096 1088 1079 10097 3073 2965 10098 1073 1064 10099 1087 1078 10100 3074 2966 10101 3075 2967 10102 1073 1064 10103 3073 2965 10104 3074 2966 10105 1073 1064 10106 3076 2968 10107 1087 1078 10108 3066 2958 10109 3076 2968 10110 3073 2965 10111 1087 1078 10112 3077 2969 10113 3066 2958 10114 3063 2955 10115 3077 2969 10116 3076 2968 10117 3066 2958 10118 3078 2970 10119 3063 2955 10120 3068 2960 10121 3078 2970 10122 3077 2969 10123 3063 2955 10124 3079 2971 10125 3068 2960 10126 3055 2947 10127 3079 2971 10128 3078 2970 10129 3068 2960 10130 3080 2972 10131 3055 2947 10132 3058 2950 10133 3080 2972 10134 3079 2971 10135 3055 2947 10136 3081 2973 10137 3080 2972 10138 3058 2950 10139 3036 2928 10140 3082 2974 10141 3049 2941 10142 3083 2975 10143 3074 2966 10144 3073 2965 10145 3084 2976 10146 3085 2977 10147 3074 2966 10148 1135 1126 10149 1155 1146 10150 3086 2978 10151 3083 2975 10152 3084 2976 10153 3074 2966 10154 3087 2979 10155 3073 2965 10156 3076 2968 10157 3087 2979 10158 3083 2975 10159 3073 2965 10160 3088 2980 10161 3076 2968 10162 3077 2969 10163 3088 2980 10164 3087 2979 10165 3076 2968 10166 3089 2981 10167 3077 2969 10168 3078 2970 10169 3089 2981 10170 3088 2980 10171 3077 2969 10172 3090 2982 10173 3078 2970 10174 3079 2971 10175 3090 2982 10176 3089 2981 10177 3078 2970 10178 3091 2983 10179 3079 2971 10180 3080 2972 10181 3091 2983 10182 3090 2982 10183 3079 2971 10184 3081 2973 10185 3092 2984 10186 3080 2972 10187 3093 2985 10188 3080 2972 10189 3092 2984 10190 3093 2985 10191 3091 2983 10192 3080 2972 10193 3094 2986 10194 3095 2987 10195 3082 2974 10196 3096 2988 10197 3093 2985 10198 3092 2984 10199 3094 2986 10200 3097 2989 10201 3095 2987 10202 3094 2986 10203 3082 2974 10204 3098 2990 10205 3036 2928 10206 3098 2990 10207 3082 2974 10208 1135 1126 10209 3086 2978 10210 3099 2991 10211 3100 2992 10212 3084 2976 10213 3083 2975 10214 3101 2993 10215 3102 2994 10216 3084 2976 10217 1137 1128 10218 3099 2991 10219 3103 2995 10220 3100 2992 10221 3101 2993 10222 3084 2976 10223 1137 1128 10224 1135 1126 10225 3099 2991 10226 3104 2996 10227 3083 2975 10228 3087 2979 10229 3104 2996 10230 3100 2992 10231 3083 2975 10232 3105 2997 10233 3087 2979 10234 3088 2980 10235 3105 2997 10236 3104 2996 10237 3087 2979 10238 3106 2998 10239 3088 2980 10240 3089 2981 10241 3106 2998 10242 3105 2997 10243 3088 2980 10244 3107 2999 10245 3089 2981 10246 3090 2982 10247 3107 2999 10248 3106 2998 10249 3089 2981 10250 3108 3000 10251 3090 2982 10252 3091 2983 10253 3108 3000 10254 3107 2999 10255 3090 2982 10256 3109 3001 10257 3091 2983 10258 3093 2985 10259 3110 3002 10260 3108 3000 10261 3091 2983 10262 3109 3001 10263 3110 3002 10264 3091 2983 10265 3111 3003 10266 3112 3004 10267 3113 3005 10268 3114 3006 10269 3109 3001 10270 3093 2985 10271 3111 3003 10272 3115 3007 10273 3112 3004 10274 3018 2910 10275 3116 3008 10276 3117 3009 10277 3018 2910 10278 3117 3009 10279 3024 2916 10280 1137 1128 10281 3103 2995 10282 3118 3010 10283 3119 3011 10284 3101 2993 10285 3100 2992 10286 3120 3012 10287 3121 3013 10288 3101 2993 10289 3122 3014 10290 3118 3010 10291 3123 3015 10292 3119 3011 10293 3120 3012 10294 3101 2993 10295 3122 3014 10296 1137 1128 10297 3118 3010 10298 3124 3016 10299 3100 2992 10300 3104 2996 10301 3124 3016 10302 3119 3011 10303 3100 2992 10304 3125 3017 10305 3104 2996 10306 3105 2997 10307 3125 3017 10308 3124 3016 10309 3104 2996 10310 3126 3018 10311 3105 2997 10312 3106 2998 10313 3126 3018 10314 3125 3017 10315 3105 2997 10316 3127 3019 10317 3106 2998 10318 3107 2999 10319 3127 3019 10320 3126 3018 10321 3106 2998 10322 3128 3020 10323 3107 2999 10324 3108 3000 10325 3128 3020 10326 3127 3019 10327 3107 2999 10328 3129 3021 10329 3108 3000 10330 3110 3002 10331 3129 3021 10332 3128 3020 10333 3108 3000 10334 3130 3022 10335 3131 3023 10336 3132 3024 10337 3133 3025 10338 3129 3021 10339 3110 3002 10340 3130 3022 10341 3134 3026 10342 3131 3023 10343 3130 3022 10344 3132 3024 10345 3115 3007 10346 3130 3022 10347 3115 3007 10348 3111 3003 10349 3122 3014 10350 3123 3015 10351 3135 3027 10352 3136 3028 10353 3120 3012 10354 3119 3011 10355 3137 3029 10356 3138 3030 10357 3120 3012 10358 3139 3031 10359 3135 3027 10360 3140 3032 10361 3136 3028 10362 3137 3029 10363 3120 3012 10364 3139 3031 10365 3122 3014 10366 3135 3027 10367 3141 3033 10368 3119 3011 10369 3124 3016 10370 3141 3033 10371 3136 3028 10372 3119 3011 10373 3142 3034 10374 3124 3016 10375 3125 3017 10376 3142 3034 10377 3141 3033 10378 3124 3016 10379 3143 3035 10380 3125 3017 10381 3126 3018 10382 3143 3035 10383 3142 3034 10384 3125 3017 10385 3144 3036 10386 3126 3018 10387 3127 3019 10388 3144 3036 10389 3143 3035 10390 3126 3018 10391 3145 3037 10392 3127 3019 10393 3128 3020 10394 3145 3037 10395 3144 3036 10396 3127 3019 10397 3146 3038 10398 3128 3020 10399 3129 3021 10400 3146 3038 10401 3145 3037 10402 3128 3020 10403 3147 3039 10404 3148 3040 10405 3134 3026 10406 3149 3041 10407 3146 3038 10408 3129 3021 10409 3147 3039 10410 3150 3042 10411 3148 3040 10412 3147 3039 10413 3134 3026 10414 3130 3022 10415 3137 3029 10416 3151 3043 10417 3138 3030 10418 3152 3044 10419 3140 3032 10420 3153 3045 10421 3152 3044 10422 3139 3031 10423 3140 3032 10424 3152 3044 10425 3153 3045 10426 3154 3046 10427 3155 3047 10428 3137 3029 10429 3136 3028 10430 3155 3047 10431 3156 3048 10432 3137 3029 10433 3152 3044 10434 3154 3046 10435 3157 3049 10436 3158 3050 10437 3136 3028 10438 3141 3033 10439 3158 3050 10440 3155 3047 10441 3136 3028 10442 3159 3051 10443 3141 3033 10444 3142 3034 10445 3159 3051 10446 3158 3050 10447 3141 3033 10448 3160 3052 10449 3142 3034 10450 3143 3035 10451 3161 3053 10452 3159 3051 10453 3142 3034 10454 3160 3052 10455 3161 3053 10456 3142 3034 10457 3162 3054 10458 3143 3035 10459 3144 3036 10460 3162 3054 10461 3160 3052 10462 3143 3035 10463 3163 3055 10464 3144 3036 10465 3145 3037 10466 3164 3056 10467 3162 3054 10468 3144 3036 10469 3163 3055 10470 3164 3056 10471 3144 3036 10472 3165 3057 10473 3145 3037 10474 3146 3038 10475 3166 3058 10476 3163 3055 10477 3145 3037 10478 3167 3059 10479 3166 3058 10480 3145 3037 10481 3165 3057 10482 3167 3059 10483 3145 3037 10484 3168 3060 10485 3169 3061 10486 3150 3042 10487 3168 3060 10488 3170 3062 10489 3169 3061 10490 3168 3060 10491 3150 3042 10492 3147 3039 10493 3171 3063 10494 3172 3064 10495 3173 3065 10496 3174 3066 10497 3152 3044 10498 3157 3049 10499 3175 3067 10500 3176 3068 10501 3177 3069 10502 3178 3070 10503 3172 3064 10504 3179 3071 10505 3171 3063 10506 3179 3071 10507 3172 3064 10508 3171 3063 10509 3173 3065 10510 3180 3072 10511 3181 3073 10512 3180 3072 10513 3182 3074 10514 3171 3063 10515 3180 3072 10516 3181 3073 10517 3183 3075 10518 3182 3074 10519 3184 3076 10520 3181 3073 10521 3182 3074 10522 3183 3075 10523 3183 3075 10524 3184 3076 10525 3185 3077 10526 3186 3078 10527 3185 3077 10528 3187 3079 10529 3183 3075 10530 3185 3077 10531 3186 3078 10532 3188 3080 10533 3187 3079 10534 3189 3081 10535 3186 3078 10536 3187 3079 10537 3188 3080 10538 3190 3082 10539 3189 3081 10540 3191 3083 10541 3188 3080 10542 3189 3081 10543 3190 3082 10544 3192 3084 10545 3191 3083 10546 3193 3085 10547 3190 3082 10548 3191 3083 10549 3192 3084 10550 3194 3086 10551 3195 3087 10552 3196 3088 10553 3197 3089 10554 3198 3090 10555 3199 3091 10556 3194 3086 10557 3200 3092 10558 3195 3087 10559 3168 3060 10560 3196 3088 10561 3170 3062 10562 3194 3086 10563 3196 3088 10564 3168 3060 10565 1123 1114 10566 1137 1128 10567 3122 3014 10568 3201 3093 10569 3122 3014 10570 3139 3031 10571 3201 3093 10572 1123 1114 10573 3122 3014 10574 3202 3094 10575 3139 3031 10576 3152 3044 10577 3202 3094 10578 3201 3093 10579 3139 3031 10580 3203 3095 10581 3152 3044 10582 3174 3066 10583 3203 3095 10584 3202 3094 10585 3152 3044 10586 3204 3096 10587 3203 3095 10588 3174 3066 10589 3175 3067 10590 3205 3097 10591 3176 3068 10592 1103 1094 10593 1123 1114 10594 3201 3093 10595 2305 2245 10596 3201 3093 10597 3202 3094 10598 2305 2245 10599 1103 1094 10600 3201 3093 10601 2302 2242 10602 3202 3094 10603 3203 3095 10604 2302 2242 10605 2305 2245 10606 3202 3094 10607 2300 2240 10608 3203 3095 10609 3204 3096 10610 2300 2240 10611 2302 2242 10612 3203 3095 10613 2296 2236 10614 2300 2240 10615 3204 3096 10616 2251 2194 10617 2299 2239 10618 3205 3097 10619 3175 3067 10620 2251 2194 10621 3205 3097 10622 3206 3098 10623 2248 2191 10624 2251 2194 10625 3175 3067 10626 3206 3098 10627 2251 2194 10628 3207 3099 10629 2242 2185 10630 2248 2191 10631 3208 3100 10632 3207 3099 10633 2248 2191 10634 3209 3101 10635 3208 3100 10636 2248 2191 10637 3206 3098 10638 3209 3101 10639 2248 2191 10640 3210 3102 10641 2238 2181 10642 2242 2185 10643 3207 3099 10644 3210 3102 10645 2242 2185 10646 3211 3103 10647 2235 2178 10648 2238 2181 10649 3210 3102 10650 3211 3103 10651 2238 2181 10652 3212 3104 10653 2231 2174 10654 2235 2178 10655 3213 3105 10656 3212 3104 10657 2235 2178 10658 3211 3103 10659 3213 3105 10660 2235 2178 10661 3214 3106 10662 2225 2168 10663 2231 2174 10664 3212 3104 10665 3214 3106 10666 2231 2174 10667 3215 3107 10668 2219 2162 10669 2225 2168 10670 3216 3108 10671 3215 3107 10672 2225 2168 10673 3217 3109 10674 3216 3108 10675 2225 2168 10676 3214 3106 10677 3217 3109 10678 2225 2168 10679 3218 3110 10680 2211 2154 10681 2219 2162 10682 3215 3107 10683 3218 3110 10684 2219 2162 10685 3218 3110 10686 2424 2362 10687 2211 2154 10688 2421 2359 10689 2425 2363 10690 3219 3111 10691 2421 2359 10692 3219 3111 10693 3220 3112 10694 2421 2359 10695 3220 3112 10696 3221 3113 10697 3222 3114 10698 3221 3113 10699 3223 3115 10700 3222 3114 10701 2421 2359 10702 3221 3113 10703 3222 3114 10704 3223 3115 10705 3224 3116 10706 3225 3117 10707 3224 3116 10708 3226 3118 10709 3222 3114 10710 3224 3116 10711 3225 3117 10712 3227 3119 10713 3225 3117 10714 3228 3120 10715 3229 3121 10716 3225 3117 10717 3227 3119 10718 3179 3071 10719 3225 3117 10720 3229 3121 10721 3222 3114 10722 3225 3117 10723 3179 3071 10724 3230 3122 10725 3179 3071 10726 3231 3123 10727 3178 3070 10728 3179 3071 10729 3230 3122 10730 3171 3063 10731 3222 3114 10732 3179 3071 10733 3232 3124 10734 2480 2418 10735 2486 2424 10736 2483 2421 10737 2485 2423 10738 3233 3125 10739 3234 3126 10740 2486 2424 10741 2488 2426 10742 3234 3126 10743 3232 3124 10744 2486 2424 10745 3235 3127 10746 2488 2426 10747 2490 2428 10748 3235 3127 10749 3234 3126 10750 2488 2426 10751 3236 3128 10752 2490 2428 10753 2493 2431 10754 3236 3128 10755 3235 3127 10756 2490 2428 10757 3237 3129 10758 2493 2431 10759 2495 2433 10760 3237 3129 10761 3236 3128 10762 2493 2431 10763 3238 3130 10764 2495 2433 10765 2421 2359 10766 3238 3130 10767 3237 3129 10768 2495 2433 10769 3222 3114 10770 3238 3130 10771 2421 2359 10772 3190 3082 10773 3232 3124 10774 3234 3126 10775 3190 3082 10776 3192 3084 10777 3232 3124 10778 3197 3089 10779 3233 3125 10780 3198 3090 10781 3239 3131 10782 3233 3125 10783 3197 3089 10784 2483 2421 10785 3233 3125 10786 3239 3131 10787 3188 3080 10788 3234 3126 10789 3235 3127 10790 3188 3080 10791 3190 3082 10792 3234 3126 10793 3186 3078 10794 3235 3127 10795 3236 3128 10796 3186 3078 10797 3188 3080 10798 3235 3127 10799 3183 3075 10800 3236 3128 10801 3237 3129 10802 3183 3075 10803 3186 3078 10804 3236 3128 10805 3181 3073 10806 3237 3129 10807 3238 3130 10808 3181 3073 10809 3183 3075 10810 3237 3129 10811 3171 3063 10812 3238 3130 10813 3222 3114 10814 3171 3063 10815 3181 3073 10816 3238 3130 10817 2964 2856 10818 3240 3132 10819 2967 2859 10820 3241 3133 10821 2962 2854 10822 3242 3134 10823 2959 2851 10824 2962 2854 10825 3241 3133 10826 3243 3135 10827 3244 3136 10828 3240 3132 10829 3245 3137 10830 3242 3134 10831 3246 3138 10832 3247 3139 10833 3243 3135 10834 3240 3132 10835 2964 2856 10836 3247 3139 10837 3240 3132 10838 3241 3133 10839 3242 3134 10840 3245 3137 10841 3248 3140 10842 3249 3141 10843 3244 3136 10844 3250 3142 10845 3246 3138 10846 3251 3143 10847 3243 3135 10848 3248 3140 10849 3244 3136 10850 3245 3137 10851 3246 3138 10852 3250 3142 10853 3239 3131 10854 3197 3089 10855 3249 3141 10856 3252 3144 10857 3251 3143 10858 3200 3092 10859 3248 3140 10860 3239 3131 10861 3249 3141 10862 3250 3142 10863 3251 3143 10864 3252 3144 10865 3252 3144 10866 3200 3092 10867 3194 3086 10868 3253 3145 10869 3239 3131 10870 3248 3140 10871 3253 3145 10872 2483 2421 10873 3239 3131 10874 3254 3146 10875 3248 3140 10876 3243 3135 10877 3254 3146 10878 3253 3145 10879 3248 3140 10880 3254 3146 10881 3243 3135 10882 3247 3139 10883 3255 3147 10884 3247 3139 10885 2964 2856 10886 3255 3147 10887 3254 3146 10888 3247 3139 10889 2968 2860 10890 3255 3147 10891 2964 2856 10892 3256 3148 10893 2478 2416 10894 3257 3149 10895 3256 3148 10896 2472 2410 10897 2478 2416 10898 3258 3150 10899 3257 3149 10900 3259 3151 10901 3258 3150 10902 3256 3148 10903 3257 3149 10904 3260 3152 10905 3259 3151 10906 3261 3153 10907 3260 3152 10908 3258 3150 10909 3259 3151 10910 3262 3154 10911 3261 3153 10912 2973 2865 10913 3262 3154 10914 3260 3152 10915 3261 3153 10916 2970 2862 10917 3262 3154 10918 2973 2865 10919 2949 2841 10920 3263 3155 10921 2952 2844 10922 2941 2833 10923 2947 2839 10924 3264 3156 10925 3265 3157 10926 3266 3158 10927 3263 3155 10928 2941 2833 10929 3264 3156 10930 3267 3159 10931 2949 2841 10932 3265 3157 10933 3263 3155 10934 3268 3160 10935 3269 3161 10936 3266 3158 10937 2994 2886 10938 3267 3159 10939 3270 3162 10940 3265 3157 10941 3268 3160 10942 3266 3158 10943 2941 2833 10944 3267 3159 10945 2994 2886 10946 3271 3163 10947 3272 3164 10948 3269 3161 10949 3008 2900 10950 3270 3162 10951 3273 3165 10952 3268 3160 10953 3271 3163 10954 3269 3161 10955 2994 2886 10956 3270 3162 10957 3008 2900 10958 3274 3166 10959 3275 3167 10960 3272 3164 10961 3008 2900 10962 3273 3165 10963 3276 3168 10964 3271 3163 10965 3274 3166 10966 3272 3164 10967 3130 3022 10968 3111 3003 10969 3275 3167 10970 3018 2910 10971 3276 3168 10972 3116 3008 10973 3274 3166 10974 3130 3022 10975 3275 3167 10976 3008 2900 10977 3276 3168 10978 3018 2910 10979 3147 3039 10980 3130 3022 10981 3274 3166 10982 3277 3169 10983 3274 3166 10984 3271 3163 10985 3277 3169 10986 3147 3039 10987 3274 3166 10988 3278 3170 10989 3271 3163 10990 3268 3160 10991 3278 3170 10992 3277 3169 10993 3271 3163 10994 3279 3171 10995 3268 3160 10996 3265 3157 10997 3279 3171 10998 3278 3170 10999 3268 3160 11000 3280 3172 11001 3265 3157 11002 2949 2841 11003 3280 3172 11004 3279 3171 11005 3265 3157 11006 2953 2845 11007 3280 3172 11008 2949 2841 11009 3168 3060 11010 3147 3039 11011 3277 3169 11012 3281 3173 11013 3277 3169 11014 3278 3170 11015 3281 3173 11016 3168 3060 11017 3277 3169 11018 3282 3174 11019 3278 3170 11020 3279 3171 11021 3282 3174 11022 3281 3173 11023 3278 3170 11024 3283 3175 11025 3279 3171 11026 3280 3172 11027 3283 3175 11028 3282 3174 11029 3279 3171 11030 3284 3176 11031 3280 3172 11032 2953 2845 11033 3284 3176 11034 3283 3175 11035 3280 3172 11036 2956 2848 11037 3284 3176 11038 2953 2845 11039 3194 3086 11040 3168 3060 11041 3281 3173 11042 3252 3144 11043 3281 3173 11044 3282 3174 11045 3252 3144 11046 3194 3086 11047 3281 3173 11048 3250 3142 11049 3282 3174 11050 3283 3175 11051 3250 3142 11052 3252 3144 11053 3282 3174 11054 3245 3137 11055 3283 3175 11056 3284 3176 11057 3245 3137 11058 3250 3142 11059 3283 3175 11060 3241 3133 11061 3284 3176 11062 2956 2848 11063 3241 3133 11064 3245 3137 11065 3284 3176 11066 2959 2851 11067 3241 3133 11068 2956 2848 11069 3036 2928 11070 3038 2930 11071 3098 2990 11072 2503 2441 11073 2472 2410 11074 3256 3148 11075 3285 3177 11076 3256 3148 11077 3258 3150 11078 3285 3177 11079 2503 2441 11080 3256 3148 11081 3286 3178 11082 3258 3150 11083 3260 3152 11084 3286 3178 11085 3285 3177 11086 3258 3150 11087 3287 3179 11088 3260 3152 11089 3262 3154 11090 3287 3179 11091 3286 3178 11092 3260 3152 11093 3288 3180 11094 3262 3154 11095 2970 2862 11096 3288 3180 11097 3287 3179 11098 3262 3154 11099 2974 2866 11100 3288 3180 11101 2970 2862 11102 2513 2451 11103 2503 2441 11104 3285 3177 11105 3289 3181 11106 3285 3177 11107 3286 3178 11108 3289 3181 11109 2513 2451 11110 3285 3177 11111 3290 3182 11112 3286 3178 11113 3287 3179 11114 3290 3182 11115 3289 3181 11116 3286 3178 11117 3291 3183 11118 3287 3179 11119 3288 3180 11120 3291 3183 11121 3290 3182 11122 3287 3179 11123 3292 3184 11124 3288 3180 11125 2974 2866 11126 3292 3184 11127 3291 3183 11128 3288 3180 11129 2977 2869 11130 3292 3184 11131 2974 2866 11132 2524 2462 11133 2513 2451 11134 3289 3181 11135 3293 3185 11136 3289 3181 11137 3290 3182 11138 3293 3185 11139 2524 2462 11140 3289 3181 11141 3294 3186 11142 3290 3182 11143 3291 3183 11144 3294 3186 11145 3293 3185 11146 3290 3182 11147 3295 3187 11148 3291 3183 11149 3292 3184 11150 3295 3187 11151 3294 3186 11152 3291 3183 11153 3296 3188 11154 3292 3184 11155 2977 2869 11156 3296 3188 11157 3295 3187 11158 3292 3184 11159 2980 2872 11160 3296 3188 11161 2977 2869 11162 3297 3189 11163 2524 2462 11164 3293 3185 11165 3297 3189 11166 2540 2478 11167 2524 2462 11168 3298 3190 11169 3293 3185 11170 3294 3186 11171 3298 3190 11172 3297 3189 11173 3293 3185 11174 3299 3191 11175 3294 3186 11176 3295 3187 11177 3299 3191 11178 3298 3190 11179 3294 3186 11180 3300 3192 11181 3295 3187 11182 3296 3188 11183 3300 3192 11184 3299 3191 11185 3295 3187 11186 3301 3193 11187 3296 3188 11188 2980 2872 11189 3301 3193 11190 3300 3192 11191 3296 3188 11192 2983 2875 11193 3301 3193 11194 2980 2872 11195 2543 2481 11196 2537 2475 11197 3302 3194 11198 2543 2481 11199 3302 3194 11200 3303 3195 11201 2555 2493 11202 3303 3195 11203 3304 3196 11204 2555 2493 11205 2543 2481 11206 3303 3195 11207 2562 2500 11208 3304 3196 11209 3305 3197 11210 2562 2500 11211 2555 2493 11212 3304 3196 11213 2562 2500 11214 3305 3197 11215 3306 3198 11216 2570 2508 11217 3306 3198 11218 2986 2878 11219 2570 2508 11220 2562 2500 11221 3306 3198 11222 3307 3199 11223 3308 3199 11224 3309 3199 11225 3307 3200 11226 3309 3200 11227 3310 3200 11228 3311 3201 11229 3310 3201 11230 3312 3201 11231 3307 2660 11232 3310 2660 11233 3311 2660 11234 3313 3202 11235 3312 3202 11236 3314 3202 11237 3311 3203 11238 3312 3203 11239 3313 3203 11240 3315 3204 11241 3314 3204 11242 3316 3204 11243 3313 2660 11244 3314 2660 11245 3315 2660 11246 3317 3205 11247 3316 3205 11248 3318 3205 11249 3315 3206 11250 3316 3206 11251 3317 3206 11252 3317 3207 11253 3318 3207 11254 3319 3207 11255 3320 3208 11256 3319 3208 11257 3321 3208 11258 3317 3209 11259 3319 3209 11260 3320 3209 11261 3322 3210 11262 3321 3210 11263 3323 3210 11264 3320 3211 11265 3321 3211 11266 3322 3211 11267 3324 3212 11268 3323 3212 11269 3325 3212 11270 3322 3213 11271 3323 3213 11272 3324 3213 11273 3326 3214 11274 3325 3214 11275 3327 3214 11276 3324 3215 11277 3325 3215 11278 3326 3215 11279 3328 3216 11280 3327 3216 11281 3329 3216 11282 3326 2660 11283 3327 2660 11284 3328 2660 11285 3330 3217 11286 3329 3217 11287 3331 3217 11288 3332 3218 11289 3329 3218 11290 3330 3218 11291 3328 2660 11292 3329 2660 11293 3332 2660 11294 3333 2660 11295 3331 2660 11296 3334 2660 11297 3330 2660 11298 3331 2660 11299 3333 2660 11300 3335 3219 11301 3334 3219 11302 3336 3219 11303 3333 3220 11304 3334 3220 11305 3335 3220 11306 3337 3221 11307 3336 3221 11308 3338 3221 11309 3335 3222 11310 3336 3222 11311 3337 3222 11312 3339 2660 11313 3338 2660 11314 3340 2660 11315 3337 3223 11316 3338 3223 11317 3339 3223 11318 3341 3224 11319 3342 3224 11320 3343 3224 11321 3344 3225 11322 3345 3225 11323 3342 3225 11324 3341 3226 11325 3344 3226 11326 3342 3226 11327 3346 3227 11328 3343 3227 11329 3347 3227 11330 3346 3228 11331 3341 3228 11332 3343 3228 11333 3348 3229 11334 3347 3229 11335 3349 3229 11336 3350 3230 11337 3346 3230 11338 3347 3230 11339 3348 3231 11340 3350 3231 11341 3347 3231 11342 3351 3232 11343 3349 3232 11344 3352 3232 11345 3351 3233 11346 3348 3233 11347 3349 3233 11348 3353 3234 11349 3352 3234 11350 3354 3234 11351 3353 3235 11352 3351 3235 11353 3352 3235 11354 3353 3236 11355 3354 3236 11356 3355 3236 11357 3356 3237 11358 3353 3237 11359 3355 3237 11360 3357 3238 11361 3356 3238 11362 3355 3238 11363 3358 3239 11364 3359 3239 11365 3345 3239 11366 3344 3240 11367 3358 3240 11368 3345 3240 11369 3358 3241 11370 3360 3241 11371 3359 3241 11372 3357 3242 11373 3361 3242 11374 3356 3242 11375 3362 3243 11376 3363 3243 11377 3361 3243 11378 3357 3244 11379 3362 3244 11380 3361 3244 11381 3364 3245 11382 3365 3245 11383 3363 3245 11384 3362 3246 11385 3364 3246 11386 3363 3246 11387 3366 3247 11388 3367 3247 11389 3365 3247 11390 3364 3248 11391 3366 3248 11392 3365 3248 11393 3368 3249 11394 3369 3249 11395 3367 3249 11396 3366 3250 11397 3368 3250 11398 3367 3250 11399 3370 3251 11400 3371 3251 11401 3369 3251 11402 3368 3252 11403 3370 3252 11404 3369 3252 11405 3372 3253 11406 3373 3253 11407 3371 3253 11408 3370 3254 11409 3372 3254 11410 3371 3254 11411 3374 3255 11412 3375 3255 11413 3373 3255 11414 3372 3256 11415 3374 3256 11416 3373 3256 11417 3374 3257 11418 3376 3257 11419 3375 3257 11420 3377 3258 11421 1290 1280 11422 1293 1283 11423 1296 1286 11424 3377 3258 11425 1293 1283 11426 3378 3259 11427 1287 1277 11428 1290 1280 11429 3377 3258 11430 3378 3259 11431 1290 1280 11432 3379 3260 11433 1285 1275 11434 1287 1277 11435 3378 3259 11436 3379 3260 11437 1287 1277 11438 3380 3261 11439 3381 3262 11440 1285 1275 11441 1043 1034 11442 1285 1275 11443 3381 3262 11444 3379 3260 11445 3380 3261 11446 1285 1275 11447 3382 3263 11448 3383 3264 11449 3381 3262 11450 1033 1024 11451 3381 3262 11452 3383 3264 11453 3380 3261 11454 3382 3263 11455 3381 3262 11456 1033 1024 11457 1043 1034 11458 3381 3262 11459 3384 3265 11460 3385 3266 11461 3383 3264 11462 1028 1019 11463 3383 3264 11464 3385 3266 11465 3382 3263 11466 3384 3265 11467 3383 3264 11468 1028 1019 11469 1033 1024 11470 3383 3264 11471 3386 3267 11472 3387 3268 11473 3385 3266 11474 772 763 11475 3385 3266 11476 3387 3268 11477 3384 3265 11478 3386 3267 11479 3385 3266 11480 772 763 11481 1028 1019 11482 3385 3266 11483 3388 3269 11484 3389 3270 11485 3387 3268 11486 797 788 11487 3387 3268 11488 3389 3270 11489 3386 3267 11490 3388 3269 11491 3387 3268 11492 797 788 11493 772 763 11494 3387 3268 11495 3390 3271 11496 3391 3272 11497 3389 3270 11498 794 785 11499 3389 3270 11500 3391 3272 11501 3388 3269 11502 3390 3271 11503 3389 3270 11504 794 785 11505 797 788 11506 3389 3270 11507 3392 3273 11508 3393 3274 11509 3391 3272 11510 792 783 11511 3391 3272 11512 3393 3274 11513 3390 3271 11514 3392 3273 11515 3391 3272 11516 792 783 11517 794 785 11518 3391 3272 11519 3394 3275 11520 1970 1916 11521 3393 3274 11522 789 780 11523 3393 3274 11524 1970 1916 11525 3392 3273 11526 3394 3275 11527 3393 3274 11528 789 780 11529 792 783 11530 3393 3274 11531 3394 3275 11532 1973 1919 11533 1970 1916 11534 787 778 11535 789 780 11536 1970 1916 11537 1737 1710 11538 1973 1919 11539 3394 3275 11540 1733 1706 11541 3394 3275 11542 3392 3273 11543 1737 1710 11544 3394 3275 11545 1733 1706 11546 1730 1703 11547 3392 3273 11548 3390 3271 11549 1733 1706 11550 3392 3273 11551 1730 1703 11552 1726 1699 11553 3390 3271 11554 3388 3269 11555 1730 1703 11556 3390 3271 11557 1726 1699 11558 1723 1696 11559 3388 3269 11560 3386 3267 11561 1726 1699 11562 3388 3269 11563 1723 1696 11564 1719 1692 11565 3386 3267 11566 3384 3265 11567 1723 1696 11568 3386 3267 11569 1719 1692 11570 1716 1689 11571 3384 3265 11572 3382 3263 11573 1719 1692 11574 3384 3265 11575 1716 1689 11576 1712 1685 11577 3382 3263 11578 3380 3261 11579 1716 1689 11580 3382 3263 11581 1712 1685 11582 1706 1679 11583 3380 3261 11584 3379 3260 11585 1712 1685 11586 3380 3261 11587 1706 1679 11588 1702 1675 11589 3379 3260 11590 3378 3259 11591 1706 1679 11592 3379 3260 11593 1702 1675 11594 1699 1672 11595 3378 3259 11596 3377 3258 11597 1702 1675 11598 3378 3259 11599 1699 1672 11600 1695 1668 11601 3377 3258 11602 1296 1286 11603 1699 1672 11604 3377 3258 11605 1695 1668 11606 1692 1665 11607 1296 1286 11608 1298 1288 11609 1695 1668 11610 1296 1286 11611 1692 1665 11612 1688 1661 11613 1298 1288 11614 1277 1268 11615 1692 1665 11616 1298 1288 11617 1688 1661 11618 1688 1661 11619 1277 1268 11620 1530 1520 11621 166 166 11622 537 533 11623 541 537 11624 134 134 11625 540 536 11626 159 159 11627 134 134 11628 534 530 11629 540 536 11630 163 163 11631 541 537 11632 543 539 11633 163 163 11634 166 166 11635 541 537 11636 2011 1957 11637 543 539 11638 546 542 11639 2011 1957 11640 163 163 11641 543 539 11642 2009 1955 11643 546 542 11644 549 545 11645 2009 1955 11646 2011 1957 11647 546 542 11648 2006 1952 11649 549 545 11650 424 421 11651 2006 1952 11652 2009 1955 11653 549 545 11654 748 739 11655 2006 1952 11656 424 421 11657 114 114 11658 526 522 11659 529 525 11660 103 103 11661 529 525 11662 532 528 11663 103 103 11664 114 114 11665 529 525 11666 98 98 11667 532 528 11668 534 530 11669 98 98 11670 103 103 11671 532 528 11672 134 134 11673 98 98 11674 534 530 11675 3395 3276 11676 3396 3276 11677 3397 3276 11678 3398 3277 11679 3396 3277 11680 3395 3277 11681 3399 3278 11682 3396 3278 11683 3398 3278 11684 3400 3279 11685 3397 3279 11686 3401 3279 11687 3395 3280 11688 3397 3280 11689 3400 3280 11690 3402 3281 11691 3401 3281 11692 3403 3281 11693 3400 3282 11694 3401 3282 11695 3402 3282 11696 3404 3283 11697 3403 3283 11698 3405 3283 11699 3402 3284 11700 3403 3284 11701 3404 3284 11702 3406 3285 11703 3405 3285 11704 3407 3285 11705 3404 3286 11706 3405 3286 11707 3406 3286 11708 3408 3287 11709 3407 3287 11710 3409 3287 11711 3406 1648 11712 3407 1648 11713 3408 1648 11714 3410 3288 11715 3409 3288 11716 3411 3288 11717 3408 3289 11718 3409 3289 11719 3410 3289 11720 3412 3290 11721 3411 3290 11722 3413 3290 11723 3414 3291 11724 3411 3291 11725 3412 3291 11726 3410 3292 11727 3411 3292 11728 3414 3292 11729 3415 3293 11730 3413 3293 11731 3416 3293 11732 3412 3294 11733 3413 3294 11734 3415 3294 11735 3417 3295 11736 3416 3295 11737 3418 3295 11738 3415 3296 11739 3416 3296 11740 3417 3296 11741 3399 3297 11742 3398 3297 11743 3419 3297 11744 3420 3298 11745 3419 3298 11746 3421 3298 11747 3399 3299 11748 3419 3299 11749 3420 3299 11750 3422 3300 11751 3421 3300 11752 3423 3300 11753 3420 3301 11754 3421 3301 11755 3422 3301 11756 3424 3302 11757 3423 3302 11758 3425 3302 11759 3422 3303 11760 3423 3303 11761 3424 3303 11762 3426 3304 11763 3425 3304 11764 3427 3304 11765 3424 1648 11766 3425 1648 11767 3426 1648 11768 3428 3305 11769 3427 3305 11770 3429 3305 11771 3426 3306 11772 3427 3306 11773 3428 3306 11774 3430 3307 11775 3429 3307 11776 3431 3307 11777 3432 3308 11778 3429 3308 11779 3430 3308 11780 3428 3309 11781 3429 3309 11782 3432 3309 11783 3433 3310 11784 3431 3310 11785 3434 3310 11786 3430 3311 11787 3431 3311 11788 3433 3311 11789 3435 3312 11790 3434 3312 11791 3436 3312 11792 3433 3313 11793 3434 3313 11794 3435 3313 11795 3437 3314 11796 3438 3314 11797 3439 3314 11798 3440 3315 11799 3441 3315 11800 3438 3315 11801 3437 3316 11802 3440 3316 11803 3438 3316 11804 3442 3317 11805 3439 3317 11806 3443 3317 11807 3442 3318 11808 3437 3318 11809 3439 3318 11810 3444 3319 11811 3443 3319 11812 3445 3319 11813 3444 3320 11814 3442 3320 11815 3443 3320 11816 3446 3321 11817 3445 3321 11818 3447 3321 11819 3446 3322 11820 3444 3322 11821 3445 3322 11822 3448 3323 11823 3447 3323 11824 3449 3323 11825 3448 3324 11826 3446 3324 11827 3447 3324 11828 3450 3325 11829 3449 3325 11830 3451 3325 11831 3450 3326 11832 3448 3326 11833 3449 3326 11834 3452 3327 11835 3450 3327 11836 3451 3327 11837 3453 3328 11838 3452 3328 11839 3451 3328 11840 3454 3329 11841 3455 3329 11842 3441 3329 11843 3440 3330 11844 3454 3330 11845 3441 3330 11846 3453 3331 11847 3456 3331 11848 3452 3331 11849 3457 3332 11850 3458 3332 11851 3456 3332 11852 3453 3333 11853 3457 3333 11854 3456 3333 11855 3457 3334 11856 3459 3334 11857 3458 3334 11858 3460 3335 11859 3461 3335 11860 3459 3335 11861 3457 3336 11862 3460 3336 11863 3459 3336 11864 3462 3337 11865 3463 3337 11866 3461 3337 11867 3460 3338 11868 3462 3338 11869 3461 3338 11870 3464 3339 11871 3465 3339 11872 3463 3339 11873 3462 3340 11874 3464 3340 11875 3463 3340 11876 3466 3341 11877 3467 3341 11878 3465 3341 11879 3468 3342 11880 3466 3342 11881 3465 3342 11882 3464 3343 11883 3468 3343 11884 3465 3343 11885 3469 3344 11886 3470 3344 11887 3467 3344 11888 3466 3345 11889 3469 3345 11890 3467 3345 11891 3471 3346 11892 3472 3347 11893 3473 3348 11894 238 3349 11895 3474 3349 11896 3475 3349 11897 3476 3350 11898 3477 3351 11899 3478 3352 11900 3479 3353 11901 3478 3353 11902 3477 3353 11903 3480 3354 11904 3477 3351 11905 3476 3350 11906 3481 3355 11907 3477 3351 11908 3480 3354 11909 3482 3356 11910 3477 3351 11911 3481 3355 11912 258 256 11913 3477 3351 11914 3482 3356 11915 3483 3357 11916 3484 3357 11917 3485 3357 11918 3471 3346 11919 3486 3358 11920 3472 3347 11921 238 3359 11922 3475 3359 11923 3487 3359 11924 3471 3346 11925 3488 3360 11926 3486 3358 11927 3479 3361 11928 3489 3361 11929 3478 3361 11930 3490 3362 11931 3489 3362 11932 3491 3362 11933 3479 3363 11934 3491 3363 11935 3489 3363 11936 238 3364 11937 3487 3364 11938 239 3364 11939 3471 3346 11940 3492 3365 11941 3488 3360 11942 3471 3346 11943 3493 3366 11944 3492 3365 11945 3471 3346 11946 3494 3367 11947 3493 3366 11948 3495 3368 11949 3496 3369 11950 3494 3367 11951 3471 3346 11952 3495 3368 11953 3494 3367 11954 258 256 11955 3482 3356 11956 3497 3370 11957 968 959 11958 3495 3368 11959 3471 3346 11960 967 958 11961 3495 3368 11962 968 959 11963 258 256 11964 3497 3370 11965 259 257 11966 3483 3371 11967 3498 3371 11968 3484 3371 11969

-
- - - - -

3499 3372 11970 3500 3373 11971 3501 3374 11972 3502 3375 11973 3503 3375 11974 3504 3375 11975 3505 3376 11976 3499 3372 11977 3501 3374 11978 3506 3377 11979 3507 3377 11980 3508 3377 11981 3506 3378 11982 3508 3378 11983 3509 3378 11984 3510 3379 11985 3511 3380 11986 3500 3373 11987 3512 3381 11988 3504 3381 11989 3513 3381 11990 3499 3372 11991 3510 3379 11992 3500 3373 11993 3514 3382 11994 3502 3382 11995 3504 3382 11996 3515 3383 11997 3514 3383 11998 3504 3383 11999 3516 3384 12000 3515 3384 12001 3504 3384 12002 3512 3385 12003 3516 3385 12004 3504 3385 12005 3517 3386 12006 3518 3387 12007 3511 3380 12008 3519 3388 12009 3520 3389 12010 3521 3390 12011 3510 3379 12012 3517 3386 12013 3511 3380 12014 3522 3391 12015 3512 3391 12016 3513 3391 12017 3517 3386 12018 3523 3392 12019 3518 3387 12020 3524 3393 12021 3521 3390 12022 3525 3394 12023 3524 3393 12024 3519 3388 12025 3521 3390 12026 3526 3395 12027 3527 3396 12028 3523 3392 12029 3528 3397 12030 3525 3394 12031 3529 3398 12032 3517 3386 12033 3526 3395 12034 3523 3392 12035 3524 3393 12036 3525 3394 12037 3528 3397 12038 3526 3395 12039 3530 3399 12040 3527 3396 12041 3531 3400 12042 3529 3398 12043 3532 3401 12044 3533 3402 12045 3529 3398 12046 3531 3400 12047 3528 3397 12048 3529 3398 12049 3533 3402 12050 3526 3395 12051 3534 3403 12052 3530 3399 12053 3535 3404 12054 3532 3401 12055 3536 3405 12056 3531 3400 12057 3532 3401 12058 3535 3404 12059 3537 3406 12060 3538 3407 12061 3534 3403 12062 3535 3404 12063 3536 3405 12064 3539 3408 12065 3526 3395 12066 3537 3406 12067 3534 3403 12068 3537 3406 12069 3540 3409 12070 3538 3407 12071 3541 3410 12072 3542 3410 12073 3543 3410 12074 3535 3404 12075 3539 3408 12076 3544 3411 12077 3545 3412 12078 3546 3413 12079 3540 3409 12080 3547 3414 12081 3543 3414 12082 3548 3414 12083 3537 3406 12084 3545 3412 12085 3540 3409 12086 3541 3415 12087 3543 3415 12088 3547 3415 12089 3545 3412 12090 3549 3416 12091 3546 3413 12092 3550 3417 12093 3551 3417 12094 3552 3417 12095 3553 3418 12096 3547 3418 12097 3548 3418 12098 3554 3419 12099 3555 3420 12100 3549 3416 12101 3556 3421 12102 3552 3421 12103 3557 3421 12104 3545 3412 12105 3554 3419 12106 3549 3416 12107 3558 3422 12108 3550 3422 12109 3552 3422 12110 3556 3423 12111 3558 3423 12112 3552 3423 12113 3559 3424 12114 3560 3425 12115 3561 3426 12116 3562 3427 12117 3557 3427 12118 3563 3427 12119 3556 3428 12120 3557 3428 12121 3562 3428 12122 3564 3429 12123 3554 3419 12124 3545 3412 12125 3565 3430 12126 3566 3431 12127 3554 3419 12128 3567 3432 12129 3561 3426 12130 3568 3433 12131 3564 3429 12132 3565 3430 12133 3554 3419 12134 3569 3434 12135 3561 3426 12136 3567 3432 12137 3559 3424 12138 3561 3426 12139 3569 3434 12140 3570 3435 12141 3545 3412 12142 3537 3406 12143 3570 3435 12144 3564 3429 12145 3545 3412 12146 3571 3436 12147 3537 3406 12148 3526 3395 12149 3571 3436 12150 3570 3435 12151 3537 3406 12152 3572 3437 12153 3526 3395 12154 3517 3386 12155 3572 3437 12156 3571 3436 12157 3526 3395 12158 3573 3438 12159 3517 3386 12160 3510 3379 12161 3573 3438 12162 3572 3437 12163 3517 3386 12164 3574 3439 12165 3510 3379 12166 3499 3372 12167 3574 3439 12168 3573 3438 12169 3510 3379 12170 3575 3440 12171 3576 3441 12172 3499 3372 12173 3577 3442 12174 3499 3372 12175 3576 3441 12176 3505 3376 12177 3575 3440 12178 3499 3372 12179 3577 3442 12180 3574 3439 12181 3499 3372 12182 3578 3443 12183 3579 3444 12184 3580 3445 12185 3581 3446 12186 3577 3442 12187 3576 3441 12188 3582 3447 12189 3583 3448 12190 3579 3444 12191 3582 3447 12192 3579 3444 12193 3578 3443 12194 3506 3449 12195 3584 3449 12196 3507 3449 12197 3578 3443 12198 3580 3445 12199 3585 3450 12200 3565 3430 12201 3586 3451 12202 3566 3431 12203 3587 3452 12204 3568 3433 12205 3588 3453 12206 3567 3432 12207 3568 3433 12208 3587 3452 12209 3565 3430 12210 3589 3454 12211 3586 3451 12212 3590 3455 12213 3588 3453 12214 3591 3456 12215 3587 3452 12216 3588 3453 12217 3590 3455 12218 3565 3430 12219 3592 3457 12220 3589 3454 12221 3593 3458 12222 3591 3456 12223 3594 3459 12224 3590 3455 12225 3591 3456 12226 3593 3458 12227 3595 3460 12228 3596 3461 12229 3592 3457 12230 3597 3462 12231 3594 3459 12232 3598 3463 12233 3565 3430 12234 3595 3460 12235 3592 3457 12236 3593 3458 12237 3594 3459 12238 3597 3462 12239 3597 3462 12240 3598 3463 12241 3599 3464 12242 3600 3465 12243 3601 3465 12244 3602 3465 12245 3597 3462 12246 3599 3464 12247 3603 3466 12248 3604 3467 12249 3565 3430 12250 3564 3429 12251 3605 3468 12252 3602 3468 12253 3606 3468 12254 3600 3469 12255 3602 3469 12256 3605 3469 12257 3607 3470 12258 3564 3429 12259 3570 3435 12260 3608 3471 12261 3609 3472 12262 3564 3429 12263 3604 3467 12264 3564 3429 12265 3609 3472 12266 3610 3473 12267 3608 3471 12268 3564 3429 12269 3607 3470 12270 3610 3473 12271 3564 3429 12272 3611 3474 12273 3570 3435 12274 3571 3436 12275 3611 3474 12276 3607 3470 12277 3570 3435 12278 3612 3475 12279 3571 3436 12280 3572 3437 12281 3612 3475 12282 3611 3474 12283 3571 3436 12284 3613 3476 12285 3572 3437 12286 3573 3438 12287 3613 3476 12288 3612 3475 12289 3572 3437 12290 3614 3477 12291 3573 3438 12292 3574 3439 12293 3614 3477 12294 3613 3476 12295 3573 3438 12296 3615 3478 12297 3574 3439 12298 3577 3442 12299 3615 3478 12300 3614 3477 12301 3574 3439 12302 3616 3479 12303 3617 3480 12304 3577 3442 12305 3618 3481 12306 3577 3442 12307 3617 3480 12308 3619 3482 12309 3616 3479 12310 3577 3442 12311 3581 3446 12312 3619 3482 12313 3577 3442 12314 3618 3481 12315 3615 3478 12316 3577 3442 12317 3620 3483 12318 3621 3484 12319 3617 3480 12320 3622 3485 12321 3623 3485 12322 3624 3485 12323 3616 3479 12324 3620 3483 12325 3617 3480 12326 3625 3486 12327 3618 3481 12328 3617 3480 12329 3626 3487 12330 3625 3486 12331 3617 3480 12332 3622 3488 12333 3627 3488 12334 3623 3488 12335 3620 3483 12336 3628 3489 12337 3621 3484 12338 3629 3490 12339 3630 3491 12340 3631 3492 12341 3622 3493 12342 3624 3493 12343 3632 3493 12344 3633 3494 12345 3631 3492 12346 3634 3495 12347 3629 3490 12348 3631 3492 12349 3633 3494 12350 3635 3496 12351 3634 3495 12352 3636 3497 12353 3633 3494 12354 3634 3495 12355 3635 3496 12356 3637 3498 12357 3636 3497 12358 3638 3499 12359 3635 3496 12360 3636 3497 12361 3637 3498 12362 3639 3500 12363 3638 3499 12364 3583 3448 12365 3637 3498 12366 3638 3499 12367 3639 3500 12368 3639 3500 12369 3583 3448 12370 3582 3447 12371 3640 3501 12372 3641 3502 12373 3642 3503 12374 3605 3504 12375 3606 3504 12376 3643 3504 12377 3605 3505 12378 3643 3505 12379 3644 3505 12380 3645 3506 12381 3642 3503 12382 3646 3507 12383 3640 3501 12384 3642 3503 12385 3645 3506 12386 3647 3508 12387 3610 3473 12388 3607 3470 12389 3648 3509 12390 3646 3507 12391 3649 3510 12392 3648 3509 12393 3645 3506 12394 3646 3507 12395 3650 3511 12396 3607 3470 12397 3611 3474 12398 3651 3512 12399 3647 3508 12400 3607 3470 12401 3652 3513 12402 3651 3512 12403 3607 3470 12404 3653 3514 12405 3652 3513 12406 3607 3470 12407 3650 3511 12408 3653 3514 12409 3607 3470 12410 3654 3515 12411 3611 3474 12412 3612 3475 12413 3654 3515 12414 3650 3511 12415 3611 3474 12416 3655 3516 12417 3612 3475 12418 3613 3476 12419 3656 3517 12420 3654 3515 12421 3612 3475 12422 3655 3516 12423 3656 3517 12424 3612 3475 12425 3657 3518 12426 3613 3476 12427 3614 3477 12428 3657 3518 12429 3655 3516 12430 3613 3476 12431 3658 3519 12432 3614 3477 12433 3615 3478 12434 3659 3520 12435 3657 3518 12436 3614 3477 12437 3658 3519 12438 3659 3520 12439 3614 3477 12440 3660 3521 12441 3615 3478 12442 3618 3481 12443 3660 3521 12444 3658 3519 12445 3615 3478 12446 3661 3522 12447 3662 3523 12448 3663 3524 12449 3664 3525 12450 3660 3521 12451 3618 3481 12452 3665 3526 12453 3664 3525 12454 3618 3481 12455 3666 3527 12456 3667 3528 12457 3662 3523 12458 3661 3522 12459 3668 3529 12460 3662 3523 12461 3666 3527 12462 3662 3523 12463 3668 3529 12464 3626 3487 12465 3669 3530 12466 3625 3486 12467 3661 3522 12468 3663 3524 12469 3670 3531 12470 3671 3532 12471 3672 3532 12472 3627 3532 12473 3661 3522 12474 3670 3531 12475 3673 3533 12476 3671 3534 12477 3627 3534 12478 3622 3534 12479 3674 3535 12480 3649 3510 12481 3675 3536 12482 3674 3535 12483 3648 3509 12484 3649 3510 12485 3676 3537 12486 3677 3538 12487 3678 3539 12488 3679 3540 12489 3677 3540 12490 3676 3540 12491 3680 3541 12492 3675 3541 12493 3681 3541 12494 3674 3535 12495 3675 3536 12496 3680 3542 12497 3682 3543 12498 3678 3539 12499 3683 3544 12500 3676 3537 12501 3678 3539 12502 3682 3543 12503 3684 3545 12504 3683 3544 12505 3685 3546 12506 3682 3543 12507 3683 3544 12508 3684 3545 12509 3686 3547 12510 3685 3546 12511 3687 3548 12512 3684 3545 12513 3685 3546 12514 3686 3547 12515 3688 3549 12516 3687 3548 12517 3689 3550 12518 3690 3551 12519 3687 3548 12520 3688 3549 12521 3686 3547 12522 3687 3548 12523 3690 3551 12524 3691 3552 12525 3689 3550 12526 3692 3553 12527 3688 3549 12528 3689 3550 12529 3691 3552 12530 3693 3554 12531 3692 3553 12532 3694 3555 12533 3695 3556 12534 3692 3553 12535 3693 3554 12536 3691 3552 12537 3692 3553 12538 3695 3556 12539 3696 3557 12540 3694 3555 12541 3697 3558 12542 3693 3554 12543 3694 3555 12544 3696 3557 12545 3698 3559 12546 3697 3558 12547 3699 3560 12548 3700 3561 12549 3697 3558 12550 3698 3559 12551 3696 3557 12552 3697 3558 12553 3700 3561 12554 3701 3562 12555 3699 3560 12556 3702 3563 12557 3698 3559 12558 3699 3560 12559 3701 3562 12560 3703 3564 12561 3702 3563 12562 3704 3565 12563 3701 3562 12564 3702 3563 12565 3703 3564 12566 3705 3566 12567 3706 3567 12568 3667 3528 12569 3707 3568 12570 3703 3564 12571 3704 3565 12572 3708 3569 12573 3705 3566 12574 3667 3528 12575 3709 3570 12576 3708 3569 12577 3667 3528 12578 3710 3571 12579 3709 3570 12580 3667 3528 12581 3666 3527 12582 3710 3571 12583 3667 3528 12584 3711 3572 12585 3506 3572 12586 3509 3572 12587 3712 3573 12588 3713 3573 12589 3714 3573 12590 3715 3574 12591 3716 3574 12592 3717 3574 12593 3715 3575 12594 3718 3575 12595 3716 3575 12596 3719 3576 12597 3716 3576 12598 3718 3576 12599 3720 3577 12600 3713 3577 12601 3712 3577 12602 3721 3578 12603 3713 3578 12604 3720 3578 12605 3722 3579 12606 3717 3579 12607 3723 3579 12608 3722 3580 12609 3715 3580 12610 3717 3580 12611 3724 3581 12612 3723 3581 12613 3725 3581 12614 3724 3582 12615 3722 3582 12616 3723 3582 12617 3726 3583 12618 3725 3583 12619 3727 3583 12620 3726 3584 12621 3724 3584 12622 3725 3584 12623 3728 3585 12624 3726 3585 12625 3727 3585 12626 3729 3586 12627 3728 3586 12628 3727 3586 12629 3730 3587 12630 3731 3587 12631 3732 3587 12632 3733 3588 12633 3734 3589 12634 3735 3590 12635 3736 3591 12636 3730 3591 12637 3732 3591 12638 3737 3592 12639 3736 3592 12640 3732 3592 12641 3738 3593 12642 3734 3589 12643 3733 3588 12644 3739 3594 12645 3740 3594 12646 3731 3594 12647 3741 3595 12648 3735 3590 12649 3742 3596 12650 3730 3597 12651 3739 3597 12652 3731 3597 12653 3733 3588 12654 3735 3590 12655 3741 3595 12656 3743 3598 12657 3744 3598 12658 3740 3598 12659 3745 3599 12660 3746 3600 12661 3703 3564 12662 3739 3601 12663 3743 3601 12664 3740 3601 12665 3741 3595 12666 3742 3596 12667 3747 3602 12668 3748 3603 12669 3749 3603 12670 3744 3603 12671 3743 3604 12672 3748 3604 12673 3744 3604 12674 3745 3599 12675 3703 3564 12676 3707 3568 12677 3750 3605 12678 3751 3605 12679 3749 3605 12680 3748 3606 12681 3750 3606 12682 3749 3606 12683 3752 3607 12684 3753 3607 12685 3751 3607 12686 3750 3608 12687 3752 3608 12688 3751 3608 12689 3754 3609 12690 3755 3609 12691 3753 3609 12692 3752 3610 12693 3754 3610 12694 3753 3610 12695 3756 3611 12696 3757 3611 12697 3755 3611 12698 3754 3612 12699 3756 3612 12700 3755 3612 12701 3756 3613 12702 3758 3613 12703 3757 3613 12704 3759 3614 12705 3760 3615 12706 3761 3616 12707 3762 3617 12708 3679 3617 12709 3676 3617 12710 3759 3614 12711 3763 3618 12712 3760 3615 12713 3759 3614 12714 3761 3616 12715 3764 3619 12716 3737 3620 12717 3765 3620 12718 3736 3620 12719 3648 3509 12720 3766 3621 12721 3645 3506 12722 3759 3614 12723 3764 3619 12724 3767 3622 12725 3768 3623 12726 3769 3623 12727 3765 3623 12728 3737 3624 12729 3768 3624 12730 3765 3624 12731 3770 3625 12732 3771 3625 12733 3769 3625 12734 3768 3626 12735 3770 3626 12736 3769 3626 12737 3772 3627 12738 3773 3627 12739 3771 3627 12740 3770 3628 12741 3772 3628 12742 3771 3628 12743 3774 3629 12744 3775 3629 12745 3773 3629 12746 3772 3630 12747 3774 3630 12748 3773 3630 12749 3776 3631 12750 3777 3631 12751 3775 3631 12752 3774 3632 12753 3776 3632 12754 3775 3632 12755 3778 3633 12756 3779 3633 12757 3777 3633 12758 3776 3634 12759 3778 3634 12760 3777 3634 12761 3780 3635 12762 3781 3635 12763 3779 3635 12764 3778 3636 12765 3780 3636 12766 3779 3636 12767 3782 3637 12768 3783 3637 12769 3781 3637 12770 3780 3638 12771 3782 3638 12772 3781 3638 12773 3719 3639 12774 3718 3639 12775 3783 3639 12776 3782 3640 12777 3719 3640 12778 3783 3640 12779 3784 3641 12780 3785 3641 12781 3786 3641 12782 3553 3642 12783 3787 3642 12784 3547 3642 12785 3788 3643 12786 3786 3643 12787 3789 3643 12788 3784 3644 12789 3786 3644 12790 3788 3644 12791 3729 3645 12792 3790 3645 12793 3728 3645 12794 3791 3646 12795 3792 3646 12796 3790 3646 12797 3729 3647 12798 3791 3647 12799 3790 3647 12800 3791 3648 12801 3793 3648 12802 3792 3648 12803 3794 3649 12804 3795 3650 12805 3796 3651 12806 3797 3652 12807 3798 3653 12808 3799 3654 12809 3800 3655 12810 3794 3649 12811 3796 3651 12812 3801 3656 12813 3800 3655 12814 3796 3651 12815 3802 3657 12816 3803 3657 12817 3804 3657 12818 3805 3658 12819 3802 3658 12820 3804 3658 12821 3806 3659 12822 3805 3659 12823 3804 3659 12824 3794 3649 12825 3807 3660 12826 3795 3650 12827 3808 3661 12828 3799 3654 12829 3809 3662 12830 3810 3663 12831 3797 3652 12832 3799 3654 12833 3811 3664 12834 3810 3663 12835 3799 3654 12836 3808 3661 12837 3811 3664 12838 3799 3654 12839 3794 3649 12840 3812 3665 12841 3807 3660 12842 3813 3666 12843 3809 3662 12844 3814 3667 12845 3813 3666 12846 3808 3661 12847 3809 3662 12848 3794 3668 12849 3815 3668 12850 3812 3668 12851 3816 3669 12852 3814 3667 12853 3817 3670 12854 3818 3671 12855 3813 3666 12856 3814 3667 12857 3816 3669 12858 3818 3671 12859 3814 3667 12860 3819 3672 12861 3820 3672 12862 3821 3672 12863 3822 3673 12864 3816 3669 12865 3817 3670 12866 3823 3674 12867 3794 3649 12868 3800 3655 12869 3819 3675 12870 3821 3675 12871 3824 3675 12872 3801 3656 12873 3825 3676 12874 3800 3655 12875 3826 3677 12876 3800 3655 12877 3825 3676 12878 3827 3678 12879 3828 3679 12880 3800 3655 12881 3823 3674 12882 3800 3655 12883 3828 3679 12884 3829 3680 12885 3827 3678 12886 3800 3655 12887 3830 3681 12888 3829 3680 12889 3800 3655 12890 3831 3682 12891 3830 3681 12892 3800 3655 12893 3832 3683 12894 3831 3682 12895 3800 3655 12896 3826 3677 12897 3832 3683 12898 3800 3655 12899 3833 3684 12900 3834 3685 12901 3825 3676 12902 3835 3686 12903 3825 3676 12904 3834 3685 12905 3836 3687 12906 3833 3684 12907 3825 3676 12908 3801 3656 12909 3836 3687 12910 3825 3676 12911 3837 3688 12912 3826 3677 12913 3825 3676 12914 3838 3689 12915 3837 3688 12916 3825 3676 12917 3835 3686 12918 3838 3689 12919 3825 3676 12920 3839 3690 12921 3840 3691 12922 3834 3685 12923 3841 3692 12924 3834 3685 12925 3840 3691 12926 3842 3693 12927 3839 3690 12928 3834 3685 12929 3843 3694 12930 3842 3693 12931 3834 3685 12932 3844 3695 12933 3843 3694 12934 3834 3685 12935 3845 3696 12936 3844 3695 12937 3834 3685 12938 3833 3684 12939 3845 3696 12940 3834 3685 12941 3846 3697 12942 3835 3686 12943 3834 3685 12944 3841 3692 12945 3846 3697 12946 3834 3685 12947 3847 3698 12948 3848 3699 12949 3840 3691 12950 3849 3700 12951 3840 3691 12952 3848 3699 12953 3850 3701 12954 3847 3698 12955 3840 3691 12956 3839 3690 12957 3850 3701 12958 3840 3691 12959 3849 3700 12960 3841 3692 12961 3840 3691 12962 3851 3702 12963 3852 3703 12964 3848 3699 12965 3853 3704 12966 3848 3699 12967 3852 3703 12968 3847 3698 12969 3851 3702 12970 3848 3699 12971 3854 3705 12972 3849 3700 12973 3848 3699 12974 3853 3704 12975 3854 3705 12976 3848 3699 12977 3855 3706 12978 3856 3707 12979 3852 3703 12980 3857 3708 12981 3852 3703 12982 3856 3707 12983 3858 3709 12984 3855 3706 12985 3852 3703 12986 3859 3710 12987 3858 3709 12988 3852 3703 12989 3860 3711 12990 3859 3710 12991 3852 3703 12992 3851 3702 12993 3860 3711 12994 3852 3703 12995 3861 3712 12996 3853 3704 12997 3852 3703 12998 3862 3713 12999 3861 3712 13000 3852 3703 13001 3857 3708 13002 3862 3713 13003 3852 3703 13004 3855 3706 13005 3863 3714 13006 3856 3707 13007 3864 3715 13008 3865 3715 13009 3866 3715 13010 3867 3716 13011 3857 3708 13012 3856 3707 13013 3868 3717 13014 3867 3716 13015 3856 3707 13016 3869 3718 13017 3868 3717 13018 3856 3707 13019 3870 3719 13020 3869 3718 13021 3856 3707 13022 3870 3719 13023 3856 3707 13024 3871 3720 13025 3871 3720 13026 3872 3721 13027 3870 3719 13028 3864 3722 13029 3873 3722 13030 3865 3722 13031 3874 3723 13032 3875 3724 13033 3876 3725 13034 3864 3726 13035 3866 3726 13036 3877 3726 13037 3878 3727 13038 3876 3725 13039 3879 3728 13040 3880 3729 13041 3876 3725 13042 3878 3727 13043 3874 3723 13044 3876 3725 13045 3880 3729 13046 3881 3730 13047 3879 3728 13048 3882 3731 13049 3883 3732 13050 3879 3728 13051 3881 3730 13052 3878 3727 13053 3879 3728 13054 3883 3732 13055 3884 3733 13056 3882 3731 13057 3885 3734 13058 3881 3730 13059 3882 3731 13060 3884 3733 13061 3886 3735 13062 3887 3735 13063 3888 3735 13064 3884 3733 13065 3885 3734 13066 3889 3736 13067 3890 3737 13068 3889 3736 13069 3885 3734 13070 3891 3738 13071 3888 3738 13072 3892 3738 13073 3893 3739 13074 3888 3739 13075 3891 3739 13076 3894 3740 13077 3888 3740 13078 3893 3740 13079 3895 3741 13080 3888 3741 13081 3894 3741 13082 3886 3742 13083 3888 3742 13084 3895 3742 13085 3896 3743 13086 3897 3744 13087 3898 3745 13088 3899 3746 13089 3897 3744 13090 3896 3743 13091 3891 3747 13092 3892 3747 13093 3900 3747 13094 3901 3748 13095 3898 3745 13096 3902 3749 13097 3896 3743 13098 3898 3745 13099 3901 3748 13100 3903 3750 13101 3902 3749 13102 3904 3751 13103 3901 3748 13104 3902 3749 13105 3903 3750 13106 3905 3752 13107 3904 3751 13108 3906 3753 13109 3903 3750 13110 3904 3751 13111 3905 3752 13112 3905 3752 13113 3906 3753 13114 3907 3754 13115 3908 3755 13116 3907 3754 13117 3909 3756 13118 3905 3752 13119 3907 3754 13120 3908 3755 13121 3910 3757 13122 3909 3756 13123 3911 3758 13124 3908 3755 13125 3909 3756 13126 3910 3757 13127 3912 3759 13128 3911 3758 13129 3913 3760 13130 3910 3757 13131 3911 3758 13132 3912 3759 13133 3914 3761 13134 3915 3761 13135 3803 3761 13136 3912 3759 13137 3913 3760 13138 3916 3762 13139 3917 3763 13140 3803 3763 13141 3802 3763 13142 3917 3764 13143 3914 3764 13144 3803 3764 13145 3918 3765 13146 3919 3766 13147 3920 3767 13148 3819 3768 13149 3824 3768 13150 3921 3768 13151 3922 3769 13152 3819 3769 13153 3921 3769 13154 3923 3770 13155 3920 3767 13156 3924 3771 13157 3925 3772 13158 3920 3767 13159 3923 3770 13160 3918 3765 13161 3920 3767 13162 3925 3772 13163 3926 3773 13164 3924 3771 13165 3927 3774 13166 3923 3770 13167 3924 3771 13168 3926 3773 13169 3928 3775 13170 3927 3774 13171 3929 3776 13172 3926 3773 13173 3927 3774 13174 3928 3775 13175 3930 3777 13176 3929 3776 13177 3931 3778 13178 3932 3779 13179 3929 3776 13180 3930 3777 13181 3928 3775 13182 3929 3776 13183 3932 3779 13184 3933 3780 13185 3931 3778 13186 3934 3781 13187 3930 3777 13188 3931 3778 13189 3935 3782 13190 3933 3780 13191 3935 3782 13192 3931 3778 13193 3936 3783 13194 3934 3781 13195 3937 3784 13196 3936 3783 13197 3933 3780 13198 3934 3781 13199 3938 3785 13200 3939 3786 13201 3940 3787 13202 3936 3783 13203 3937 3784 13204 3941 3788 13205 3942 3789 13206 3940 3787 13207 3943 3790 13208 3944 3791 13209 3940 3787 13210 3942 3789 13211 3945 3792 13212 3938 3785 13213 3940 3787 13214 3944 3791 13215 3945 3792 13216 3940 3787 13217 3946 3793 13218 3943 3790 13219 3947 3794 13220 3942 3789 13221 3943 3790 13222 3946 3793 13223 3948 3795 13224 3947 3794 13225 3949 3796 13226 3946 3793 13227 3947 3794 13228 3948 3795 13229 3950 3797 13230 3949 3796 13231 3951 3798 13232 3952 3799 13233 3949 3796 13234 3950 3797 13235 3948 3795 13236 3949 3796 13237 3952 3799 13238 3953 3800 13239 3951 3798 13240 3954 3801 13241 3950 3797 13242 3951 3798 13243 3953 3800 13244 3953 3800 13245 3954 3801 13246 3955 3802 13247 3956 3803 13248 3955 3802 13249 3957 3804 13250 3956 3803 13251 3953 3800 13252 3955 3802 13253 3958 3805 13254 3959 3806 13255 3960 3807 13256 3958 3805 13257 3961 3808 13258 3959 3806 13259 3962 3809 13260 3957 3804 13261 3963 3810 13262 3962 3809 13263 3956 3803 13264 3957 3804 13265 3964 3811 13266 3960 3807 13267 3965 3812 13268 3964 3811 13269 3958 3805 13270 3960 3807 13271 3966 3813 13272 3965 3812 13273 3967 3814 13274 3966 3813 13275 3968 3815 13276 3965 3812 13277 3969 3816 13278 3965 3812 13279 3968 3815 13280 3970 3817 13281 3964 3811 13282 3965 3812 13283 3969 3816 13284 3970 3817 13285 3965 3812 13286 3971 3818 13287 3967 3814 13288 3972 3819 13289 3973 3820 13290 3967 3814 13291 3971 3818 13292 3966 3813 13293 3967 3814 13294 3973 3820 13295 3974 3821 13296 3972 3819 13297 3975 3822 13298 3976 3823 13299 3972 3819 13300 3974 3821 13301 3971 3818 13302 3972 3819 13303 3976 3823 13304 3977 3824 13305 3975 3822 13306 3978 3825 13307 3974 3821 13308 3975 3822 13309 3977 3824 13310 3979 3826 13311 3978 3825 13312 3980 3827 13313 3977 3824 13314 3978 3825 13315 3979 3826 13316 3864 3828 13317 3981 3828 13318 3873 3828 13319 3979 3826 13320 3980 3827 13321 3982 3829 13322 3983 3830 13323 3984 3831 13324 3985 3832 13325 3917 3833 13326 3802 3833 13327 3986 3833 13328 3797 3652 13329 3984 3831 13330 3983 3830 13331 3810 3663 13332 3984 3831 13333 3797 3652 13334 3987 3834 13335 3988 3834 13336 3989 3834 13337 3990 3835 13338 3989 3835 13339 3991 3835 13340 3990 3836 13341 3987 3836 13342 3989 3836 13343 3992 3837 13344 3993 3837 13345 3988 3837 13346 3994 3838 13347 3995 3838 13348 3993 3838 13349 3992 3839 13350 3994 3839 13351 3993 3839 13352 3996 3840 13353 3992 3840 13354 3988 3840 13355 3987 3841 13356 3996 3841 13357 3988 3841 13358 3997 3842 13359 3991 3842 13360 3998 3842 13361 3997 3843 13362 3990 3843 13363 3991 3843 13364 3999 3844 13365 3998 3844 13366 4000 3844 13367 3999 3845 13368 3997 3845 13369 3998 3845 13370 4001 3846 13371 4000 3846 13372 4002 3846 13373 4001 3847 13374 3999 3847 13375 4000 3847 13376 4003 3848 13377 4002 3848 13378 4004 3848 13379 4003 3849 13380 4001 3849 13381 4002 3849 13382 4005 3850 13383 4004 3850 13384 4006 3850 13385 4005 3851 13386 4003 3851 13387 4004 3851 13388 4005 3852 13389 4006 3852 13390 4007 3852 13391 4008 3853 13392 4007 3853 13393 4009 3853 13394 4008 3854 13395 4005 3854 13396 4007 3854 13397 4010 3855 13398 4011 3855 13399 4012 3855 13400 4013 3856 13401 4014 3857 13402 4015 3858 13403 4016 3859 13404 4010 3859 13405 4012 3859 13406 4017 3860 13407 4016 3860 13408 4012 3860 13409 4018 3861 13410 3969 3861 13411 3968 3861 13412 4019 3862 13413 4020 3862 13414 4011 3862 13415 4021 3863 13416 4015 3858 13417 4022 3864 13418 4010 3865 13419 4019 3865 13420 4011 3865 13421 4023 3866 13422 4015 3858 13423 4021 3863 13424 4024 3867 13425 4015 3858 13426 4023 3866 13427 4013 3856 13428 4015 3858 13429 4024 3867 13430 4025 3868 13431 4026 3868 13432 4020 3868 13433 4027 3869 13434 4022 3864 13435 4028 3870 13436 4019 3871 13437 4025 3871 13438 4020 3871 13439 4021 3863 13440 4022 3864 13441 4027 3869 13442 4029 3872 13443 4030 3872 13444 4026 3872 13445 3956 3803 13446 4031 3873 13447 3953 3800 13448 4025 3874 13449 4029 3874 13450 4026 3874 13451 4032 3875 13452 4027 3869 13453 4028 3870 13454 3956 3876 13455 4033 3876 13456 4031 3876 13457 4032 3875 13458 4028 3870 13459 4034 3877 13460 4029 3878 13461 4035 3878 13462 4030 3878 13463 4036 3879 13464 4037 3879 13465 4035 3879 13466 4029 3880 13467 4036 3880 13468 4035 3880 13469 4038 3881 13470 4039 3882 13471 4040 3883 13472 4041 3884 13473 3944 3884 13474 3942 3884 13475 4042 3885 13476 4040 3883 13477 4043 3886 13478 4044 3887 13479 4040 3883 13480 4042 3885 13481 4038 3881 13482 4040 3883 13483 4044 3887 13484 4045 3888 13485 4043 3886 13486 4046 3889 13487 4045 3888 13488 4042 3885 13489 4043 3886 13490 4017 3890 13491 4047 3890 13492 4016 3890 13493 3933 3780 13494 4048 3891 13495 3935 3782 13496 4049 3892 13497 4048 3892 13498 3933 3892 13499 4050 3893 13500 4045 3888 13501 4046 3889 13502 4051 3894 13503 4052 3894 13504 4047 3894 13505 4017 3895 13506 4051 3895 13507 4047 3895 13508 4053 3896 13509 4054 3896 13510 4052 3896 13511 4051 3897 13512 4053 3897 13513 4052 3897 13514 4055 3898 13515 4056 3898 13516 4054 3898 13517 4053 3899 13518 4055 3899 13519 4054 3899 13520 4057 3900 13521 4058 3900 13522 4056 3900 13523 4055 3901 13524 4057 3901 13525 4056 3901 13526 4059 3902 13527 4060 3902 13528 4058 3902 13529 4057 3903 13530 4059 3903 13531 4058 3903 13532 4061 3904 13533 4062 3904 13534 4060 3904 13535 4059 3905 13536 4061 3905 13537 4060 3905 13538 4063 3906 13539 4009 3906 13540 4062 3906 13541 4061 3907 13542 4063 3907 13543 4062 3907 13544 4063 3908 13545 4008 3908 13546 4009 3908 13547 4064 3909 13548 4065 3909 13549 3995 3909 13550 3994 3910 13551 4064 3910 13552 3995 3910 13553 4066 3911 13554 4067 3911 13555 4065 3911 13556 4064 3912 13557 4066 3912 13558 4065 3912 13559 4066 3913 13560 4068 3913 13561 4067 3913 13562 4069 3914 13563 4070 3915 13564 3889 3736 13565 4069 3914 13566 4071 3916 13567 4070 3915 13568 3890 3737 13569 4069 3914 13570 3889 3736 13571 4013 3856 13572 4024 3867 13573 4072 3917 13574 4038 3881 13575 4044 3887 13576 4073 3918 13577 4032 3919 13578 4034 3919 13579 4074 3919 13580 4050 3893 13581 4075 3920 13582 4045 3888 13583

-
-
-
-
- - - - - -4.37108e-11 -1.62919e-10 -9.99987e-4 0 -9.99987e-4 -2.98019e-11 4.37108e-11 0 -2.98019e-11 9.99987e-4 -1.62919e-10 -0.6104 0 0 0 1 - - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl deleted file mode 100644 index 130906df3bec23f23a958664684c702aa13b1102..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6884 zcmb7I32;@_8UDebWoaB5StK9HpvR4(~fjrZasr@J` zU(SH(FHg>yGJagbgq+Ef68cUYpFM7T&Lb&Z9_^X%aPHJG3CSJl|N6|0P@lSxXE$+I zmv0}HRsLGx(9n^+heJC?W%W+~bXaJ_$qtsR_3uP;E>>F&*Jasn>|0fiJO4~+5qk4N zd}!Cw4wkGB@jp3<$S%&Z_ui71aEAR%N~UFfG`L)-60_#@ zZuMNEH92=eXctQ<2t@me)bH6x^^5DMzTh+eTsYJbDs?TK()ny7H}j!k)(4E#zZ3m5 zCC_$7{K>hudGd$b(q0HH%s#hmZS!7MA@iHle!r94<<|y3qE7X{aF_l)Nxgq5Ug23= za@Ut9Pi*2IIW*EbkkZ0oT|C}I4XtE#xU8xA>{lmU+?mVL6-IdcCU=6fJE9ZO%HRyu zoi(4yn&ZxVMkKHm;@Jx93#T|@H=@+yELFkQZM>w1c<;{6F_xkz;*X=e-gn0zODya-X_pi8NRG8Dw^Jx? z(Pihc9ltj$O?2^%%uuT?GgW?f%Zs1WnLl?crj52rR>Xz=(YJ}aXX^9T@-h2+f2(5M z4|-);?7`-f)q?C2_d>y2p^Ds2&e)X8&LBRQ`8k>&TAFA~{#vWwJ3*E4Nn0fmr+MJH zU*)dv{e8agO`=a`kFbrgIPn#2wyLxjoZ?7a zp(H3F(SY&|;brfYl)qS&XR{T{heYn3oU3n?SXbXiqU)~~u>M3prcSfv`-t7l4djf|BH zyRI)gM+bJWp9LXQpYr-@#zp7BOS70q6iswCb(#|SE13uHI3me5MzGHv z%}>@^LZYgepoh53dLY#vzJo#~I+=(iuNJsNXWSLO!ukl6ocl@*`yg86kx#xVSP~PE zcol@it4Jtokx=4I))H?%z5ajMQ|T!p$(I}cXklK#-~IFD|Kc&Pm!jr!?)9jx?(ieJ z%{HnR+at_ASDXWTS0%-|6AlfxBwj@l$v%?pWG&f_s9u9qC;ffSCu*?uE?coEsfoLr zZxLq#M@N3anEmAk`9^K=Zq#YE(bLCUgwL?eB>I|7Z|oL+^^$jMTi3IQ+()9t zi|!9(y!K1`z1ID0)DShtTR_A-l;$Cl2#VY$rp#bO{RTmWHoV59yU^DL? zXnEUuF)+$r_|SZ#_dzO*1)|{IO#Ac7d+eES-m2C6=&lAUD$$Tt)9pRWa;(mM_8Ywq zYKwgkQTwiqx=Zhq%DoTX53J7E2NAWKKPz015&dg)OPE(o1Xnft8?I`d7q!`nl3-k6 zO(gomhIieoY2DP```RnaIM@ea=S1{%^?G+~Qc(Sn)z;{*P$v^{nt5zy9`%~FSGa>W z7djj{Sih8O9RcW};quGu3wX`ES|h*pVR>_FY7u zwY=?4q+N5fQk9(T6=zlwPVQ z?qElbQE4J@2YrJ!G!f_zq(ZcbKwF^|kT=oB<0}J#6YHYpsFR5(Em>IVbILbj7o|ep zL>)$F+Z}0(n>J{%H~r{}jJF7DFwqL`sT0#Txrw&fQ)7RH{WZ~ovDx;jAIsbx2}L2? z!E=!xQO}(*R*QqvRb}cRqYFobR8ifL6SWzgtuk1TTLTw|@aEu+lC`e$MCVUstH2Yb z?t`uWYV_?`aj+6`<;=-edxn*{IWv~l;-SwKw4MNnW^tz<&z=5s?({LMVI-QJetc-X z^<8{7we?@^jMx>;wQo$s?DL;n_kEP4UTNG~;STb^h#_iZCEG`M9^A?EAnxFeGW~IG zN}f8yQ|j8J|DGnKr;?u9oGi{prip8HOcR2T zIRPgNou5VD=20L%a@SLsfy-h3k$5sW9^8_W6i4j1Ve)u0+19r9-M4 z5pUlc#2xIMWUYBedBiaS&y}^FYw;wWSRymd$2DdgmeA{WYtB1F7q}Nqd)_UrYsL{h zWO^|tmM6GF7TFHfG2;lrp8<(P554wu@n$LPaj~a1J7l4kyne0QfHK^{o*GZ`=>;Jx zv=#aWt>7ah=ia~R?lN=cj83dVg*wUKJ`dc%Nl*GxK}b{zjeL9r?$nf|Hjn+!E(}YS zksaw+aUMYZd=8?=nvB>W+5~M?8zEBdV;*Q9(+bgu@p%Yh?z2w@VfE}R4q!@ z1W|UBur8^5B=*tR0pi-Pn9p=w7FbQxfsW8vW+4*Y7g$|{BYimuydN!zy@MR*x z9a-xNAZzU>p9doFTs_y|Nkm8awhBUCDDX~TSB!OqHIE>EU6lgjgX z|BBl4xvpwhMTw3@vS=dTcZ?-j>xzt(nn=ImT&ZKC*ZIoyIU~Fq8^b)%ifCQ4o*#}N zBn#n=#F&0_z<4A2hNThf{=`U(K3VIRROzquq)+rx1aXTIxP$&cKM~#4z<=>N!Pyk; zj{d;6fhgj59j^x3x@dLpRn4;%zp5$J5H-hHgy;ZMiso^3yfbLc(IWgdcDAVWI=?e~ zUE`er>p4yqL_1%eRl1qq8U9k^odNp?^VT}&huf_N{LcFRXE%*ED~SwU`*70Zne$}2 zwV=4E{q(;dH{Kbr_L+#Ct!+>9!Td5Iv4rU54yP_ky; - - - - Blender User - Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9d68b - - 2019-01-16T08:12:43 - 2019-01-16T08:12:43 - - Z_UP - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.663 0.667 0.674 1 - - - 0.25 0.25 0.25 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - -62.67052 931.9716 14.69951 -60.852 935.2482 18.28853 -62.25659 935.7335 12 -58.87258 934.5645 12 -62.25659 935.7335 12 -60.852 935.2482 18.28853 -63.94472 931.9716 7.398792 -62.70845 937.0785 6.033858 -62.02388 936.506 12 -58.87258 934.5645 12 -62.02388 936.506 12 -62.25659 935.7335 12 -60.56562 931.9716 21.80539 -58.87258 934.5645 24.40083 -58.87258 934.5645 24.40083 -57.65792 931.9716 28.62224 -58.18949 934.4147 26.08606 -58.87258 934.5645 12 -58.87258 934.5645 24.40083 -58.18949 934.4147 26.08606 -57.54951 934.4197 27.46604 -58.06918 934.4053 12 -57.54951 934.4197 27.46604 -56.96586 934.5469 28.58106 -57.25921 934.4682 12 -56.96586 934.5469 28.58106 -53.98598 931.9716 35.05971 -56.44681 934.7716 29.46158 -56.49779 934.7449 12 -56.44681 934.7716 29.46158 -55.9966 935.0755 30.13236 -55.9966 935.0755 30.13236 -55.62137 935.4405 30.6073 -55.83888 935.2144 12 -55.62137 935.4405 30.6073 -55.32942 935.8418 30.8958 -55.32942 935.8418 30.8958 -55.12098 936.2529 31.02024 -55.32879 935.8438 12 -55.12098 936.2529 31.02024 -54.98164 936.6762 31.00728 -55.00495 936.5888 12 -54.98164 936.6762 31.00728 -53.2886 939.0808 32.3461 -54.90479 937.1342 30.85495 -54.90479 937.1342 30.85495 -54.90255 937.6392 30.53003 -54.893 937.4 12 -54.90255 937.6392 30.53003 -54.99153 938.1626 30.01408 -54.93143 937.8712 12 -54.99153 938.1626 30.01408 -55.17924 938.6789 29.29951 -55.03704 938.3184 12 -55.17924 938.6789 29.29951 -41.28906 964.9195 19.8271 -55.17924 938.6789 29.29951 -53.2886 939.0808 32.3461 -55.21226 938.7459 12 -55.48388 939.1878 27.92171 -42.72776 964.4782 17.71942 -55.48388 939.1878 27.92171 -49.37286 939.0809 38.05603 -51.19286 939.5262 35.29479 -39.66504 965.4011 21.8766 -51.19286 939.5262 35.29479 -49.59845 931.9716 41.03245 -44.8481 939.0809 43.29652 -48.33262 940.1342 38.77003 -44.5535 931.9716 46.46132 -39.77009 939.0809 48.00292 -42.72406 941.3276 44.25068 -45.21295 940.7973 42.00425 -38.91799 931.9716 51.27434 -34.20149 939.0809 52.11716 -37.3836 942.4613 48.27422 -40.11109 941.8822 46.34355 -32.76663 931.9716 55.40773 -28.211 939.0809 55.58849 -31.6243 943.6854 51.62348 -34.55152 943.0639 50.03557 -26.18095 931.9716 58.80668 -21.87248 939.0809 58.3741 -25.52735 944.9815 54.25511 -28.613 944.3261 53.03096 -19.24824 931.9716 61.42616 -15.26416 939.0809 60.43961 -14.5762 945.9179 57.70845 -22.37883 945.651 55.29077 -21.14233 945.9141 55.64122 -12.0604 931.9716 63.23143 -8.467541 939.0809 61.75955 -4.712694 931.9716 64.19858 -1.566466 939.0809 62.31763 -7.82003 945.9179 59.0049 2.697475 931.9716 64.31478 5.353932 939.0809 62.10697 -0.95939 945.9179 59.51311 10.07189 931.9717 63.57849 12.20828 939.0809 61.13018 5.914066 945.9179 59.2263 17.3128 931.9717 61.99946 18.91204 939.0809 59.39929 12.70852 945.9179 58.1483 24.32423 931.9717 59.59864 25.3825 939.0809 56.93566 19.3332 945.9179 56.2935 31.01324 931.9717 56.40785 31.53984 939.0809 53.76969 25.69961 945.9179 53.68669 37.25696 936.9123 50.86442 37.25696 939.0947 49.97259 31.72271 945.9179 50.36269 37.25696 931.9776 52.49203 87 934.5101 37.42399 37.25696 939.0947 49.97259 37.25696 936.9123 50.86442 37.25696 942.9152 48.13413 37.25696 942.9152 48.13413 87 931.8104 38.54377 37.25696 931.9776 52.49203 37.25696 930.6123 52.85218 87 929.0297 39.47208 37.25696 930.6123 52.85218 25.65672 924.6796 60.37168 37.25696 924.6832 53.98956 31.6264 924.6796 57.4698 19.42435 924.6796 62.65542 12.99309 924.6796 64.29765 6.439184 924.6938 65.27893 2.339567 926.6361 65.30867 4.570069 925.8533 65.2967 -6.444386 924.6898 65.27887 0 926.9 65.31265 -2.330073 926.6382 65.3087 -4.545989 925.8649 65.29688 -13.77441 924.6796 64.13481 -20.93515 924.6796 62.16693 -27.82758 924.6796 59.4023 -34.36336 924.6796 55.87635 -40.45874 924.6796 51.63428 -46.03558 924.6796 46.73044 -51.02241 924.6796 41.22768 -55.35532 924.6795 35.19654 -58.97878 924.6795 28.71431 -61.84635 924.6795 21.86407 -63.92127 924.6795 14.73361 -63.01863 937.0126 0 -64.37135 931.9716 0 -65.17697 924.6795 7.414317 -62.67754 937.0852 -6.326257 -64.37135 931.9716 0 -63.01863 937.0126 0 -64.79264 929.9664 0 -63.94465 931.9716 -7.399402 -64.79264 929.9664 0 -47.93976 962.7628 0 -63.01863 937.0126 0 -62.70845 937.0785 6.033858 -47.85824 962.791 -2.290539 -63.01863 937.0126 0 -47.93976 962.7628 0 -62.67754 937.0852 -6.326257 -61.78159 937.2755 12 -47.62354 962.8721 4.504169 -61.78159 937.2755 12 -47.86124 962.79 2.248175 -61.78159 937.2755 12 -60.62262 939.1965 12 -47.22624 963.0084 6.749334 -60.62262 939.1965 12 -44.76399 948.7677 33.95393 -51.19286 939.5262 35.29479 -48.33262 940.1342 38.77003 -39.55772 965.4002 22.04029 -47.27775 948.1519 30.93052 -47.27775 948.1519 30.93052 -42.10007 949.4152 36.84221 -45.21295 940.7973 42.00425 -42.10007 949.4152 36.84221 -45.21295 940.7973 42.00425 -42.72406 941.3276 44.25068 -38.28533 950.3464 40.37538 -40.11109 941.8822 46.34355 -37.3836 942.4613 48.27422 -34.13038 951.3438 43.51502 -34.55152 943.0639 50.03557 -31.6243 943.6854 51.62348 -29.6704 952.3931 46.23006 -28.613 944.3261 53.03096 -25.52735 944.9815 54.25511 -24.94227 953.4788 48.49188 -22.37883 945.651 55.29077 -21.14233 945.9141 55.64122 -15.93596 947.0202 56.78635 -19.98495 954.5836 50.2748 -15.93596 947.0202 56.78635 -12.66454 947.7163 57.24101 -6.076632 949.1165 57.55987 -9.373752 948.4148 57.49968 0.496272 950.5112 57.09117 -2.782607 949.8156 57.42374 7.012398 951.9006 55.82592 3.746744 951.2041 56.5619 15.48784 952.3969 53.77119 9.355464 952.3978 55.16907 21.42216 952.3969 51.69435 27.08605 952.3969 48.96489 37.25696 945.939 46.40523 32.40798 952.3969 45.61729 87 937.1297 36.1111 37.25696 945.939 46.40523 37.25696 948.5344 44.70538 87 939.6497 34.61606 37.25696 948.5344 44.70538 -14.83925 955.689 51.55542 -12.66454 947.7163 57.24101 -9.373752 948.4148 57.49968 -9.548305 956.7749 52.31264 -6.076632 949.1165 57.55987 -2.782607 949.8156 57.42374 -4.158053 957.82 52.52753 0.496272 950.5112 57.09117 1.281909 958.8028 52.18364 3.746744 951.2041 56.5619 7.012398 951.9006 55.82592 9.355464 952.3978 55.16907 10.22851 952.5828 54.89579 6.717409 959.7022 51.2677 10.22851 952.5828 54.89579 16.46084 953.9069 52.46221 13.38217 953.2515 53.77348 22.35687 955.1597 49.29885 19.45627 954.5428 50.96928 27.83622 956.3239 45.4541 25.15301 955.7545 47.45801 37.25696 952.4202 41.73136 32.82505 957.3839 40.98546 30.39585 956.8689 43.29315 87 942.0554 32.94503 37.25696 952.4202 41.73136 35.11503 957.8693 38.53786 37.25696 953.6942 40.62818 87 944.3442 31.10175 37.25696 953.6942 40.62818 13.38217 953.2515 53.77348 12.08885 960.4994 49.77082 16.46084 953.9069 52.46221 19.45627 954.5428 50.96928 17.33087 961.1805 47.69044 22.35687 955.1597 49.29885 25.15301 955.7545 47.45801 22.37288 961.7377 45.03258 27.83622 956.3239 45.4541 27.14096 962.1717 41.81409 30.39585 956.8689 43.29315 32.82505 957.3839 40.98546 31.5609 962.4909 38.06404 35.11503 957.8693 38.53786 37.25696 958.3267 35.95722 37.25696 958.3267 35.95722 87 946.4901 29.10347 37.25696 958.3267 35.95722 87 948.4984 26.94602 87 950.3364 24.66879 38.2222 960.8385 32.44842 35.5619 962.7105 33.82387 38.2222 960.8385 32.44842 87 926.2002 40.19765 37.25696 924.6832 53.98956 37.25696 924.1187 54.06272 87 923.3153 40.72205 37.25696 924.1187 54.06272 31.03131 917.2962 58.24987 37.25696 917.4836 54.47854 37.25696 917.2977 54.47851 24.42344 917.2962 61.31464 17.51809 917.2962 63.63258 6.569955 924.5906 65.27736 10.46113 917.3027 65.16557 10.24522 918.699 65.18701 9.47367 920.9277 65.2212 8.225384 922.9263 65.25186 6.546148 924.6096 48.7 6.439184 924.6938 65.27893 4.570069 925.8533 65.2967 6.569955 924.5906 65.27736 4.55936 925.8585 48.7 2.339567 926.6361 65.30867 2.340802 926.6358 48.7 0 926.9 65.31265 0 926.9 48.7 0 926.9 65.31265 -2.330073 926.6382 65.3087 0 926.9 48.7 -2.35033 926.6336 48.7 -4.545989 925.8649 65.29688 -4.583739 925.8466 48.7 -6.444386 924.6898 65.27887 -6.535737 924.6179 65.27778 -6.535737 924.6179 65.27778 -17.40695 917.2962 63.66307 -8.190952 922.9695 65.25251 -9.449559 920.9778 65.22197 -10.23418 918.7477 65.18776 -10.46117 917.3022 65.16556 -24.2082 917.2962 61.39994 -30.72391 917.2962 58.41259 -36.87723 917.2962 54.73627 -42.59559 917.2961 50.41433 -47.81153 917.2961 45.49776 -52.46354 917.2961 40.04455 -56.49674 917.2961 34.11901 -59.86357 917.2961 27.79104 -62.52431 917.2961 21.13528 -64.44758 917.2961 14.23022 -65.59733 924.6795 0 -65.61069 917.296 7.15732 -65.59733 924.6795 0 -65.78135 922.7679 0 -65.16783 924.6795 -7.494164 -65.78135 922.7679 0 87 920.4078 41.03981 37.25696 917.4836 54.47854 87 917.4786 41.14924 37.25696 917.2977 54.47851 31.95196 909.914 57.26283 37.25696 910.7951 54.07674 87 914.5473 41.05097 37.25696 910.7951 54.07674 26.33157 909.914 60.05504 20.47001 909.914 62.29718 14.42094 909.914 63.96871 10.49994 916.4249 48.7 10.46113 917.3027 65.16557 10.24522 918.699 65.18701 10.49991 916.3556 65.15105 10.49991 916.3556 65.15105 10.23089 918.7619 48.7 9.47367 920.9277 65.2212 9.447655 920.9816 48.7 8.225384 922.9263 65.25186 8.194878 922.9645 48.7 37.25696 909.912 53.96154 37.25696 909.912 53.96154 37.25696 904.174 52.84875 87 911.6337 40.74331 37.25696 904.174 52.84875 31.02474 902.6258 56.34881 37.25696 902.6129 52.43338 24.34045 902.6258 59.54213 17.33335 902.6258 61.94577 9.432517 911.7872 65.0809 8.250819 909.9058 65.052 10.09636 902.6258 63.52784 10.22493 914.0124 65.11508 8.230257 909.8798 48.7 8.250819 909.9058 65.052 9.432517 911.7872 65.0809 8.169685 909.8041 65.05044 8.169685 909.8041 65.05044 9.472749 911.8705 48.7 10.22493 914.0124 65.11508 10.24256 914.0894 48.7 87 908.7388 40.22796 37.25696 902.6129 52.43338 31.66401 895.5231 53.61708 37.25696 897.7628 50.81631 87 905.8959 39.50868 37.25696 897.7628 50.81631 25.63868 895.5231 56.74556 19.30857 895.5231 59.19949 12.74893 895.5231 60.94969 4.530846 906.9279 65.00622 2.725466 902.6258 64.26737 6.037742 895.5231 61.97537 6.515366 908.1659 65.02526 -4.554728 906.9393 65.0064 -4.681572 902.6258 64.15455 -0.74522 895.5231 62.26432 -2.332171 906.1623 64.99443 0 905.9 64.99038 2.322807 906.1602 64.9944 -8.253356 909.9091 65.05205 -12.02652 902.6258 63.19086 -7.519323 895.5231 61.81311 -8.204166 909.847 65.0511 -6.549449 908.193 65.02568 -15.41009 909.914 63.73765 -19.21197 902.6258 61.38911 -14.20404 895.5231 60.6271 -22.38371 909.914 61.63545 -26.14261 902.6258 58.77317 -20.71991 895.5231 58.7204 -29.08116 909.914 58.77283 -32.72653 902.6258 55.37776 -26.98948 895.5231 56.11567 -35.41983 909.914 55.1851 -38.87642 902.6258 51.24789 -32.9382 895.5231 52.84387 -41.3215 909.914 50.91653 -44.51071 902.6257 46.43833 -38.49539 895.5231 48.9439 -46.71338 909.914 46.01977 -49.55466 902.6257 41.01289 -43.59496 895.5231 44.46212 -51.52893 909.914 40.55525 -53.94139 902.6257 35.04351 -48.17631 895.5231 39.45179 -55.70875 909.914 34.59038 -57.61272 902.6257 28.60936 -55.34395 898.9819 30.88398 -52.18496 895.5231 33.97249 -54.98893 898.1526 31.01222 -55.13266 898.575 31.01631 -59.20126 909.914 28.19876 -60.51996 902.6257 21.79578 -57.56399 900.3819 27.43669 -55.63959 899.3804 30.58638 -56.01777 899.7417 30.10307 -56.46791 900.0399 29.4279 -56.98489 900.2593 28.54673 -61.96338 909.914 21.45923 -62.62454 902.6257 14.69312 -60.852 899.5518 18.28853 -58.19752 900.3845 26.06759 -58.87258 900.2355 24.40083 -63.96102 909.914 14.45495 -63.89856 902.6257 7.395605 -62.25659 899.0665 12 -65.36458 908.2637 0 -64.32512 902.6257 0 -61.97613 895.5231 6.029772 -65.57407 909.9139 0 -65.16957 909.9139 7.272337 -61.34257 896.2083 12 -61.10149 895.5229 12 -65.14486 909.9139 -7.490384 -64.32512 902.6257 0 -65.36458 908.2637 0 -63.96415 901.1339 0 -63.8987 902.6257 -7.394437 -63.96415 901.1339 0 -65.57407 909.9139 0 -65.97277 915.5043 0 -65.56958 917.296 -7.524658 -65.97277 915.5043 0 -65.99992 917.296 0 -9.456836 911.8373 65.08168 -10.5 916.4029 65.15177 -10.23619 914.0611 65.11582 -9.447655 911.8184 48.7 -8.253356 909.9091 65.05205 -8.204166 909.847 65.0511 -9.456836 911.8373 65.08168 -8.194878 909.8355 48.7 -6.549449 908.193 65.02568 -6.546148 908.1904 48.7 -4.554728 906.9393 65.0064 -2.340802 906.1643 48.7 -2.332171 906.1623 64.99443 -4.55936 906.9416 48.7 0 905.9 64.99038 0 905.9 48.7 0 905.9 64.99038 2.322807 906.1602 64.9944 0 905.9 48.7 2.35033 906.1665 48.7 4.530846 906.9279 65.00622 4.583739 906.9534 48.7 6.515366 908.1659 65.02526 6.581006 908.2183 48.7 37.25696 895.5 49.88296 87 903.0982 38.58416 37.25696 895.5 49.88296 31.89458 888.695 50.14735 37.25696 891.7093 48.04066 87 900.3798 37.46491 37.25696 891.7093 48.04066 26.06389 888.695 53.41061 19.90376 888.695 55.99875 13.49203 888.695 57.87905 6.909759 888.695 59.02774 0.240148 888.695 59.43031 -6.432498 888.695 59.08166 -13.02383 888.695 57.98619 -19.45055 888.695 56.15777 -25.6314 888.695 53.61949 -31.48826 888.695 50.40345 -36.9471 888.6949 46.55029 -41.93892 888.6949 42.10873 -46.40061 888.6949 37.13489 -55.41906 895.7031 28.53016 -55.55694 895.5178 28.11753 -50.27579 888.6949 31.69167 -55.14807 896.1895 29.40755 -54.97671 896.6962 30.08184 -54.89906 897.2094 30.56837 -54.90814 897.701 30.87141 -55.44979 895.6591 12 -55.55694 895.5178 28.11753 -55.41906 895.7031 28.53016 -55.79754 895.2531 27.42539 -55.74558 895.3057 12 -55.79754 895.2531 27.42539 -55.21226 896.0541 12 -55.14807 896.1895 29.40755 -55.03704 896.4816 12 -54.97671 896.6962 30.08184 -54.93143 896.9288 12 -54.89906 897.2094 30.56837 -54.893 897.4 12 -54.90814 897.701 30.87141 -54.98893 898.1526 31.01222 -55.00498 898.2113 12 -55.13266 898.575 31.01631 -55.32887 898.9564 12 -55.34395 898.9819 30.88398 -55.63959 899.3804 30.58638 -55.83901 899.5857 12 -56.01777 899.7417 30.10307 -56.46791 900.0399 29.4279 -56.49795 900.0552 12 -56.98489 900.2593 28.54673 -57.25935 900.3318 12 -57.56399 900.3819 27.43669 -58.06927 900.3947 12 -58.19752 900.3845 26.06759 -58.87258 900.2355 24.40083 -62.25659 899.0665 12 -58.87258 900.2355 24.40083 -60.852 899.5518 18.28853 -58.87258 900.2355 12 -58.87258 900.2355 12 -61.10149 895.5229 12 -62.25659 899.0665 12 -61.34257 896.2083 12 -60.29742 893.3954 12 -58.87258 900.2355 12 -59.05516 888.6949 6.671181 -60.29742 893.3954 12 -62.26875 895.523 0 -62.26875 895.523 0 -61.78846 894.2012 0 -61.88791 895.523 -6.876325 -61.78846 894.2012 0 37.25696 888.6637 46.2833 87 897.7401 36.14891 37.25696 888.6637 46.2833 32.28773 882.2271 45.56723 37.25696 886.1171 44.60159 87 895.1998 34.6478 37.25696 886.1171 44.60159 26.83996 882.2271 48.97434 21.0369 882.2271 51.73314 14.95536 882.2271 53.80712 8.675845 882.2271 55.16882 2.281482 882.2271 55.80021 -4.143081 882.2271 55.69293 -10.5128 882.2271 54.84842 -16.74335 882.2271 53.27784 -22.75226 882.2271 51.00198 -28.45998 882.2271 48.05098 -33.79096 882.2271 44.4639 -38.67463 882.2271 40.28821 -43.04633 882.2271 35.57921 -46.8482 882.2271 30.39922 -53.51547 888.6949 25.84785 -50.02991 882.2271 24.81682 -56.91341 894.5645 24.40083 -56.0787 888.6949 19.67731 -52.54934 882.2271 18.9059 -56.29208 894.8629 26.06296 -58.893 893.8806 18.28789 -57.93308 888.6949 13.25804 -54.37314 882.2271 12.74471 -55.47716 882.2271 6.414815 -59.43077 888.6949 0 -59.43077 888.6949 0 -58.86388 887.5496 0 -59.05517 888.6949 -6.671046 -58.86388 887.5496 0 -56.91341 894.5645 12 -60.29742 893.3954 12 -58.893 893.8806 18.28789 -56.91341 894.5645 12 -56.91341 894.5645 24.40083 -56.91341 894.5645 12 -56.91341 894.5645 24.40083 -56.29208 894.8629 26.06296 -56.0924 895.0005 12 -56.4806 894.7546 12 37.25696 882.1956 41.576 87 892.7752 32.9677 37.25696 882.1956 41.576 33.03694 876.2008 39.58773 37.25696 881.1212 40.64189 87 890.4689 31.1129 37.25696 881.1212 40.64189 28.34891 876.2008 43.06932 23.29728 876.2008 45.99852 17.94684 876.2008 48.33774 12.36622 876.2008 50.057 6.626997 876.2008 51.13423 0.802775 876.2008 51.55562 -5.031743 876.2008 51.31576 -10.80173 876.2008 50.41774 -16.43317 876.2008 48.87306 -21.85383 876.2008 46.70156 -26.99421 876.2008 43.93106 -31.78836 876.2008 40.59711 -36.1748 876.2008 36.74246 -40.09726 876.2008 32.41657 -43.50545 876.2008 27.6749 -46.35564 876.2008 22.57828 -48.61128 876.2008 17.19208 -50.24344 876.2008 11.58537 -55.8468 882.2271 0 -51.23118 876.2008 5.830074 -55.8468 882.2271 0 -55.22585 881.2599 0 -55.47709 882.2271 -6.415464 -55.22585 881.2599 0 37.25696 876.791 36.31565 87 888.3088 29.10226 37.25696 876.791 36.31565 37.25696 876.1665 35.60494 87 886.2891 26.93124 37.25696 876.1665 35.60494 30.21151 870.6917 35.51892 33.96576 870.6917 31.94771 37.25696 873.1555 31.78582 87 884.4432 24.64163 37.25696 873.1555 31.78582 26.08421 870.6917 38.65156 21.63483 870.6917 41.30694 16.91831 870.6917 43.45227 11.99288 870.6917 45.06106 6.919378 870.6917 46.11346 1.760431 870.6917 46.59646 -3.420252 870.6917 46.5041 -8.558705 870.6917 45.83751 -13.59147 870.6917 44.60494 -18.45642 870.6917 42.8216 -23.09347 870.6917 40.50951 -27.44537 870.6917 37.69722 -31.45839 870.6917 34.41946 -35.07554 870.7 30.73776 -36.89781 870.7085 28.53865 -35.30246 870.7638 30.57442 -35.81478 870.8403 30.09145 -36.35129 870.8254 29.41745 -39.82493 870.6917 24.25496 -36.93766 870.6957 28.46606 -42.23521 870.6917 19.76146 -44.14042 870.6917 15.03165 -45.5178 870.6916 10.12209 -51.56184 876.2008 0 -46.35086 870.6916 5.091485 -51.56184 876.2008 0 -50.91846 875.4082 0 -51.23134 876.2008 -5.82867 -50.91846 875.4082 0 37.25696 870.6586 27.98499 74.12786 880.8034 25.49057 37.25696 870.6586 27.98499 36.44896 870.4472 28.6867 36.86367 870.354 27.99563 37.25696 870.205 27.21301 72.0554 878.5068 22.93998 37.25696 870.205 27.21301 73.6902 880.632 25.44933 73.2704 880.3842 25.28748 72.8708 880.0464 24.97885 72.51555 879.6145 24.49606 72.23542 879.098 23.82264 27.24083 865.7687 30.79207 36.01498 870.481 29.28399 35.56452 870.4492 29.77947 35.10453 870.3442 30.15667 34.65559 870.1629 30.39118 34.24197 869.9119 30.46931 33.87297 869.5966 30.38783 33.55815 869.2238 30.1476 30.53138 865.7687 27.5327 23.60455 865.7687 33.66065 19.6687 865.7687 36.10203 15.48323 865.7687 38.08522 11.10125 865.7687 39.58506 6.578382 865.7687 40.5825 1.972024 865.7687 41.06489 -2.659361 865.7687 41.02611 -7.256996 865.7687 40.46665 -11.76253 865.7687 39.39362 -16.11878 865.7687 37.82062 -20.27046 865.7687 35.76762 -24.16488 865.7687 33.26068 -34.83491 870.6105 30.87515 -27.75261 865.7687 30.33162 -34.06479 870.1384 31.01503 -34.4251 870.3994 31.01386 -34.68685 870.5426 12 -35.07554 870.7 30.73776 -35.30246 870.7638 30.57442 -34.83491 870.6105 30.87515 -35.47725 870.7994 12 -35.81478 870.8403 30.09145 -36.30836 870.8296 12 -36.35129 870.8254 29.41745 -36.89781 870.7085 28.53865 -36.93766 870.6957 28.46606 -37.44038 870.4776 27.43188 -37.11742 870.6298 12 -37.44038 870.4776 27.43188 -39.09337 868.6921 21.33566 -37.9595 870.1176 26.06632 -38.42712 869.6093 24.40084 -39.66579 867.9042 18.24251 -40.53142 866.7127 12 -40.14495 867.2447 15.12831 -40.31156 865.7687 8.074136 -39.32033 865.7675 12 -46.62966 870.6916 0 -40.91154 865.7687 4.056867 -46.62966 870.6916 0 -45.99393 870.0655 0 -46.32926 870.6916 -5.28439 -45.99393 870.0655 0 37.28482 870.1914 12 37.25696 870.205 27.21301 36.86367 870.354 27.99563 37.68489 869.9631 26.55007 37.68489 869.9631 26.55007 36.46509 870.444 12 36.44896 870.4472 28.6867 36.01498 870.481 29.28399 35.60842 870.4546 12 35.56452 870.4492 29.77947 35.10453 870.3442 30.15667 34.78369 870.2227 12 34.65559 870.1629 30.39118 34.24197 869.9119 30.46931 34.05735 869.7664 12 33.87297 869.5966 30.38783 33.55815 869.2238 30.1476 33.31307 868.8153 29.76242 33.48864 869.1214 12 33.31307 868.8153 29.76242 33.14242 868.3944 29.25851 33.14242 868.3944 29.25851 33.03994 867.9689 28.65232 33.12548 868.3392 12 33.03994 867.9689 28.65232 33.00065 867.5433 27.95144 33.00065 867.5433 27.95144 33.02167 867.121 27.1588 33 867.481 12 33.02167 867.121 27.1588 33.10222 866.7045 26.27191 33.02567 867.0894 12 33.10222 866.7045 26.27191 33.36269 865.7324 23.94181 33.99432 863.3752 16.7841 33.10222 866.7045 26.27191 33.36269 865.7324 23.94181 34.15203 862.7866 14.39387 34.28388 862.2945 12 33.10222 866.7045 12 33.10222 866.7045 12 27.42559 861.494 21.87118 33.60139 864.8416 21.55367 29.70194 861.494 18.66297 33.60139 864.8416 21.55367 24.80435 861.494 24.80435 21.87118 861.494 27.42559 18.66297 861.494 29.70194 15.22006 861.494 31.60477 11.58574 861.494 33.11015 7.805734 861.494 34.19915 3.927563 861.494 34.85808 0 861.494 35.07865 -3.927563 861.494 34.85808 -7.805734 861.494 34.19915 -11.58574 861.494 33.11015 -15.22006 861.494 31.60477 -18.66297 861.494 29.70194 -21.87118 861.494 27.42559 -33.06299 868.4575 29.4529 -30.98812 865.7687 27.01761 -24.80435 861.494 24.80435 -33.21776 868.9682 30.11537 -33.44975 869.426 30.58758 -33.73841 869.8171 30.88021 -33.57287 866.0828 24.40084 -33.80931 865.7573 23.36403 -27.42559 861.494 21.87118 -33.22749 866.7001 26.10452 -33.04761 867.3137 27.48123 -33.00055 867.9036 28.5843 -33.57287 866.0828 12 -33.80931 865.7573 23.36403 -33.57287 866.0828 24.40084 -29.70194 861.494 18.66297 -34.24095 865.1632 21.32634 -34.24095 865.1632 21.32634 -33.57287 866.0828 12 -33.57287 866.0828 24.40084 -33.22749 866.7001 26.10452 -33.06555 867.2224 12 -33.04761 867.3137 27.48123 -33.25934 866.6259 12 -33 867.846 12 -33.00055 867.9036 28.5843 -33.06299 868.4575 29.4529 -33.11797 868.6786 12 -33.21776 868.9682 30.11537 -33.44975 869.426 30.58758 -33.45975 869.4413 12 -33.73841 869.8171 30.88021 -33.9968 870.0785 12 -34.06479 870.1384 31.01503 -34.4251 870.3994 31.01386 33.99432 863.3752 16.7841 31.60477 861.494 15.22006 34.15203 862.7866 14.39387 33.11015 861.494 11.58574 34.28388 862.2945 12 37.25696 864.2595 12 34.28388 862.2945 12 35.78392 863.2566 12 35.78392 863.2566 12 33.10222 866.7045 12 34.19915 861.494 7.805734 37.25696 864.2595 12 37.25696 863.6765 9.038722 87 877.1889 8.736272 37.25696 864.2595 12 37.25696 863.6765 9.038722 38.51999 864.6065 12 38.51999 864.6065 12 39.78305 864.9536 12 37.25696 863.2579 6.0454 87 876.668 5.851431 37.25696 863.2579 6.0454 34.85808 861.494 3.927563 37.25696 863.0057 3.029343 87 876.3556 2.941395 37.25696 863.0057 3.029343 35.07865 861.494 0 37.25696 862.9214 0 37.25696 862.9214 0 34.85808 861.494 -3.927563 37.25696 862.9214 0 35.07865 861.494 0 37.25696 862.9683 -2.260576 87 876.25 0 37.25696 862.9214 0 37.25696 862.9683 -2.260576 87 876.25 0 31.63372 859.475 0 28.42494 857.9209 -3.202722 31.63372 859.475 0 28.4181 857.9209 3.262946 28.60481 857.9209 0 27.8604 857.9209 6.483296 26.939 857.9209 9.61901 25.66593 857.9209 12.62915 24.0578 857.9209 15.47443 22.1356 857.9209 18.11769 19.92444 857.9209 20.52444 17.45316 857.9209 22.66325 14.75405 857.9209 24.5062 11.86233 857.9209 26.02924 8.815751 857.9209 27.21248 5.654085 857.9209 28.04047 2.419688 857.9235 28.50759 -0.238821 859.1405 31.0125 2.403126 857.9458 28.55565 2.026692 858.3619 29.43459 1.598386 858.6887 30.10704 1.13654 858.9264 30.58659 0.667092 859.0749 30.88267 0.2093909 859.1427 31.01688 -5.655437 857.9209 28.04019 -0.695256 859.0683 30.86961 -1.162168 858.9158 30.5653 -1.619158 858.6755 30.08017 -2.041546 858.3482 29.40608 -2.412744 857.9329 28.52787 2.35033 906.1665 48.7 -2.340802 906.1643 48.7 0 905.9 48.7 -8.816952 857.9209 27.21209 -11.86337 857.9209 26.02876 -14.75494 857.9209 24.50567 -17.45389 857.9209 22.66269 -19.92501 857.9209 20.52388 -22.13604 857.9209 18.11716 -24.05811 857.9209 15.47394 -34.81368 864.3748 18.22994 -31.60477 861.494 15.22006 -25.66613 857.9209 12.62874 -35.29208 863.7163 15.11877 -33.11015 861.494 11.58574 -26.93912 857.9209 9.618685 -34.19915 861.494 7.805734 -27.86046 857.9209 6.483072 -38.14508 864.8933 12 -35.67718 863.1862 12 -34.85808 861.494 3.927563 -28.41811 857.9209 3.262832 -40.51194 865.2965 0 -35.07865 861.494 0 -41.11218 865.7687 0 -40.85104 865.7687 -4.626395 -35.07865 861.494 0 -40.51194 865.2965 0 -34.53894 861.1589 0 -34.85808 861.494 -3.927563 -34.53894 861.1589 0 -41.11218 865.7687 0 -33.57287 866.0828 12 -39.32033 865.7675 12 -38.14508 864.8933 12 -33.25934 866.6259 12 -40.53142 866.7127 12 -35.67718 863.1862 12 -35.67718 863.1862 12 -35.29208 863.7163 15.11877 -34.81368 864.3748 18.22994 28.60481 857.9209 0 25.69459 856.607 0 21.63501 855.0944 -2.43768 25.69459 856.607 0 21.24769 855.0944 4.748893 21.77191 855.0944 0 21.64046 855.0944 2.38887 20.59834 855.0944 7.051571 19.70026 855.0944 9.2691 18.56428 855.0944 11.3747 17.20414 855.0944 13.34294 15.63624 855.0944 15.15006 13.87953 855.0944 16.77424 11.95522 855.0944 18.19586 9.886541 855.0944 19.39776 7.698476 855.0944 20.36542 5.417449 855.0944 21.08716 2.70908 857.4388 27.44651 3 855.0659 21.47125 2.919602 856.8399 26.07576 2.510289 857.7917 12 2.419688 857.9235 28.50759 2.403126 857.9458 28.55565 2.70908 857.4388 27.44651 2.026692 858.3619 29.43459 1.946467 858.4323 12 1.598386 858.6887 30.10704 1.230266 858.8858 12 1.13654 858.9264 30.58659 0.667092 859.0749 30.88267 0.413992 859.1205 12 0.2093909 859.1427 31.01688 -0.238821 859.1405 31.0125 -0.437745 859.117 12 -0.695256 859.0683 30.86961 -1.162168 858.9158 30.5653 -1.251954 858.8759 12 -1.619158 858.6755 30.08017 -1.961929 858.4193 12 -2.041546 858.3482 29.40608 -2.412744 857.9329 28.52787 4.583739 906.9534 48.7 -4.55936 906.9416 48.7 -2.714106 857.4282 27.42281 -2.516978 857.7816 12 -2.714106 857.4282 27.42281 -5.417449 855.0944 21.08716 -2.921121 856.8334 26.06059 -3 856.15 24.40159 -3 855.0659 21.47125 -7.698476 855.0944 20.36542 -9.886541 855.0944 19.39776 -11.95522 855.0944 18.19586 -13.87953 855.0944 16.77424 -15.63624 855.0944 15.15006 -17.20414 855.0944 13.34294 -18.56428 855.0944 11.3747 -19.70026 855.0944 9.2691 -20.59834 855.0944 7.051571 -21.24769 855.0944 4.748893 -28.60481 857.9209 0 -21.64046 855.0944 2.38887 -28.60481 857.9209 0 -28.14731 857.703 0 -28.42494 857.9209 -3.202722 -28.14731 857.703 0 21.77191 855.0944 0 19.49887 854.3461 0 14.57351 853.0501 -1.64204 19.49887 854.3461 0 14.57206 853.0501 1.654893 14.66573 853.0501 0 14.29225 853.0501 3.288647 13.82987 853.0501 4.880392 13.19084 853.0501 6.409797 12.3833 853.0501 7.857324 11.41758 853.0501 9.204483 10.30602 853.0501 10.43406 9.062809 853.0501 11.53036 7.70383 853.0501 12.47938 6.246443 853.0501 13.26898 4.709266 853.0501 13.88909 3 853.0252 14.25964 3 856.15 24.40159 3 856.15 12 3 855.0659 21.47125 3 856.15 24.40159 3 853.9539 17.93332 3 853.9539 17.93332 3 856.15 12 3 856.15 24.40159 2.919602 856.8399 26.07576 2.874678 857.0078 12 14.66573 853.0501 0 13.10844 852.7149 0 7.329081 851.8134 -0.825789 13.10844 852.7149 0 7.190538 851.8134 1.641193 7.375456 851.8134 0 7.329081 851.8134 0.825789 6.96157 851.8134 2.435959 6.645057 851.8134 3.200091 6.244977 851.8134 3.923979 5.766364 851.8134 4.598522 5.215235 851.8134 5.215235 4.598522 851.8134 5.766364 3.923979 851.8134 6.244977 3.200091 851.8134 6.645057 2.435959 851.8134 6.96157 3 852.5695 12 3 853.0252 14.25964 3 852.5695 12 7.375456 851.8134 0 6.587109 851.7296 0 0 851.4 0 6.587109 851.7296 0 0 851.4 0 1.641193 851.8134 7.190538 2.000279 852.5309 12 0.825789 851.8134 7.329081 0 852.5001 12 0 851.8134 7.375456 1.000319 852.5078 12 -1.000319 852.5078 12 -0.825789 851.8134 7.329081 -2.000279 852.5309 12 -1.641193 851.8134 7.190538 -4.709266 853.0501 13.88909 -2.435959 851.8134 6.96157 -3 852.5695 12 -6.246443 853.0501 13.26898 -3.200091 851.8134 6.645057 -7.70383 853.0501 12.47938 -3.923979 851.8134 6.244977 -9.062809 853.0501 11.53036 -4.598522 851.8134 5.766364 -10.30602 853.0501 10.43406 -5.215235 851.8134 5.215235 -11.41758 853.0501 9.204483 -5.766364 851.8134 4.598522 -12.3833 853.0501 7.857324 -6.244977 851.8134 3.923979 -13.19084 853.0501 6.409797 -6.645057 851.8134 3.200091 -13.82987 853.0501 4.880392 -6.96157 851.8134 2.435959 -14.29225 853.0501 3.288647 -7.190538 851.8134 1.641193 -14.57206 853.0501 1.654893 -7.329081 851.8134 0.825789 -14.4222 852.9951 0 -7.375456 851.8134 0 -14.66573 853.0501 0 -14.57351 853.0501 -1.64204 -7.375456 851.8134 0 -14.4222 852.9951 0 -7.255066 851.8 0 -7.329081 851.8134 -0.825789 -7.255066 851.8 0 -14.66573 853.0501 0 -21.41453 854.9707 0 -21.63501 855.0944 -2.43768 -21.41453 854.9707 0 -21.77191 855.0944 0 -3 853.0252 14.25964 -3 856.15 24.40159 -3 853.0252 14.25964 -3 852.5695 12 -3 855.0659 21.47125 -3 853.9539 17.93332 -3 853.9539 17.93332 3 852.5695 12 -3 852.5695 12 -2.000279 852.5309 12 3 856.15 12 -3 856.15 12 -3 856.15 12 2.000279 852.5309 12 -1.000319 852.5078 12 1.000319 852.5078 12 0 852.5001 12 -7.190538 851.8134 -1.641193 -6.96157 851.8134 -2.435959 -6.645057 851.8134 -3.200091 -6.244977 851.8134 -3.923979 -5.766364 851.8134 -4.598522 -5.215235 851.8134 -5.215235 -4.598522 851.8134 -5.766364 -3.923979 851.8134 -6.244977 -3.200091 851.8134 -6.645057 -2.435959 851.8134 -6.96157 -1.641193 851.8134 -7.190538 -0.825789 851.8134 -7.329081 0 851.8134 -7.375456 0.825789 851.8134 -7.329081 1.641193 851.8134 -7.190538 2.435959 851.8134 -6.96157 3.200091 851.8134 -6.645057 3.923979 851.8134 -6.244977 4.598522 851.8134 -5.766364 5.215235 851.8134 -5.215235 5.766364 851.8134 -4.598522 6.244977 851.8134 -3.923979 6.645057 851.8134 -3.200091 6.96157 851.8134 -2.435959 7.190538 851.8134 -1.641193 -65.99992 917.296 0 -6.581006 924.5817 48.7 -8.190952 922.9695 65.25251 -8.230257 922.9202 48.7 -9.449559 920.9778 65.22197 -9.472749 920.9295 48.7 -10.23418 918.7477 65.18776 -10.24256 918.7107 48.7 -10.46117 917.3022 65.16556 -10.5 916.4029 65.15177 -10.49994 916.3751 48.7 -10.23619 914.0611 65.11582 -10.23089 914.0382 48.7 -37.84226 870.2136 12 -37.9595 870.1176 26.06632 -38.42712 869.6093 24.40084 -39.66579 867.9042 18.24251 -38.42712 869.6093 24.40084 -39.09337 868.6921 21.33566 -40.14495 867.2447 15.12831 -40.53142 866.7127 12 -38.42712 869.6093 12 -38.42712 869.6093 12 -33.45975 869.4413 12 -38.42712 869.6093 12 -33.11797 868.6786 12 -33 867.846 12 -33.06555 867.2224 12 -21.77191 855.0944 0 -2.875674 857.0042 12 -2.921121 856.8334 26.06059 -3 856.15 24.40159 -3 856.15 12 -59.46238 941.1162 12 -59.46238 941.1162 12 -57.25921 934.4682 12 -56.91341 940.2355 12 -56.91341 940.2355 22.88183 -59.46238 941.1162 12 -56.91341 940.2355 12 -58.06918 934.4053 12 -46.66674 963.1986 8.983836 -58.39623 940.7478 17.41578 -58.39623 940.7478 17.41578 -56.49779 934.7449 12 -56.4806 940.0454 12 -56.91341 940.2355 22.88183 -56.91341 940.2355 12 -56.4806 940.0454 12 -55.83888 935.2144 12 -56.0924 939.7995 12 -56.35051 939.9731 24.74449 -56.0924 939.7995 12 -55.74558 939.4943 12 -55.87509 939.6199 26.41399 -55.74558 939.4943 12 -55.32879 935.8438 12 -55.44979 939.1409 12 -55.44979 939.1409 12 -55.21226 938.7459 12 -55.00495 936.5888 12 -55.03704 938.3184 12 -54.93143 937.8712 12 -54.893 937.4 12 -44.50112 977.3314 0 -47.93976 962.7628 0 -47.86124 962.79 2.248175 -44.29661 977.3762 -3.791381 -47.85824 962.791 -2.290539 -47.93976 962.7628 0 -44.50112 977.3314 0 -44.29661 977.3762 3.791381 -47.62354 962.8721 4.504169 -47.22624 963.0084 6.749334 -43.68806 977.5079 7.53378 -46.66674 963.1986 8.983836 -45.94218 963.4418 11.20084 -45.94218 963.4418 11.20084 -45.04833 963.737 13.399 -45.04456 966.1377 12 -45.04833 963.737 13.399 -42.68884 977.7186 11.18026 -56.91341 940.2355 22.88183 -43.97847 964.0832 15.57508 -44.04953 965.9978 14.5243 -43.97847 964.0832 15.57508 -55.87509 939.6199 26.41399 -42.87273 965.8325 16.9462 -42.72776 964.4782 17.71942 -56.35051 939.9731 24.74449 -41.52141 965.6425 19.25525 -41.28906 964.9195 19.8271 -39.83607 965.4105 21.65902 -39.66504 965.4011 21.8766 -40.00352 965.4292 21.44097 -40.00352 965.4292 12 -39.66504 965.4011 21.8766 -39.55772 965.4002 22.04029 -39.83607 965.4105 21.65902 -43.36265 956.7775 26.56626 -39.44754 965.4032 22.20199 -39.44754 965.4032 22.20199 -38.84014 965.4942 23.02524 -39.44754 965.4032 22.20199 -43.36265 956.7775 26.56626 -39.14841 965.4321 12 -38.84014 965.4942 23.02524 -41.19537 957.4013 29.13781 -53.35694 939.0655 -32.24349 -41.09028 964.9794 -20.09465 -39.41567 965.4735 -22.16646 -37.60331 978.6867 -21.14724 -39.41567 965.4735 -22.16646 -41.09028 964.9794 -20.09465 -43.3414 956.8244 -26.54257 -41.19536 957.4013 -29.1378 -43.3414 956.8244 -26.54257 -39.41567 965.4735 -22.16646 -37.6587 966.0241 -24.28212 -39.41567 965.4735 -22.16646 -37.60331 978.6867 -21.14724 -37.6587 966.0241 -24.28212 -54.71067 938.7782 -30.09512 -42.57107 964.5269 -17.96529 -39.61511 978.324 -18.02054 -42.57107 964.5269 -17.96529 -57.65056 938.1535 -24.52965 -43.85488 964.1227 -15.80338 -43.85488 964.1227 -15.80338 -44.9534 963.768 -13.60892 -41.32167 977.9957 -14.6882 -44.9534 963.768 -13.60892 -59.97632 937.6593 -18.66554 -45.87407 963.4645 -11.38519 -42.68884 977.7186 -11.18026 -45.87407 963.4645 -11.38519 -61.65904 937.3016 -12.57327 -46.62189 963.2138 -9.138074 -46.62189 963.2138 -9.138074 -47.20038 963.0173 -6.869502 -43.68806 977.5079 -7.53378 -47.20038 963.0173 -6.869502 -47.61177 962.8761 -4.586817 -47.61177 962.8761 -4.586817 -61.65904 937.3016 -12.57327 -62.67024 931.9716 -14.70071 -59.97632 937.6593 -18.66554 -60.565 931.9716 -21.80713 -57.65056 938.1535 -24.52965 -57.65684 931.9716 -28.62444 -54.71067 938.7782 -30.09512 -53.35694 939.0655 -32.24349 -47.26713 948.1753 -30.91868 -51.19286 939.5262 -35.29479 -49.44237 939.0808 -37.96575 -51.19286 939.5262 -35.29479 -53.98431 931.9716 -35.06228 -48.3326 940.1342 -38.77006 -51.19286 939.5262 -35.29479 -47.26713 948.1753 -30.91868 -48.3326 940.1342 -38.77006 -44.76398 948.7677 -33.95392 -35.79095 991.9 -20.12801 -34.4468 979.276 -25.4637 -35.79095 991.9 -20.12801 -37.62725 966.0346 -24.32106 -35.87351 966.6519 -26.51835 -38.06859 991.9 -15.39189 -37.00771 991.9 -17.79149 -38.97531 991.9 -12.92409 -39.72275 991.9 -10.40343 -40.7262 991.9 -5.244555 -40.30683 991.9 -7.84 -40.97774 991.9 -2.632987 -41.0625 991.9 0 -41.0625 991.9 0 35.92845 991.9 -19.88127 -35.79095 991.9 -20.12801 -37.00771 991.9 -17.79149 -34.47204 991.9 -22.31159 34.42625 991.9 -22.38125 -34.47204 991.9 -22.31159 37.25172 991.9 -17.27391 -38.06859 991.9 -15.39189 38.38709 991.9 -14.57941 -38.97531 991.9 -12.92409 39.3263 991.9 -11.81151 -39.72275 991.9 -10.40343 40.06954 991.9 -8.974722 -40.30683 991.9 -7.84 40.60614 991.9 -6.098397 -40.7262 991.9 -5.244555 40.93793 991.9 -3.175976 -40.97774 991.9 -2.632987 41.06209 991.9 -0.258373 -41.0625 991.9 0 -40.97774 991.9 2.632987 -40.97774 991.9 2.632987 -37.62725 966.0346 -24.32106 -38.98367 958.0422 -31.6751 -35.87351 966.6519 -26.51835 -31.19065 991.9 -26.70669 -35.87351 966.6519 -26.51835 -34.4468 979.276 -25.4637 -33.97824 967.3474 -28.75585 -38.98367 958.0422 -31.6751 -35.87351 966.6519 -26.51835 -33.97824 967.3474 -28.75585 -33.0201 991.9 -24.40905 -33.0201 991.9 -24.40905 -33.0201 991.9 -24.40905 32.74561 991.9 -24.77552 -31.19065 991.9 -26.70669 -45.21324 940.7972 -42.00397 -45.21324 940.7972 -42.00397 -42.10005 949.4153 -36.84218 -38.03607 950.4067 -40.58281 -45.21324 940.7972 -42.00397 -42.10005 949.4153 -36.84218 -44.92121 939.0808 -43.22072 -42.7242 941.3276 -44.25056 -42.7242 941.3276 -44.25056 -35.62234 959.0133 -35.07421 37.25696 863.1083 -4.509339 87 876.3579 -2.962667 37.25696 863.1083 -4.509339 34.19915 861.494 -7.805734 37.25696 863.6609 -8.945619 87 876.6737 -5.888951 37.25696 863.6609 -8.945619 33.11015 861.494 -11.58574 37.25696 864.5828 -13.35143 87 877.1993 -8.784898 37.25696 864.5828 -13.35143 31.60477 861.494 -15.22006 37.25696 865.7534 -17.33643 87 877.9334 -11.64655 37.25696 865.7534 -17.33643 35.0945 865.7687 -21.41466 37.25696 865.9014 -17.77122 37.25696 865.9014 -17.77122 29.70194 861.494 -18.66297 32.46177 865.7687 -25.22786 37.25696 869.9598 -26.78343 37.25696 867.6675 -22.23947 27.42559 861.494 -21.87118 29.41667 865.7687 -28.72057 33.90768 870.6916 -32.00929 37.25696 870.6448 -27.962 24.80435 861.494 -24.80435 25.99786 865.7687 -31.84843 30.06173 870.6916 -35.64572 21.87118 861.494 -27.42559 22.2488 865.7687 -34.5717 25.82845 870.6916 -38.82289 18.66297 861.494 -29.70194 18.21709 865.7687 -36.85578 21.26239 870.6916 -41.49983 15.22006 861.494 -31.60477 13.95396 865.7687 -38.67167 16.42236 870.6916 -43.64208 11.58574 861.494 -33.11015 9.513563 865.7687 -39.99629 11.37075 870.6916 -45.22202 7.805734 861.494 -34.19915 4.952311 865.7687 -40.81282 6.172631 870.6916 -46.2193 3.927563 861.494 -34.85808 0.328148 865.7687 -41.11087 0.89498 870.6916 -46.62107 0 861.494 -35.07865 -4.300184 865.7687 -40.88667 -4.394202 870.6916 -46.42215 -3.927563 861.494 -34.85808 -8.873888 865.7687 -40.14306 -9.626768 870.6916 -45.62511 -7.805734 861.494 -34.19915 -13.33486 865.7687 -38.88949 -14.7353 870.6916 -44.24021 -11.58574 861.494 -33.11015 -17.62644 865.7687 -37.14189 -19.65397 870.6916 -42.2853 -15.22006 861.494 -31.60477 -21.69409 865.7687 -34.92245 -24.31941 870.6916 -39.78557 -18.66297 861.494 -29.70194 -25.48616 865.7687 -32.25938 -28.67151 870.6916 -36.77322 -21.87118 861.494 -27.42559 -28.95445 865.7687 -29.18649 -32.65419 870.6916 -33.28707 -24.80435 861.494 -24.80435 -32.05492 865.7687 -25.74283 -36.21614 870.6916 -29.37203 -27.42559 861.494 -21.87118 -34.74818 865.7687 -21.97214 -39.31147 870.6916 -25.07855 -29.70194 861.494 -18.66297 -37.00002 865.7687 -17.92233 -41.90029 870.6916 -20.46195 -31.60477 861.494 -15.22006 -38.78182 865.7687 -13.64484 -43.94924 870.6916 -15.5817 -33.11015 861.494 -11.58574 -40.07095 865.7687 -9.194019 -45.43194 870.6916 -10.50069 -34.19915 861.494 -7.805734 -27.88762 857.9209 -6.365168 -26.9996 857.9209 -9.447568 -25.77204 857.9209 -12.41116 -24.22038 857.9209 -15.21867 -22.36414 857.9209 -17.83481 -20.22665 857.9209 -20.22665 -17.83481 857.9209 -22.36414 -15.21867 857.9209 -24.22038 -12.41116 857.9209 -25.77204 -9.447568 857.9209 -26.9996 -6.365168 857.9209 -27.88762 -3.202722 857.9209 -28.42494 0 857.9209 -28.60481 3.202722 857.9209 -28.42494 6.365168 857.9209 -27.88762 9.447568 857.9209 -26.9996 12.41116 857.9209 -25.77204 15.21867 857.9209 -24.22038 17.83481 857.9209 -22.36414 20.22665 857.9209 -20.22665 22.36414 857.9209 -17.83481 24.22038 857.9209 -15.21867 25.77204 857.9209 -12.41116 26.9996 857.9209 -9.447568 27.88762 857.9209 -6.365168 87 878.8644 -14.43332 37.25696 867.6675 -22.23947 87 879.9959 -17.15091 37.25696 869.9598 -26.78343 87 881.3097 -19.76913 37.25696 870.6448 -27.962 37.25696 872.8857 -31.40689 87 882.799 -22.27482 37.25696 872.8857 -31.40689 37.25696 876.1842 -35.6255 33.01521 876.2008 -39.6058 28.32646 876.2008 -43.08404 23.27457 876.2008 -46.00997 17.92431 876.2008 -48.34607 12.34427 876.2008 -50.06238 6.605977 876.2008 -51.13692 0.782998 876.2008 -51.5559 -5.050019 876.2008 -51.31394 -10.8183 876.2008 -50.41416 -16.44789 876.2008 -48.86809 -21.86662 876.2008 -46.69555 -27.00503 876.2008 -43.92438 -31.79725 876.2008 -40.59012 -36.18183 876.2008 -36.73551 -40.10258 876.2008 -32.40997 -43.50923 876.2008 -27.66894 -46.35811 876.2008 -22.5732 -48.61268 876.2008 -17.18808 -50.24407 876.2008 -11.58262 87 884.4636 -24.66879 37.25696 876.1842 -35.6255 37.25696 876.47 -35.95347 87 886.3017 -26.94602 37.25696 876.47 -35.95347 32.29783 882.2271 -45.56002 37.25696 880.7156 -40.27622 37.25696 882.1907 -41.5719 26.85026 882.2271 -48.96866 21.04718 882.2271 -51.72893 14.96542 882.2271 -53.80429 8.68552 882.2271 -55.16727 2.290619 882.2271 -55.79981 -4.134611 882.2271 -55.69354 -10.5051 882.2271 -54.84987 -16.73649 882.2271 -53.27997 -22.74629 882.2271 -51.00463 -28.45492 882.2271 -48.05396 -33.78679 882.2271 -44.46705 -38.67132 882.2271 -40.29137 -43.04382 882.2271 -35.58222 -46.84642 882.2271 -30.40196 -50.02874 882.2271 -24.81916 -52.54867 882.2271 -18.90774 -54.37284 882.2271 -12.74598 87 888.31 -29.10347 37.25696 880.7156 -40.27622 87 890.4558 -31.10175 37.25696 882.1907 -41.5719 37.25696 885.5974 -44.23245 87 892.7446 -32.94503 37.25696 885.5974 -44.23245 31.89239 888.6949 -50.1487 37.25696 888.6608 -46.28148 26.06169 888.6949 -53.41165 19.90157 888.6949 -55.9995 13.48991 888.6949 -57.87952 6.907735 888.6949 -59.02796 0.238249 888.6949 -59.43029 -6.434249 888.6949 -59.08144 -13.02542 888.6949 -57.98582 -19.45195 888.6949 -56.15726 -25.63261 888.6949 -53.61889 -31.48929 888.6949 -50.40279 -36.94794 888.6949 -46.54961 -41.93958 888.6949 -42.10805 -46.40111 888.6949 -37.13425 -50.27615 888.6949 -31.69109 -53.5157 888.6949 -25.84736 -56.07883 888.6949 -19.67692 -57.93313 888.6949 -13.25777 87 895.1503 -34.61606 37.25696 888.6608 -46.28148 37.25696 891.0592 -47.68733 37.25696 891.0592 -47.68733 31.56795 895.523 -53.67366 37.25696 895.5014 -49.88356 25.44771 895.523 -56.83143 19.01618 895.523 -59.29403 12.35205 895.523 -61.03134 5.536825 895.523 -62.0221 -1.346126 895.523 -62.25419 -8.212612 895.523 -61.72479 -14.97864 895.523 -60.44036 -21.56144 895.523 -58.41662 -27.88051 895.523 -55.67831 -33.85853 895.523 -52.25894 -39.42239 895.523 -48.20033 -44.50403 895.523 -43.55213 -49.0413 895.523 -38.37119 -52.97868 895.523 -32.72089 -56.26802 895.523 -26.67034 -58.86908 895.523 -20.29356 -60.75004 895.523 -13.66854 87 897.6704 -36.1111 37.25696 895.5014 -49.88356 37.25696 897.0153 -50.52113 87 900.2899 -37.42399 37.25696 897.0153 -50.52113 31.00619 902.6257 -56.359 37.25696 902.6172 -52.43459 24.32194 902.6257 -59.54967 17.31523 902.6257 -61.95082 10.07894 902.6257 -63.53059 2.709023 902.6257 -64.26805 -4.696812 902.6257 -64.15342 -12.04037 902.6257 -63.18821 -19.2243 902.6257 -61.38523 -26.15335 902.6257 -58.76839 -32.73564 902.6257 -55.37237 -38.88391 902.6257 -51.24219 -44.51664 902.6257 -46.43264 -49.55915 902.6257 -41.00745 -53.94459 902.6257 -35.03858 -57.61481 902.6257 -28.60515 -60.52115 902.6257 -21.79246 -62.62508 902.6257 -14.69084 87 902.9897 -38.54377 37.25696 902.6172 -52.43459 37.25696 903.3555 -52.63717 87 905.7703 -39.47208 37.25696 903.3555 -52.63717 30.84943 909.9139 -57.86425 37.25696 909.914 -53.96183 24.0378 909.9139 -61.00936 16.91149 909.9139 -63.35582 9.563803 909.9139 -64.8729 2.090914 909.9139 -65.54073 -5.409347 909.9139 -65.35057 -12.83879 909.9139 -64.30493 -20.10017 909.9139 -62.41748 -27.09842 909.9139 -59.71293 -33.74193 909.9139 -56.22669 -39.94373 909.9139 -52.00439 -45.62263 909.9139 -47.10132 -50.70429 909.9139 -41.58164 -55.12219 909.9139 -35.51763 -58.8185 909.9139 -28.98867 -61.74481 909.9139 -22.08021 -63.86285 909.9139 -14.88271 87 908.5998 -40.19765 37.25696 909.914 -53.96183 37.25696 916.6749 -54.47378 87 914.3922 -41.03981 37.25696 916.6749 -54.47378 87 911.4847 -40.72205 30.81978 917.296 -58.36206 37.25696 917.2969 -54.47851 23.96496 917.296 -61.49528 16.79761 917.296 -63.82656 9.411213 917.296 -65.32548 1.902083 917.296 -65.97251 -5.631852 917.296 -65.7592 -13.09234 917.296 -64.68833 -20.3821 917.296 -62.77387 -27.40606 917.296 -60.0408 -34.07262 917.296 -56.52474 -40.29484 917.296 -52.27155 -45.99158 917.296 -47.3367 -51.08856 917.296 -41.78454 -55.5193 917.296 -35.68747 -59.22603 917.296 -29.12502 -62.1604 917.296 -22.18274 -64.28414 917.296 -14.95119 87 917.3215 -41.14924 37.25696 917.2969 -54.47851 30.87833 924.6795 -57.87519 37.25696 923.4138 -54.14566 87 920.2527 -41.05097 37.25696 923.4138 -54.14566 24.06421 924.6795 -61.02395 16.93498 924.6795 -63.37362 9.583977 924.6795 -64.89343 2.10748 924.6795 -65.56346 -5.396614 924.6795 -65.37496 -12.83004 924.6795 -64.33039 -20.09546 924.6795 -62.44343 -27.09774 924.6795 -59.73878 -33.74517 924.6795 -56.25186 -39.95072 924.6795 -52.02835 -45.63312 924.6795 -47.12353 -50.71797 924.6795 -41.60164 -55.13868 924.6795 -35.53498 -58.83736 924.6795 -29.00301 -61.76557 924.6795 -22.09124 -63.88498 924.6795 -14.89019 37.25696 924.6824 -53.98967 37.25696 924.6824 -53.98967 31.02293 931.9716 -56.40255 37.25696 930.0737 -52.98391 87 923.1663 -40.74331 37.25696 930.0737 -52.98391 24.3339 931.9716 -59.59473 17.32226 931.9716 -61.99684 10.08098 931.9716 -63.57707 2.706058 931.9716 -64.31444 -4.70474 931.9716 -64.19918 -12.05317 931.9716 -63.23283 -19.2418 931.9716 -61.42819 -26.17535 931.9716 -58.80919 -32.76188 931.9716 -55.41055 -38.91409 931.9716 -51.27732 -44.5504 931.9716 -46.4643 -49.59611 931.9716 -41.0353 37.25696 931.9782 -52.49187 87 926.0612 -40.22796 37.25696 931.9782 -52.49187 31.5382 939.0808 -53.7707 37.25696 936.5443 -51.00407 87 928.9041 -39.50868 37.25696 936.5443 -51.00407 25.37289 939.0808 -56.93999 18.8938 939.0808 -59.40514 12.18106 939.0808 -61.13565 5.317684 939.0808 -62.11013 -1.611454 939.0808 -62.31653 -8.520665 939.0808 -61.75228 -15.3245 939.0808 -60.42438 -21.93883 939.0808 -58.34924 -28.28185 939.0808 -55.55252 -34.27513 939.0808 -52.06882 -39.84454 939.0808 -47.9412 37.25696 939.0963 -49.97189 87 931.7018 -38.58416 37.25696 939.0963 -49.97189 31.72589 945.9177 -50.36076 37.25696 942.7074 -48.2437 87 934.4202 -37.46491 37.25696 942.7074 -48.2437 25.7025 945.9177 -53.68537 19.33571 945.9177 -56.2927 12.71057 945.9177 -58.14791 5.915605 945.9177 -59.22621 -0.958396 945.9177 -59.51319 -7.819593 945.9177 -59.00502 -14.57631 945.9177 -57.70848 -21.14295 945.914 -55.64105 -28.613 944.3261 -53.03096 -22.37883 945.651 -55.29077 -25.52735 944.9815 -54.25511 -34.55152 943.0639 -50.03557 -31.6243 943.6854 -51.62348 -40.11112 941.8822 -46.34352 -37.38358 942.4613 -48.27424 37.25696 945.9406 -46.40425 87 937.06 -36.14891 37.25696 945.9406 -46.40425 32.40855 952.3968 -45.61698 37.25696 948.4624 -44.75544 87 939.6003 -34.6478 37.25696 948.4624 -44.75544 27.08649 952.3968 -48.96473 21.42247 952.3968 -51.6943 15.48798 952.3968 -53.77123 9.355441 952.3977 -55.16915 3.746761 951.204 -56.56193 7.012432 951.9005 -55.82597 -2.782607 949.8156 -57.42374 0.496278 950.5112 -57.09118 -9.373754 948.4149 -57.49968 -6.076634 949.1165 -57.55986 -15.93596 947.0202 -56.78635 -12.66454 947.7163 -57.24101 -18.40032 954.9287 -50.72861 -21.14295 945.914 -55.64105 -22.37883 945.651 -55.29077 -15.93596 947.0202 -56.78635 -23.72681 953.7529 -48.98193 -25.52735 944.9815 -54.25511 -28.613 944.3261 -53.03096 -28.80595 952.5937 -46.68803 -31.6243 943.6854 -51.62348 -34.55152 943.0639 -50.03557 -33.59058 951.4719 -43.87709 -37.38358 942.4613 -48.27424 -40.11112 941.8822 -46.34352 37.25696 952.4295 -41.72359 87 942.0249 -32.9677 37.25696 952.4295 -41.72359 32.82512 957.3837 -40.98553 35.11508 957.8692 -38.53794 37.25696 953.7031 -40.62019 87 944.3311 -31.1129 37.25696 953.7031 -40.62019 30.39594 956.8688 -43.29321 25.15309 955.7543 -47.45808 27.8363 956.3238 -45.45416 19.45633 954.5427 -50.96934 22.35694 955.1596 -49.29891 13.38223 953.2514 -53.77355 16.46091 953.9068 -52.46228 10.07531 960.2118 -50.4037 9.355441 952.3977 -55.16915 7.012432 951.9005 -55.82597 10.22856 952.5827 -54.89586 10.22856 952.5827 -54.89586 4.333768 959.3186 -51.74123 3.746761 951.204 -56.56193 -1.449783 958.319 -52.4269 0.496278 950.5112 -57.09118 -2.782607 949.8156 -57.42374 -7.207044 957.2369 -52.47407 -6.076634 949.1165 -57.55986 -9.373754 948.4149 -57.49968 -12.87613 956.0983 -51.90079 -12.66454 947.7163 -57.24101 37.25696 958.3267 -35.95722 87 946.4913 -29.10226 37.25696 958.3267 -35.95722 35.31389 962.6988 -34.1157 37.25696 958.3267 -35.95722 35.11508 957.8692 -38.53794 87 948.5109 -26.93124 38.4441 961.3686 -31.62472 38.4441 961.3686 -31.62472 31.01789 962.4559 -38.57167 32.82512 957.3837 -40.98553 30.39594 956.8688 -43.29321 26.25904 962.0984 -42.46797 27.8363 956.3238 -45.45416 25.15309 955.7543 -47.45808 21.12311 961.6089 -45.75723 22.35694 955.1596 -49.29891 19.45633 954.5427 -50.96934 15.69929 960.9793 -48.4079 16.46091 953.9068 -52.46228 13.38223 953.2514 -53.77355 -21.22604 855.0944 -4.844705 -20.55014 855.0944 -7.190805 -19.61581 855.0944 -9.446477 -18.4348 855.0944 -11.58335 -17.02196 855.0944 -13.57456 -15.39506 855.0944 -15.39506 -13.57456 855.0944 -17.02196 -11.58335 855.0944 -18.4348 -9.446477 855.0944 -19.61581 -7.190805 855.0944 -20.55014 -4.844705 855.0944 -21.22604 -2.43768 855.0944 -21.63501 0 855.0944 -21.77191 2.43768 855.0944 -21.63501 4.844705 855.0944 -21.22604 7.190805 855.0944 -20.55014 9.446477 855.0944 -19.61581 11.58335 855.0944 -18.4348 13.57456 855.0944 -17.02196 15.39506 855.0944 -15.39506 17.02196 855.0944 -13.57456 18.4348 855.0944 -11.58335 19.61581 855.0944 -9.446477 20.55014 855.0944 -7.190805 21.22604 855.0944 -4.844705 -14.29802 853.0501 -3.263431 -13.84273 853.0501 -4.843782 -13.21336 853.0501 -6.36322 -12.41782 853.0501 -7.802636 -11.46613 853.0501 -9.143931 -10.37023 853.0501 -10.37023 -9.143931 853.0501 -11.46613 -7.802636 853.0501 -12.41782 -6.36322 853.0501 -13.21336 -4.843782 853.0501 -13.84273 -3.263431 853.0501 -14.29802 -1.64204 853.0501 -14.57351 0 853.0501 -14.66573 1.64204 853.0501 -14.57351 3.263431 853.0501 -14.29802 4.843782 853.0501 -13.84273 6.36322 853.0501 -13.21336 7.802636 853.0501 -12.41782 9.143931 853.0501 -11.46613 10.37023 853.0501 -10.37023 11.46613 853.0501 -9.143931 12.41782 853.0501 -7.802636 13.21336 853.0501 -6.36322 13.84273 853.0501 -4.843782 14.29802 853.0501 -3.263431 87 882.5017 -2.656713 87 876.25 0 87 876.3579 -2.962667 87 882.4942 2.555263 87 876.3556 2.941395 87 876.6737 -5.888951 87 883.2821 -7.806154 87 877.1993 -8.784898 87 877.9334 -11.64655 87 884.8183 -12.78341 87 878.8644 -14.43332 87 879.9959 -17.15091 87 887.0791 -17.48244 87 881.3097 -19.76913 87 890.018 -21.79955 87 882.799 -22.27482 87 884.4636 -24.66879 87 893.5777 -25.6398 87 886.3017 -26.94602 87 897.6411 -28.8901 87 888.31 -29.10347 87 890.4558 -31.10175 87 902.1492 -31.50128 87 892.7446 -32.94503 87 907.0262 -33.42635 87 895.1503 -34.61606 87 914.7573 -34.89903 87 897.6704 -36.1111 87 909.5718 -34.11265 87 912.1499 -34.60385 87 937.06 -36.14891 87 900.2899 -37.42399 87 939.6003 -34.6478 87 917.4 -35 87 934.4202 -37.46491 87 902.9897 -38.54377 87 931.7018 -38.58416 87 905.7703 -39.47208 87 928.9041 -39.50868 87 908.5998 -40.19765 87 926.0612 -40.22796 87 911.4847 -40.72205 87 923.1663 -40.74331 87 914.3922 -41.03981 87 920.2527 -41.05097 87 917.3215 -41.14924 87 922.618 -34.60894 87 942.0249 -32.9677 87 932.6004 -31.52566 87 944.3311 -31.1129 87 927.7251 -33.44159 87 946.4913 -29.10226 87 937.1191 -28.91718 87 948.5109 -26.93124 87 950.3569 -24.64163 87 941.2013 -25.65904 87 950.3569 -24.64163 39.06637 962.8107 -29.20958 87 952.0256 -22.23638 87 943.069 -23.79108 87 952.0256 -22.23638 39.65026 964.1392 -26.71894 87 953.5162 -19.72166 87 944.7825 -21.79878 87 953.5162 -19.72166 40.43379 965.9984 -22.67359 87 954.8287 -17.09739 87 947.7385 -17.45213 87 954.8287 -17.09739 40.59867 966.4183 -21.64164 87 955.9565 -14.37693 87 955.9565 -14.37693 41.20526 968.2026 -16.51845 87 956.8829 -11.59188 87 950.0059 -12.72118 87 956.8829 -11.59188 42.80348 969.1866 -11.24027 87 957.6112 -8.736272 87 957.6112 -8.736272 87 958.132 -5.851431 87 951.5377 -7.718456 87 958.132 -5.851431 43.78722 969.8113 -5.778301 87 958.4445 -2.941395 87 958.4445 -2.941395 44.13534 970.0355 0 87 958.55 0 87 952.3059 -2.555263 87 958.55 0 43.97042 969.9291 3.981252 87 958.55 0 44.13534 970.0355 0 87 958.4421 2.962667 87 952.2984 2.656713 87 958.4421 2.962667 41.06209 991.9 -0.258373 44.13534 970.0355 0 43.78722 969.8113 -5.778301 40.97778 991.9 2.65007 43.97042 969.9291 3.981252 40.60614 991.9 -6.098397 42.80348 969.1866 -11.24027 40.93793 991.9 -3.175976 39.3263 991.9 -11.81151 41.20526 968.2026 -16.51845 40.06954 991.9 -8.974722 38.63683 969.0092 -21.63046 41.20526 968.2026 -16.51845 40.59867 966.4183 -21.64164 38.38709 991.9 -14.57941 37.25172 991.9 -17.27391 38.63683 969.0092 -21.63046 40.43379 965.9984 -22.67359 37.12499 966.4744 -27.86741 39.65026 964.1392 -26.71894 35.32812 969.9661 -26.47102 39.06637 962.8107 -29.20958 33.18815 966.9323 -32.59121 45.40438 968.3001 12 42.61396 969.068 12 40.62145 965.5022 12 87 957.6007 8.784898 45.40438 968.3001 12 48.19501 967.5316 12 48.19501 967.5316 12 72.91872 960.6907 12 46.08581 966.9664 16.09131 48.19501 967.5316 12 40.62145 965.5022 23.59409 40.62145 965.5022 12 46.08581 966.9664 16.09131 42.61396 969.068 12 43.46034 969.6022 8.031613 40.1878 991.9 8.424599 42.61396 969.068 12 43.46034 969.6022 8.031613 42.39053 970.598 12 42.16701 972.128 12 39.48369 991.9 11.2765 42.39053 970.598 12 87 958.1263 5.888951 40.68656 991.9 5.544225 87 958.1263 5.888951 87 951.5179 7.806154 87 957.6007 8.784898 78.69912 959.0812 12 87 956.8666 11.64655 87 956.8666 11.64655 75.80873 959.8865 12 78.34936 957.7759 16.10123 87 955.9356 14.43332 87 949.9818 12.78341 87 955.9356 14.43332 87 954.8042 17.15091 87 954.8042 17.15091 77.89778 956.0905 20.07578 87 953.4903 19.76913 87 947.721 17.48244 87 953.4903 19.76913 76.79188 954.4609 23.50334 87 952.001 22.27482 87 944.7821 21.79955 87 952.001 22.27482 77.24806 954.8805 22.5923 77.62958 955.4229 21.45973 74.77876 953.8752 25.35962 87 950.3364 24.66879 75.26214 953.8785 25.12731 75.7737 953.9685 24.75247 76.29214 954.1596 24.21613 87 941.2223 25.6398 87 948.4984 26.94602 74.32845 953.9431 25.47337 87 937.1589 28.8901 87 946.4901 29.10347 87 944.3442 31.10175 87 932.6508 31.50128 87 942.0554 32.94503 87 927.7739 33.42635 87 939.6497 34.61606 87 920.0427 34.89903 87 937.1297 36.1111 87 925.2282 34.11265 87 922.6502 34.60385 87 897.7401 36.14891 87 934.5101 37.42399 87 895.1998 34.6478 87 917.4 35 87 900.3798 37.46491 87 931.8104 38.54377 87 903.0982 38.58416 87 929.0297 39.47208 87 905.8959 39.50868 87 926.2002 40.19765 87 908.7388 40.22796 87 923.3153 40.72205 87 911.6337 40.74331 87 920.4078 41.03981 87 914.5473 41.05097 87 917.4786 41.14924 87 912.182 34.60894 87 892.7752 32.9677 87 902.1997 31.52566 87 890.4689 31.1129 87 907.0749 33.44159 87 888.3088 29.10226 87 897.6809 28.91718 87 886.2891 26.93124 87 893.5987 25.65904 87 884.4432 24.64163 76.17849 880.6918 24.34911 87 882.7744 22.23638 87 891.731 23.79108 87 882.7744 22.23638 75.6296 880.8662 24.87218 75.09415 880.9315 25.22103 74.59309 880.9053 25.4188 77.61096 879.4105 21.52891 87 881.2838 19.72166 87 890.0175 21.79878 87 881.2838 19.72166 77.20108 879.9714 22.7026 76.71192 880.3966 23.63356 77.89778 878.7095 20.07578 87 879.9713 17.09739 87 887.0616 17.45213 87 879.9713 17.09739 78.34936 877.0242 16.10123 87 878.8435 14.37693 87 878.8435 14.37693 78.69912 875.7188 12 87 877.9171 11.59188 87 884.7941 12.72118 87 877.9171 11.59188 39.78305 864.9536 12 87 877.1889 8.736272 72.91872 874.1093 12 75.80873 874.9135 12 87 883.2623 7.718456 87 876.668 5.851431 39.40809 866.353 17.31022 38.89778 868.2575 12 39.78305 864.9536 12 39.40809 866.353 17.31022 38.89778 868.2575 12 72.56317 875.4363 16.30158 38.89778 868.2575 22.47707 38.89778 868.2575 22.47707 72.10223 877.1566 20.45118 38.56658 869.0343 24.30115 38.89778 868.2575 12 38.89778 868.2575 22.47707 38.56658 869.0343 24.30115 38.03735 869.6831 25.85385 38.55442 869.054 12 38.03735 869.6831 25.85385 72.00103 877.8545 21.82633 38.00112 869.7156 12 72.43317 955.3142 24.33727 39.07763 962.8289 29.17572 39.07763 962.8289 29.17572 72.7469 954.8862 24.83962 73.11013 954.5371 25.1856 73.49979 954.2691 25.39266 73.90462 954.0741 25.48388 72.19092 955.8139 23.66468 39.26716 963.265 28.38879 33.96085 966.8505 31.7571 39.26716 963.265 28.38879 72.10223 957.6434 20.45118 40.1983 965.4209 24.0138 39.64611 965.4066 25.0559 40.1983 965.4209 24.0138 72.00254 956.9905 21.7437 72.04038 956.3765 22.80603 39.12027 965.4888 25.86855 38.63216 965.6561 26.47516 38.19573 965.8941 26.89 37.83159 966.176 27.12593 37.60157 966.4083 27.20705 72.56317 959.3637 16.30158 40.4129 965.4542 23.81777 40.16407 965.4179 12 40.1983 965.4209 24.0138 40.4129 965.4542 23.81777 39.71076 965.403 12 39.64611 965.4066 25.0559 40.62145 965.5022 23.59409 40.62145 965.5022 23.59409 43.58931 966.2975 19.87369 43.58931 966.2975 19.87369 40.62145 965.5022 12 72.10223 957.6434 12 78.69912 959.0812 12 75.80873 959.8865 12 78.34936 957.7759 16.10123 78.69912 959.0812 12 77.89778 956.0905 20.07578 77.89778 956.0905 12 72 956.867 12 77.89778 956.0905 12 72.02568 957.2586 12 72.91872 960.6907 12 72.10223 957.6434 12 72.91872 960.6907 12 72.56317 959.3637 16.30158 72.10223 957.6434 20.45118 72.10223 957.6434 12 72.10223 957.6434 20.45118 72.00254 956.9905 21.7437 72 956.867 12 72.04038 956.3765 22.80603 72.02568 957.2586 12 72.1255 956.0087 12 72.19092 955.8139 23.66468 72.43317 955.3142 24.33727 72.48872 955.2265 12 72.7469 954.8862 24.83962 73.05747 954.5816 12 73.11013 954.5371 25.1856 73.49979 954.2691 25.39266 73.78386 954.1253 12 73.90462 954.0741 25.48388 74.32845 953.9431 25.47337 74.60861 953.8934 12 74.77876 953.8752 25.35962 75.26214 953.8785 25.12731 75.46528 953.904 12 75.7737 953.9685 24.75247 76.28497 954.1567 12 76.29214 954.1596 24.21613 76.79188 954.4609 23.50334 77.00121 954.6325 12 77.24806 954.8805 22.5923 77.55447 955.2941 12 77.62958 955.4229 21.45973 77.89778 956.0905 20.07578 77.89778 956.0905 12 77.89778 878.7095 12 78.69912 875.7188 12 78.34936 877.0242 16.10123 75.80873 874.9135 12 78.69912 875.7188 12 72.10223 877.1566 12 72.91872 874.1093 12 77.89778 878.7095 12 77.89778 878.7095 20.07578 77.89778 878.7095 12 77.89778 878.7095 20.07578 77.61096 879.4105 21.52891 77.55443 879.506 12 77.20108 879.9714 22.7026 77.00112 880.1676 12 76.71192 880.3966 23.63356 76.28482 880.6434 12 76.17849 880.6918 24.34911 75.6296 880.8662 24.87218 75.4651 880.8961 12 75.09415 880.9315 25.22103 74.60842 880.9066 12 74.59309 880.9053 25.4188 74.12786 880.8034 25.49057 73.78369 880.6746 12 73.6902 880.632 25.44933 73.2704 880.3842 25.28748 73.05735 880.2183 12 72.8708 880.0464 24.97885 72.51555 879.6145 24.49606 72.48865 879.5734 12 72.23542 879.098 23.82264 72.12548 878.7912 12 72.0554 878.5068 22.93998 72 877.933 12 72.00103 877.8545 21.82633 72.02568 877.5415 12 72.10223 877.1566 20.45118 72.91872 874.1093 12 72.10223 877.1566 20.45118 72.56317 875.4363 16.30158 72.10223 877.1566 12 72.10223 877.1566 12 39.06854 971.2978 12 40.16407 965.4179 12 39.71076 965.403 12 39.25651 965.4589 12 39.25651 965.4589 12 38.81638 965.5819 12 39.12027 965.4888 25.86855 38.81638 965.5819 12 38.34349 970.9972 12 38.40104 965.771 12 38.63216 965.6561 26.47516 38.40104 965.771 12 38.0188 966.0199 12 38.19573 965.8941 26.89 38.0188 966.0199 12 37.72311 970.5208 12 37.67942 966.3247 12 37.83159 966.176 27.12593 37.67942 966.3247 12 37.24739 969.9008 12 37.38921 966.677 12 37.60157 966.4083 27.20705 37.38921 966.677 12 37.15645 967.0703 12 37.27371 966.8546 27.18171 37.15645 967.0703 12 37.53168 966.4899 27.21825 36.9477 969.1782 12 36.9849 967.4946 12 37.05631 967.294 26.98994 36.9849 967.4946 12 36.8819 967.9364 12 36.90527 967.8017 26.60538 36.8819 967.9364 12 36.845 968.4 12 36.84543 968.3491 26.01167 36.845 968.4 12 36.88938 968.9141 25.19555 36.9477 969.1782 12 37.04524 969.4777 24.13514 37.24739 969.9008 12 37.34121 970.0526 23.52346 37.72311 970.5208 12 37.77733 970.5737 22.67448 38.34349 970.9972 12 38.35449 971.0036 21.56083 39.06854 971.2978 12 40.81229 971.765 16.15338 39.06854 971.2978 12 42.16701 972.128 12 39.06854 971.2978 20.1482 39.06854 971.2978 20.1482 42.16701 972.128 12 38.57771 991.9 14.06498 40.81229 971.765 16.15338 34.69087 991.9 21.96774 37.04524 969.4777 24.13514 37.34121 970.0526 23.52346 36.29096 969.6942 25.20181 36.88938 968.9141 25.19555 37.04524 969.4777 24.13514 33.0201 991.9 24.40905 36.29096 969.6942 25.20181 37.77733 970.5737 22.67448 38.35449 971.0036 21.56083 36.17323 991.9 19.43227 39.06854 971.2978 20.1482 37.46931 991.9 16.79673 37.53168 966.4899 27.21825 37.27371 966.8546 27.18171 31.49897 970.9649 30.72834 37.05631 967.294 26.98994 35.50472 969.9151 26.24573 36.90527 967.8017 26.60538 36.84543 968.3491 26.01167 29.80633 967.2426 35.82531 26.93832 971.9911 34.61316 25.23004 967.537 39.3393 21.95622 972.9058 37.82074 20.32981 967.6899 42.25598 13.9872 973.9084 41.28605 15.20743 967.6693 44.55268 16.69553 973.632 40.30915 8.322786 974.2595 42.73888 9.961332 967.4597 46.22696 11.18933 974.117 42.10017 2.550839 974.3063 43.46033 4.680271 967.0615 47.29352 5.437526 974.3227 43.19189 -0.346035 974.21 43.54728 -0.560375 966.4893 47.77937 -6.14689 973.7741 43.17455 -5.699526 965.7671 47.71856 -3.248987 974.0318 43.45241 -11.92163 973.0198 42.05897 -10.6891 964.9245 47.14784 -9.04347 973.4364 42.71045 -14.70831 972.5491 41.23756 -15.49154 963.9923 46.10362 -19.9874 971.4492 39.12716 -20.0771 963.0009 44.62049 -17.37807 972.0241 40.26586 -22.55959 970.822 37.80541 -24.42127 961.9781 42.73046 -27.4672 969.4639 34.64938 -28.50292 960.9494 40.46336 -25.05984 970.1538 36.31069 -29.77198 968.7487 32.82612 -32.3026 959.9373 37.847 -31.94721 968.0413 30.85648 -35.80223 958.9622 34.90878 -35.87351 966.6519 26.51835 -38.98368 958.0422 31.67511 -33.983 967.3439 28.75098 -38.98368 958.0422 31.67511 -35.87351 966.6519 26.51835 -34.4468 979.276 25.4637 -35.87351 966.6519 26.51835 -33.983 967.3439 28.75098 -36.85497 966.299 25.28302 -34.4468 979.276 25.4637 -36.85497 966.299 25.28302 -35.87351 966.6519 26.51835 -31.17197 991.9 26.72777 -31.94721 968.0413 30.85648 -33.0201 991.9 24.40905 -29.1757 991.9 28.89469 -29.77198 968.7487 32.82612 -27.02589 991.9 30.91426 -27.4672 969.4639 34.64938 -24.73221 991.9 32.77852 -25.05984 970.1538 36.31069 -22.3177 991.9 34.46762 -22.55959 970.822 37.80541 -19.78125 991.9 35.9834 -19.9874 971.4492 39.12716 -17.15159 991.9 37.30857 -17.37807 972.0241 40.26586 -14.42535 991.9 38.4448 -14.70831 972.5491 41.23756 -11.63374 991.9 39.37984 -11.92163 973.0198 42.05897 -8.774662 991.9 40.11348 -9.04347 973.4364 42.71045 -5.877292 991.9 40.63964 -6.14689 973.7741 43.17455 -3.248987 974.0318 43.45241 -2.944813 991.9 40.95619 -0.346035 974.21 43.54728 1.71e-4 991.9 41.06247 2.550839 974.3063 43.46033 2.945151 991.9 40.95617 5.437526 974.3227 43.19189 5.877622 991.9 40.6396 8.322786 974.2595 42.73888 8.774976 991.9 40.11341 11.18933 974.117 42.10017 11.63403 991.9 39.37976 13.9872 973.9084 41.28605 14.42562 991.9 38.44469 16.69553 973.632 40.30915 17.15183 991.9 37.30846 21.95622 972.9058 37.82074 22.31788 991.9 34.46751 26.93832 971.9911 34.61316 19.78146 991.9 35.98328 27.02599 991.9 30.91416 31.49897 970.9649 30.72834 24.73235 991.9 32.77841 31.172 991.9 26.72773 35.50472 969.9151 26.24573 29.17577 991.9 28.89462 -38.30104 965.6892 23.64666 -38.33186 965.6748 12 -38.30104 965.6892 23.64666 -37.62747 966.0345 24.32079 -37.83117 965.9668 24.06906 -37.83117 965.9668 24.06906 -37.41783 966.3266 24.52818 -37.83117 965.9668 24.06906 -37.62747 966.0345 24.32079 -37.61779 966.1359 12 -37.41783 966.3266 24.52818 -37.10533 966.7129 24.8512 -36.71862 967.5179 25.17703 -36.61995 967.95 25.20676 -36.87744 967.1102 25.06113 -40.00352 965.4292 21.44097 -41.52141 965.6425 19.25525 -40.00352 965.4292 21.44097 -40.00352 965.4292 12 -39.16848 971.3708 12 -40.00352 965.4292 12 -39.14841 965.4321 12 -43.70859 972.0089 12 -44.37454 969.0775 12 -45.04456 966.1377 12 -44.04953 965.9978 14.5243 -45.04456 966.1377 12 -42.87273 965.8325 16.9462 -38.34454 971.1311 12 -38.33186 965.6748 12 -37.62484 970.6702 12 -37.61779 966.1359 12 -37.06489 970.026 12 -37.06174 966.7789 12 -37.10533 966.7129 24.8512 -37.06174 966.7789 12 -36.70871 969.2492 12 -36.70785 967.5537 12 -36.71862 967.5179 25.17703 -36.70785 967.5537 12 -36.87744 967.1102 25.06113 -36.586 968.4 12 -36.61995 967.95 25.20676 -36.586 968.4 12 -36.62918 968.9072 24.96719 -36.70871 969.2492 12 -36.58603 968.4136 25.14241 -37.01671 969.9488 24.19589 -37.06489 970.026 12 -36.76635 969.4245 24.65905 -37.3964 970.4508 23.56185 -37.62484 970.6702 12 -37.92157 970.8959 22.74364 -38.34454 971.1311 12 -39.16848 971.3708 20.95294 -39.16848 971.3708 12 -38.89677 971.3198 21.33886 -38.62448 971.2418 21.72152 -43.70859 972.0089 12 -39.16848 971.3708 12 -39.16848 971.3708 20.95294 -39.61511 978.324 18.02054 -39.16848 971.3708 20.95294 -38.89677 971.3198 21.33886 -42.80307 971.8816 14.37518 -40.52716 971.5618 18.86025 -41.74071 971.7323 16.6648 -40.52716 971.5618 18.86025 -38.62448 971.2418 21.72152 -38.62448 971.2418 21.72152 -37.92157 970.8959 22.74364 -37.60331 978.6867 21.14724 -37.60331 978.6867 21.14724 -37.3964 970.4508 23.56185 -37.01671 969.9488 24.19589 -36.76635 969.4245 24.65905 -36.62918 968.9072 24.96719 -36.58603 968.4136 25.14241 -44.37454 969.0775 12 -43.70859 972.0089 12 -42.80307 971.8816 14.37518 -40.7262 991.9 5.244555 -40.30683 991.9 7.84 -41.32168 977.9957 14.6882 -39.72275 991.9 10.40343 -41.74071 971.7323 16.6648 -38.06859 991.9 15.39189 -38.97531 991.9 12.92409 -37.00771 991.9 17.79149 -35.79095 991.9 20.12801 -34.47204 991.9 22.31159 -35.79095 991.9 20.12801 -33.0201 991.9 24.40905 40.97778 991.9 2.65007 -40.7262 991.9 5.244555 40.68656 991.9 5.544225 -40.30683 991.9 7.84 40.1878 991.9 8.424599 -39.72275 991.9 10.40343 39.48369 991.9 11.2765 -38.97531 991.9 12.92409 38.57771 991.9 14.06498 -38.06859 991.9 15.39189 37.46931 991.9 16.79673 -37.00771 991.9 17.79149 36.17323 991.9 19.43227 -35.79095 991.9 20.12801 34.69087 991.9 21.96774 -34.47204 991.9 22.31159 30.90552 991.9 -27.03609 -29.21377 991.9 -28.85643 -31.92681 968.05 -30.87584 -29.21377 991.9 -28.85643 28.90163 991.9 -29.16811 -27.08464 991.9 -30.86237 -29.72438 968.7633 -32.86647 -27.08464 991.9 -30.86237 26.75707 991.9 -31.14769 -24.8064 991.9 -32.72183 -27.37714 969.4906 -34.71581 -24.8064 991.9 -32.72183 24.47146 991.9 -32.97302 -22.41103 991.9 -34.40716 -24.90498 970.1979 -36.40958 -22.41103 991.9 -34.40716 22.06106 991.9 -34.63287 -19.89231 991.9 -35.92117 -22.30995 970.8833 -37.94326 -19.89231 991.9 -35.92117 19.54064 991.9 -36.11423 -17.28246 991.9 -37.24848 -19.62304 971.5346 -39.29775 -17.28246 991.9 -37.24848 16.91199 991.9 -37.41786 -14.59464 991.9 -38.38217 -16.90075 972.1209 -40.4538 -14.59464 991.9 -38.38217 14.2041 991.9 -38.52701 -11.82884 991.9 -39.32237 -14.14937 972.65 -41.41769 -11.82884 991.9 -39.32237 11.41075 991.9 -39.44465 -8.989476 991.9 -40.06464 -11.32973 973.1133 -42.20866 -8.989476 991.9 -40.06464 8.565549 991.9 -40.15898 -6.081171 991.9 -40.60873 -8.424906 973.5129 -42.8258 -6.081171 991.9 -40.60873 5.66666 991.9 -40.66884 -3.155215 991.9 -40.9408 -5.48893 973.84 -43.25378 -3.155215 991.9 -40.9408 2.737826 991.9 -40.97111 -0.2043319 991.9 -41.06113 -2.575804 974.0803 -43.49068 -0.2043319 991.9 -41.06113 0.316042 974.2382 -43.54356 2.737826 991.9 -40.97111 3.183427 974.3176 -43.41699 5.66666 991.9 -40.66884 6.011004 974.3167 -43.11668 8.565549 991.9 -40.15898 11.56782 974.0953 -42.0009 11.41075 991.9 -39.44465 8.804798 974.2412 -42.64482 14.2041 991.9 -38.52701 16.97285 973.6011 -40.19788 16.91199 991.9 -37.41786 19.54064 991.9 -36.11423 22.19472 972.866 -37.68777 22.06106 991.9 -34.63287 24.47146 991.9 -32.97302 27.01438 971.9717 -34.5573 26.75707 991.9 -31.14769 28.90163 991.9 -29.16811 31.41175 970.9822 -30.81403 30.90552 991.9 -27.03609 32.74561 991.9 -24.77552 35.32812 969.9661 -26.47102 34.42625 991.9 -22.38125 35.92845 991.9 -19.88127 -33.0201 991.9 24.40905 33.0201 991.9 24.40905 -31.17197 991.9 26.72777 31.172 991.9 26.72773 -29.1757 991.9 28.89469 29.17577 991.9 28.89462 -27.02589 991.9 30.91426 27.02599 991.9 30.91416 24.73235 991.9 32.77841 -24.73221 991.9 32.77852 22.31788 991.9 34.46751 -22.3177 991.9 34.46762 19.78146 991.9 35.98328 -19.78125 991.9 35.9834 17.15183 991.9 37.30846 -17.15159 991.9 37.30857 14.42562 991.9 38.44469 -14.42535 991.9 38.4448 11.63403 991.9 39.37976 -8.774662 991.9 40.11348 8.774976 991.9 40.11341 -11.63374 991.9 39.37984 -5.877292 991.9 40.63964 5.877622 991.9 40.6396 -2.944813 991.9 40.95619 2.945151 991.9 40.95617 1.71e-4 991.9 41.06247 -31.92681 968.05 -30.87584 -31.90884 960.0444 -38.14375 -29.72438 968.7633 -32.86647 -27.37714 969.4906 -34.71581 -27.86432 961.1144 -40.85266 -24.90498 970.1979 -36.40958 -23.51016 962.1989 -43.16897 -22.30995 970.8833 -37.94326 -19.62304 971.5346 -39.29775 -18.86938 963.2711 -45.05971 -16.90075 972.1209 -40.4538 -13.96751 964.3004 -46.48941 -14.14937 972.65 -41.41769 -11.32973 973.1133 -42.20866 -8.834792 965.2532 -47.4197 -8.424906 973.5129 -42.8258 -3.508899 966.0937 -47.80931 -5.48893 973.84 -43.25378 -2.575804 974.0803 -43.49068 1.961654 966.786 -47.61517 0.316042 974.2382 -43.54356 3.183427 974.3176 -43.41699 7.51393 967.298 -46.79527 6.011004 974.3167 -43.11668 8.804798 974.2412 -42.64482 13.06797 967.6066 -45.31334 11.56782 974.0953 -42.0009 18.52649 967.7036 -43.14523 16.97285 973.6011 -40.19788 23.77808 967.5999 -40.28555 22.19472 972.866 -37.68777 28.70412 967.3267 -36.75288 27.01438 971.9717 -34.5573 31.41175 970.9822 -30.81403 113.5 917.4 35 87 917.4 35 87 912.182 34.60894 113.5 922.618 34.60894 87 920.0427 34.89903 87 917.4 35 113.5 917.4 35 113.5 912.1499 34.60385 87 907.0749 33.44159 113.5 914.7573 34.89903 113.5 907.0262 33.42635 87 902.1997 31.52566 113.5 909.5718 34.11265 113.5 902.1492 31.50128 87 897.6809 28.91718 113.5 897.6411 28.8901 87 893.5987 25.65904 113.5 893.5777 25.6398 87 891.731 23.79108 113.5 890.018 21.79955 87 890.0175 21.79878 113.5 887.0791 17.48244 87 887.0616 17.45213 113.5 884.8183 12.78341 87 884.7941 12.72118 113.5 883.2821 7.806154 87 883.2623 7.718456 113.5 882.5017 2.656713 87 882.4942 2.555263 113.5 882.4942 -2.555263 87 882.5017 -2.656713 113.5 883.2623 -7.718456 87 883.2821 -7.806154 113.5 884.7941 -12.72118 87 884.8183 -12.78341 113.5 887.0616 -17.45213 87 887.0791 -17.48244 113.5 890.0175 -21.79878 87 890.018 -21.79955 113.5 891.731 -23.79108 87 893.5777 -25.6398 113.5 893.5987 -25.65904 87 897.6411 -28.8901 113.5 897.6809 -28.91718 87 902.1492 -31.50128 113.5 902.1997 -31.52566 87 907.0262 -33.42635 113.5 907.0749 -33.44159 87 909.5718 -34.11265 87 912.1499 -34.60385 113.5 912.182 -34.60894 87 914.7573 -34.89903 87 917.4 -35 113.5 917.4 -35 87 917.4 -35 87 922.618 -34.60894 113.5 917.4 -35 113.5 922.6502 -34.60385 87 927.7251 -33.44159 113.5 920.0427 -34.89903 113.5 927.7739 -33.42635 87 932.6004 -31.52566 113.5 925.2282 -34.11265 113.5 932.6508 -31.50128 87 937.1191 -28.91718 113.5 937.1589 -28.8901 87 941.2013 -25.65904 113.5 941.2223 -25.6398 87 943.069 -23.79108 113.5 944.7821 -21.79955 87 944.7825 -21.79878 113.5 947.721 -17.48244 87 947.7385 -17.45213 113.5 949.9818 -12.78341 87 950.0059 -12.72118 113.5 951.5179 -7.806154 87 951.5377 -7.718456 113.5 952.2984 -2.656713 87 952.3059 -2.555263 113.5 952.3059 2.555263 87 952.2984 2.656713 113.5 951.5377 7.718456 87 951.5179 7.806154 113.5 950.0059 12.72118 87 949.9818 12.78341 113.5 947.7385 17.45213 87 947.721 17.48244 113.5 944.7825 21.79878 87 944.7821 21.79955 113.5 943.069 23.79108 87 941.2223 25.6398 113.5 941.2013 25.65904 87 937.1589 28.8901 113.5 937.1191 28.91718 87 932.6508 31.50128 113.5 932.6004 31.52566 87 927.7739 33.42635 113.5 927.7251 33.44159 87 925.2282 34.11265 87 922.6502 34.60385 113.5 922.618 34.60894 113.5 917.4 35 113.5 914.7573 34.89903 113.5 912.1499 34.60385 113.5 909.5718 34.11265 113.5 927.7251 33.44159 113.5 907.0262 33.42635 113.5 932.6004 31.52566 113.5 902.1492 31.50128 113.5 937.1191 28.91718 113.5 897.6411 28.8901 113.5 941.2013 25.65904 113.5 893.5777 25.6398 113.5 943.069 23.79108 113.5 890.018 21.79955 113.5 944.7825 21.79878 113.5 887.0791 17.48244 113.5 947.7385 17.45213 113.5 884.8183 12.78341 113.5 950.0059 12.72118 113.5 883.2821 7.806154 113.5 951.5377 7.718456 113.5 882.5017 2.656713 113.5 952.3059 2.555263 113.5 882.4942 -2.555263 113.5 952.2984 -2.656713 113.5 883.2623 -7.718456 113.5 951.5179 -7.806154 113.5 884.7941 -12.72118 113.5 949.9818 -12.78341 113.5 887.0616 -17.45213 113.5 947.721 -17.48244 113.5 890.0175 -21.79878 113.5 944.7821 -21.79955 113.5 891.731 -23.79108 113.5 941.2223 -25.6398 113.5 893.5987 -25.65904 113.5 937.1589 -28.8901 113.5 897.6809 -28.91718 113.5 932.6508 -31.50128 113.5 902.1997 -31.52566 113.5 927.7739 -33.42635 113.5 907.0749 -33.44159 113.5 925.2282 -34.11265 113.5 912.182 -34.60894 113.5 920.0427 -34.89903 113.5 917.4 -35 113.5 922.6502 -34.60385 33.02567 867.0894 12 33 867.481 12 33.12548 868.3392 12 38.55442 869.054 12 33.48864 869.1214 12 38.00112 869.7156 12 34.05735 869.7664 12 37.28482 870.1914 12 34.78369 870.2227 12 36.46509 870.444 12 35.60842 870.4546 12 72.1255 956.0087 12 77.55447 955.2941 12 72.48872 955.2265 12 77.00121 954.6325 12 73.05747 954.5816 12 76.28497 954.1567 12 73.78386 954.1253 12 75.46528 953.904 12 74.60861 953.8934 12 72.02568 877.5415 12 72 877.933 12 72.12548 878.7912 12 77.55443 879.506 12 72.48865 879.5734 12 77.00112 880.1676 12 73.05735 880.2183 12 76.28482 880.6434 12 73.78369 880.6746 12 75.4651 880.8961 12 74.60842 880.9066 12 -58.06927 900.3947 12 -57.25935 900.3318 12 -56.49795 900.0552 12 -56.0924 895.0005 12 -55.83901 899.5857 12 -56.4806 894.7546 12 -55.44979 895.6591 12 -55.32887 898.9564 12 -55.74558 895.3057 12 -55.03704 896.4816 12 -55.00498 898.2113 12 -55.21226 896.0541 12 -54.93143 896.9288 12 -54.893 897.4 12 -33.9968 870.0785 12 -37.84226 870.2136 12 -34.68685 870.5426 12 -37.11742 870.6298 12 -35.47725 870.7994 12 -36.30836 870.8296 12 2.874678 857.0078 12 -2.875674 857.0042 12 -2.516978 857.7816 12 2.510289 857.7917 12 -1.961929 858.4193 12 1.946467 858.4323 12 -1.251954 858.8759 12 1.230266 858.8858 12 -0.437745 859.117 12 0.413992 859.1205 12 2.340802 926.6358 48.7 0 926.9 48.7 -2.35033 926.6336 48.7 4.55936 925.8585 48.7 -4.583739 925.8466 48.7 6.546148 924.6096 48.7 -6.581006 924.5817 48.7 8.194878 922.9645 48.7 -8.230257 922.9202 48.7 9.447655 920.9816 48.7 -9.472749 920.9295 48.7 10.23089 918.7619 48.7 -10.24256 918.7107 48.7 10.49994 916.4249 48.7 -10.49994 916.3751 48.7 10.24256 914.0894 48.7 -10.23089 914.0382 48.7 9.472749 911.8705 48.7 -9.447655 911.8184 48.7 8.230257 909.8798 48.7 -8.194878 909.8355 48.7 6.581006 908.2183 48.7 -6.546148 908.1904 48.7 - - - - - - - - - - -0.9495562 0.220768 0.2227204 -0.9219927 0.2704532 0.2771006 -0.9432824 0.2777786 0.1818174 0.3265271 0.9451879 8.6245e-6 0.3265313 0.9451864 1.08437e-5 0.3265143 0.9451923 1.9721e-6 -0.9688675 0.2207496 0.1120958 -0.9501317 0.2981482 0.09141945 -0.939753 0.2894846 0.1818323 0 0 1 -0.9176561 0.2208017 0.3303846 -0.8920102 0.2600632 0.3697093 0.3265106 0.9451935 0 -0.8736072 0.2207638 0.4336748 -0.8816531 0.2578144 0.3952463 0.3265468 0.945181 5.54474e-6 0.326529 0.9451872 -4.06057e-6 0.09881579 0.9951058 1.6354e-6 -0.871958 0.2578913 0.4161506 0.05946958 0.9982301 1.71316e-5 -0.1145178 0.9934212 -2.57231e-6 -0.8631189 0.2597908 0.4330527 -0.2108436 0.9775199 -2.66747e-5 -0.3090484 0.9510463 3.83705e-7 -0.8179647 0.2207679 0.5312205 -0.8552578 0.2631921 0.4463901 -0.4650145 0.885303 2.17105e-5 -0.4820525 0.8761423 -1.71922e-6 -0.8484326 0.2678231 0.4565449 -0.6321207 0.7748699 -1.70432e-6 -0.8427505 0.2733606 0.4637302 -0.6849763 0.7285653 -3.57839e-5 -0.7572231 0.6531563 1.30944e-6 -0.8383286 0.2794311 0.4681062 -0.8545264 0.5194082 6.90576e-7 -0.8351585 0.2856447 0.4700187 -0.8550952 0.5184711 2.68948e-5 -0.9240216 0.3823406 -1.0652e-6 -0.833064 0.2920654 0.4697898 -0.9629376 0.2697244 5.19217e-5 -0.9704481 0.2413098 3.01981e-7 -0.8074049 0.3285163 0.4900762 -0.8319028 0.2989984 0.4674802 -0.9960677 0.08859634 6.06291e-7 -0.8318439 0.3066685 0.4625908 -1 -8.36604e-6 -1.32562e-6 -0.9968162 -0.07973533 -2.73809e-7 -0.8332081 0.3145795 0.4547573 -0.9878597 -0.1553485 1.44753e-5 -0.9671517 -0.2542001 -2.00793e-6 -0.8360397 0.3224189 0.4439411 -0.9520583 -0.3059167 1.35667e-4 -0.9045794 -0.4263052 1.53668e-6 -0.7304491 0.5406853 0.4172574 -0.7586318 0.5340774 0.3731477 -0.7338224 0.5405681 0.4114498 -0.8936485 -0.4487677 -1.24319e-5 -0.8030444 -0.5959194 -3.28384e-6 -0.7586362 0.533374 0.3741435 -0.7667465 0.531914 0.3593987 -0.7480809 0.3284786 0.5766081 -0.7756435 0.3352659 0.5347654 -0.698704 0.5488461 0.4588909 -0.7066811 0.5475046 0.4481523 -0.7514927 0.220751 0.6217136 -0.6795122 0.3285162 0.6560033 -0.7323107 0.3444555 0.5874279 -0.6750534 0.2207865 0.7039576 -0.6025787 0.3284844 0.7273218 -0.6473343 0.3625195 0.670476 -0.6850411 0.354511 0.6364281 -0.5896676 0.2207941 0.7768797 -0.5182068 0.3284846 0.789658 -0.5664176 0.3797129 0.7314296 -0.6077476 0.3709295 0.7021782 -0.4964585 0.2207252 0.8395293 -0.4274386 0.3284776 0.8422582 -0.479156 0.3982447 0.7821833 -0.523507 0.3888441 0.7581166 -0.3966855 0.2208148 0.8910003 -0.3313854 0.3284909 0.8844645 -0.3867765 0.4178791 0.822059 -0.4335316 0.4079844 0.8034919 -0.2916317 0.220731 0.9307141 -0.2312772 0.3284747 0.9157595 -0.2208526 0.4320882 0.8743707 -0.3390771 0.4280278 0.8377464 -0.3202652 0.4320827 0.843051 -0.182716 0.2206868 0.9580774 -0.1282967 0.3285077 0.9357472 -0.07141047 0.2207954 0.9727025 -0.02374941 0.3286057 0.9441686 -0.1184837 0.4320904 0.8940132 0.0408737 0.2208245 0.9744567 0.08111971 0.3284988 0.9410144 -0.01453751 0.4321002 0.9017085 0.1524618 0.2211509 0.9632486 0.1849594 0.3285529 0.9261983 0.08960723 0.4320864 0.8973696 0.2622245 0.220808 0.9394053 0.286531 0.3285293 0.8999825 0.1925569 0.4320784 0.8810393 0.3685594 0.2207422 0.9030154 0.3846768 0.3281927 0.862736 0.2929493 0.4320198 0.8529593 0.4698172 0.2207278 0.8547228 0.4778465 0.3285012 0.8147084 0.3893924 0.4320769 0.813439 0.5644477 0.2956604 0.7707034 0.5652564 0.3285046 0.7566836 0.480615 0.4320932 0.7630891 0.5650259 0.2207814 0.7949852 0.2591238 0.4016193 0.8783831 0.2588849 0.3846183 0.886029 0.2588188 0.345943 0.9018516 0.5644804 0.3866093 0.7293115 0.2588201 0.4524024 0.8534309 0.2588638 0.3382853 0.904739 0.2588738 0.2584511 0.9306919 0.5644979 0.2001988 0.8007887 0.2587735 0.2734761 0.9264163 0.2588195 0.2342485 0.9370913 0.3887405 0.1102981 0.9147214 0.5647315 0.1102945 0.8178713 0.4791803 0.1105659 0.8707247 0.2943584 0.1103082 0.9493078 0.1968819 0.1103081 0.9742021 0.0974192 0.1103154 0.9891108 0.03544515 0.139922 0.989528 0.06923282 0.1280607 0.989347 -0.09753417 0.1102989 0.9891013 -3.58559e-6 0.1439404 0.9895864 -0.03530037 0.1399582 0.9895281 -0.06887811 0.1282547 0.9893466 -0.2086839 0.1102815 0.9717454 -0.3171977 0.1102923 0.9419243 -0.4216499 0.1103908 0.9000141 -0.520668 0.1103764 0.8465943 -0.6130105 0.1102908 0.7823389 -0.6975098 0.110328 0.708031 -0.7730659 0.1104344 0.6246386 -0.8387151 0.1103601 0.5332707 -0.893618 0.1102985 0.4350647 -0.9370598 0.1104413 0.3312427 -0.968506 0.1102544 0.223249 -0.9548281 0.2971589 -3.06219e-6 -0.975323 0.2207832 2.24039e-5 -0.9875323 0.1102957 0.1123157 -0.9496544 0.298277 -0.09585088 -0.975324 0.220779 2.05226e-5 -0.954832 0.2971462 -1.19205e-5 -0.9817069 0.1903988 -9.53674e-6 -0.9688587 0.22078 -0.1121123 -0.9817074 0.1903962 -6.92904e-7 -0.8629323 0.5053197 -1.08164e-5 -0.862933 0.5053185 -5.48381e-6 -0.8588203 0.5063906 0.07743597 -0.8611707 0.5059608 -0.04887419 -0.8629317 0.5053209 -6.01634e-6 -0.8629328 0.5053188 -1.64169e-5 -0.8583728 0.5065545 -0.0812329 -0.9360839 0.3011447 0.1818208 -0.8564817 0.5070798 0.09648466 -0.8462511 0.5100923 0.1538348 -0.8613677 0.5057147 0.04794162 -0.8484491 0.5093981 0.1436934 -0.8452318 0.5103718 0.158442 -0.6834444 0.5500845 0.479907 -0.706669 0.5475069 0.4481686 -0.67135 0.5528474 0.4936082 -0.6962986 0.5495819 0.461658 -0.7036405 0.5481427 0.4521392 -0.7036716 0.5481359 0.4520987 -0.6607872 0.5467203 0.5142542 -0.6347849 0.5527154 0.5399573 -0.6607884 0.546719 0.514254 -0.6347713 0.5527195 0.5399691 -0.6056596 0.5506933 0.5743809 -0.6128407 0.5419063 0.5751208 -0.5742642 0.548654 0.6076179 -0.5408124 0.5464178 0.6394916 -0.5579115 0.5368813 0.6328454 -0.5051883 0.544142 0.6698467 -0.4674666 0.541808 0.6985121 -0.4957332 0.5317846 0.686625 -0.427718 0.5394111 0.7253227 -0.3860123 0.5368921 0.7501611 -0.426566 0.5264854 0.7354283 -0.3424389 0.534334 0.772802 -0.3250493 0.533297 0.7809849 -0.2414615 0.4487769 0.8604045 -0.3504094 0.5212009 0.7781793 -0.2501032 0.5289501 0.8109626 -0.1918876 0.4593375 0.8672878 -0.092076 0.4805678 0.8721104 -0.1420285 0.4699071 0.8712149 0.007515907 0.5016878 0.8650162 -0.04215902 0.4911254 0.8700681 0.1062411 0.5227526 0.8458384 0.05677253 0.5121787 0.8570006 0.234667 0.5302495 0.814719 0.1417932 0.5302476 0.8359021 0.3245785 0.5302548 0.7832489 0.410389 0.5302692 0.7418864 0.5654982 0.4320853 0.7025056 0.4910296 0.5302588 0.6911697 0.2589131 0.4630957 0.8476477 0.2588126 0.5059472 0.8228206 0.5645 0.4717296 0.6773557 0.2593727 0.5221738 0.8124409 0.2588189 0.5520294 0.7926388 -0.2676975 0.5160288 0.8136661 -0.2016173 0.5261827 0.826125 -0.1518244 0.5233535 0.8384811 -0.1790007 0.5110428 0.8407104 -0.1008414 0.5205069 0.8478819 -0.04894191 0.5176694 0.8541797 -0.08518809 0.5063478 0.8581113 0.003673076 0.5148749 0.8572575 0.01260459 0.5022963 0.8646038 0.05695414 0.512236 0.8569543 0.1109406 0.5096101 0.8532232 0.150276 0.5078645 0.848228 0.1549834 0.5330776 0.8317502 0.1127794 0.4990893 0.8591803 0.1649995 0.5072461 0.8458586 0.2494158 0.5531257 0.7948861 0.20276 0.543214 0.8147435 0.3387347 0.5721235 0.7469495 0.2947925 0.5627667 0.7722637 0.4217714 0.589739 0.6887066 0.3811137 0.5811137 0.7190684 0.5654754 0.5302537 0.6317188 0.497359 0.6058015 0.6209981 0.4605343 0.5980277 0.6559506 0.2588447 0.5787839 0.7733103 0.2588191 0.620924 0.7399096 0.5320541 0.613158 0.5839142 0.5646027 0.549854 0.615536 0.2587721 0.6324237 0.7301214 0.2588176 0.6435198 0.7203442 0.2186825 0.5052356 0.8348144 0.2135955 0.4971886 0.8409402 0.2715724 0.5036633 0.8201048 0.3233835 0.5026016 0.8017573 0.3126414 0.4969081 0.8095294 0.3738261 0.5022056 0.7797715 0.4224656 0.5026136 0.7542563 0.4074292 0.4988584 0.7649457 0.4690648 0.5039247 0.7252849 0.4953488 0.5036565 0.7077851 0.513219 0.5063275 0.6929928 0.5546125 0.5099101 0.6575688 0.5738915 0.5117962 0.639307 0.5929602 0.5148261 0.6191546 0.5645015 0.6201002 0.5448062 0.6279612 0.5211536 0.5779825 0.2588495 0.6829236 0.6830904 0.258818 0.7256363 0.6375463 0.2588263 0.7298815 0.6326785 0.2587986 0.7731748 0.5789856 0.2588191 0.7738566 0.5780646 0.6407372 0.5240082 0.5611339 0.6633518 0.5300769 0.5281884 0.2588827 0.2061337 0.9436571 0.2588195 0.1290998 0.9572595 0.5645141 0.101794 0.8191226 0.2588798 0.1392375 0.9558213 0.2588189 0.1191218 0.9585524 0.4702364 -0.001429498 0.8825395 0.5644975 0.001255452 0.8254339 0.5645757 -0.001569271 0.8253799 0.3700547 -0.001544296 0.9290087 0.2654733 -0.001319229 0.9641174 0.09955245 0.108959 0.9890487 0.1575673 -0.001574933 0.9875071 0.1552457 0.01968562 0.9876798 0.1435549 0.05345392 0.9881978 0.1246435 0.08374905 0.9886608 -0.6234641 -0.781852 -1.01386e-5 -0.6132088 -0.7899209 6.9238e-7 -0.4352132 -0.9003274 3.48891e-6 -0.6257228 -0.7800455 1.48185e-6 -0.4341101 -0.9008599 3.76018e-5 -0.2227778 -0.9748693 -3.41255e-5 -0.2228246 -0.9748587 0 4.93228e-6 -1 4.22266e-6 1.49682e-5 -1 -5.78561e-6 1.70469e-5 -1 -1.87829e-4 0.2216944 -0.9751163 -5.66385e-5 -1.093e-5 -1 0 0.2238715 -0.9746187 1.91298e-4 0.4328971 -0.9014433 -3.14318e-6 0.4364352 -0.8997356 3.41484e-4 0.6137369 -0.7895106 -9.96515e-7 -0.09903693 0.109375 0.9890546 0.62244 -0.7826676 -2.47266e-6 -0.2637587 -0.001571476 0.9645875 -0.1240863 0.08437079 0.988678 -0.1431661 0.05420666 0.9882132 -0.1550549 0.02041894 0.9876948 -0.1575985 -0.001567125 0.987502 -0.366909 -0.001661002 0.9302554 -0.4657301 -0.001737296 0.8849252 -0.5587563 -0.001581966 0.8293305 -0.6453582 -0.001549661 0.7638786 -0.7243965 -0.001555621 0.6893819 -0.7948934 -0.001565635 0.6067473 -0.8560399 -0.001606225 0.5169073 -0.9070241 -0.001574993 0.4210761 -0.9473356 -0.001571297 0.3202389 -0.9764955 -0.001602351 0.2155321 -0.9938991 0.1102932 -1.86563e-5 -0.9940991 -0.001640141 0.1084629 -0.9938993 0.1102924 1.86153e-5 -0.9966872 0.08132988 2.68221e-6 -0.9873847 0.1103056 -0.1135967 -0.9966871 0.0813325 -5.7295e-6 0.2590067 0.07037025 0.9633088 0.2588199 0.00149101 0.9659245 0.2588916 0.001895189 0.9659046 0.2588186 -0.001826882 0.9659242 0.4841144 -0.1133707 0.8676292 0.5645074 -0.1000837 0.819338 0.2588766 -0.0669502 0.9635874 0.2589297 -0.1170825 0.9587737 0.3989819 -0.1134297 0.909916 0.3103157 -0.113475 0.9438366 0.2185181 -0.113439 0.969217 -0.9999971 -0.002402186 2.58428e-4 -0.9962972 -0.08597558 3.319e-6 -0.975735 -0.2189553 9.28063e-7 0.1591113 -0.01582312 0.9871339 -0.9999911 0.004235327 0 -0.9743626 -0.224983 3.78545e-4 -0.9022349 -0.431245 -1.77414e-5 -0.8998546 -0.4361899 3.32584e-4 -0.7832929 -0.6216529 -6.13487e-5 -0.7806906 -0.6249178 2.42361e-4 0.5648325 -0.1134298 0.8173727 0.2588194 -0.1327791 0.9567562 0.5645104 -0.2003859 0.8007332 0.2587873 -0.1354284 0.9563934 0.2588197 -0.2344931 0.9370301 0.4700734 -0.2238479 0.8537699 0.5651305 -0.2238477 0.7940527 0.3689507 -0.2238863 0.9020812 0.2625351 -0.224298 0.9384912 0.1429007 -0.0850352 0.9860774 0.1248562 -0.1134321 0.9856694 0.1529776 -0.223855 0.9625419 0.1549175 -0.05132895 0.9865931 -0.7838514 0.6209485 1.07879e-4 -0.785818 0.6184579 -7.27072e-7 -0.8983554 0.4392696 -2.10021e-6 0.1237708 -0.1150795 0.9856154 -0.7780577 0.6281929 2.34519e-6 -0.9021703 0.4313801 1.37848e-5 -0.9738299 0.2272785 -5.89155e-5 -0.9754886 0.2200503 1.2868e-4 0.2587932 -0.2032176 0.944314 0.2588193 -0.2621225 0.9296798 0.4796878 -0.3314717 0.8124198 0.5645137 -0.2975212 0.7699386 0.2588037 -0.2701452 0.9273847 0.2589037 -0.348174 0.9009683 0.3884363 -0.3315412 0.8597661 0.2925653 -0.3312695 0.8970319 0.193001 -0.3315143 0.9234982 0.06864297 -0.1586628 0.9849439 0.04129576 -0.2238555 0.9737471 0.09115129 -0.3317341 0.9389591 0.09872412 -0.1399204 0.9852289 -0.06900721 -0.1584821 0.9849475 -0.07093364 -0.2238546 0.9720379 -0.01128357 -0.3314607 0.9434016 -0.03533053 -0.1702615 0.9847654 6.60168e-6 -0.1742249 0.984706 0.03519052 -0.1702864 0.9847661 -0.1249579 -0.1134336 0.9856564 -0.182052 -0.2235189 0.9575471 -0.1140063 -0.3315551 0.9365222 -0.1242995 -0.1144304 0.9856243 -0.09924066 -0.139503 0.9852361 -0.2334933 -0.1134291 0.9657199 -0.2908431 -0.2236045 0.9302749 -0.2151993 -0.3314505 0.9186022 -0.3391421 -0.1135286 0.9338598 -0.3962249 -0.2238977 0.8904358 -0.3139805 -0.3315316 0.8896646 -0.4407138 -0.1131373 0.8904894 -0.4955545 -0.2239348 0.8392133 -0.4089541 -0.3315092 0.8502107 -0.5366711 -0.1134107 0.8361353 -0.5890671 -0.223818 0.77647 -0.4990797 -0.3315399 0.8006252 -0.6260444 -0.1134892 0.7714848 -0.6742809 -0.2241548 0.7036334 -0.5835081 -0.3317398 0.7412605 -0.7080203 -0.1130722 0.697081 -0.7508234 -0.2238752 0.6214051 -0.6608452 -0.3310248 0.6735772 -0.7806906 -0.1134952 0.6145252 -0.8172856 -0.2238364 0.5309818 -0.7299823 -0.3313602 0.5977678 -0.8440783 -0.1134166 0.5240885 -0.8729193 -0.223858 0.4334738 -0.8385468 -0.2790794 0.4679251 -0.7906644 -0.3314809 0.5147526 -0.833172 -0.2916276 0.4698701 -0.8353454 -0.285228 0.4699395 -0.8971999 -0.1131527 0.4268825 -0.9169662 -0.2238634 0.3302397 -0.8721871 -0.2578368 0.415704 -0.8430255 -0.2730036 0.4634406 -0.8487538 -0.2675671 0.4560973 -0.8555746 -0.2630177 0.4458854 -0.8634076 -0.2597053 0.4325283 -0.9388357 -0.1134291 0.3251484 -0.9488584 -0.2238457 0.2226226 -0.9220001 -0.2704291 0.2770991 -0.881775 -0.2578299 0.3949641 -0.8920133 -0.2600519 0.3697097 -0.9692159 -0.1133205 0.2185841 -0.9681528 -0.2238752 0.1120721 -0.943284 -0.2777787 0.1818083 -0.9903728 -0.138426 9.72301e-6 -0.9746231 -0.2238522 -3.33041e-6 -0.9390284 -0.3314943 0.09130853 -0.9935466 -0.113425 -8.25524e-6 -0.9874135 -0.1134565 0.1101918 -0.9294295 -0.3210895 0.1818311 -0.9257743 -0.3314667 0.1818567 -0.9870386 -0.1133649 -0.1135925 -0.9746244 -0.2238468 -1.7181e-5 -0.9903718 -0.1384332 -1.57803e-5 -0.9691532 -0.246459 1.36793e-5 -0.9681721 -0.223791 -0.1120736 -0.9691532 -0.2464593 -6.57141e-6 -0.9935463 -0.1134276 1.16192e-5 -0.9995873 -0.02872717 1.97962e-5 -0.9934753 -0.001564443 -0.1140367 -0.9995874 -0.02872568 -1.53407e-5 -0.9999988 -0.001576483 -2.10702e-5 -0.1432704 -0.08427399 0.9860891 -0.159102 -0.01510822 0.9871466 -0.1551128 -0.05059385 0.9866004 0.8998628 0.4361732 1.39718e-4 0.7860404 0.6181752 1.00862e-6 0.7813356 0.6241112 3.3332e-6 0.9006572 0.4345305 -5.78795e-7 0.780701 0.6249048 6.44583e-5 0.623575 0.7817636 5.49684e-5 0.6234937 0.7818284 0 0.4337078 0.9010537 7.10228e-6 0.2228108 0.9748618 1.70833e-5 0.2224862 0.9749358 0 0.4341564 0.9008376 2.73115e-6 -1.02744e-5 1 -1.89424e-6 -5.31226e-6 1 -1.54732e-6 -2.11075e-5 1 1.91051e-4 -0.2213979 0.9751836 -8.86598e-5 -1.47894e-5 1 0 -0.2238398 0.974626 2.65759e-4 -0.4316483 0.9020421 -9.57908e-5 -0.4364217 0.8997422 4.40697e-4 -0.6207911 0.783976 -4.24465e-4 -0.6267833 0.7791937 -2.33398e-5 0.5653599 -0.3314626 0.7553151 0.2587229 -0.3353558 0.9058693 0.258819 -0.3881506 0.8845066 0.4832127 -0.4349356 0.7598267 0.5644715 -0.3892676 0.727903 0.2588049 -0.399563 0.8794144 0.2588173 -0.4554854 0.8517903 0.3948989 -0.4349523 0.8092412 0.3015857 -0.4348565 0.8484963 0.204421 -0.4349673 0.8769354 0.1046929 -0.4349268 0.8943591 0.003637671 -0.4349128 0.9004653 -0.09746134 -0.4349281 0.8951753 -0.1973563 -0.434834 0.8786182 -0.2947317 -0.4348506 0.8509044 -0.3883656 -0.4349011 0.8124243 -0.4771028 -0.4349008 0.7636976 -0.5598 -0.4349372 0.7053039 -0.6354527 -0.4348997 0.6380143 -0.7029315 -0.4350711 0.5626726 -0.8396831 -0.3287428 0.4322736 -0.8420247 -0.3314558 0.4255956 -0.7618491 -0.4348573 0.4800888 -0.8355807 -0.321362 0.4455687 -0.8329828 -0.3136906 0.4557829 -0.8318125 -0.3059109 0.4631486 -0.8319473 -0.2984677 0.4677399 -0.8144575 0.5802232 3.717e-4 -0.7777863 0.6285289 9.03383e-7 -0.8246519 0.5656407 -2.40654e-6 -0.8454077 -0.3355797 0.4155386 -0.7157822 0.6983236 4.2578e-4 -0.698498 0.7156119 2.32831e-7 -0.8936859 0.4486933 6.69601e-6 -0.9149684 0.4035255 0 -0.9521088 0.3057594 2.87126e-4 -0.9720917 0.2346016 1.34297e-6 -0.9878618 0.1553362 6.09038e-6 -0.9979808 0.06351792 -8.2422e-7 -1 1.85067e-5 -1.63596e-6 -0.994955 -0.1003232 -4.23286e-7 -0.9680278 -0.2508431 -2.53494e-6 -0.9629344 -0.2697359 -1.18442e-5 -0.9201161 -0.3916459 -3.11644e-7 -0.8550874 -0.5184841 3.03786e-6 -0.8496759 -0.5273055 0 -0.7511329 -0.6601511 1.46218e-6 -0.6848759 -0.7286598 1.40674e-4 -0.6250813 -0.7805598 -3.18512e-7 -0.4750286 -0.8799704 -1.05053e-6 -0.4650105 -0.8853052 9.73216e-5 -0.3026989 -0.9530863 -2.86847e-7 -0.2108476 -0.977519 1.15715e-4 -0.1096688 -0.9939682 -2.69711e-6 0.0595079 -0.9982278 7.2987e-5 0.1015108 -0.9948344 0 0.3265163 -0.9451916 -3.81264e-7 0.3265148 -0.9451922 2.18754e-6 0.3265109 -0.9451935 8.87261e-6 0.3264808 -0.9452039 5.97474e-5 0.3265161 -0.9451918 0 0.3265509 -0.9451797 0 -0.8947659 -0.4349528 0.101046 -0.9135964 -0.363698 0.1818393 -0.9434661 -0.331469 -1.74418e-5 -0.9434688 -0.3314616 -2.20612e-5 -0.9361881 -0.3514996 2.00123e-5 -0.9376958 -0.331469 -0.1041871 -0.936187 -0.3515024 -1.28224e-5 0.5655012 -0.4349204 0.7007515 0.2591213 -0.4613755 0.8485216 0.2588195 -0.5093013 0.8207466 0.4892047 -0.5329234 0.690414 0.5644769 -0.474003 0.6757862 0.2593165 -0.5209733 0.8132293 0.2588179 -0.5546677 0.7907953 0.4067408 -0.5328413 0.7420526 0.3190603 -0.5326082 0.783919 0.2265673 -0.5329486 0.8152504 0.1317871 -0.5326367 0.8360206 0.03465253 -0.5328508 0.8454994 -0.06279087 -0.5329369 0.8438221 -0.1592963 -0.5329326 0.8310279 -0.2536113 -0.5328407 0.807318 -0.344734 -0.5329271 0.7727531 -0.4312109 -0.5329208 0.7280471 -0.5119534 -0.5328098 0.6738082 -0.5859733 -0.5327898 0.6105493 -0.652199 -0.533032 0.538993 -0.7098481 -0.5328442 0.4606441 -0.8108228 -0.4349511 0.3916429 -0.75805 -0.5328794 0.3760321 -0.8623221 -0.3460023 0.3697067 -0.8496868 -0.4349073 0.298141 -0.7962148 -0.5329008 0.2864593 -0.8529196 -0.3414521 0.3948907 -0.8923192 -0.3563532 0.2770898 -0.8777841 -0.4349052 0.2008795 -0.8238975 -0.5328236 0.1931112 -0.8406701 -0.5327129 0.0974214 -0.9004661 -0.4349263 -4.18723e-6 -0.9004656 -0.4349274 8.21426e-6 -0.8918773 -0.4522775 2.87592e-6 -0.8948007 -0.4348598 -0.1011382 -0.8918782 -0.4522757 1.07475e-5 -0.3265332 0.9451857 8.62498e-6 -0.326532 0.9451861 1.08448e-5 -0.3265369 0.9451845 1.97249e-6 -0.326538 0.9451842 0 -0.3265435 0.9451822 -1.27055e-6 -0.3265282 0.9451875 1.94833e-6 -0.5336409 0.8457113 -4.41447e-7 -0.6000312 0.7999767 1.83722e-4 -0.4693807 0.882996 6.83643e-6 0.5652776 -0.5329194 0.6296492 0.2589491 -0.578087 0.7737964 0.2588183 -0.6239264 0.7373798 0.5005583 -0.6242311 0.5998142 0.5645274 -0.5496705 0.6157688 0.2591986 -0.6320528 0.7302913 0.2588182 -0.6432453 0.7205892 0.4293242 -0.6241421 0.6527845 0.3527908 -0.6240009 0.6972529 0.2719277 -0.6242401 0.7323794 0.1872363 -0.6239588 0.758695 0.1003885 -0.6241853 0.7747999 0.01213479 -0.6241694 0.7811949 -0.07625526 -0.6241967 0.7775369 -0.1637068 -0.6241441 0.7639661 -0.249001 -0.6242051 0.7405177 -0.3311648 -0.6241532 0.7076458 -0.4090119 -0.6242164 0.6656299 -0.4816354 -0.6242402 0.615103 -0.5480974 -0.6242387 0.5567005 -0.6075254 -0.6242424 0.4911561 -0.6591977 -0.6241978 0.4193276 -0.7023896 -0.6241903 0.3421044 -0.7365862 -0.624166 0.260495 -0.761263 -0.6242324 0.1755358 -0.846166 -0.5329194 1.56201e-5 -0.7762368 -0.6242215 0.08834081 -0.8461584 -0.5329317 1.87308e-5 -0.8367578 -0.5475732 -1.54749e-5 -0.8405533 -0.5329395 -0.09718906 -0.8367536 -0.5475797 -2.09734e-6 0.5645473 -0.6152673 0.5502113 0.2591929 -0.6830161 0.6828675 0.2588186 -0.7200191 0.6438832 0.5651529 -0.6242451 0.5393704 0.2590844 -0.7300692 0.6323561 0.2588185 -0.7308027 0.6316173 0.4577361 -0.7077242 0.5381489 0.5146345 -0.7077021 0.4840549 0.5644975 -0.6703552 0.4816289 0.2588056 -0.7736442 0.5783549 0.2587997 -0.784446 0.5636199 0.3952382 -0.7076658 0.5856586 0.327861 -0.7075955 0.6259521 0.2563942 -0.7075912 0.6584656 0.1817032 -0.7077184 0.6827289 0.1048233 -0.7077417 0.6986514 0.02670311 -0.7076216 0.7060868 -0.05169928 -0.7074069 0.7049133 -0.1295656 -0.7075277 0.6947067 -0.2058089 -0.7076495 0.6759253 -0.2794867 -0.7077625 0.6488139 -0.3496927 -0.7078765 0.6136986 -0.4158768 -0.7076621 0.5711926 -0.4766439 -0.7077038 0.5215036 -0.5315621 -0.7077032 0.465401 -0.5590615 -0.7074416 0.4324078 -0.5348868 -0.7066084 0.4632502 -0.5426531 -0.7054425 0.455937 -0.5507791 -0.7056756 0.4457178 -0.6034097 -0.7077001 0.3675017 -0.5596769 -0.707698 0.4311908 -0.6399515 -0.7076782 0.2994224 -0.66878 -0.7077165 0.2277511 -0.6896638 -0.7077027 0.1533649 -0.7812388 -0.6242324 -1.6138e-5 -0.7023249 -0.7076622 0.0771622 -0.7812418 -0.6242287 -6.47456e-6 -0.7714896 -0.636242 2.30297e-5 -0.7762172 -0.6242521 -0.08829736 -0.7714931 -0.6362378 0 0.5651604 -0.707701 0.423973 0.2588185 -0.7926026 0.5520817 0.2588182 -0.8284961 0.4965957 0.5522477 -0.711415 0.4346394 0.5585418 -0.7128146 0.4241774 0.5644994 -0.7150766 0.4123178 0.2588701 -0.8321642 0.4903968 0.2588195 -0.8367801 0.4825055 0.2588244 -0.7942403 0.5497202 0.258807 -0.797567 0.5448908 0.2588257 -0.8029446 0.5369259 0.2587899 -0.8104842 0.5254933 0.258811 -0.8202081 0.5101721 0.4127357 -0.7822962 0.4665426 0.545691 -0.7109098 0.443654 0.5388413 -0.7113886 0.4511945 0.5318772 -0.7129808 0.4569082 0.5250803 -0.7157326 0.4604538 0.518809 -0.7195091 0.4616752 0.5132141 -0.7242967 0.4604408 0.5084692 -0.7299398 0.456779 0.4626134 -0.7822834 0.4171589 0.3576274 -0.7823142 0.5099875 0.298025 -0.7822704 0.547023 0.2346118 -0.7822573 0.5770881 0.1681972 -0.7823017 0.5997617 0.09968185 -0.782252 0.6149353 0.02987945 -0.7822887 0.6221992 -0.04029417 -0.7822664 0.6216396 -0.1099581 -0.7822718 0.613156 -0.1782246 -0.782278 0.5968896 -0.2442296 -0.7822802 0.573053 -0.3071368 -0.7822774 0.5419493 -0.3661298 -0.7822973 0.5039444 -0.5277992 -0.7089428 0.4677907 -0.4204858 -0.782292 0.459577 -0.516144 -0.7160851 0.4699122 -0.5215899 -0.7121188 0.4699265 -0.4379281 -0.89901 3.37579e-5 -0.3068333 -0.9517633 1.29454e-7 -0.2325361 -0.9725878 5.22239e-6 -0.3883581 -0.9215086 -1.45659e-6 -0.1741825 -0.9847134 1.29164e-4 -0.06175351 -0.9980915 1.52923e-6 0.103156 -0.9946652 1.0057e-4 0.1170746 -0.9931232 1.09151e-6 0.2992727 -0.9541677 -3.59863e-6 0.31291 -0.9497828 -9.57795e-6 -0.5672683 -0.7109533 0.4156348 0.3729808 -0.9278391 -1.62524e-5 0.4801377 -0.8771931 4.30271e-7 -0.5923394 -0.7379935 0.3232643 -0.575134 -0.7164098 0.3949404 -0.5822498 -0.7240893 0.3697026 -0.6010051 -0.7499317 0.2763972 -0.6141107 -0.7679864 0.1818383 -0.608251 -0.7599248 0.2292271 -0.6108231 -0.7822614 0.122321 -0.5957311 -0.7822927 0.1819959 -0.7065124 -0.7077007 7.87154e-6 -0.6201834 -0.7820513 0.06138747 -0.7065122 -0.7077009 -9.75654e-6 -0.6968812 -0.7171866 -1.37761e-5 -0.7019681 -0.7076925 -0.08007675 -0.6968805 -0.7171874 1.01812e-5 -0.4287733 -0.9034122 -6.17078e-5 -0.4189707 -0.9079998 -1.49384e-6 -0.2878997 -0.9576606 1.66334e-6 0.258826 -0.8428509 0.4718174 -0.5616466 -0.8273772 6.57514e-7 -0.1553178 -0.9878646 1.32899e-5 -0.1496313 -0.9887419 1.21444e-6 -0.004980623 -0.9999877 -8.41916e-7 0.1305574 -0.9914408 -2.83018e-5 0.1451766 -0.9894058 -2.06754e-7 0.2984965 -0.9544108 -1.41375e-6 0.4057524 -0.9139831 8.25311e-5 0.4481547 -0.8939561 2.70316e-7 0.5861158 -0.8102273 -5.60172e-5 0.6480212 -0.7616224 -4.65348e-5 0.7089932 -0.7052153 8.91276e-7 0.8139457 -0.5809411 -7.00355e-7 0.5047613 -0.7361221 0.4509329 0.8375094 -0.546423 -2.45585e-5 0.8956446 -0.4447706 -9.574e-7 0.5021536 -0.7425077 0.4433104 0.9525285 -0.3044497 -3.59491e-7 0.5006156 -0.7489476 0.4341217 0.9583736 -0.2855173 -4.89524e-5 0.9866837 -0.1626507 2.22586e-6 0.5000215 -0.755397 0.423502 0.9997845 -0.0207625 -2.47918e-6 0.5003309 -0.7618004 0.4114964 1 -4.06429e-6 3.22328e-4 0.9927726 0.1200113 2.01538e-6 0.5015336 -0.7681256 0.3980545 0.9914394 0.1305682 6.17879e-5 0.9659312 0.2587992 2.49856e-7 0.5065935 -0.7822857 0.3624808 0.9659316 0.2587978 0 0.9659258 0.2588194 5.8463e-6 0.9659245 0.2588244 3.92044e-5 0.9659186 0.2588461 0 0.9659255 0.2588204 0 0.9659261 0.2588182 0 0.9659318 0.2587967 0 0.4155701 -0.847035 0.3314111 0.9659106 0.2588762 -3.94749e-5 0.45002 -0.8470664 0.2827734 0.509092 -0.7963504 0.3265753 0.3761689 -0.84677 0.3761351 0.33172 -0.8467383 0.4159281 0.282854 -0.8469703 0.4501501 0.2305791 -0.8470998 0.4788062 0.1755949 -0.8469672 0.5018098 0.1183146 -0.8469422 0.5183538 0.05949604 -0.8471228 0.5280561 -2.80642e-6 -0.8470653 0.5314888 -0.05949181 -0.8470739 0.5281352 -0.1182685 -0.8470624 0.5181677 -0.1756537 -0.846901 0.5019009 -0.2306818 -0.8469752 0.478977 -0.2828897 -0.8469475 0.4501704 -0.3314848 -0.846975 0.4156336 -0.5009735 -0.7415449 0.4462474 -0.4695328 -0.7822796 0.4093626 -0.3759047 -0.8469998 0.3758819 -0.5033123 -0.7338128 0.4562847 -0.5068249 -0.7268794 0.4634383 -0.5111906 -0.7209482 0.4678868 -0.5086708 -0.7775401 0.3697098 -0.5125944 -0.7822826 0.3539506 -0.4156785 -0.8469617 0.3314626 -0.5034373 -0.7681887 0.3955212 -0.5007316 -0.7588794 0.4163775 -0.5000028 -0.7499482 0.4330993 -0.8090445 0.5877473 -2.57145e-6 -0.8090716 0.5877102 -8.14535e-7 -0.8090772 0.5877025 0 -0.4500062 -0.8470729 0.2827758 -0.5187993 -0.7914787 0.3231235 -0.8090344 0.5877615 -5.07879e-6 -0.8090358 0.5877593 8.77481e-7 -0.809045 0.5877467 2.80887e-6 -0.9241668 0.3819894 3.18699e-6 -0.9781528 0.2078874 -8.57836e-5 -0.9841347 0.1774227 -2.94857e-6 -0.9134027 0.4070571 -7.8757e-5 -1 -1.53623e-5 2.21247e-7 -0.9998162 -0.01917368 -4.71249e-7 -0.9790001 -0.2038602 9.20147e-7 -0.9608814 -0.2769604 -3.51464e-5 -0.9274097 -0.3740475 -5.04777e-7 -0.8500822 -0.5266501 -2.17929e-7 -0.8471061 -0.5314238 1.59907e-4 -0.7538526 -0.6570438 -3.553e-7 -0.6681302 -0.7440445 1.89913e-5 -0.6450763 -0.7641182 0 -0.5249647 -0.8511241 0 0.515056 -0.8185625 0.2543088 0.4788559 -0.8470647 0.2306043 0.5174645 -0.8274357 0.2181303 0.5016566 -0.8470703 0.1755348 0.5194526 -0.834928 0.1818355 0.5421839 -0.8203558 0.1818047 0.5181707 -0.8470606 0.1182688 0.5645039 -0.8051556 0.1818245 0.5644971 -0.8140041 0.1368955 0.2592653 -0.9437314 0.2053114 0.2588179 -0.9422003 0.2127722 0.2586226 -0.9525821 0.1603178 0.2588189 -0.9418991 0.2141003 0.5645032 -0.8203338 0.09158945 0.2589507 -0.9560827 0.1372973 0.2585753 -0.9600288 0.1071623 0.5281383 -0.8470706 0.05951064 0.5644887 -0.8241602 0.04596233 0.2591231 -0.9633979 0.06870126 0.2587766 -0.9644379 0.0538004 0.5314915 -0.8470637 1.14646e-5 0.5644884 -0.8254411 1.79936e-5 0.2588201 -0.9659256 -7.63126e-6 0.5281606 -0.8470567 -0.05950933 0.5645098 -0.8254265 1.08909e-5 0.531499 -0.847059 9.61125e-6 0.5645314 -0.8246903 -0.03449994 0.2588193 -0.9659259 2.07238e-5 0.2588189 -0.9659259 -5.23802e-6 0.2587772 -0.965107 -0.04003566 0.2588196 -0.9659258 -1.43638e-5 0.4792957 -0.8776535 1.95354e-5 0.4306799 -0.9011991 -0.04853194 0.4793007 -0.8776508 -6.95139e-6 0.4305821 -0.9011961 0.04944378 0.4334083 -0.9011977 1.24834e-5 0.4221888 -0.9011686 0.09824419 0.4081801 -0.9011919 0.1457473 0.3889244 -0.9011739 0.1913725 0.3645442 -0.9011806 0.2344806 0.335403 -0.9011892 0.274523 0.3018866 -0.9011977 0.3109776 0.2644846 -0.9011649 0.3434382 0.2235664 -0.9011798 0.3713398 0.1797555 -0.9011713 0.3944342 0.1335773 -0.9011902 0.4123266 0.08565473 -0.9012047 0.4248454 0.03665369 -0.901194 0.4318634 -0.003618836 -0.8827193 0.4698866 0.03643345 -0.9008258 0.4326496 0.0307132 -0.8945267 0.4459582 0.02424055 -0.8895613 0.4561723 0.0172134 -0.8859679 0.4634269 0.01009589 -0.8837219 0.4679037 0.003174483 -0.8826825 0.4699591 -0.08568954 -0.9011977 0.4248531 -0.01052904 -0.8838194 0.4677101 -0.01760631 -0.8861256 0.4631106 -0.02454853 -0.8897614 0.4557656 -0.03094565 -0.8947232 0.4455478 -0.03657603 -0.90101 0.4322536 -0.1336101 -0.9011669 0.4123671 -0.1797901 -0.9011493 0.3944687 -0.2235823 -0.9011778 0.371335 -0.2644699 -0.9011853 0.343396 -0.3019314 -0.901173 0.3110061 -0.3354193 -0.9011836 0.2745217 -0.364516 -0.9011991 0.2344532 -0.5275054 -0.8033989 0.2762033 -0.4788722 -0.8470539 0.2306107 -0.3888868 -0.9011955 0.1913476 -0.5347134 -0.8133887 0.2290865 -0.5016518 -0.8470758 0.1755222 -0.4081839 -0.9011909 0.1457433 -0.51845 -0.8469034 0.1181707 -0.4221467 -0.9011897 0.09823179 -0.577982 -0.7955388 0.1818104 -0.540574 -0.8214133 0.1818246 -0.5282609 -0.8469914 0.05954986 -0.4305819 -0.9011964 0.04943972 -0.6138173 -0.7894481 5.96046e-7 -0.5314983 -0.8470594 1.96621e-5 -0.6229141 -0.7822903 5.96419e-6 -0.6190038 -0.7822477 -0.07016289 -0.5314848 -0.8470679 1.23531e-5 -0.6138157 -0.7894495 -5.23403e-6 -0.5233161 -0.8521387 1.4022e-5 -0.5281378 -0.8470718 -0.05949693 -0.5233182 -0.8521373 4.92483e-6 -0.6229232 -0.7822831 -2.0884e-5 -0.809045 0.5877467 -1.09323e-5 -0.809042 0.5877509 3.83622e-6 -0.8090488 0.5877414 5.90492e-6 0.4334049 -0.9011994 5.36442e-7 0.3893135 -0.9211053 2.61143e-6 0.3278023 -0.9440241 -0.03693783 0.389316 -0.9211044 4.02331e-6 0.3219771 -0.9440088 0.07196038 0.3298856 -0.9440209 1.42232e-5 0.3278684 -0.9440305 0.03617918 0.312066 -0.9440346 0.1068334 0.29853 -0.9440082 0.1404579 0.2812674 -0.9440277 0.1723386 0.2607017 -0.9440097 0.2021895 0.2369094 -0.9440255 0.2295429 0.2103024 -0.9440204 0.2541621 0.1811818 -0.9439983 0.2757542 0.1498427 -0.9439899 0.2939903 0.1166463 -0.9440215 0.308573 0.08207875 -0.944018 0.3195201 0.04105234 -0.9085032 0.4158567 0.04653918 -0.9440237 0.3265783 0.04424184 -0.9175785 0.3950853 -0.8371854 -0.5469194 -2.72781e-5 -0.806713 -0.5909436 0 -0.8010377 -0.5986139 -2.77534e-6 -0.9030292 -0.4295794 -2.10106e-6 -0.6755712 -0.7372948 -1.41002e-6 -0.6492435 -0.7605807 2.09652e-5 -0.5328124 -0.8462336 -1.66521e-6 -0.4104282 -0.911893 1.63839e-5 -0.3788649 -0.925452 -1.13249e-6 -0.2223406 -0.9749692 4.54485e-7 -0.1381683 -0.9904088 -1.57382e-5 -0.06981068 -0.9975603 -9.40752e-7 0.0795837 -0.9968282 1.69291e-6 0.1460611 -0.9892756 6.06706e-5 0.2317348 -0.972779 0 0.3873735 -0.9219229 8.28877e-7 0.4176835 -0.9085927 -4.05475e-7 0.5397147 -0.841848 3.55765e-7 0.6543536 -0.7561888 2.18695e-5 0.6805031 -0.7327452 -1.17347e-6 0.8042611 -0.5942762 1.64844e-6 3.64349e-7 0 1 -5.89537e-7 0 1 -0.04110503 -0.9086665 0.4154946 0.839381 -0.5435435 2.00598e-5 0.9046995 -0.4260505 -2.99327e-6 -0.08206915 -0.9440307 0.3194853 -0.04425859 -0.9176763 0.3948561 -0.04543143 -0.9280312 0.369722 -0.04651594 -0.9440263 0.3265742 -0.1166597 -0.9440091 0.3086057 -0.1498408 -0.9439915 0.293986 -0.1812093 -0.9439817 0.2757933 -0.2103071 -0.944018 0.2541677 -0.2369105 -0.9440249 0.2295438 -0.2606583 -0.9440282 0.2021585 -0.2812638 -0.944029 0.1723369 -0.2985275 -0.9440092 0.1404567 -0.3120667 -0.9440345 0.1068335 -0.3219776 -0.9440085 0.07196056 -0.4334059 -0.9011989 -1.37389e-5 -0.3279568 -0.9439977 0.03623193 -0.4334071 -0.9011983 1.00769e-6 -0.4264762 -0.9044989 8.09133e-6 -0.4307079 -0.9011848 -0.04854702 -0.4264848 -0.9044948 1.30776e-5 0.3298764 -0.9440242 -7.55675e-6 0.2954413 -0.9553609 -1.80788e-5 0.2207925 -0.9750021 -0.02493149 0.2954441 -0.9553601 -1.12802e-5 0.2207869 -0.9749998 0.02507227 0.2222152 -0.9749977 7.61263e-6 0.2165554 -0.9749979 0.04982924 0.2095901 -0.9749882 0.0739597 0.1998304 -0.975007 0.09710389 0.1876501 -0.9749928 0.1190652 0.1730652 -0.9749785 0.139519 0.1562232 -0.9749764 0.1581629 0.1373281 -0.9749947 0.1747182 0.1167479 -0.9749895 0.1891175 0.09465342 -0.9749938 0.2010668 0.07136768 -0.9749953 0.2104542 0.04714363 -0.9750004 0.2171447 0.04551792 -0.9280282 0.3697184 -1 0 0 0.04542982 -0.961313 0.2716863 -1 8.70228e-6 9.21963e-6 -1 -1.55345e-5 4.34369e-6 -0.9732041 -0.2299431 1.35787e-6 -0.9583827 -0.2854868 2.54898e-5 0.2222062 -0.9749998 -4.84847e-6 0.1986177 -0.980077 -6.08712e-6 0.111046 -0.9937365 -0.01251626 0.19863 -0.9800747 -6.52671e-6 0.1089448 -0.9937368 0.02486616 0.1117542 -0.9937359 2.01073e-6 0.1110502 -0.9937361 0.01251566 0.1054752 -0.9937368 0.03690701 0.1007103 -0.993733 0.04849934 0.09468948 -0.9937273 0.05949807 0.08741647 -0.9937297 0.06971251 0.07902723 -0.9937351 0.07902723 0.06968671 -0.9937343 0.08738398 0.05948293 -0.9937303 0.09466749 0.04848241 -0.9937373 0.1006753 0.03689998 -0.9937357 0.1054885 0.04547351 -0.982283 0.181803 0.1117444 -0.9937371 -2.704e-5 0.09979444 -0.9950081 1.64062e-5 1.61387e-6 -1 -1.73226e-5 0.09982073 -0.9950055 0 -1.14418e-6 -1 -1.85072e-5 0.02486491 -0.993738 0.1089335 0.03020697 -0.982865 0.1818351 0.01251101 -0.9937376 0.1110372 9.63431e-7 -0.9833271 0.181846 7.05157e-7 -0.9937356 0.1117578 0.01515763 -0.9832157 0.1818163 -0.01515704 -0.9832133 0.1818291 -0.01251202 -0.9937359 0.111052 -0.03020888 -0.9828642 0.181839 -0.02485638 -0.9937345 0.1089679 -0.07134628 -0.9750007 0.2104366 -0.03690552 -0.9937373 0.1054711 -0.04547321 -0.9822826 0.1818057 -0.09467166 -0.9749929 0.2010629 -0.04848426 -0.9937369 0.1006795 -0.1167459 -0.9749904 0.1891143 -0.05948644 -0.9937295 0.09467333 -0.1372637 -0.975018 0.1746385 -0.06971055 -0.99373 0.08741384 -0.1562522 -0.9749671 0.1581909 -0.07901751 -0.9937367 0.07901769 -0.1730001 -0.9750015 0.1394383 -0.0873816 -0.9937347 0.06968492 -0.18766 -0.9749923 0.1190539 -0.09464401 -0.9937334 0.05946868 -0.199887 -0.9749944 0.09711468 -0.1007528 -0.9937277 0.04851996 -0.2095966 -0.9749867 0.0739625 -0.1054337 -0.9937419 0.03689128 -0.2165547 -0.9749981 0.04982912 -0.1089406 -0.9937372 0.02486532 -0.2208202 -0.9749919 0.02508658 -0.1110959 -0.9937308 0.01252591 -0.2185311 -0.97583 2.15173e-5 -0.1117492 -0.9937365 -8.97981e-6 -0.2222095 -0.974999 7.12462e-6 -0.2208035 -0.9750011 -0.02487343 -0.1117622 -0.993735 -3.23262e-6 -0.2185378 -0.9758285 1.26474e-5 -0.1099311 -0.9939392 0 -0.1111006 -0.99373 -0.01254916 -0.1099432 -0.9939379 7.09016e-6 -0.222218 -0.9749971 -5.07757e-6 -0.3244678 -0.9458968 -6.95884e-6 -0.3278304 -0.9440136 -0.03695487 -0.3244632 -0.9458984 1.47522e-6 -0.3298765 -0.9440241 -8.27387e-6 -0.04716134 -0.974997 0.2171558 1 0 0 1 7.68894e-7 0 1 0 0 1 0 0 -0.04539698 -0.9613059 0.2717171 -0.1089974 -0.9937307 -0.02488005 -0.1055269 -0.9937315 -0.03690314 -0.100729 -0.9937322 -0.04847735 -0.09462279 -0.9937354 -0.05947005 -0.08737134 -0.9937372 -0.06966155 -0.07905501 -0.9937299 -0.07906508 -0.06964564 -0.993739 -0.087363 -0.05945569 -0.9937374 -0.09460985 -0.04848742 -0.9937369 -0.1006779 -0.03689318 -0.993741 -0.1054404 -0.02486705 -0.9937345 -0.1089649 -0.01250666 -0.9937407 -0.1110092 0 -0.9937418 -0.1117018 0.0125122 -0.9937368 -0.1110435 0.02486699 -0.9937344 -0.1089656 0.03689289 -0.9937387 -0.1054633 0.04848712 -0.9937349 -0.1006973 0.05942964 -0.9937428 -0.09456938 0.06964528 -0.9937378 -0.08737683 0.07905477 -0.9937294 -0.07907164 0.08735358 -0.9937387 -0.06966322 0.09462285 -0.9937354 -0.05946934 0.1007287 -0.9937304 -0.04851555 0.1054806 -0.9937357 -0.03692179 0.1089499 -0.9937362 -0.02486735 -0.9999988 -0.001577854 1.65552e-5 0.6267751 -0.7792003 -9.30994e-6 0.7800811 -0.6256785 -1.4549e-5 0.7839291 -0.6208503 3.57291e-4 0.8998935 -0.4361099 -6.72252e-5 0.9022052 -0.4313071 2.84356e-4 0.9746849 -0.2235829 -8.12055e-7 0.9754933 -0.220029 3.76315e-4 0.9962981 -0.08596599 -1.37836e-7 1 -2.70344e-4 -7.83475e-7 0.999997 0.002446472 1.60583e-4 0.9748681 0.2227829 4.51446e-6 0.9743645 0.2249751 1.40496e-4 0.6145632 -0.7888677 9.55269e-6 0.6531702 -0.7572112 -8.62405e-7 0.8090373 -0.5877574 -4.51657e-6 0.8090729 -0.5877083 -1.55134e-4 0.8090482 -0.5877424 5.3097e-6 0.8089766 -0.5878409 -1.22039e-4 0.8090168 -0.5877856 -2.5233e-6 0.8090375 -0.5877571 0 0.8090388 -0.5877554 0 0.8090298 -0.5877678 0 -0.3298724 -0.9440255 5.3905e-6 0.9587491 -0.2842542 9.80069e-5 0.9737111 -0.2277867 2.26684e-6 1 -2.1264e-5 -3.37767e-6 1 2.08616e-7 0 -0.8440774 0.510686 0.1635027 -0.3265329 -0.9451859 0 -0.3265393 -0.9451837 0 -0.326541 -0.9451831 0 -0.8372098 0.5123373 0.1912859 -0.8237057 0.5164061 0.234166 -0.3264795 -0.9452043 0 -0.3265262 -0.9451882 2.57569e-7 -0.3265256 -0.9451884 0 -0.4694653 -0.882951 6.3902e-5 -0.5141535 -0.8576983 3.4906e-6 -0.6001458 -0.7998907 6.91207e-5 -0.6726436 -0.7399668 5.90458e-7 -0.7159122 -0.6981904 8.7332e-5 -0.8145034 -0.5801588 -3.61004e-5 -0.9732576 0.2297165 -5.60656e-6 -0.9732577 0.2297163 -6.90338e-6 -0.9714106 0.2290595 0.06239539 -0.9687033 0.2275213 -0.09923762 -0.9713317 0.2290739 -0.06355971 -0.9732576 0.2297167 1.76393e-5 -0.9732573 0.2297176 1.84625e-5 -0.9686602 0.2276872 0.09927701 -0.9658057 0.2271095 0.1250628 -0.956408 0.2238308 0.1875731 -0.9548975 0.2214962 0.1977635 -0.9430108 0.2190666 0.2504805 -0.8226039 0.5163189 0.2381966 -0.9256183 0.2129348 0.3128733 -0.8048 0.5210767 0.2842112 -0.9193862 0.2099546 0.3326385 -0.9039921 0.2051703 0.3751047 -0.9320811 0.2111343 0.2943589 -0.7963154 0.5239464 0.3022617 -0.7833636 0.5268362 0.3298261 -0.8924883 0.2001082 0.404254 -0.877847 0.1957119 0.4371287 -0.7757607 0.5295094 0.3432425 -0.8601164 0.188333 0.4740576 -0.8469692 0.1843602 0.4986526 -0.7856101 0.5268459 0.3244225 -0.8226207 0.1745483 0.541136 -0.8112726 0.1709803 0.5591088 -0.7755411 0.1572956 0.611387 -0.7708393 0.15558 0.6177392 -0.7802041 0.1590433 0.6049685 0.1391568 0.9902704 -9.33697e-6 0.02636015 0.9996526 -3.13902e-6 -0.009431421 0.9999555 7.27363e-7 0.0833587 0.9965196 -4.41447e-7 -0.6996052 0.5489601 0.4573788 -0.6939585 0.5500536 0.4646103 -0.04617351 0.9989335 3.4906e-6 -0.7062728 0.5474606 0.4488493 -0.6939212 0.5500629 0.4646549 -0.6996083 0.5489706 0.4573615 -0.1458604 0.9893053 4.36758e-5 -0.2486175 0.9686018 7.6741e-7 -0.6989313 0.5463641 0.461499 -0.7348136 0.5403012 -0.4100289 -0.7264298 0.5417506 -0.4228548 -0.6938614 0.5500736 -0.4647316 -0.8131321 0.1548181 -0.5611129 -0.764609 0.1531672 -0.6260294 -0.8063234 0.1691308 -0.5667783 -0.6995934 0.5489642 -0.457392 -0.6989347 0.5463423 -0.4615198 -0.6995865 0.548955 -0.4574137 -0.6938837 0.5500655 -0.4647079 -0.7883099 0.1428522 -0.5984655 -0.7646082 0.1531639 -0.6260312 -0.8131135 0.1548073 -0.5611428 -0.7196418 0.5407022 -0.4356111 -0.7524868 0.5356947 -0.3831381 -0.7556273 0.5339511 -0.3793728 -0.8606554 0.1776643 -0.4771875 -0.843102 0.1829236 -0.5056856 -0.7911808 0.5254071 -0.3130182 -0.7808783 0.5274821 -0.3346518 -0.8747797 0.1945987 -0.4437249 -0.8028764 0.5216208 -0.2886198 -0.9005669 0.1965912 -0.3877257 -0.9016796 0.2043418 -0.3810753 -0.8220873 0.5168538 -0.2388193 -0.8212471 0.5166818 -0.2420605 -0.9321451 0.2108611 -0.2943519 -0.9239795 0.2123433 -0.3180758 -0.8446102 0.5105269 -0.1612334 -0.8362841 0.5126146 -0.1945645 -0.9419324 0.2187351 -0.2547909 -0.8479959 0.5093941 -0.1463578 -0.9548708 0.2215052 -0.1978823 -0.9557797 0.2236066 -0.1910117 -0.8562841 0.5071415 -0.09790366 -0.9655289 0.2270139 -0.1273524 -0.9342323 0.3015261 -0.1905049 -0.9495455 0.220798 -0.2227366 -0.9087288 0.3069698 -0.2828105 -0.9176505 0.220788 -0.3304094 -0.8734943 0.3144435 -0.3716627 -0.8735916 0.2207377 -0.4337196 -0.8289483 0.3239159 -0.4559859 -0.8083628 0.3285166 -0.4884942 -0.7036471 0.5481414 -0.4521303 -0.7066938 0.5475012 -0.4481366 -0.7491198 0.3285138 -0.5752376 -0.7756474 0.3352662 -0.5347595 -0.8179432 0.2207858 -0.5312462 -0.6713458 0.5528517 -0.4936091 -0.7066896 0.5475018 -0.4481424 -0.7036382 0.5481415 -0.4521441 -0.7323128 0.3444396 -0.5874346 -0.683332 0.5501649 -0.479975 -0.8610243 0.1554479 -0.4842243 -0.796317 0.1391732 -0.5886512 -0.8610334 0.1554582 -0.4842048 -0.7885075 0.1427309 -0.5982339 -0.7963173 0.1391863 -0.5886477 -0.9105402 0.1880673 -0.3681674 -0.8876335 0.1728836 -0.4268703 -0.9298219 0.2008933 -0.3083394 -0.9455238 0.2113302 -0.2476375 -0.966337 0.2251597 -0.1244823 -0.9576765 0.2194326 -0.1862931 -0.9714707 0.2287981 -0.06242001 -0.973257 0.2297193 -1.72881e-5 -0.9732571 0.2297187 -1.26995e-5 0 1 -8.07237e-5 0 1 1.09815e-4 0 1 7.96261e-5 -0.830869 0.1430487 -0.5377674 0 1 -5.90105e-5 0 1 1.94128e-5 0 1 -2.8374e-5 0 1 1.74459e-5 0 1 0 0 1 -2.7068e-5 0 1 -4.75244e-7 0 1 7.69607e-6 0 1 4.7738e-7 0 1 3.75122e-5 0 1 3.32231e-7 0 1 1.26673e-5 0 1 0 0 1 7.35298e-6 0 1 0 0 1 0 -0.9715374 0.2285524 0.06228101 0 1 -4.22867e-5 -0.7199542 0.5404784 -0.4353724 -0.6937782 0.5376367 -0.4791855 -0.7363095 0.5230745 -0.4292336 -0.7523728 0.1394424 -0.6438099 -0.7963129 0.1391734 -0.5886566 -0.7963088 0.1391731 -0.5886623 -0.7106264 0.5160703 -0.4782068 -0.6937801 0.5376342 -0.4791856 -0.7363118 0.5230726 -0.4292321 -0.7559378 0.1391742 -0.6396787 -0.7963098 0.1391713 -0.5886614 -0.7963194 0.1391738 -0.5886477 0 1 -2.87778e-5 0 1 -1.58715e-5 0 1 -1.24126e-5 -0.634787 0.5527211 -0.5399489 -0.6850383 0.3545197 -0.6364263 -0.6607794 0.5467206 -0.5142639 -0.6096285 0.541606 -0.5788057 -0.6347762 0.5527191 -0.5399636 -0.6607769 0.5467211 -0.5142666 -0.6806221 0.3285029 -0.6548584 -0.6473363 0.362527 -0.6704699 -0.6056502 0.5506677 -0.5744155 -0.649126 0.5306887 -0.5449816 0.5645319 -0.8225697 -0.06843215 0.259001 -0.9633843 -0.06934839 0.2588192 -0.9626112 -0.0799517 0.5181489 -0.8470745 -0.1182658 0.5644917 -0.8142315 -0.1355596 0.2589135 -0.9559757 -0.1381101 0.2587558 -0.9528292 -0.1586254 0.5016418 -0.8470784 -0.175539 0.5645089 -0.8002609 -0.2022681 0.2590433 -0.9435794 -0.2062877 0.2588173 -0.9364703 -0.2367218 0.4788365 -0.8470695 -0.2306275 0.5648882 -0.782279 -0.262566 0.2587547 -0.9264615 -0.273341 0.2589095 -0.9156502 -0.3074909 0.531741 -0.782288 -0.3244642 0.5644813 -0.7803056 -0.2692289 0.2588194 -0.9130858 -0.3150984 0.4501234 -0.8469882 -0.2828429 0.4918299 -0.7822979 -0.3822478 0.5644612 -0.7188066 -0.4058334 0.5645292 -0.7535169 -0.3369257 0.4155488 -0.8470534 -0.3313911 0.4457073 -0.7822918 -0.4351606 0.5137388 -0.7077098 -0.4849942 0.5653991 -0.7077076 -0.4236437 0.3758732 -0.847014 -0.3758813 0.3938927 -0.7823134 -0.4825293 0.4555693 -0.7075753 -0.5401795 0.3313899 -0.8470529 -0.4155504 0.3370973 -0.7823022 -0.5238023 0.3913886 -0.7076253 -0.5882868 0.28283 -0.8469851 -0.4501373 0.2760686 -0.7821707 -0.5585652 0.3221557 -0.7077058 -0.6287832 0.2306126 -0.8470523 -0.4788739 0.2114269 -0.7822827 -0.585946 0.2488489 -0.7076438 -0.6612976 0.1755645 -0.8470095 -0.5017491 0.1441587 -0.7822084 -0.6061092 0.1723098 -0.7076218 -0.6852596 0.1182867 -0.8469945 -0.5182747 0.07503658 -0.7822253 -0.6184603 0.0935319 -0.70767 -0.7003249 0.05950921 -0.8470587 -0.5281576 0.004973351 -0.782305 -0.6228759 0.0135616 -0.7076838 -0.7063992 7.3883e-7 -0.8470706 -0.5314804 -0.06515336 -0.782295 -0.6194915 -0.06658017 -0.7076622 -0.703407 -0.05949795 -0.8471049 -0.5280848 -0.1344805 -0.78222 -0.6083149 -0.1458638 -0.707678 -0.6913145 -0.1182796 -0.8470365 -0.5182078 -0.202086 -0.7822077 -0.5893321 -0.2232744 -0.7076576 -0.6703501 -0.1755799 -0.8469974 -0.5017642 -0.2671101 -0.782224 -0.5628303 -0.2978135 -0.7076338 -0.6407508 -0.2306092 -0.8470589 -0.4788641 -0.3287143 -0.7822705 -0.5291502 -0.368519 -0.707615 -0.6028888 -0.2828359 -0.8469905 -0.4501234 -0.3861855 -0.7822554 -0.4888122 -0.4344601 -0.7076299 -0.5572292 -0.3314183 -0.8470264 -0.415582 -0.4387247 -0.7822699 -0.4422383 -0.4947992 -0.7076464 -0.504391 -0.3758512 -0.8470378 -0.3758494 -0.485751 -0.7822237 -0.3900924 -0.5487866 -0.7076281 -0.4450795 -0.4155573 -0.8470472 -0.3313959 -0.5265119 -0.7822704 -0.3329242 -0.5956189 -0.7077143 -0.3799719 -0.4500748 -0.8470284 -0.2827996 -0.5606526 -0.7822524 -0.2715696 -0.6348899 -0.7076622 -0.3100472 -0.4788564 -0.8470643 -0.2306053 -0.5876708 -0.7822361 -0.2067603 -0.6659202 -0.7076793 -0.2360939 -0.5017296 -0.8470217 -0.1755618 -0.6071122 -0.7823112 -0.1392986 -0.688402 -0.707663 -0.1591096 -0.5182181 -0.8470302 -0.1182795 -0.4226042 -0.901167 -0.0964564 -0.4091466 -0.9011674 -0.1431664 -0.3905458 -0.9011666 -0.1880769 -0.3669564 -0.9012092 -0.2305753 -0.3389003 -0.9011684 -0.270263 -0.3065415 -0.9011464 -0.3065415 -0.2702361 -0.9011894 -0.3388661 -0.230642 -0.9011487 -0.3670631 -0.1880189 -0.9012314 -0.3904241 -0.1431665 -0.901167 -0.4091473 -0.09645712 -0.9011667 -0.4226046 -0.04852879 -0.901188 -0.4307033 -1.89572e-7 -0.9011685 -0.433469 0.04852843 -0.9011909 -0.4306972 0.09644669 -0.901188 -0.4225615 0.1431537 -0.901186 -0.4091098 0.1880372 -0.9012109 -0.3904628 0.2305952 -0.9011905 -0.36699 0.2702357 -0.9011898 -0.3388655 0.3065132 -0.9011656 -0.3065134 0.3389385 -0.9011449 -0.2702937 0.3669939 -0.9011883 -0.2305976 0.3905069 -0.9011873 -0.1880586 0.4091475 -0.9011669 -0.1431668 0.4226041 -0.901167 -0.09645617 0.258921 -0.9044999 -0.3388806 0.2587964 -0.881752 -0.394383 0.2587034 -0.8779866 -0.4027557 0.258819 -0.8411333 -0.4748764 0.258828 -0.8472766 -0.4638218 0.2588183 -0.8286398 -0.4963561 0.5645476 -0.6744317 -0.4758445 0.25892 -0.8121564 -0.5228409 0.2588168 -0.7892445 -0.5568726 0.5648758 -0.6242181 -0.5396918 0.5002124 -0.624242 -0.6000913 0.4291812 -0.6242365 -0.6527881 0.3526549 -0.6242237 -0.6971221 0.2711962 -0.6244753 -0.7324502 0.1869592 -0.6242732 -0.7585047 0.09972816 -0.6243958 -0.7747156 0.0115118 -0.6243489 -0.7810609 -0.07652884 -0.6242337 -0.7774804 -0.1639164 -0.624231 -0.7638502 -0.2495476 -0.6241872 -0.7403488 -0.3311868 -0.6242726 -0.7075303 -0.4089913 -0.6243198 -0.6655456 -0.4818606 -0.6241741 -0.6149936 -0.5482257 -0.6242175 -0.556598 -0.6076895 -0.6241593 -0.4910588 -0.6592314 -0.6242305 -0.419226 -0.7025336 -0.6240753 -0.3420186 -0.7367032 -0.6240575 -0.260424 -0.7612795 -0.6242241 -0.1754938 0.2588069 -0.7731709 -0.5789868 0.2588188 -0.7306613 -0.6317807 0.564516 -0.6201409 -0.5447449 0.2589808 -0.7297968 -0.6327129 0.25882 -0.7256966 -0.6374768 0.4893326 -0.5329362 -0.6903135 0.5644904 -0.5558385 -0.6102411 0.5654379 -0.5329157 -0.6295086 0.4069052 -0.5328273 -0.7419726 0.3189802 -0.5328361 -0.7837967 0.2267297 -0.5329411 -0.8152101 0.1316873 -0.5328429 -0.8359048 0.03503865 -0.532626 -0.8456252 -0.06265264 -0.532929 -0.8438373 -0.1588675 -0.5326228 -0.8313087 -0.2533171 -0.5326165 -0.8075581 -0.3446373 -0.5329177 -0.7728027 -0.4311292 -0.5329107 -0.7281029 -0.5118908 -0.5328003 -0.6738633 -0.5859283 -0.5328906 -0.6105045 -0.6521885 -0.5328686 -0.5391672 -0.7099628 -0.5324297 -0.4609465 -0.7582725 -0.5323716 -0.3763022 -0.7962086 -0.5328942 -0.286489 -0.8239489 -0.5327343 -0.1931388 0.258938 -0.6829729 -0.6830075 0.2588185 -0.6504268 -0.7141134 0.2592736 -0.632345 -0.7300117 0.2588193 -0.623997 -0.7373197 0.5644731 -0.4818785 -0.6701965 0.2592173 -0.5788151 -0.7731621 0.2588228 -0.563848 -0.7842745 0.4831246 -0.4349457 -0.7598768 0.565472 -0.434916 -0.700778 0.3948588 -0.4349678 -0.8092525 0.301558 -0.4348573 -0.8485059 0.2044098 -0.4348365 -0.8770028 0.1046825 -0.4347295 -0.8944563 0.003609955 -0.4349349 -0.9004546 -0.09748923 -0.4349224 -0.895175 -0.1973785 -0.4347801 -0.8786399 -0.2947318 -0.4349052 -0.8508764 -0.3884229 -0.4347668 -0.8124688 -0.4771705 -0.4347646 -0.7637331 -0.5598222 -0.4348996 -0.7053096 -0.6355206 -0.4347742 -0.6380321 -0.7030515 -0.4349179 -0.5626412 -0.7617328 -0.434976 -0.4801657 -0.8108302 -0.4349507 -0.3916279 -0.8496761 -0.4349316 -0.2981357 -0.8777562 -0.4349601 -0.2008823 0.2588232 -0.5222486 -0.8125683 0.2588191 -0.509301 -0.8207467 0.5645176 -0.3991018 -0.7225218 0.2588193 -0.4670161 -0.8455228 0.4783024 -0.3314702 -0.813237 0.5651956 -0.3314647 -0.755437 0.3855863 -0.3314333 -0.8610895 0.2880996 -0.3315413 -0.8983758 0.1871288 -0.3316287 -0.924665 0.08381468 -0.3313047 -0.9397937 -0.02059078 -0.3314263 -0.9432564 -0.1247375 -0.3315331 -0.9351611 -0.2273467 -0.3316207 -0.9156097 -0.3267538 -0.3315002 -0.8850647 -0.4224272 -0.3314675 -0.8436141 -0.5130653 -0.331502 -0.7917515 -0.5974039 -0.3315253 -0.7302052 -0.6743528 -0.3314989 -0.6598159 -0.7430742 -0.3314837 -0.5813427 -0.8027406 -0.3314861 -0.495706 -0.8526741 -0.3315012 -0.4037994 -0.8919419 -0.3314734 -0.3075147 -0.9205259 -0.3313924 -0.2069086 0.2587949 -0.463097 -0.847683 0.2589329 -0.3881056 -0.8844929 0.564525 -0.3088428 -0.7654592 0.2587776 -0.4020617 -0.8782828 0.2588187 -0.3614241 -0.8957598 0.4697642 -0.2237729 -0.8539598 0.5648441 -0.2238524 -0.7942551 0.3685261 -0.2237668 -0.9022843 0.262357 -0.2238084 -0.9386579 0.1527127 -0.2238341 -0.9625889 0.04104304 -0.2238903 -0.9737498 -0.0711627 -0.2238295 -0.972027 -0.1824299 -0.2238451 -0.957399 -0.2912753 -0.2237937 -0.9300942 -0.3962622 -0.223773 -0.8904505 -0.4959952 -0.2238284 -0.8389814 -0.589151 -0.2238209 -0.7764054 -0.6744982 -0.2237984 -0.7035387 -0.7508952 -0.2238638 -0.6213223 -0.8173518 -0.2237776 -0.5309046 -0.872963 -0.2237846 -0.4334236 -0.9170089 -0.2237414 -0.3302038 -0.9488669 -0.2238442 -0.2225884 0.2588437 -0.3378533 -0.9049062 0.2585379 -0.2620772 -0.9297708 0.5645089 -0.2127904 -0.7975274 0.2588672 -0.2734127 -0.9264088 0.258818 -0.2490231 -0.9332742 0.4673277 -0.113292 -0.8767952 0.5644844 -0.1134271 -0.8176135 0.3642053 -0.113405 -0.9243884 0.2562379 -0.11344 -0.9599342 0.1448845 -0.1133317 -0.9829366 0.03167909 -0.1134182 -0.9930422 -0.08198922 -0.1133146 -0.9901705 -0.1945858 -0.1132118 -0.9743304 -0.3045695 -0.1133508 -0.9457215 -0.4105909 -0.1133953 -0.9047412 -0.5112919 -0.1132491 -0.8519128 -0.6052864 -0.1131528 -0.7879245 -0.6914051 -0.1128665 -0.7135967 -0.7682549 -0.1133956 -0.6300206 -0.8352972 -0.1129697 -0.5380674 -0.8911724 -0.1135002 -0.4392375 -0.935501 -0.1135549 -0.3345792 -0.9676113 -0.113468 -0.2255074 0.2589154 -0.2061957 -0.9436346 0.2588173 -0.1327276 -0.9567638 0.5644934 -0.0109964 -0.8253644 0.2590204 -0.07058709 -0.9632891 0.2588196 -0.01286149 -0.9658402 0.2588048 -0.139081 -0.9558644 0.4666469 -0.001606822 -0.8844423 0.5647197 -0.001572608 -0.8252814 0.3631698 -0.00156784 -0.9317218 0.2542536 -0.001601755 -0.9671363 0.142346 -0.001600086 -0.9898157 0.02858215 -0.001598536 -0.9995902 -0.08555388 -0.001596927 -0.9963323 -0.1985743 -0.001595556 -0.9800845 -0.3090063 -0.00159353 -0.9510587 -0.4154064 -0.001591086 -0.9096346 -0.5159686 -0.001546144 -0.8566062 -0.6106482 -0.00158751 -0.7919006 -0.696939 -0.001585602 -0.7171287 -0.7741473 -0.001583576 -0.6330036 -0.8412596 -0.001581668 -0.5406292 -0.8974044 -0.001579344 -0.4412061 -0.9418492 -0.001577556 -0.3360324 -0.9740155 -0.001575291 -0.2264759 0.2590082 -0.001737236 -0.9658735 0.2588175 -0.0018031 -0.9659246 0.4677795 0.1102546 -0.8769414 0.5645064 0.09111022 -0.8203849 0.2588917 0.06687051 -0.9635889 0.258847 0.1066257 -0.9600152 0.3645915 0.1101989 -0.9246239 0.2565577 0.1101351 -0.9602336 0.145183 0.1101691 -0.9832521 0.03189748 0.1101568 -0.9934023 -0.08181923 0.1100974 -0.9905475 -0.1944654 0.1100396 -0.9747177 -0.3044837 0.1102709 -0.9461131 -0.4106227 0.1101196 -0.9051314 -0.5113011 0.1102575 -0.8522996 -0.6053399 0.1102052 -0.7883011 -0.6915561 0.1097723 -0.7139329 -0.7684537 0.1102964 -0.6303282 -0.8355417 0.109867 -0.5383302 -0.8914527 0.1103928 -0.4394605 -0.9358114 0.1104419 -0.3347535 -0.9680038 0.1100203 -0.2255311 0.5649868 0.1102871 -0.817696 0.2588195 0.129127 -0.9572558 0.4699882 0.220739 -0.8546258 0.5644676 0.1920354 -0.8028069 0.2587293 0.1355074 -0.956398 0.2588194 0.2246999 -0.9394267 0.3686969 0.2207676 -0.9029532 0.2624641 0.2207183 -0.9393594 0.1527449 0.2207422 -0.9632974 0.04100316 0.2207401 -0.9744705 -0.07128316 0.2207627 -0.9727193 -0.1826233 0.2207557 -0.9580792 -0.2915419 0.2207203 -0.9307448 -0.3965964 0.2207558 -0.8910546 -0.4963927 0.2207632 -0.8395581 -0.5896093 0.2207449 -0.776938 -0.6750087 0.2207459 -0.7040133 -0.7514521 0.2208207 -0.621738 0.565144 0.2207885 -0.7948992 0.258665 0.2030432 -0.9443865 0.2588192 0.2585104 -0.9306906 0.4778273 0.3284991 -0.8147205 0.5644723 0.2900852 -0.7728011 0.2589268 0.2703382 -0.927294 0.2587526 0.3394099 -0.9043496 0.3845391 0.3281708 -0.8628057 0.2862655 0.3284962 -0.9000791 0.1845582 0.3285105 -0.9262933 0.08054441 0.3286301 -0.941018 -0.02444779 0.3287249 -0.9441093 -0.1291024 0.3285166 -0.9356333 -0.2321874 0.3285298 -0.9155093 -0.3323997 0.3285227 -0.8840721 -0.4285061 0.3284668 -0.8417196 -0.5193184 0.3285186 -0.7889133 -0.6037066 0.3284868 -0.7263847 0.56537 0.3284921 -0.7566042 0.2589712 0.3354303 -0.9057706 0.2588192 0.3846386 -0.8860394 0.4806604 0.432092 -0.7630611 0.5644794 0.3834558 -0.7309753 0.2586888 0.3995634 -0.8794483 0.2588293 0.4487444 -0.8553572 0.3894015 0.4321642 -0.8133883 0.2929557 0.432115 -0.8529089 0.1925836 0.4320892 -0.8810282 0.08963835 0.4320644 -0.897377 -0.01452213 0.4320977 -0.9017099 -0.1184785 0.4321066 -0.8940061 -0.2208534 0.4320893 -0.8743699 -0.3202782 0.4321047 -0.8430347 -0.4335285 0.4079837 -0.8034939 -0.3390754 0.4280629 -0.8377291 -0.3867825 0.4179118 -0.8220396 -0.5235083 0.3888423 -0.7581166 -0.4791535 0.3982619 -0.782176 -0.6077418 0.3709445 -0.7021753 -0.5664169 0.3797 -0.7314369 0.5655421 0.4320828 -0.7024717 0.2592653 0.4614101 -0.8484588 0.2588117 0.5059283 -0.8228324 0.4910319 0.5302298 -0.6911903 0.5645344 0.4706259 -0.6780945 0.2588992 0.5210751 -0.813297 0.2588192 0.5507463 -0.7935309 0.4104028 0.5302491 -0.7418932 0.3245925 0.5302286 -0.7832608 0.2346623 0.5302742 -0.8147043 0.141782 0.5302695 -0.8358902 0.05676561 0.5121974 -0.8569898 0.1062494 0.5227301 -0.8458513 -0.04216295 0.491162 -0.8700473 0.007519006 0.5016851 -0.8650178 -0.1420274 0.4699197 -0.8712083 -0.09207469 0.4805632 -0.8721132 -0.2414624 0.4487732 -0.8604061 -0.1918855 0.4593356 -0.8672893 -0.3253259 0.5196118 -0.7900422 -0.3250508 0.5332954 -0.7809854 -0.3424164 0.5343255 -0.7728179 -0.250092 0.5289543 -0.8109633 -0.4082206 0.5251665 -0.7466968 -0.3860193 0.5368883 -0.75016 -0.4277459 0.5393757 -0.7253326 -0.483371 0.5307669 -0.6961602 -0.4674727 0.5418067 -0.698509 -0.5051971 0.5441402 -0.6698413 -0.550563 0.536251 -0.6397776 -0.5407945 0.5464317 -0.639495 -0.5743097 0.5485804 -0.6076414 0.5654847 0.5302511 -0.6317127 0.2593063 0.5781002 -0.7736669 0.2588195 0.6209418 -0.7398946 0.4973607 0.6057959 -0.6210022 0.5320526 0.6131611 -0.5839123 0.5645745 0.5500016 -0.6154298 0.2592533 0.6320653 -0.7302611 0.2588191 0.6436654 -0.7202136 0.4605451 0.5980073 -0.6559615 0.3811039 0.5811333 -0.7190577 0.4217679 0.5897504 -0.6886991 0.2947961 0.5627518 -0.7722731 0.3387385 0.5721201 -0.7469504 0.2027596 0.5431942 -0.8147568 0.2494093 0.5531347 -0.7948818 0.1756833 0.4977145 -0.849362 0.1502329 0.5078623 -0.848237 0.1109226 0.5095877 -0.8532389 0.1549676 0.533077 -0.8317536 0.1650035 0.5072635 -0.8458474 0.06860786 0.5003833 -0.8630815 0.05676722 0.5121808 -0.8569997 -0.0368635 0.5042313 -0.8627815 0.003678202 0.5148518 -0.8572714 -0.04895025 0.5176639 -0.8541827 -0.1386675 0.5089443 -0.8495571 -0.1008372 0.5205234 -0.8478723 -0.1518432 0.523333 -0.8384906 -0.2352154 0.5140891 -0.8248552 -0.2016164 0.5261811 -0.8261262 0.5644985 0.6201008 -0.5448087 0.2588682 0.6829642 -0.6830428 0.2588179 0.7256404 -0.6375417 0.6366906 0.5231356 -0.5665284 0.627961 0.5211558 -0.5779806 0.5929494 0.5148655 -0.6191322 0.2585272 0.7303484 -0.6322619 0.2588192 0.7841593 -0.5640096 0.6712974 0.5325363 -0.515524 0.5644319 0.5105916 -0.648624 0.5546336 0.5099043 -0.6575556 0.5131997 0.5063617 -0.692982 0.4792926 0.5024909 -0.7195703 0.4690563 0.5039223 -0.725292 0.4224346 0.5026468 -0.7542515 0.3840483 0.4981281 -0.7774158 0.3738076 0.5021891 -0.779791 0.323388 0.5025855 -0.8017656 0.2818105 0.496734 -0.8208765 0.2715564 0.5036304 -0.8201302 0.2186715 0.5052467 -0.8348106 -0.3216171 -0.9440201 -0.07340735 -0.3113768 -0.9440198 -0.1089557 -0.2972609 -0.9440039 -0.1431528 -0.2793264 -0.9440191 -0.1755129 -0.2579195 -0.944019 -0.2056834 -0.2332985 -0.9440042 -0.2332982 -0.2057096 -0.9440044 -0.2579521 -0.1755126 -0.9440189 -0.2793274 -0.1431343 -0.9440188 -0.2972222 -0.1089562 -0.9440191 -0.3113784 -0.07340759 -0.9440199 -0.3216174 -0.03693628 -0.9440196 -0.3278151 7.35795e-7 -0.9440197 -0.3298894 0.03694087 -0.9440043 -0.3278586 0.07341766 -0.9440041 -0.3216616 0.1089379 -0.9440386 -0.3113258 0.1431289 -0.9440233 -0.297211 0.1755112 -0.9440199 -0.2793249 0.2056829 -0.9440193 -0.2579193 0.2333368 -0.943985 -0.2333373 0.2579557 -0.9440028 -0.2057128 0.2793201 -0.9440219 -0.1755081 0.2972179 -0.9440206 -0.1431323 0.3113797 -0.9440187 -0.1089568 0.3216193 -0.9440193 -0.07340794 -0.2167097 -0.9749823 -0.04946285 -0.2097648 -0.9749929 -0.07340025 -0.2003255 -0.974968 -0.09647381 -0.1881447 -0.9750005 -0.1182191 -0.1737524 -0.9749926 -0.1385625 -0.1571764 -0.9749827 -0.1571763 -0.1385615 -0.9749932 -0.1737501 -0.1182343 -0.9749941 -0.1881684 -0.09646427 -0.974972 -0.200311 -0.07338583 -0.975003 -0.2097235 -0.04944247 -0.9750035 -0.2166189 -0.02488642 -0.9749825 -0.2208847 -1.80024e-7 -0.974983 -0.2222795 0.02488636 -0.974983 -0.2208821 0.0494647 -0.9749799 -0.2167197 0.07338684 -0.9750023 -0.209726 0.09646141 -0.9749737 -0.2003036 0.1182575 -0.9749841 -0.1882054 0.1385192 -0.9750083 -0.1736986 0.1571654 -0.9749863 -0.1571649 0.1737165 -0.9750031 -0.1385338 0.1881878 -0.9749886 -0.1182475 0.2002772 -0.9749804 -0.09644901 0.2097603 -0.974994 -0.07339882 0.2167088 -0.9749825 -0.04946225 1 2.34291e-7 0 1 8.31991e-7 0 1 4.58711e-7 0 1 6.44607e-7 0 1 7.11485e-7 0 1 4.80669e-7 0 1 1.39462e-7 0 1 7.96937e-7 0 1 1.98802e-7 0 1 -1.13834e-6 0 1 -1.90575e-7 0 1 -2.18119e-7 0 1 4.11638e-7 0 1 -2.27895e-7 0 1 1.0259e-6 0 1 -2.14664e-7 0 1 -4.02025e-7 0 1 -7.7914e-7 0 1 -3.98123e-7 0 1 1.07614e-6 0 1 0 0 1 0 0 1 -1.56599e-7 0 1 0 0 1 8.58967e-7 0 1 -3.23112e-7 0 1 0 0 1 -2.44847e-7 0 1 0 0 1 -3.26183e-7 0 1 0 0 1 1.44475e-7 0 1 -4.83404e-7 0 1 0 0 0.258751 0.7735609 -0.5784907 1 -1.08145e-6 0 0.2588202 0.8125216 -0.5223227 0.2590712 0.8126417 -0.5220111 1 -1.44228e-7 0 1 -4.15679e-7 0 0.2588173 0.8385871 -0.4793595 0.2588997 0.8477897 -0.462843 1 -2.18069e-7 0 1 -1.09952e-6 0 0.2588186 0.8752824 -0.4085264 0.2588387 0.8786085 -0.40131 1 -7.39368e-7 0 1 -5.79068e-7 0 0.2588191 0.8836377 -0.3901247 0.2589749 0.9049751 -0.337568 1 -8.89765e-7 0 0.2588169 0.9185829 -0.2986958 0.2591037 0.9268388 -0.2717264 1 -2.22317e-7 0 1 -5.96689e-7 0 0.2588165 0.9439439 -0.2048999 0.2588331 0.9438501 -0.2053107 0.2588471 0.9561111 -0.1372945 1 -1.64064e-7 0 1 -1.04379e-6 0 0.2588064 0.9601086 -0.1058808 0.259093 0.9634078 -0.06867593 1 -4.58711e-7 0 0.2588204 0.9659255 -1.23791e-5 0.2588193 0.9659259 1.87977e-5 0.2588183 0.9631626 0.0730139 0.258819 0.9659259 -7.95349e-6 0.2588211 0.9659253 -2.01225e-5 0.258835 0.9634304 0.06932806 1 -2.34292e-7 0 1 -8.31991e-7 0 0.990249 0.139172 -0.006174147 0.9902681 0.1391727 -7.53766e-6 0.981756 0.1392049 -0.1295264 0.9882203 0.1390467 0.06392806 0.9862347 0.1391485 0.08932489 0.9792965 0.1392012 -0.1469751 0.9577962 0.1391776 -0.2515077 0.9873009 0.1391527 -0.0766381 0.9483786 0.1391031 -0.2850062 0.9191601 0.1391631 -0.368481 0.9663156 0.1391606 -0.2164914 0.7493825 0.5683273 -0.3397499 0.7685599 0.59165 -0.243446 0.7479477 0.5698338 -0.3403876 0.9257564 0.1391543 -0.351584 0.8984056 0.139178 -0.4165298 0.8640754 0.1391715 -0.4837406 0.7421875 0.5655323 -0.3596261 0.7018631 0.5430084 -0.4610099 0.7142503 0.549341 -0.4336715 0.7117556 0.5462044 -0.4416613 0.6939215 0.5404976 -0.4757473 0.6427515 0.5244941 -0.5583695 0.259036 0.9435946 0.2062271 0.2588201 0.9401591 0.2216151 0.2588192 0.9393844 0.2248774 0.2588706 0.9308267 0.2579685 -0.2587968 0.9659318 -3.74207e-6 -0.2588198 0.9659256 0 -0.2588321 0.9659224 -1.56057e-5 -0.2588226 0.965925 0 0.2588194 0.9187276 0.2982486 0.2588203 0.9408795 0.2185359 0.2588159 0.9546875 0.1469222 0.9691728 0.139256 0.2032532 0.9531907 0.139176 0.2684357 0.9737789 0.1391711 0.1799614 0.9521836 0.139259 0.2719437 0.9528485 0.1391744 0.2696486 0.258575 0.9560592 0.138166 0.9811899 0.1392344 0.1337171 1 -6.44607e-7 0 1 -7.11486e-7 0 0.2588468 0.9282277 0.2671924 0.2588419 0.9264505 0.2732954 1 -4.80673e-7 0 0.2588179 0.9295582 0.2625545 0.2588336 0.8972146 0.3577864 0.2587979 0.904555 0.3388273 1 -1.39473e-7 0 1 -7.96956e-7 0 0.2588409 0.8780312 0.4025702 1 -1.98804e-7 0 0.2588192 0.8573762 0.4448806 0.2588839 0.8471327 0.4640533 1 1.13834e-6 0 1 1.90577e-7 0 0.2588332 0.8157124 0.517319 0.2588765 0.8121716 0.5228388 1 2.1812e-7 0 0.2588076 0.8272693 0.4986425 0.258845 0.8411474 0.4748373 0.2588199 0.7930749 0.5514024 1 -4.11638e-7 0 0.258823 0.7954624 0.5479509 0.2588412 0.7998678 0.5414915 0.258825 0.8065829 0.5314447 1 2.27895e-7 0 1 -1.02589e-6 0 0.2588194 0.7924039 0.5523664 1 2.14663e-7 0 1 4.02017e-7 0 1 7.79136e-7 0 1 3.98125e-7 0 1 -1.07614e-6 0 1 0 0 1 0 0 1 1.56599e-7 0 1 0 0 1 -8.58973e-7 0 1 3.23112e-7 0 1 0 0 1 2.44847e-7 0 1 0 0 1 3.26183e-7 0 1 0 0 1 -1.44473e-7 0 1 4.83405e-7 0 1 0 0 1 1.08145e-6 0 0.2588175 -0.8049442 0.5339274 0.2588655 -0.8127419 0.5219572 1 1.44229e-7 0 1 4.15674e-7 0 0.2588199 -0.7984525 0.5435861 0.2588223 -0.7944393 0.5494335 0.2588184 -0.7926136 0.5520659 0.2588453 -0.8403336 0.4762757 0.258868 -0.8477497 0.4629339 1 2.1807e-7 0 1 1.09951e-6 0 0.2588483 -0.8258546 0.5009608 0.2588207 -0.8140724 0.519902 0.2588187 -0.8573783 0.444877 0.2588043 -0.8786155 0.4013169 1 7.39365e-7 0 1 5.79063e-7 0 0.2588016 -0.8972162 0.3578055 0.2588385 -0.9050551 0.3374584 1 8.89765e-7 0 0.2588213 -0.9282279 0.2672164 0.2585712 -0.9268057 0.2723456 1 2.22316e-7 0 1 5.96693e-7 0 0.2588185 -0.9415953 0.2154334 0.2588204 -0.9308308 0.2580041 0.2588211 -0.9295689 0.2625135 1 1.64064e-7 0 1 1.04379e-6 0 0.2588141 -0.9147606 0.3102072 -0.9659257 -0.2588195 0 -0.9659258 -0.2588196 0 -0.9659258 -0.2588194 0 0.258834 -0.9003812 0.3497411 0.2588181 -0.8784154 0.4017457 -0.9659259 -0.2588193 0 0.2587481 -0.8611315 0.4376096 0.2588194 -0.8630999 0.4336717 -0.9659307 -0.2588011 -1.00581e-5 -0.9659269 -0.2588149 4.95464e-6 -0.8555176 -0.5177738 6.51926e-7 0.2588194 -0.8492742 0.4601584 -0.8518016 -0.5238646 -3.19784e-5 -0.6791215 -0.7340259 -4.65661e-7 0.2588253 -0.8457099 0.4666736 -0.6675041 -0.7446061 3.67052e-5 0.2588179 0.8128673 0.5217856 0.2588192 0.812913 0.5217138 0.6940779 0.540552 0.4754571 0.2588449 0.8052039 0.5335223 0.2588459 0.7994506 0.5421048 0.2588108 0.7954962 0.5479079 0.2588192 0.7932235 0.5511889 0.2588261 0.8224576 0.5065301 0.2588186 0.8213272 0.5083646 0.6550946 0.5275638 0.5408582 0.7006111 0.5432144 0.4626688 0.2588218 0.8610979 0.437632 0.258821 0.8639218 0.4320311 0.7265864 0.555477 0.4043732 0.7337588 0.5599772 0.3847386 0.2588083 0.846648 0.4649791 0.2588099 0.8337047 0.4878052 0.7204076 0.551968 0.4199337 0.7153798 0.5493004 0.4318575 0.7116273 0.5474365 0.4403406 0.7092747 0.5462579 0.4455689 0.7084137 0.5457872 0.4475115 0.2588242 0.9003773 0.3497583 0.2588144 0.8654567 0.428952 -0.1080248 0.9941482 -1.02053e-5 -0.1177768 0.9930401 3.48315e-7 -0.1892862 0.981922 -3.25032e-7 0.04463887 0.9990032 7.26225e-5 0.06627684 0.9978013 1.88686e-6 0.25881 0.8672219 0.4253746 -0.2588374 0.9659209 -1.43587e-6 -0.2588036 0.9659301 2.03e-5 0.2588193 0.8948414 0.3636915 -0.258823 0.9659248 0 -0.9659501 0.2587288 0 -0.9659262 0.258818 0 -0.965928 0.2588109 0 -0.9659252 0.2588216 0 0.9659276 -0.2588124 0 0.965928 -0.2588109 0 0.9659268 -0.2588157 0 0.9659264 -0.258817 0 0.9659314 -0.2587981 -2.13735e-7 0.9659241 -0.2588258 -2.8871e-6 0.9991516 -0.04118353 -1.41934e-6 1 -5.37979e-6 1.01456e-6 0.9865415 0.1635112 1.63913e-6 0.9914488 -0.1304965 3.25335e-5 0.9583525 0.285588 3.22616e-5 0.9363541 0.3510574 1.00769e-6 0.8556045 0.5176301 1.84029e-6 0.8374752 0.5464754 6.35543e-5 0.7510439 0.6602524 3.31551e-7 0.6479616 0.761673 5.03028e-5 0.6299554 0.7766314 -3.15718e-7 0.5000621 0.8659896 -4.20259e-7 0.4057026 0.9140052 1.89678e-5 0.3651459 0.9309504 -1.52782e-6 0.2238481 0.974624 0 0.1304954 0.991449 -2.76221e-5 0.07377052 0.9972752 1.37836e-7 -0.08737534 0.9961755 6.35162e-7 -0.155372 0.9878561 4.15142e-5 -0.2578955 0.9661729 9.70438e-7 -0.4288032 0.903398 2.46801e-5 -0.4307065 0.9024922 1.17905e-6 -0.597297 0.8020203 1.29268e-6 -0.6675415 0.7445726 -3.0057e-5 -0.7493414 0.6621839 -1.61678e-6 -0.8518065 0.5238566 2.22581e-5 -0.8765288 0.4813497 1.16043e-6 -0.9659312 0.2587991 3.79351e-6 -0.9659197 0.258842 0 -0.9659254 -0.2588206 3.57583e-6 -0.9659258 -0.2588192 4.80666e-6 -0.9659247 -0.2588235 1.13693e-6 -0.9659243 -0.2588248 0 -0.9659275 -0.258813 5.88061e-6 -0.9659209 -0.2588375 3.83705e-6 -0.8703269 -0.4924744 3.17022e-6 -0.8517896 -0.523884 -3.41246e-5 -0.7337058 -0.6794673 -2.03401e-6 -0.6675028 -0.7446073 1.20385e-5 -0.5706441 -0.8211975 -1.99676e-6 -0.4287735 -0.9034121 -4.06154e-5 -0.3928326 -0.9196101 2.12342e-6 -0.2098896 -0.9777251 1.40257e-6 -0.1553206 -0.9878641 -4.10752e-5 -0.03137135 -0.9995078 8.97795e-7 0.130558 -0.9914407 1.33107e-5 0.1356238 -0.9907605 2.23517e-7 0.2908751 -0.9567611 -1.5287e-5 0.4057605 -0.9139795 1.88625e-5 0.4366201 -0.8996461 0 0.5765201 -0.817083 9.5088e-7 0.648012 -0.7616302 -6.75349e-5 0.7097425 -0.7044613 3.63216e-7 0.8281542 -0.5605005 -1.28895e-6 0.8374884 -0.5464553 2.88442e-5 0.9215177 -0.3883365 1.38395e-6 0.9583631 -0.2855525 8.28109e-6 0.9815385 -0.1912649 1.21444e-6 1 -8.98289e-6 1.39151e-6 0.9996577 0.0261619 -3.81842e-7 0.9914278 0.1306555 1.48872e-4 0.9659317 0.2587972 -3.68734e-6 0.9659273 0.2588137 -1.18806e-6 0.965927 0.2588148 -3.69732e-6 0.965924 0.2588261 -3.11351e-5 0.9659275 0.2588133 0 0.9659202 0.2588403 0 0.1961669 0.9805706 1.29517e-4 0.2415586 0.9703863 -9.33185e-7 0.3428416 0.9393932 2.51256e-4 0.4042649 0.914642 -7.71135e-7 0.4814151 0.8764928 1.21733e-4 0.5497421 0.8353345 6.83591e-7 0.6087446 0.7933663 1.16505e-4 0.6711277 0.7413418 7.63103e-7 0.7220527 0.691838 5.25522e-4 0.7476463 0.6640973 1.42679e-6 0.8186034 0.5743591 5.14066e-5 0.8570887 0.515169 -1.36014e-6 0.8963515 0.4433444 1.16093e-4 0.7711027 0.6367109 -1.37067e-6 0.9295564 0.3686801 -4.44241e-7 0.9533672 0.301813 8.49836e-5 0.9799138 0.1994214 2.14204e-7 0.9882481 0.1528593 -1.55382e-6 0.9998567 0.01693379 -9.72301e-7 1 -1.79986e-5 -3.3644e-7 0.9852066 -0.1713711 -2.40654e-6 0.9657701 -0.2593998 6.90855e-6 0.9332426 -0.3592471 1.60001e-6 0.8658705 -0.5002682 5.43473e-5 0.8346048 -0.5508494 -1.8049e-6 0.7072985 -0.7069151 7.17468e-6 0.6892237 -0.7245486 -4.13507e-7 0.5004225 -0.8657813 1.0742e-4 0.4968233 -0.8678517 -2.02283e-6 0.2588295 -0.965923 -8.79968e-7 0.2588127 -0.9659276 0 0.2588108 -0.9659281 0 0.2588098 -0.9659283 0 0.2588037 -0.9659301 1.10269e-6 0.2588136 -0.9659273 0 0.9524565 0.1391732 0.2710306 0.9303497 0.1392568 0.3392008 0.9207616 0.139151 0.3644658 0.8364807 0.1391116 0.5300455 0.8297148 0.1391723 0.5405594 0.8378703 0.1391731 0.5278298 0.7238698 0.5519316 0.4139859 0.7243641 0.5525013 0.4123581 0.7327634 0.5567814 0.3912191 0.7961313 0.1395621 0.5888101 0.8133975 0.1391875 0.5648109 0.8490258 0.1392039 0.5096838 0.8632385 0.1391616 0.4852355 0.8722919 0.1393792 0.4687007 0.8801225 0.1391727 0.4538893 0.903622 0.1394104 0.4050087 0.7081257 0.5456368 0.44815 0.7081022 0.5455185 0.4483311 0.6558899 0.527691 0.5397692 0.7094832 0.5459997 0.4455536 0.714049 0.5472071 0.4366905 0.7125995 0.5472363 0.4390153 0.7175804 0.5493683 0.4281039 0.5854251 0.5133393 0.6275032 0.5772331 0.5118003 0.6362881 0.5013248 0.5027684 0.7041998 0.4804435 0.4992125 0.7210832 0.4054358 0.4953251 0.7682934 0.3094261 0.4852784 0.8177778 0.3012477 0.4906461 0.8176286 0.369349 0.4893302 0.7900236 0.1800532 0.478608 0.8593692 0.1921709 0.4882346 0.8512915 0.2460202 0.4816808 0.8411051 0.0447852 0.4741471 0.879306 0.08192729 0.4878149 0.8690943 0.1126265 0.4760987 0.8721498 -0.02347207 0.472789 0.880863 -0.02667796 0.4890197 0.8718647 -0.1592735 0.4719476 0.8671203 -0.1310226 0.4915248 0.8609508 -0.09175097 0.4720214 0.8767997 -0.2911437 0.4739294 0.8310393 -0.2292109 0.495324 0.837924 -0.2260605 0.4725455 0.8518201 -0.3526687 0.4759965 0.8056377 -0.320249 0.4999994 0.8046373 -0.4642382 0.4821811 0.7429565 -0.4032016 0.505429 0.7628696 -0.4099969 0.4787604 0.7763319 -0.5156781 0.4863738 0.7053486 -0.4778513 0.5113814 0.7142459 -0.6069 0.4967712 0.6203958 -0.5439821 0.5177768 0.660296 -0.5633571 0.4912645 0.664295 -0.6462265 0.5028068 0.5740876 -0.6018576 0.5243387 0.6023592 -0.6806825 0.5093316 0.526548 -0.6515965 0.5310403 0.5416811 -0.7363097 0.5230768 0.4292304 -0.6937692 0.5376338 0.4792017 -0.7107056 0.5160874 0.4780705 -0.6937711 0.537634 0.4791988 -0.7362897 0.5230925 0.4292457 -0.7963223 0.1391741 0.5886438 -0.7963232 0.1391726 0.588643 -0.7559825 0.1391736 0.639626 -0.7270767 0.5339473 0.4315784 -0.796319 0.1391741 0.5886482 -0.7923218 0.1403036 0.5937517 -0.7962918 0.1391728 0.5886853 -0.7519119 0.1392 0.6444005 -0.7122812 0.1391726 0.6879583 -0.796323 0.1391711 0.5886434 -0.7036285 0.1394379 0.6967526 -0.6652782 0.1391717 0.7335096 -0.6517329 0.1392989 0.7455469 -0.6151438 0.139177 0.7760335 -0.5964931 0.1391562 0.7904629 -0.562468 0.139176 0.8150213 -0.538176 0.1392043 0.8312574 -0.5074897 0.1391621 0.8503459 -0.4771018 0.1391929 0.8677553 -0.4504919 0.1391671 0.8818671 -0.41358 0.1391504 0.8997716 -0.3924569 0.1391596 0.9091822 -0.3479413 0.1391017 0.9271394 -0.332691 0.1391691 0.9327104 -0.2805014 0.139221 0.9497035 -0.2700842 0.1391674 0.9527261 -0.2116454 0.139186 0.9673849 -0.2051491 0.139171 0.9687855 -0.1416104 0.1395304 0.9800397 -0.1395989 0.1391729 0.9803791 -0.07381165 0.1391728 0.9875135 -0.07114607 0.1395699 0.9876531 -0.00800985 0.139135 0.9902411 1.92707e-5 0.1390731 0.9902821 0.05798351 0.1391258 0.9885757 0.07103711 0.139185 0.9877153 0.1237025 0.1391304 0.9825175 0.141712 0.1391279 0.9800822 0.1893206 0.1391291 0.9720087 0.2116529 0.1392025 0.967381 0.2543742 0.1391609 0.9570413 0.2805148 0.139178 0.9497058 0.3177943 0.1391407 0.9378948 0.34794 0.1392042 0.9271246 0.3789201 0.1391757 0.9149042 0.4136458 0.1391344 0.8997437 0.4971579 0.1391872 0.8564234 0.5383975 0.1390432 0.8311408 0.6082235 0.1391593 0.7814723 0.4770744 0.139151 0.8677771 0.6517904 0.1391388 0.7455264 0.7088366 0.1391772 0.6915059 0.5964292 0.1391429 0.7905135 0.7519549 0.1389975 0.644394 0.7963258 0.1391748 0.5886389 0.7037129 0.13919 0.6967169 -0.7133412 0.544572 0.4411189 -0.4180479 0.9084251 1.34632e-5 -0.4283112 0.9036313 0 -0.7199516 0.5404919 0.4353599 -0.7179018 0.5419366 0.4369459 -0.584941 0.8110759 -2.73809e-7 -0.7898978 0.1420378 0.5965625 -0.7871636 0.1436006 0.5997936 -0.7885041 0.142691 0.5982479 -0.6560821 0.7546896 2.80492e-5 -0.7227277 0.6911329 1.41561e-6 -0.7916135 0.1411313 0.5944999 -0.7933775 0.1403322 0.5923336 -0.7938959 0.1402226 0.5916646 -0.7926712 0.1403307 0.5932788 0.1391688 0.9902687 0 0.1391723 0.9902682 -8.79845e-6 0.1391679 0.9902689 0 0.1391724 0.9902682 -7.44046e-6 0.1391678 0.9902689 0 0.1391775 0.9902675 0 0.1391776 0.9902675 -2.46389e-5 -0.826892 0.5623608 9.53674e-7 -0.8414629 0.540315 1.59618e-4 -0.9557902 0.2940495 -1.46707e-6 -0.95938 0.2821174 5.18166e-5 -0.9028514 0.4299528 -7.37142e-7 -0.9886856 0.1500024 -8.08916e-5 -1 -3.40403e-6 2.98109e-5 -0.9856054 -0.1690626 2.7474e-7 -0.9590995 -0.2830694 1.51654e-5 -0.9999898 -0.004523873 -2.52388e-7 -0.8564253 -0.5162711 0 -0.8403855 -0.5419891 6.59103e-5 -0.9398812 -0.3415017 -1.3411e-7 -0.7298734 -0.6835824 -2.34507e-6 -0.6537241 -0.756733 7.37538e-6 -0.5548085 -0.8319781 2.5034e-6 -0.4137959 -0.9103698 3.4087e-5 -0.1391525 -0.990271 -4.74229e-6 -0.1391753 -0.9902678 0 -0.2297447 -0.9732511 4.82425e-7 -0.320507 -0.9472462 2.83867e-6 -0.1391718 -0.9902684 0 -0.1391711 -0.9902684 0 -0.1391889 -0.9902659 4.47909e-5 -0.8606266 0.1776646 0.4772393 -0.8009316 0.1600303 0.576974 -0.7934461 0.1570274 0.5880356 -0.1391797 -0.9902672 -8.3555e-6 -0.8376706 0.1749271 0.5174055 -0.1391751 -0.9902679 -1.40363e-5 -0.1392047 -0.9902637 1.5229e-4 -0.7857225 0.15398 0.599108 -0.7857156 0.1539954 0.5991131 -0.793422 0.1479172 0.5904255 -0.8131204 0.1548147 0.5611308 -0.8131194 0.1548104 0.5611334 -0.7949035 0.1443489 0.5893149 -0.7950195 0.1422632 0.5896654 -0.7948276 0.1411146 0.5901997 -0.7945609 0.1405194 0.5907008 -0.794269 0.1402739 0.5911516 -0.9207823 0.2095289 0.3290254 -0.9222754 0.2090782 0.3251069 -0.898553 0.1994855 0.3909067 -0.9663361 0.225161 0.1244875 -0.9576835 0.2194071 0.1862874 -0.9005351 0.1964809 0.3878555 -0.9455261 0.2113072 0.2476481 -0.8702692 0.1880724 0.4552587 -0.9105413 0.188067 0.3681648 -0.9298335 0.2008633 0.3083239 -0.8876264 0.1728879 0.4268831 -0.8610293 0.1554513 0.4842143 -0.83086 0.1430695 0.5377759 -0.861019 0.1554526 0.4842323 -0.7963277 0.1391769 0.5886358 0 1 3.03398e-5 0 1 -5.07418e-5 0 1 6.57209e-5 0 1 -3.66678e-5 0 1 6.68413e-5 0 1 -3.91293e-5 0 1 4.01484e-5 0 1 -2.00333e-5 0 1 0 0 1 -1.74408e-5 0 1 2.82405e-5 0 1 -4.72328e-5 0 1 5.1791e-5 0 1 -3.54449e-5 0 1 -1.78115e-5 0 1 3.38203e-5 0 1 -5.60948e-5 0 1 4.51184e-5 -0.7118498 0.1391725 -0.6884046 -0.7045952 0.1391565 -0.6958312 0 1 -6.38832e-5 0 1 3.90764e-5 -0.664231 0.1391738 -0.7344576 -0.653111 0.1393358 -0.744333 0 1 -5.6356e-5 0 1 2.36405e-5 -0.6132097 0.1391714 -0.7775636 -0.598299 0.1392312 -0.7890837 0 1 -1.97927e-5 0 1 -1.18453e-5 -0.5590937 0.1391712 -0.8173406 -0.5404062 0.1392385 -0.8298035 0 1 -8.64477e-5 0 1 1.55037e-5 -0.5019479 0.1391679 -0.853628 -0.4797677 0.1393283 -0.8662624 0 1 -2.18962e-7 0 1 -2.11105e-5 -0.442413 0.1391689 -0.8859474 -0.416787 0.1392347 -0.8982775 0 1 -1.45369e-5 0 1 -1.97862e-5 -0.3817504 0.1391698 -0.9137277 -0.3519464 0.139294 -0.9255977 0 1 -1.23269e-4 0 1 1.4246e-4 -0.3201244 0.1391769 -0.9370967 -0.2853038 0.1392043 -0.9482741 0 1 -1.63854e-4 0 1 1.46621e-4 -0.2567489 0.1391625 -0.9564067 -0.2167429 0.1391806 -0.9662563 0 1 2.47371e-6 0 1 2.00675e-4 -0.1911395 0.1391758 -0.971646 -0.1467498 0.139308 -0.979315 0 1 0 -0.124715 0.1391521 -0.9823863 -0.07602041 0.139154 -0.9873486 -0.05849432 0.1392002 -0.9885352 -0.004966437 0.1392976 -0.9902382 0.007156789 0.1391555 -0.9902447 0.06606459 0.1392444 -0.9880519 0.07242375 0.1391793 -0.9876154 0.1368258 0.1394277 -0.9807338 0.1367201 0.139164 -0.980786 0.2064749 0.1392324 -0.968495 0.262968 0.1391696 -0.9547144 0.2752284 0.1391758 -0.9512516 0.2004014 0.1391901 -0.969776 0.3423442 0.1391115 -0.9292193 0.3851826 0.139182 -0.9122844 0.4079211 0.1391718 -0.9023478 0.4711592 0.1391328 -0.8710058 0.5025278 0.1391646 -0.8532872 0.5320677 0.1391679 -0.8351864 0.5901545 0.1391588 -0.795206 0.6099007 0.1391665 -0.7801628 0.6452636 0.1391527 -0.7511801 0.69703 0.1391591 -0.7034089 0.7069153 0.1391736 -0.6934707 0.7452924 0.1391531 -0.652055 0.7897449 0.1391702 -0.5974401 0.7924858 0.1391721 -0.5937992 0.830196 0.1391192 -0.5398337 0.8665921 0.1391524 -0.4792231 0 1 5.91018e-5 0 1 -3.83559e-5 0 1 -3.64284e-5 0 1 1.95261e-5 0 1 -1.6131e-5 0 1 1.0466e-5 0 1 -5.01034e-5 0 1 1.53287e-5 0 1 5.36995e-5 0 1 -1.87125e-5 0 1 4.12271e-5 0 1 -8.57777e-5 0 1 -7.14494e-6 0 1 1.30582e-6 0 1 7.99638e-5 0 1 -1.46786e-6 0 1 -9.15627e-5 0 1 2.11454e-6 0 1 1.7469e-4 0 1 -2.10545e-4 0 1 -1.79222e-4 0 1 -1.87254e-5 0 1 1.28485e-5 0 1 3.45608e-5 0 1 -6.88008e-5 0 1 -8.59343e-5 0 1 -1.29825e-5 -0.6803683 0.5092606 -0.5270225 -0.5960555 0.523621 -0.608719 -0.6454441 0.5026895 -0.5750699 -0.60531 0.4965474 -0.6221259 -0.5338955 0.5167321 -0.669286 -0.5604712 0.4909305 -0.6669778 -0.4625308 0.5100876 -0.7251731 -0.5108038 0.4859337 -0.7091883 -0.4568282 0.4816452 -0.747881 -0.3817608 0.5039099 -0.7748119 -0.3998728 0.4782106 -0.7819311 -0.2917929 0.4984269 -0.8163502 -0.3404489 0.4755166 -0.8111587 -0.2778201 0.4735818 -0.8357849 -0.1931328 0.4938153 -0.8478479 -0.2119119 0.4723631 -0.8555505 -0.08685213 0.4903209 -0.8672036 -0.1440827 0.4719091 -0.8697944 -0.07591348 0.4721325 -0.8782529 0.0253691 0.4882456 -0.8723375 -0.007916271 0.4730188 -0.8810169 0.05972993 0.4745374 -0.8782065 0.1410545 0.4878422 -0.8614603 0.1260877 0.4765409 -0.8700636 0.1911588 0.4791072 -0.8566882 0.2569521 0.4894369 -0.833323 0.25476 0.4821514 -0.8382287 0.3691493 0.4934131 -0.7875738 0.3754033 0.4897936 -0.7868766 0.4734492 0.5001936 -0.7250189 0.4852477 0.4997264 -0.7175014 0.565778 0.5103644 -0.6476291 0.5785816 0.5120246 -0.6348813 0.6544631 0.527332 -0.5418478 6.39817e-7 -8.95932e-6 1 3.56918e-6 -1.76281e-5 1 -8.8696e-6 -0.1489707 0.9888416 7.86551e-6 0.1489698 0.9888418 1.28902e-5 0.07515704 0.9971717 -4.624e-7 1.1038e-5 1 -3.56918e-6 1.9826e-5 1 -3.48699e-5 -0.1499056 0.9887004 -3.26424e-4 -0.2951248 0.9554587 -1.31903e-5 -0.07515668 0.9971718 9.88873e-5 -0.2963385 0.955083 2.05279e-5 -0.4343236 0.900757 -4.3489e-5 -0.2237197 0.9746536 1.26803e-4 -0.4354089 0.9002329 -1.29228e-4 -0.5634481 0.8261514 8.88993e-5 -0.5645377 0.8254074 -7.9893e-5 -0.6801153 0.7331052 1.30854e-5 -0.6807149 0.7325485 2.07544e-4 -0.7331687 0.6800468 5.87549e-5 -0.7824113 0.622762 -3.37765e-7 -0.7824109 0.6227627 4.32387e-5 -0.8662775 0.4995632 1.69811e-4 -0.8668631 0.4985464 1.2183e-4 -0.9309042 0.3652634 -1.96491e-4 -0.9315804 0.3635354 1.84878e-4 -0.9748135 0.2230215 -2.37474e-4 -0.9753692 0.2205784 2.279e-4 -0.9971165 0.0758863 -2.46783e-4 -0.9973298 0.0730291 2.46784e-4 -0.9973298 -0.07302916 1.07483e-4 -0.9971106 -0.07596391 -1.0445e-4 -0.9753603 -0.2206181 -1.84877e-4 -0.9748135 -0.2230215 1.9648e-4 -0.9315804 -0.3635354 -1.21823e-4 -0.9309043 -0.3652635 1.2693e-4 -0.8667759 -0.4986979 -4.32278e-5 -0.8662775 -0.4995633 3.49362e-7 -0.7824107 -0.6227629 -5.87524e-5 -0.7824113 -0.622762 -2.0754e-4 -0.7331686 -0.6800469 3.06716e-5 -0.6807312 -0.7325333 7.9893e-5 -0.6801154 -0.7331051 -8.88993e-5 -0.5645374 -0.8254076 1.29228e-4 -0.5634482 -0.8261514 -1.06511e-5 -0.4357002 -0.9000919 1.27799e-4 -0.4340435 -0.9008919 -9.89967e-5 -0.2963383 -0.9550831 3.26417e-4 -0.2951248 -0.9554587 4.33859e-5 -0.2237198 -0.9746536 3.49938e-5 -0.1499055 -0.9887004 8.89142e-6 -0.1489707 -0.9888416 1.31903e-5 -0.07515668 -0.9971718 -6.39817e-7 -8.96305e-6 -1 6.52856e-7 1.10343e-5 -1 3.56918e-6 1.97738e-5 -1 -7.85876e-6 0.1489698 -0.9888418 -3.56918e-6 -1.76877e-5 -1 2.00816e-6 0.1498785 -0.9887045 9.25548e-5 0.2948806 -0.9555342 -1.27743e-5 0.0751571 -0.9971717 9.89013e-5 0.2963316 -0.9550852 -1.27486e-4 0.4340565 -0.9008857 -4.44043e-5 0.2237194 -0.9746537 1.27211e-4 0.4353992 -0.9002376 -1.28652e-4 0.5634716 -0.8261355 8.88943e-5 0.564515 -0.8254229 -7.98968e-5 0.6801395 -0.7330828 -2.0221e-5 0.6807277 -0.7325367 2.06667e-4 0.7331939 -0.6800196 5.44187e-5 0.7824098 -0.622764 1.14743e-6 0.7824178 -0.622754 4.23964e-5 0.8662768 -0.4995644 -1.27825e-4 0.8667757 -0.4986982 1.20616e-4 0.9309048 -0.3652619 -1.97643e-4 0.931585 -0.3635236 1.83923e-4 0.9748167 -0.2230079 1.07736e-4 0.9753625 -0.2206084 -1.03291e-4 0.9971104 -0.07596677 -2.4652e-4 0.9973278 -0.07305687 -9.68676e-5 0.9973297 0.07303196 -2.29169e-4 0.9971172 0.07587754 2.36491e-4 0.9753642 0.2206008 -1.83923e-4 0.9748166 0.2230078 1.97631e-4 0.931585 0.3635237 -1.2061e-4 0.9309048 0.365262 1.27823e-4 0.8667756 0.4986983 -4.23803e-5 0.8662767 0.4995645 -1.12341e-6 0.7824176 0.6227542 -5.43835e-5 0.7824098 0.622764 -2.06648e-4 0.7331939 0.6800197 2.01575e-5 0.6807277 0.7325366 7.98967e-5 0.6801038 0.7331159 -8.88943e-5 0.5645146 0.8254231 1.28652e-4 0.5634714 0.8261355 -1.37988e-5 0.4356914 0.9000962 1.27486e-4 0.4340564 0.9008858 -9.89013e-5 0.2963314 0.9550853 3.26889e-4 0.295122 0.9554596 2.00304e-6 0.2237428 0.9746482 3.69495e-5 0.1499073 0.9887002 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.38346e-7 0 1 0 0 1 1.48459e-7 0 1 0 0 1 -1.78357e-7 0 1 0 0 1 -1.61632e-7 0 1 0 0 1 0 0 1 -1.45574e-7 0 1 0 0 1 -1.91671e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.04641e-7 0 5.89603e-7 0 1 -3.64282e-7 0 1 0 0 1 0 0 1 -2.37317e-7 0 1 0 0 1 -1.39627e-7 0 1 -1.47166e-7 0 1 0 0 1 -1.83958e-7 0 1 0 0 1 0 0 1 - - - - - - - - - - 0.573463 0.614479 0.596785 0.641817 0.600238 0.593917 0.591918 0.593917 0.600238 0.593917 0.596785 0.641817 0.573463 0.55887 0.573463 0.614479 0.600238 0.593917 0.609811 0.548473 0.573463 0.55887 0.600238 0.593917 0.605736 0.593917 0.609811 0.548473 0.600238 0.593917 0.591918 0.593917 0.605736 0.593917 0.600238 0.593917 0.573463 0.668605 0.591918 0.688374 0.596785 0.641817 0.591918 0.593917 0.596785 0.641817 0.591918 0.688374 0.573463 0.614479 0.573463 0.668605 0.596785 0.641817 0.573463 0.720529 0.590852 0.701211 0.591918 0.688374 0.591918 0.593917 0.591918 0.688374 0.590852 0.701211 0.573463 0.668605 0.573463 0.720529 0.591918 0.688374 0.573463 0.720529 0.590888 0.711722 0.590852 0.701211 0.590785 0.593917 0.590852 0.701211 0.590888 0.711722 0.591918 0.593917 0.590852 0.701211 0.590785 0.593917 0.573463 0.720529 0.591793 0.720215 0.590888 0.711722 0.591233 0.593917 0.590888 0.711722 0.591793 0.720215 0.590785 0.593917 0.590888 0.711722 0.591233 0.593917 0.573463 0.769563 0.593392 0.726922 0.591793 0.720215 0.593202 0.593917 0.591793 0.720215 0.593392 0.726922 0.573463 0.720529 0.573463 0.769563 0.591793 0.720215 0.591233 0.593917 0.591793 0.720215 0.593202 0.593917 0.573463 0.769563 0.595555 0.732032 0.593392 0.726922 0.593202 0.593917 0.593392 0.726922 0.595555 0.732032 0.573463 0.769563 0.598153 0.735649 0.595555 0.732032 0.596544 0.593917 0.595555 0.732032 0.598153 0.735649 0.593202 0.593917 0.595555 0.732032 0.596544 0.593917 0.573463 0.769563 0.601009 0.737847 0.598153 0.735649 0.596544 0.593917 0.598153 0.735649 0.601009 0.737847 0.573463 0.769563 0.603935 0.738794 0.601009 0.737847 0.601023 0.593917 0.601009 0.737847 0.603935 0.738794 0.596544 0.593917 0.601009 0.737847 0.601023 0.593917 0.573463 0.769563 0.606948 0.738696 0.603935 0.738794 0.606326 0.593917 0.603935 0.738794 0.606948 0.738696 0.601023 0.593917 0.603935 0.738794 0.606326 0.593917 0.624062 0.748894 0.610208 0.737535 0.606948 0.738696 0.606326 0.593917 0.606948 0.738696 0.610208 0.737535 0.573463 0.769563 0.624062 0.748894 0.606948 0.738696 0.624062 0.748894 0.613802 0.735061 0.610208 0.737535 0.6121 0.593917 0.610208 0.737535 0.613802 0.735061 0.606326 0.593917 0.610208 0.737535 0.6121 0.593917 0.624062 0.748894 0.617527 0.731131 0.613802 0.735061 0.615453 0.593917 0.613802 0.735061 0.617527 0.731131 0.6121 0.593917 0.613802 0.735061 0.615453 0.593917 0.624062 0.748894 0.621202 0.725688 0.617527 0.731131 0.618636 0.593917 0.617527 0.731131 0.621202 0.725688 0.615453 0.593917 0.617527 0.731131 0.618636 0.593917 0.807968 0.653536 0.621202 0.725688 0.624062 0.748894 0.618636 0.593917 0.621202 0.725688 0.621679 0.593917 0.624824 0.715193 0.621679 0.593917 0.621202 0.725688 0.807968 0.653536 0.804827 0.637482 0.621202 0.725688 0.624824 0.715193 0.621202 0.725688 0.804827 0.637482 0.573463 0.769563 0.624063 0.792386 0.624062 0.748894 0.627233 0.771354 0.624062 0.748894 0.624063 0.792386 0.811395 0.669147 0.624062 0.748894 0.627233 0.771354 0.811395 0.669147 0.807968 0.653536 0.624062 0.748894 0.573463 0.815058 0.624063 0.832303 0.624063 0.792386 0.63156 0.797825 0.624063 0.792386 0.624063 0.832303 0.573463 0.769563 0.573463 0.815058 0.624063 0.792386 0.63156 0.797825 0.627233 0.771354 0.624063 0.792386 0.573463 0.856409 0.624063 0.868152 0.624063 0.832303 0.640054 0.839571 0.624063 0.832303 0.624063 0.868152 0.573463 0.815058 0.573463 0.856409 0.624063 0.832303 0.636279 0.82246 0.63156 0.797825 0.624063 0.832303 0.640054 0.839571 0.636279 0.82246 0.624063 0.832303 0.573463 0.89307 0.624063 0.89949 0.624063 0.868152 0.648123 0.870218 0.624063 0.868152 0.624063 0.89949 0.573463 0.856409 0.573463 0.89307 0.624063 0.868152 0.644001 0.855512 0.640054 0.839571 0.624063 0.868152 0.648123 0.870218 0.644001 0.855512 0.624063 0.868152 0.573463 0.924554 0.624063 0.925931 0.624063 0.89949 0.656835 0.89573 0.624063 0.89949 0.624063 0.925931 0.573463 0.89307 0.573463 0.924554 0.624063 0.89949 0.652412 0.883634 0.648123 0.870218 0.624063 0.89949 0.656835 0.89573 0.652412 0.883634 0.624063 0.89949 0.573463 0.950444 0.624063 0.947149 0.624063 0.925931 0.66606 0.915775 0.624063 0.925931 0.624063 0.947149 0.573463 0.924554 0.573463 0.950444 0.624063 0.925931 0.661396 0.90645 0.656835 0.89573 0.624063 0.925931 0.66606 0.915775 0.661396 0.90645 0.624063 0.925931 0.573464 0.970397 0.624063 0.962882 0.624063 0.947149 0.672725 0.942079 0.624063 0.947149 0.624063 0.962882 0.573463 0.950444 0.573464 0.970397 0.624063 0.947149 0.670825 0.923663 0.66606 0.915775 0.624063 0.947149 0.672698 0.926333 0.670825 0.923663 0.624063 0.947149 0.672725 0.942079 0.672698 0.926333 0.624063 0.947149 0.573464 0.984147 0.624063 0.972936 0.624063 0.962882 0.672725 0.942079 0.624063 0.962882 0.624063 0.972936 0.573464 0.970397 0.573464 0.984147 0.624063 0.962882 0.573464 0.991514 0.624063 0.977187 0.624063 0.972936 0.672725 0.951954 0.624063 0.972936 0.624063 0.977187 0.573464 0.984147 0.573464 0.991514 0.624063 0.972936 0.672725 0.951954 0.672725 0.942079 0.624063 0.972936 0.573464 0.992399 0.624063 0.975582 0.624063 0.977187 0.672725 0.955825 0.624063 0.977187 0.624063 0.975582 0.573464 0.991514 0.573464 0.992399 0.624063 0.977187 0.672725 0.955825 0.672725 0.951954 0.624063 0.977187 0.573464 0.986791 0.624063 0.968142 0.624063 0.975582 0.672725 0.95364 0.624063 0.975582 0.624063 0.968142 0.573464 0.992399 0.573464 0.986791 0.624063 0.975582 0.672725 0.95364 0.672725 0.955825 0.624063 0.975582 0.573464 0.974763 0.624063 0.954958 0.624063 0.968142 0.672725 0.945429 0.624063 0.968142 0.624063 0.954958 0.573464 0.986791 0.573464 0.974763 0.624063 0.968142 0.672725 0.945429 0.672725 0.95364 0.624063 0.968142 0.573464 0.956476 0.624063 0.936192 0.624063 0.954958 0.672725 0.931301 0.624063 0.954958 0.624063 0.936192 0.573464 0.974763 0.573464 0.956476 0.624063 0.954958 0.672725 0.931301 0.672725 0.945429 0.624063 0.954958 0.573464 0.932172 0.624063 0.912077 0.624063 0.936192 0.672725 0.911445 0.624063 0.936192 0.624063 0.912077 0.573464 0.956476 0.573464 0.932172 0.624063 0.936192 0.672725 0.911445 0.672725 0.931301 0.624063 0.936192 0.608628 0.889948 0.624161 0.883155 0.624063 0.912077 0.672725 0.886126 0.624063 0.912077 0.624161 0.883155 0.573506 0.902345 0.608628 0.889948 0.624063 0.912077 0.573464 0.932172 0.573506 0.902345 0.624063 0.912077 0.672725 0.886126 0.672725 0.911445 0.624063 0.912077 0.591531 0.787572 0.624161 0.883155 0.608628 0.889948 0.651354 0.869151 0.672725 0.886126 0.624161 0.883155 0.591531 0.787572 0.651354 0.869151 0.624161 0.883155 0.572316 0.796101 0.608628 0.889948 0.573506 0.902345 0.572316 0.796101 0.591531 0.787572 0.608628 0.889948 0.563789 0.905089 0.573506 0.902345 0.573464 0.932172 0.552525 0.803172 0.573506 0.902345 0.563789 0.905089 0.552525 0.803172 0.572316 0.796101 0.573506 0.902345 0.521563 0.962365 0.573464 0.932172 0.573464 0.956476 0.521589 0.913752 0.563789 0.905089 0.573464 0.932172 0.521563 0.940261 0.521589 0.913752 0.573464 0.932172 0.521563 0.962365 0.521563 0.940261 0.573464 0.932172 0.521563 0.97976 0.573464 0.956476 0.573464 0.974763 0.521563 0.97976 0.521563 0.962365 0.573464 0.956476 0.521563 0.992269 0.573464 0.974763 0.573464 0.986791 0.521563 0.992269 0.521563 0.97976 0.573464 0.974763 0.521664 0.999743 0.573464 0.986791 0.573464 0.992399 0.521664 0.999743 0.521563 0.992269 0.573464 0.986791 0.535488 0.99997 0.573464 0.992399 0.573464 0.991514 0.529917 0.999879 0.521664 0.999743 0.573464 0.992399 0.535488 0.99997 0.529917 0.999879 0.573464 0.992399 0.521635 0.999743 0.573464 0.991514 0.573464 0.984147 0.537367 1 0.535488 0.99997 0.573464 0.991514 0.535503 0.99997 0.537367 1 0.573464 0.991514 0.529999 0.99988 0.535503 0.99997 0.573464 0.991514 0.521635 0.999743 0.529999 0.99988 0.573464 0.991514 0.521563 0.991028 0.573464 0.984147 0.573464 0.970397 0.521563 0.991028 0.521635 0.999743 0.573464 0.984147 0.521563 0.976039 0.573464 0.970397 0.573463 0.950444 0.521563 0.976039 0.521563 0.991028 0.573464 0.970397 0.521563 0.954981 0.573463 0.950444 0.573463 0.924554 0.521563 0.954981 0.521563 0.976039 0.573463 0.950444 0.521563 0.928124 0.573463 0.924554 0.573463 0.89307 0.521563 0.928124 0.521563 0.954981 0.573463 0.924554 0.521563 0.895812 0.573463 0.89307 0.573463 0.856409 0.521563 0.895812 0.521563 0.928124 0.573463 0.89307 0.521563 0.858459 0.573463 0.856409 0.573463 0.815058 0.521563 0.858459 0.521563 0.895812 0.573463 0.856409 0.521563 0.816545 0.573463 0.815058 0.573463 0.769563 0.521563 0.816545 0.521563 0.858459 0.573463 0.815058 0.521562 0.770605 0.573463 0.769563 0.573463 0.720529 0.521562 0.770605 0.521563 0.816545 0.573463 0.769563 0.521562 0.72123 0.573463 0.720529 0.573463 0.668605 0.521562 0.72123 0.521562 0.770605 0.573463 0.720529 0.521562 0.669052 0.573463 0.668605 0.573463 0.614479 0.521562 0.669052 0.521562 0.72123 0.573463 0.668605 0.521562 0.614739 0.573463 0.614479 0.573463 0.55887 0.521562 0.614739 0.521562 0.669052 0.573463 0.614479 0.609342 0.502513 0.573463 0.502513 0.573463 0.55887 0.521562 0.558988 0.573463 0.55887 0.573463 0.502513 0.609811 0.548473 0.609342 0.502513 0.573463 0.55887 0.521562 0.558988 0.521562 0.614739 0.573463 0.55887 0.609859 0.454326 0.573463 0.502513 0.609342 0.502513 0.559191 0.502513 0.521562 0.558988 0.573463 0.502513 0.573463 0.446152 0.559191 0.502513 0.573463 0.502513 0.573463 0.446152 0.573463 0.502513 0.609859 0.454326 0.792617 0.502513 0.609342 0.502513 0.609811 0.548473 0.792819 0.485066 0.609342 0.502513 0.792617 0.502513 0.609859 0.454326 0.609342 0.502513 0.792819 0.485066 0.605736 0.593917 0.611214 0.593917 0.609811 0.548473 0.793395 0.536821 0.609811 0.548473 0.611214 0.593917 0.792811 0.519637 0.792617 0.502513 0.609811 0.548473 0.793395 0.536821 0.792811 0.519637 0.609811 0.548473 0.591918 0.593917 0.611214 0.593917 0.605736 0.593917 0.591918 0.593917 0.624886 0.593917 0.611214 0.593917 0.794366 0.553923 0.611214 0.593917 0.624886 0.593917 0.794366 0.553923 0.793395 0.536821 0.611214 0.593917 0.693008 0.76114 0.627233 0.771354 0.63156 0.797825 0.811389 0.670394 0.811395 0.669147 0.627233 0.771354 0.688625 0.738111 0.811389 0.670394 0.627233 0.771354 0.693008 0.76114 0.688625 0.738111 0.627233 0.771354 0.697617 0.78314 0.63156 0.797825 0.636279 0.82246 0.693008 0.76114 0.63156 0.797825 0.697617 0.78314 0.697617 0.78314 0.636279 0.82246 0.640054 0.839571 0.704244 0.810053 0.640054 0.839571 0.644001 0.855512 0.697617 0.78314 0.640054 0.839571 0.704244 0.810053 0.704244 0.810053 0.644001 0.855512 0.648123 0.870218 0.711343 0.833967 0.648123 0.870218 0.652412 0.883634 0.704244 0.810053 0.648123 0.870218 0.711343 0.833967 0.711343 0.833967 0.652412 0.883634 0.656835 0.89573 0.718812 0.854648 0.656835 0.89573 0.661396 0.90645 0.711343 0.833967 0.656835 0.89573 0.718812 0.854648 0.718812 0.854648 0.661396 0.90645 0.66606 0.915775 0.726539 0.871876 0.66606 0.915775 0.670825 0.923663 0.718812 0.854648 0.66606 0.915775 0.726539 0.871876 0.726539 0.871876 0.670825 0.923663 0.672698 0.926333 0.680571 0.935055 0.672698 0.926333 0.672725 0.942079 0.734403 0.885457 0.672698 0.926333 0.680571 0.935055 0.726539 0.871876 0.672698 0.926333 0.734403 0.885457 0.685525 0.938518 0.672725 0.942079 0.672725 0.951954 0.685525 0.938518 0.680571 0.935055 0.672725 0.942079 0.695491 0.940947 0.672725 0.951954 0.672725 0.955825 0.690497 0.940489 0.685525 0.938518 0.672725 0.951954 0.695491 0.940947 0.690497 0.940489 0.672725 0.951954 0.705418 0.937377 0.672725 0.955825 0.672725 0.95364 0.700467 0.93991 0.695491 0.940947 0.672725 0.955825 0.705418 0.937377 0.700467 0.93991 0.672725 0.955825 0.715307 0.92774 0.672725 0.95364 0.672725 0.945429 0.710349 0.933345 0.705418 0.937377 0.672725 0.95364 0.715307 0.92774 0.710349 0.933345 0.672725 0.95364 0.718839 0.912089 0.672725 0.945429 0.672725 0.931301 0.718846 0.922736 0.715307 0.92774 0.672725 0.945429 0.718839 0.912089 0.718846 0.922736 0.672725 0.945429 0.718839 0.896269 0.672725 0.931301 0.672725 0.911445 0.718839 0.896269 0.718839 0.912089 0.672725 0.931301 0.718839 0.875479 0.672725 0.911445 0.672725 0.886126 0.718839 0.875479 0.718839 0.896269 0.672725 0.911445 0.651354 0.869151 0.672875 0.855982 0.672725 0.886126 0.718839 0.84998 0.672725 0.886126 0.672875 0.855982 0.718839 0.84998 0.718839 0.875479 0.672725 0.886126 0.610176 0.777572 0.672875 0.855982 0.651354 0.869151 0.691348 0.843034 0.718839 0.84998 0.672875 0.855982 0.628112 0.766184 0.691348 0.843034 0.672875 0.855982 0.610176 0.777572 0.628112 0.766184 0.672875 0.855982 0.591531 0.787572 0.610176 0.777572 0.651354 0.869151 0.74227 0.895211 0.680571 0.935055 0.685525 0.938518 0.734403 0.885457 0.680571 0.935055 0.74227 0.895211 0.74227 0.895211 0.685525 0.938518 0.690497 0.940489 0.749999 0.900979 0.690497 0.940489 0.695491 0.940947 0.74227 0.895211 0.690497 0.940489 0.749999 0.900979 0.749999 0.900979 0.695491 0.940947 0.700467 0.93991 0.757438 0.902616 0.700467 0.93991 0.705418 0.937377 0.749999 0.900979 0.700467 0.93991 0.757438 0.902616 0.764433 0.899996 0.705418 0.937377 0.710349 0.933345 0.757438 0.902616 0.705418 0.937377 0.764433 0.899996 0.764433 0.899996 0.710349 0.933345 0.715307 0.92774 0.764433 0.899996 0.715307 0.92774 0.718846 0.922736 0.720162 0.920655 0.718846 0.922736 0.718839 0.912089 0.770834 0.89302 0.718846 0.922736 0.720162 0.920655 0.764433 0.899996 0.718846 0.922736 0.770834 0.89302 0.729587 0.902118 0.718839 0.912089 0.718839 0.896269 0.724922 0.912106 0.720162 0.920655 0.718839 0.912089 0.729587 0.902118 0.724922 0.912106 0.718839 0.912089 0.738503 0.878023 0.718839 0.896269 0.718839 0.875479 0.734112 0.890746 0.729587 0.902118 0.718839 0.896269 0.738503 0.878023 0.734112 0.890746 0.718839 0.896269 0.746789 0.848737 0.718839 0.875479 0.718839 0.84998 0.742736 0.864001 0.738503 0.878023 0.718839 0.875479 0.746789 0.848737 0.742736 0.864001 0.718839 0.875479 0.691348 0.843034 0.719005 0.820381 0.718839 0.84998 0.754333 0.8147 0.718839 0.84998 0.719005 0.820381 0.750668 0.832277 0.746789 0.848737 0.718839 0.84998 0.754333 0.8147 0.750668 0.832277 0.718839 0.84998 0.645234 0.753456 0.719005 0.820381 0.691348 0.843034 0.757789 0.796056 0.754333 0.8147 0.719005 0.820381 0.728073 0.811978 0.757789 0.796056 0.719005 0.820381 0.661524 0.739415 0.728073 0.811978 0.719005 0.820381 0.645234 0.753456 0.661524 0.739415 0.719005 0.820381 0.628112 0.766184 0.645234 0.753456 0.691348 0.843034 0.770834 0.89302 0.720162 0.920655 0.724922 0.912106 0.776508 0.881618 0.724922 0.912106 0.729587 0.902118 0.770834 0.89302 0.724922 0.912106 0.776508 0.881618 0.776508 0.881618 0.729587 0.902118 0.734112 0.890746 0.781356 0.865771 0.734112 0.890746 0.738503 0.878023 0.776508 0.881618 0.734112 0.890746 0.781356 0.865771 0.781356 0.865771 0.738503 0.878023 0.742736 0.864001 0.785322 0.845527 0.742736 0.864001 0.746789 0.848737 0.781356 0.865771 0.742736 0.864001 0.785322 0.845527 0.78841 0.821011 0.746789 0.848737 0.750668 0.832277 0.785322 0.845527 0.746789 0.848737 0.78841 0.821011 0.78841 0.821011 0.750668 0.832277 0.754333 0.8147 0.790682 0.792447 0.754333 0.8147 0.757789 0.796056 0.78841 0.821011 0.754333 0.8147 0.790682 0.792447 0.728073 0.811978 0.761044 0.776399 0.757789 0.796056 0.790682 0.792447 0.757789 0.796056 0.761044 0.776399 0.676797 0.724194 0.761044 0.776399 0.728073 0.811978 0.691091 0.707761 0.704174 0.690415 0.761044 0.776399 0.778922 0.749673 0.761044 0.776399 0.704174 0.690415 0.676797 0.724194 0.691091 0.707761 0.761044 0.776399 0.792246 0.76015 0.761044 0.776399 0.778922 0.749673 0.790682 0.792447 0.761044 0.776399 0.792246 0.76015 0.661524 0.739415 0.676797 0.724194 0.728073 0.811978 0.532386 0.808699 0.563789 0.905089 0.521589 0.913752 0.532386 0.808699 0.552525 0.803172 0.563789 0.905089 0.517571 0.914309 0.521589 0.913752 0.521563 0.940261 0.511853 0.812693 0.521589 0.913752 0.517571 0.914309 0.511853 0.812693 0.532386 0.808699 0.521589 0.913752 0.469012 0.946203 0.521563 0.940261 0.521563 0.962365 0.470346 0.917477 0.517571 0.914309 0.521563 0.940261 0.469022 0.917476 0.470346 0.917477 0.521563 0.940261 0.469012 0.946203 0.469022 0.917476 0.521563 0.940261 0.469012 0.969547 0.521563 0.962365 0.521563 0.97976 0.469012 0.969547 0.469012 0.946203 0.521563 0.962365 0.469012 0.987203 0.521563 0.97976 0.521563 0.992269 0.469012 0.987203 0.469012 0.969547 0.521563 0.97976 0.520929 0.999731 0.521563 0.992269 0.521664 0.999743 0.469058 0.99888 0.469012 0.987203 0.521563 0.992269 0.478996 0.999043 0.469058 0.99888 0.521563 0.992269 0.494859 0.999303 0.478996 0.999043 0.521563 0.992269 0.509084 0.999537 0.494859 0.999303 0.521563 0.992269 0.520929 0.999731 0.509084 0.999537 0.521563 0.992269 0.521065 0.873461 0.521664 0.999743 0.529917 0.999879 0.521065 0.873461 0.520929 0.999731 0.521664 0.999743 0.529953 0.873461 0.529917 0.999879 0.535488 0.99997 0.529953 0.873461 0.521065 0.873461 0.529917 0.999879 0.535486 0.873461 0.535488 0.99997 0.537367 1 0.535486 0.873461 0.529953 0.873461 0.535488 0.99997 0.537367 0.873461 0.537367 1 0.535503 0.99997 0.535486 0.873461 0.537367 1 0.537367 0.873461 0.53547 0.873461 0.535503 0.99997 0.529999 0.99988 0.53547 0.873461 0.537367 0.873461 0.535503 0.99997 0.529869 0.873461 0.529999 0.99988 0.521635 0.999743 0.529869 0.873461 0.53547 0.873461 0.529999 0.99988 0.521124 0.999734 0.521635 0.999743 0.521563 0.991028 0.529869 0.873461 0.521635 0.999743 0.521124 0.999734 0.469012 0.987435 0.521563 0.991028 0.521563 0.976039 0.509391 0.999542 0.521124 0.999734 0.521563 0.991028 0.495215 0.999309 0.509391 0.999542 0.521563 0.991028 0.479343 0.999049 0.495215 0.999309 0.521563 0.991028 0.469055 0.99888 0.479343 0.999049 0.521563 0.991028 0.469012 0.987435 0.469055 0.99888 0.521563 0.991028 0.469012 0.970197 0.521563 0.976039 0.521563 0.954981 0.469012 0.970197 0.469012 0.987435 0.521563 0.976039 0.469012 0.947442 0.521563 0.954981 0.521563 0.928124 0.469012 0.947442 0.469012 0.970197 0.521563 0.954981 0.469011 0.91944 0.521563 0.928124 0.521563 0.895812 0.469011 0.91944 0.469012 0.947442 0.521563 0.928124 0.469011 0.886519 0.521563 0.895812 0.521563 0.858459 0.469011 0.886519 0.469011 0.91944 0.521563 0.895812 0.469011 0.84907 0.521563 0.858459 0.521563 0.816545 0.469011 0.84907 0.469011 0.886519 0.521563 0.858459 0.469011 0.807533 0.521563 0.816545 0.521562 0.770605 0.469011 0.807533 0.469011 0.84907 0.521563 0.816545 0.469011 0.762398 0.521562 0.770605 0.521562 0.72123 0.469011 0.762398 0.469011 0.807533 0.521562 0.770605 0.469011 0.714198 0.521562 0.72123 0.521562 0.669052 0.469011 0.714198 0.469011 0.762398 0.521562 0.72123 0.469011 0.663501 0.521562 0.669052 0.521562 0.614739 0.469011 0.663501 0.469011 0.714198 0.521562 0.669052 0.469011 0.610905 0.521562 0.614739 0.521562 0.558988 0.469011 0.610905 0.469011 0.663501 0.521562 0.614739 0.559191 0.502513 0.521562 0.502513 0.521562 0.558988 0.469011 0.55703 0.521562 0.558988 0.521562 0.502513 0.469011 0.55703 0.469011 0.610905 0.521562 0.558988 0.573463 0.446152 0.521562 0.502513 0.559191 0.502513 0.469011 0.55703 0.521562 0.502513 0.507956 0.502513 0.521562 0.44543 0.507956 0.502513 0.521562 0.502513 0.573463 0.446152 0.521562 0.44543 0.521562 0.502513 0.491159 0.815114 0.517571 0.914309 0.470346 0.917477 0.491159 0.815114 0.511853 0.812693 0.517571 0.914309 0.47031 0.815947 0.470346 0.917477 0.469022 0.917476 0.47031 0.815947 0.491159 0.815114 0.470346 0.917477 0.41647 0.938685 0.469022 0.917476 0.469012 0.946203 0.41647 0.938685 0.422741 0.914416 0.469022 0.917476 0.449447 0.815199 0.469022 0.917476 0.422741 0.914416 0.449447 0.815199 0.47031 0.815947 0.469022 0.917476 0.41647 0.959953 0.469012 0.946203 0.469012 0.969547 0.41647 0.959953 0.41647 0.938685 0.469012 0.946203 0.41647 0.977031 0.469012 0.969547 0.469012 0.987203 0.41647 0.977031 0.41647 0.959953 0.469012 0.969547 0.41647 0.989763 0.469012 0.987203 0.469058 0.99888 0.41647 0.989763 0.41647 0.977031 0.469012 0.987203 0.462811 0.873461 0.469058 0.99888 0.478996 0.999043 0.462317 0.998769 0.41647 0.989763 0.469058 0.99888 0.462811 0.873461 0.462317 0.998769 0.469058 0.99888 0.479444 0.873461 0.478996 0.999043 0.494859 0.999303 0.479444 0.873461 0.462811 0.873461 0.478996 0.999043 0.495243 0.873461 0.494859 0.999303 0.509084 0.999537 0.495243 0.873461 0.479444 0.873461 0.494859 0.999303 0.509356 0.873461 0.509084 0.999537 0.520929 0.999731 0.509356 0.873461 0.495243 0.873461 0.509084 0.999537 0.521065 0.873461 0.509356 0.873461 0.520929 0.999731 0.41647 0.938685 0.416455 0.913539 0.422741 0.914416 0.449447 0.815199 0.422741 0.914416 0.416455 0.913539 0.375615 0.905062 0.416455 0.913539 0.41647 0.938685 0.42871 0.812855 0.416455 0.913539 0.375615 0.905062 0.42871 0.812855 0.449447 0.815199 0.416455 0.913539 0.364597 0.931722 0.41647 0.938685 0.41647 0.959953 0.364504 0.901899 0.375615 0.905062 0.41647 0.938685 0.364597 0.931722 0.364504 0.901899 0.41647 0.938685 0.364597 0.956046 0.41647 0.959953 0.41647 0.977031 0.364597 0.956046 0.364597 0.931722 0.41647 0.959953 0.364596 0.974354 0.41647 0.977031 0.41647 0.989763 0.364596 0.974354 0.364597 0.956046 0.41647 0.977031 0.429802 0.998235 0.416412 0.998015 0.41647 0.989763 0.364596 0.986405 0.41647 0.989763 0.416412 0.998015 0.44564 0.998495 0.429802 0.998235 0.41647 0.989763 0.462317 0.998769 0.44564 0.998495 0.41647 0.989763 0.364596 0.986405 0.364596 0.974354 0.41647 0.989763 0.416227 0.873461 0.416412 0.998015 0.429802 0.998235 0.415687 0.998003 0.364596 0.986405 0.416412 0.998015 0.416227 0.873461 0.415687 0.998003 0.416412 0.998015 0.430395 0.873461 0.429802 0.998235 0.44564 0.998495 0.430395 0.873461 0.416227 0.873461 0.429802 0.998235 0.446187 0.873461 0.44564 0.998495 0.462317 0.998769 0.446187 0.873461 0.430395 0.873461 0.44564 0.998495 0.462811 0.873461 0.446187 0.873461 0.462317 0.998769 0.408105 0.80893 0.375615 0.905062 0.364504 0.901899 0.408105 0.80893 0.42871 0.812855 0.375615 0.905062 0.314043 0.910915 0.364504 0.901899 0.364597 0.931722 0.314043 0.910915 0.329984 0.889581 0.364504 0.901899 0.387871 0.803451 0.364504 0.901899 0.329984 0.889581 0.387871 0.803451 0.408105 0.80893 0.364504 0.901899 0.314043 0.934744 0.364597 0.931722 0.364597 0.956046 0.314043 0.934744 0.314043 0.910915 0.364597 0.931722 0.314043 0.953436 0.364597 0.956046 0.364596 0.974354 0.314043 0.953436 0.314043 0.934744 0.364597 0.956046 0.314043 0.966767 0.364596 0.974354 0.364596 0.986405 0.314043 0.966767 0.314043 0.953436 0.364596 0.974354 0.395216 0.997666 0.364596 0.992038 0.364596 0.986405 0.314043 0.97458 0.364596 0.986405 0.364596 0.992038 0.404028 0.997811 0.395216 0.997666 0.364596 0.986405 0.415687 0.998003 0.404028 0.997811 0.364596 0.986405 0.314043 0.97458 0.314043 0.966767 0.364596 0.986405 0.395298 0.997667 0.364596 0.991179 0.364596 0.992038 0.314043 0.976781 0.364596 0.992038 0.364596 0.991179 0.389767 0.997576 0.395298 0.997667 0.364596 0.992038 0.3879 0.997545 0.389767 0.997576 0.364596 0.992038 0.389752 0.997576 0.3879 0.997545 0.364596 0.992038 0.395216 0.997666 0.389752 0.997576 0.364596 0.992038 0.314043 0.976781 0.314043 0.97458 0.364596 0.992038 0.416435 0.998015 0.364596 0.983838 0.364596 0.991179 0.314043 0.973344 0.364596 0.991179 0.364596 0.983838 0.415993 0.998008 0.416435 0.998015 0.364596 0.991179 0.404221 0.997814 0.415993 0.998008 0.364596 0.991179 0.395298 0.997667 0.404221 0.997814 0.364596 0.991179 0.314043 0.973344 0.314043 0.976781 0.364596 0.991179 0.41647 0.988003 0.364596 0.970114 0.364596 0.983838 0.314043 0.96431 0.364596 0.983838 0.364596 0.970114 0.416435 0.998015 0.41647 0.988003 0.364596 0.983838 0.314043 0.96431 0.314043 0.973344 0.364596 0.983838 0.41647 0.971991 0.364596 0.950189 0.364596 0.970114 0.314043 0.949787 0.364596 0.970114 0.364596 0.950189 0.41647 0.988003 0.41647 0.971991 0.364596 0.970114 0.314043 0.949787 0.314043 0.96431 0.364596 0.970114 0.41647 0.950186 0.364596 0.924326 0.364596 0.950189 0.314043 0.929947 0.364596 0.950189 0.364596 0.924326 0.41647 0.971991 0.41647 0.950186 0.364596 0.950189 0.314043 0.929947 0.314043 0.949787 0.364596 0.950189 0.41647 0.922858 0.364596 0.892869 0.364596 0.924326 0.314043 0.905025 0.364596 0.924326 0.364596 0.892869 0.41647 0.950186 0.41647 0.922858 0.364596 0.924326 0.314043 0.905025 0.314043 0.929947 0.364596 0.924326 0.416469 0.890345 0.364596 0.856234 0.364596 0.892869 0.314043 0.875319 0.364596 0.892869 0.364596 0.856234 0.41647 0.922858 0.416469 0.890345 0.364596 0.892869 0.314043 0.875319 0.314043 0.905025 0.364596 0.892869 0.416469 0.853046 0.364596 0.814909 0.364596 0.856234 0.314043 0.841181 0.364596 0.856234 0.364596 0.814909 0.416469 0.890345 0.416469 0.853046 0.364596 0.856234 0.314043 0.841181 0.314043 0.875319 0.364596 0.856234 0.416469 0.811423 0.364596 0.76944 0.364596 0.814909 0.314043 0.803018 0.364596 0.814909 0.364596 0.76944 0.416469 0.853046 0.416469 0.811423 0.364596 0.814909 0.314043 0.803018 0.314043 0.841181 0.364596 0.814909 0.416469 0.765988 0.364596 0.720431 0.364596 0.76944 0.338661 0.737757 0.364596 0.76944 0.364596 0.720431 0.416469 0.811423 0.416469 0.765988 0.364596 0.76944 0.314043 0.761282 0.314043 0.803018 0.364596 0.76944 0.332759 0.738733 0.314043 0.761282 0.364596 0.76944 0.335765 0.738765 0.332759 0.738733 0.364596 0.76944 0.338661 0.737757 0.335765 0.738765 0.364596 0.76944 0.416469 0.717303 0.364596 0.668532 0.364596 0.720431 0.348626 0.711499 0.364596 0.720431 0.364596 0.668532 0.416469 0.765988 0.416469 0.717303 0.364596 0.720431 0.341498 0.73549 0.338661 0.737757 0.364596 0.720431 0.344069 0.731808 0.341498 0.73549 0.364596 0.720431 0.346192 0.726666 0.344069 0.731808 0.364596 0.720431 0.347753 0.719954 0.346192 0.726666 0.364596 0.720431 0.348626 0.711499 0.347753 0.719954 0.364596 0.720431 0.416469 0.665968 0.364596 0.614431 0.364596 0.668532 0.342717 0.641817 0.364596 0.668532 0.364596 0.614431 0.416469 0.717303 0.416469 0.665968 0.364596 0.668532 0.348644 0.70107 0.348626 0.711499 0.364596 0.668532 0.347584 0.688374 0.348644 0.70107 0.364596 0.668532 0.342717 0.641817 0.347584 0.688374 0.364596 0.668532 0.416469 0.612617 0.364596 0.558845 0.364596 0.614431 0.339263 0.593917 0.364596 0.614431 0.364596 0.558845 0.416469 0.665968 0.416469 0.612617 0.364596 0.614431 0.339263 0.593917 0.342717 0.641817 0.364596 0.614431 0.404724 0.502513 0.364596 0.502513 0.364596 0.558845 0.314043 0.548442 0.364596 0.558845 0.364596 0.502513 0.416469 0.502513 0.404724 0.502513 0.364596 0.558845 0.416469 0.557907 0.416469 0.502513 0.364596 0.558845 0.416469 0.612617 0.416469 0.557907 0.364596 0.558845 0.31892 0.593917 0.339263 0.593917 0.364596 0.558845 0.314042 0.593917 0.31892 0.593917 0.364596 0.558845 0.314043 0.548442 0.314042 0.593917 0.364596 0.558845 0.416469 0.445459 0.364596 0.502513 0.404724 0.502513 0.353978 0.502513 0.314043 0.548442 0.364596 0.502513 0.364596 0.44619 0.353978 0.502513 0.364596 0.502513 0.416469 0.445459 0.364596 0.44619 0.364596 0.502513 0.416469 0.445459 0.404724 0.502513 0.416469 0.502513 0.456258 0.502513 0.416469 0.502513 0.416469 0.557907 0.469011 0.445198 0.416469 0.502513 0.456258 0.502513 0.469011 0.445198 0.416469 0.445459 0.416469 0.502513 0.469011 0.610905 0.416469 0.557907 0.416469 0.612617 0.469011 0.55703 0.416469 0.557907 0.469011 0.610905 0.469011 0.502513 0.416469 0.557907 0.469011 0.55703 0.456258 0.502513 0.416469 0.557907 0.469011 0.502513 0.469011 0.663501 0.416469 0.612617 0.416469 0.665968 0.469011 0.610905 0.416469 0.612617 0.469011 0.663501 0.469011 0.714198 0.416469 0.665968 0.416469 0.717303 0.469011 0.663501 0.416469 0.665968 0.469011 0.714198 0.469011 0.762398 0.416469 0.717303 0.416469 0.765988 0.469011 0.714198 0.416469 0.717303 0.469011 0.762398 0.469011 0.807533 0.416469 0.765988 0.416469 0.811423 0.469011 0.762398 0.416469 0.765988 0.469011 0.807533 0.469011 0.84907 0.416469 0.811423 0.416469 0.853046 0.469011 0.807533 0.416469 0.811423 0.469011 0.84907 0.469011 0.886519 0.416469 0.853046 0.416469 0.890345 0.469011 0.84907 0.416469 0.853046 0.469011 0.886519 0.469011 0.91944 0.416469 0.890345 0.41647 0.922858 0.469011 0.886519 0.416469 0.890345 0.469011 0.91944 0.469012 0.947442 0.41647 0.922858 0.41647 0.950186 0.469011 0.91944 0.41647 0.922858 0.469012 0.947442 0.469012 0.970197 0.41647 0.950186 0.41647 0.971991 0.469012 0.947442 0.41647 0.950186 0.469012 0.970197 0.469012 0.987435 0.41647 0.971991 0.41647 0.988003 0.469012 0.970197 0.41647 0.971991 0.469012 0.987435 0.430159 0.998241 0.41647 0.988003 0.416435 0.998015 0.462654 0.998775 0.469012 0.987435 0.41647 0.988003 0.445986 0.998501 0.462654 0.998775 0.41647 0.988003 0.430159 0.998241 0.445986 0.998501 0.41647 0.988003 0.430024 0.873461 0.416435 0.998015 0.415993 0.998008 0.430024 0.873461 0.430159 0.998241 0.416435 0.998015 0.415911 0.873461 0.415993 0.998008 0.404221 0.997814 0.415911 0.873461 0.430024 0.873461 0.415993 0.998008 0.404202 0.873461 0.404221 0.997814 0.395298 0.997667 0.404202 0.873461 0.415911 0.873461 0.404221 0.997814 0.389781 0.873461 0.395298 0.997667 0.389767 0.997576 0.395314 0.873461 0.404202 0.873461 0.395298 0.997667 0.389781 0.873461 0.395314 0.873461 0.395298 0.997667 0.389781 0.873461 0.389767 0.997576 0.3879 0.997545 0.3879 0.873461 0.3879 0.997545 0.389752 0.997576 0.3879 0.873461 0.389781 0.873461 0.3879 0.997545 0.389797 0.873461 0.389752 0.997576 0.395216 0.997666 0.389797 0.873461 0.3879 0.873461 0.389752 0.997576 0.395398 0.873461 0.395216 0.997666 0.404028 0.997811 0.395398 0.873461 0.389797 0.873461 0.395216 0.997666 0.404401 0.873461 0.404028 0.997811 0.415687 0.998003 0.404401 0.873461 0.395398 0.873461 0.404028 0.997811 0.416227 0.873461 0.404401 0.873461 0.415687 0.998003 0.314043 0.910915 0.313879 0.882472 0.329984 0.889581 0.367959 0.796409 0.329984 0.889581 0.313879 0.882472 0.367959 0.796409 0.387871 0.803451 0.329984 0.889581 0.265445 0.884486 0.313879 0.882472 0.314043 0.910915 0.265445 0.884486 0.286899 0.868439 0.313879 0.882472 0.348611 0.787884 0.313879 0.882472 0.286899 0.868439 0.348611 0.787884 0.367959 0.796409 0.313879 0.882472 0.265444 0.909342 0.314043 0.910915 0.314043 0.934744 0.265444 0.909342 0.265445 0.884486 0.314043 0.910915 0.265444 0.929056 0.314043 0.934744 0.314043 0.953436 0.265444 0.929056 0.265444 0.909342 0.314043 0.934744 0.265444 0.943378 0.314043 0.953436 0.314043 0.966767 0.265444 0.943378 0.265444 0.929056 0.314043 0.953436 0.265444 0.952128 0.314043 0.966767 0.314043 0.97458 0.265444 0.952128 0.265444 0.943378 0.314043 0.966767 0.265444 0.955194 0.314043 0.97458 0.314043 0.976781 0.265444 0.955194 0.265444 0.952128 0.314043 0.97458 0.265444 0.952539 0.314043 0.976781 0.314043 0.973344 0.265444 0.952539 0.265444 0.955194 0.314043 0.976781 0.265444 0.944194 0.314043 0.973344 0.314043 0.96431 0.265444 0.944194 0.265444 0.952539 0.314043 0.973344 0.265444 0.930267 0.314043 0.96431 0.314043 0.949787 0.265444 0.930267 0.265444 0.944194 0.314043 0.96431 0.265444 0.910933 0.314043 0.949787 0.314043 0.929947 0.265444 0.910933 0.265444 0.930267 0.314043 0.949787 0.265444 0.910933 0.314043 0.929947 0.314043 0.905025 0.265444 0.886437 0.314043 0.905025 0.314043 0.875319 0.265444 0.886437 0.265444 0.910933 0.314043 0.905025 0.265444 0.857087 0.314043 0.875319 0.314043 0.841181 0.265444 0.857087 0.265444 0.886437 0.314043 0.875319 0.265444 0.823256 0.314043 0.841181 0.314043 0.803018 0.265444 0.823256 0.265444 0.857087 0.314043 0.841181 0.265444 0.78537 0.314043 0.803018 0.314043 0.761282 0.265444 0.78537 0.265444 0.823256 0.314043 0.803018 0.315324 0.719827 0.314005 0.716685 0.314043 0.761282 0.265444 0.743909 0.314043 0.761282 0.314005 0.716685 0.318786 0.726511 0.315324 0.719827 0.314043 0.761282 0.322393 0.731647 0.318786 0.726511 0.314043 0.761282 0.326045 0.735353 0.322393 0.731647 0.314043 0.761282 0.329544 0.737661 0.326045 0.735353 0.314043 0.761282 0.332759 0.738733 0.329544 0.737661 0.314043 0.761282 0.265444 0.743909 0.265444 0.78537 0.314043 0.761282 0.315012 0.593917 0.314005 0.716685 0.315324 0.719827 0.312122 0.711412 0.265444 0.743909 0.314005 0.716685 0.312496 0.593917 0.312122 0.711412 0.314005 0.716685 0.312496 0.593917 0.314005 0.716685 0.315012 0.593917 0.317823 0.593917 0.315324 0.719827 0.318786 0.726511 0.315012 0.593917 0.315324 0.719827 0.317823 0.593917 0.320866 0.593917 0.318786 0.726511 0.322393 0.731647 0.317823 0.593917 0.318786 0.726511 0.320866 0.593917 0.324049 0.593917 0.322393 0.731647 0.326045 0.735353 0.320866 0.593917 0.322393 0.731647 0.324049 0.593917 0.327402 0.593917 0.326045 0.735353 0.329544 0.737661 0.324049 0.593917 0.326045 0.735353 0.327402 0.593917 0.327402 0.593917 0.329544 0.737661 0.332759 0.738733 0.333177 0.593917 0.332759 0.738733 0.335765 0.738765 0.327402 0.593917 0.332759 0.738733 0.333177 0.593917 0.338479 0.593917 0.335765 0.738765 0.338661 0.737757 0.333177 0.593917 0.335765 0.738765 0.338479 0.593917 0.338479 0.593917 0.338661 0.737757 0.341498 0.73549 0.342959 0.593917 0.341498 0.73549 0.344069 0.731808 0.338479 0.593917 0.341498 0.73549 0.342959 0.593917 0.342959 0.593917 0.344069 0.731808 0.346192 0.726666 0.3463 0.593917 0.346192 0.726666 0.347753 0.719954 0.342959 0.593917 0.346192 0.726666 0.3463 0.593917 0.348269 0.593917 0.347753 0.719954 0.348626 0.711499 0.3463 0.593917 0.347753 0.719954 0.348269 0.593917 0.348716 0.593917 0.348626 0.711499 0.348644 0.70107 0.348269 0.593917 0.348626 0.711499 0.348716 0.593917 0.348716 0.593917 0.348644 0.70107 0.347584 0.688374 0.339263 0.593917 0.347584 0.688374 0.342717 0.641817 0.347584 0.593917 0.347584 0.688374 0.339263 0.593917 0.348716 0.593917 0.347584 0.688374 0.347584 0.593917 0.314042 0.593917 0.339263 0.593917 0.31892 0.593917 0.2989 0.593917 0.339263 0.593917 0.314042 0.593917 0.347584 0.593917 0.339263 0.593917 0.2989 0.593917 0.265444 0.553328 0.314042 0.593917 0.314043 0.548442 0.2989 0.593917 0.314042 0.593917 0.265444 0.553328 0.353978 0.502513 0.314043 0.502513 0.314043 0.548442 0.265444 0.553328 0.314043 0.548442 0.314043 0.502513 0.364596 0.44619 0.314043 0.502513 0.353978 0.502513 0.304635 0.502513 0.265444 0.553328 0.314043 0.502513 0.314043 0.450136 0.304635 0.502513 0.314043 0.502513 0.364596 0.44619 0.314043 0.450136 0.314043 0.502513 0.265445 0.884486 0.265222 0.855053 0.286899 0.868439 0.329822 0.77786 0.286899 0.868439 0.265222 0.855053 0.329822 0.77786 0.348611 0.787884 0.286899 0.868439 0.21941 0.849599 0.265222 0.855053 0.265445 0.884486 0.21941 0.849599 0.247097 0.842244 0.265222 0.855053 0.311742 0.766426 0.265222 0.855053 0.247097 0.842244 0.311742 0.766426 0.329822 0.77786 0.265222 0.855053 0.21941 0.875551 0.265445 0.884486 0.265444 0.909342 0.21941 0.875551 0.21941 0.849599 0.265445 0.884486 0.21941 0.896565 0.265444 0.909342 0.265444 0.929056 0.21941 0.896565 0.21941 0.875551 0.265444 0.909342 0.21941 0.912362 0.265444 0.929056 0.265444 0.943378 0.21941 0.912362 0.21941 0.896565 0.265444 0.929056 0.21941 0.922734 0.265444 0.943378 0.265444 0.952128 0.21941 0.922734 0.21941 0.912362 0.265444 0.943378 0.21941 0.927544 0.265444 0.952128 0.265444 0.955194 0.21941 0.927544 0.21941 0.922734 0.265444 0.952128 0.21941 0.926727 0.265444 0.955194 0.265444 0.952539 0.21941 0.926727 0.21941 0.927544 0.265444 0.955194 0.21941 0.920294 0.265444 0.952539 0.265444 0.944194 0.21941 0.920294 0.21941 0.926727 0.265444 0.952539 0.21941 0.908331 0.265444 0.944194 0.265444 0.930267 0.21941 0.908331 0.21941 0.920294 0.265444 0.944194 0.21941 0.890996 0.265444 0.930267 0.265444 0.910933 0.21941 0.890996 0.21941 0.908331 0.265444 0.930267 0.21941 0.868518 0.265444 0.910933 0.265444 0.886437 0.21941 0.868518 0.21941 0.890996 0.265444 0.910933 0.21941 0.841195 0.265444 0.886437 0.265444 0.857087 0.21941 0.841195 0.21941 0.868518 0.265444 0.886437 0.21941 0.809389 0.265444 0.857087 0.265444 0.823256 0.21941 0.809389 0.21941 0.841195 0.265444 0.857087 0.21941 0.77352 0.265444 0.823256 0.265444 0.78537 0.21941 0.77352 0.21941 0.809389 0.265444 0.823256 0.21941 0.734064 0.265444 0.78537 0.265444 0.743909 0.21941 0.734064 0.21941 0.77352 0.265444 0.78537 0.312122 0.711412 0.265444 0.699396 0.265444 0.743909 0.21941 0.691543 0.265444 0.743909 0.265444 0.699396 0.21941 0.691543 0.21941 0.734064 0.265444 0.743909 0.30722 0.688374 0.265444 0.652395 0.265444 0.699396 0.21941 0.646519 0.265444 0.699396 0.265444 0.652395 0.309344 0.701035 0.30722 0.688374 0.265444 0.699396 0.312122 0.711412 0.309344 0.701035 0.265444 0.699396 0.21941 0.646519 0.21941 0.691543 0.265444 0.699396 0.302353 0.641812 0.265444 0.6035 0.265444 0.652395 0.21941 0.59959 0.265444 0.652395 0.265444 0.6035 0.30722 0.688374 0.302353 0.641812 0.265444 0.652395 0.21941 0.59959 0.21941 0.646519 0.265444 0.652395 0.2989 0.593917 0.265444 0.553328 0.265444 0.6035 0.21941 0.551375 0.265444 0.6035 0.265444 0.553328 0.302353 0.641812 0.2989 0.593917 0.265444 0.6035 0.21941 0.551375 0.21941 0.59959 0.265444 0.6035 0.304635 0.502513 0.265444 0.502513 0.265444 0.553328 0.21941 0.551375 0.265444 0.553328 0.265444 0.502513 0.314043 0.450136 0.265444 0.502513 0.304635 0.502513 0.257293 0.502513 0.21941 0.551375 0.265444 0.502513 0.265444 0.4517 0.257293 0.502513 0.265444 0.502513 0.314043 0.450136 0.265444 0.4517 0.265444 0.502513 0.30722 0.593917 0.2989 0.593917 0.302353 0.641812 0.30722 0.593917 0.347584 0.593917 0.2989 0.593917 0.30722 0.593917 0.302353 0.641812 0.30722 0.688374 0.30722 0.593917 0.30722 0.688374 0.309344 0.701035 0.310324 0.593917 0.309344 0.701035 0.312122 0.711412 0.308574 0.593917 0.309344 0.701035 0.310324 0.593917 0.30722 0.593917 0.309344 0.701035 0.308574 0.593917 0.310324 0.593917 0.312122 0.711412 0.312496 0.593917 0.21941 0.849599 0.2191849 0.819198 0.247097 0.842244 0.294485 0.753628 0.247097 0.842244 0.2191849 0.819198 0.294485 0.753628 0.311742 0.766426 0.247097 0.842244 0.176518 0.804053 0.2191849 0.819198 0.21941 0.849599 0.176518 0.804053 0.211538 0.812083 0.2191849 0.819198 0.27807 0.7395 0.2191849 0.819198 0.211538 0.812083 0.27807 0.7395 0.294485 0.753628 0.2191849 0.819198 0.176518 0.830572 0.21941 0.849599 0.21941 0.875551 0.176518 0.830572 0.176518 0.804053 0.21941 0.849599 0.176518 0.852884 0.21941 0.875551 0.21941 0.896565 0.176518 0.852884 0.176518 0.830572 0.21941 0.875551 0.176518 0.870702 0.21941 0.896565 0.21941 0.912362 0.176518 0.870702 0.176518 0.852884 0.21941 0.896565 0.176518 0.883798 0.21941 0.912362 0.21941 0.922734 0.176518 0.883798 0.176518 0.870702 0.21941 0.912362 0.176518 0.892003 0.21941 0.922734 0.21941 0.927544 0.176518 0.892003 0.176518 0.883798 0.21941 0.922734 0.176518 0.895213 0.21941 0.927544 0.21941 0.926727 0.176518 0.895213 0.176518 0.892003 0.21941 0.927544 0.176518 0.893386 0.21941 0.926727 0.21941 0.920294 0.176518 0.893386 0.176518 0.895213 0.21941 0.926727 0.176518 0.886545 0.21941 0.920294 0.21941 0.908331 0.176518 0.886545 0.176518 0.893386 0.21941 0.920294 0.176518 0.87478 0.21941 0.908331 0.21941 0.890996 0.176518 0.87478 0.176518 0.886545 0.21941 0.908331 0.176518 0.858239 0.21941 0.890996 0.21941 0.868518 0.176518 0.858239 0.176518 0.87478 0.21941 0.890996 0.176518 0.837136 0.21941 0.868518 0.21941 0.841195 0.176518 0.837136 0.176518 0.858239 0.21941 0.868518 0.176518 0.811742 0.21941 0.841195 0.21941 0.809389 0.176518 0.811742 0.176518 0.837136 0.21941 0.841195 0.176518 0.782381 0.21941 0.809389 0.21941 0.77352 0.176518 0.782381 0.176518 0.811742 0.21941 0.809389 0.176518 0.74943 0.21941 0.77352 0.21941 0.734064 0.176518 0.74943 0.176518 0.782381 0.21941 0.77352 0.176518 0.713313 0.21941 0.734064 0.21941 0.691543 0.176518 0.713313 0.176518 0.74943 0.21941 0.734064 0.176518 0.674492 0.21941 0.691543 0.21941 0.646519 0.176518 0.674492 0.176518 0.713313 0.21941 0.691543 0.176518 0.633465 0.21941 0.646519 0.21941 0.59959 0.176518 0.633465 0.176518 0.674492 0.21941 0.646519 0.176518 0.590759 0.21941 0.59959 0.21941 0.551375 0.176518 0.590759 0.176518 0.633465 0.21941 0.59959 0.257293 0.502513 0.21941 0.502513 0.21941 0.551375 0.176518 0.546921 0.21941 0.551375 0.21941 0.502513 0.176518 0.546921 0.176518 0.590759 0.21941 0.551375 0.265444 0.4517 0.21941 0.502513 0.257293 0.502513 0.212526 0.502513 0.176518 0.546921 0.21941 0.502513 0.21941 0.453646 0.212526 0.502513 0.21941 0.502513 0.265444 0.4517 0.21941 0.453646 0.21941 0.502513 0.176518 0.804053 0.180719 0.77913 0.211538 0.812083 0.262696 0.724185 0.211538 0.812083 0.180719 0.77913 0.262696 0.724185 0.27807 0.7395 0.211538 0.812083 0.176518 0.804053 0.176274 0.773716 0.180719 0.77913 0.2483209 0.707649 0.180719 0.77913 0.176274 0.773716 0.2483209 0.707649 0.262696 0.724185 0.180719 0.77913 0.137307 0.773061 0.176274 0.773716 0.176518 0.804053 0.137307 0.745859 0.154843 0.744626 0.176274 0.773716 0.235183 0.690209 0.176274 0.773716 0.154843 0.744626 0.137307 0.773061 0.137307 0.745859 0.176274 0.773716 0.235183 0.690209 0.2483209 0.707649 0.176274 0.773716 0.137307 0.796922 0.176518 0.804053 0.176518 0.830572 0.137307 0.796922 0.137307 0.773061 0.176518 0.804053 0.137307 0.817148 0.176518 0.830572 0.176518 0.852884 0.137307 0.817148 0.137307 0.796922 0.176518 0.830572 0.137307 0.833489 0.176518 0.852884 0.176518 0.870702 0.137307 0.833489 0.137307 0.817148 0.176518 0.852884 0.137307 0.845744 0.176518 0.870702 0.176518 0.883798 0.137307 0.845744 0.137307 0.833489 0.176518 0.870702 0.137307 0.85376 0.176518 0.883798 0.176518 0.892003 0.137307 0.85376 0.137307 0.845744 0.176518 0.883798 0.137307 0.857439 0.176518 0.892003 0.176518 0.895213 0.137307 0.857439 0.137307 0.85376 0.176518 0.892003 0.137307 0.856735 0.176518 0.895213 0.176518 0.893386 0.137307 0.856735 0.137307 0.857439 0.176518 0.895213 0.137307 0.851658 0.176518 0.893386 0.176518 0.886545 0.137307 0.851658 0.137307 0.856735 0.176518 0.893386 0.137307 0.842269 0.176518 0.886545 0.176518 0.87478 0.137307 0.842269 0.137307 0.851658 0.176518 0.886545 0.137307 0.828686 0.176518 0.87478 0.176518 0.858239 0.137307 0.828686 0.137307 0.842269 0.176518 0.87478 0.137307 0.811074 0.176518 0.858239 0.176518 0.837136 0.137307 0.811074 0.137307 0.828686 0.176518 0.858239 0.137307 0.789653 0.176518 0.837136 0.176518 0.811742 0.137307 0.789653 0.137307 0.811074 0.176518 0.837136 0.137307 0.764686 0.176518 0.811742 0.176518 0.782381 0.137307 0.764686 0.137307 0.789653 0.176518 0.811742 0.137367 0.736643 0.176518 0.782381 0.176518 0.74943 0.137367 0.736643 0.137307 0.764686 0.176518 0.782381 0.137427 0.719892 0.176518 0.74943 0.176518 0.713313 0.13782 0.735399 0.137367 0.736643 0.176518 0.74943 0.138365 0.73172 0.13782 0.735399 0.176518 0.74943 0.1382589 0.726586 0.138365 0.73172 0.176518 0.74943 0.137427 0.719892 0.1382589 0.726586 0.176518 0.74943 0.137307 0.687263 0.176518 0.713313 0.176518 0.674492 0.137336 0.719339 0.137427 0.719892 0.176518 0.713313 0.137307 0.687263 0.137336 0.719339 0.176518 0.713313 0.137307 0.653036 0.176518 0.674492 0.176518 0.633465 0.137307 0.653036 0.137307 0.687263 0.176518 0.674492 0.137307 0.617009 0.176518 0.633465 0.176518 0.590759 0.137307 0.617009 0.137307 0.653036 0.176518 0.633465 0.137307 0.579613 0.176518 0.590759 0.176518 0.546921 0.137307 0.579613 0.137307 0.617009 0.176518 0.590759 0.212526 0.502513 0.176518 0.502513 0.176518 0.546921 0.137307 0.541295 0.176518 0.546921 0.176518 0.502513 0.137307 0.541295 0.137307 0.579613 0.176518 0.546921 0.21941 0.453646 0.176518 0.502513 0.212526 0.502513 0.170877 0.502513 0.137307 0.541295 0.176518 0.502513 0.176518 0.458116 0.170877 0.502513 0.176518 0.502513 0.21941 0.453646 0.176518 0.458116 0.176518 0.502513 0.137307 0.745859 0.137072 0.715675 0.154843 0.744626 0.209277 0.696675 0.154843 0.744626 0.137072 0.715675 0.209277 0.696675 0.235183 0.690209 0.154843 0.744626 0.135567 0.72102 0.137072 0.715675 0.137307 0.745859 0.134904 0.715756 0.133843 0.709795 0.137072 0.715675 0.1929309 0.677247 0.137072 0.715675 0.133843 0.709795 0.135567 0.72102 0.134904 0.715756 0.137072 0.715675 0.208057 0.696361 0.209277 0.696675 0.137072 0.715675 0.206293 0.695128 0.208057 0.696361 0.137072 0.715675 0.203889 0.692777 0.206293 0.695128 0.137072 0.715675 0.200815 0.6891 0.203889 0.692777 0.137072 0.715675 0.197138 0.68397 0.200815 0.6891 0.137072 0.715675 0.1929309 0.677247 0.197138 0.68397 0.137072 0.715675 0.102269 0.737057 0.137307 0.745859 0.137307 0.773061 0.135808 0.725569 0.135567 0.72102 0.137307 0.745859 0.135582 0.729344 0.135808 0.725569 0.137307 0.745859 0.134834 0.732217 0.135582 0.729344 0.137307 0.745859 0.133544 0.734003 0.134834 0.732217 0.137307 0.745859 0.131757 0.734598 0.133544 0.734003 0.137307 0.745859 0.129513 0.733977 0.131757 0.734598 0.137307 0.745859 0.12686 0.732148 0.129513 0.733977 0.137307 0.745859 0.102269 0.71223 0.12686 0.732148 0.137307 0.745859 0.102269 0.737057 0.102269 0.71223 0.137307 0.745859 0.102269 0.758907 0.137307 0.773061 0.137307 0.796922 0.102269 0.758907 0.102269 0.737057 0.137307 0.773061 0.102269 0.777503 0.137307 0.796922 0.137307 0.817148 0.102269 0.777503 0.102269 0.758907 0.137307 0.796922 0.102269 0.792608 0.137307 0.817148 0.137307 0.833489 0.102269 0.792608 0.102269 0.777503 0.137307 0.817148 0.102269 0.804033 0.137307 0.833489 0.137307 0.845744 0.102269 0.804033 0.102269 0.792608 0.137307 0.833489 0.102269 0.81163 0.137307 0.845744 0.137307 0.85376 0.102269 0.81163 0.102269 0.804033 0.137307 0.845744 0.102269 0.815305 0.137307 0.85376 0.137307 0.857439 0.102269 0.815305 0.102269 0.81163 0.137307 0.85376 0.102269 0.815009 0.137307 0.857439 0.137307 0.856735 0.102269 0.815009 0.102269 0.815305 0.137307 0.857439 0.102269 0.810748 0.137307 0.856735 0.137307 0.851658 0.102269 0.810748 0.102269 0.815009 0.137307 0.856735 0.102269 0.802575 0.137307 0.851658 0.137307 0.842269 0.102269 0.802575 0.102269 0.810748 0.137307 0.851658 0.102269 0.790593 0.137307 0.842269 0.137307 0.828686 0.102269 0.790593 0.102269 0.802575 0.137307 0.842269 0.102269 0.774955 0.137307 0.828686 0.137307 0.811074 0.102269 0.774955 0.102269 0.790593 0.137307 0.828686 0.102269 0.75586 0.137307 0.811074 0.137307 0.789653 0.102269 0.75586 0.102269 0.774955 0.137307 0.811074 0.102269 0.75586 0.137307 0.789653 0.137307 0.764686 0.13673 0.737689 0.137307 0.764686 0.137367 0.736643 0.102269 0.733549 0.102269 0.75586 0.137307 0.764686 0.133369 0.738755 0.102269 0.733549 0.137307 0.764686 0.135227 0.738746 0.133369 0.738755 0.137307 0.764686 0.13673 0.737689 0.135227 0.738746 0.137307 0.764686 0.136246 0.593917 0.137367 0.736643 0.13782 0.735399 0.136246 0.593917 0.13673 0.737689 0.137367 0.736643 0.138074 0.593917 0.13782 0.735399 0.138365 0.73172 0.136246 0.593917 0.13782 0.735399 0.138074 0.593917 0.138289 0.593917 0.138365 0.73172 0.1382589 0.726586 0.138074 0.593917 0.138365 0.73172 0.138289 0.593917 0.138289 0.593917 0.1382589 0.726586 0.137427 0.719892 0.138289 0.593917 0.137427 0.719892 0.137336 0.719339 0.135784 0.711462 0.137336 0.719339 0.137307 0.687263 0.136866 0.593917 0.137336 0.719339 0.135784 0.711462 0.138289 0.593917 0.137336 0.719339 0.136866 0.593917 0.123076 0.665027 0.137307 0.687263 0.137307 0.653036 0.133222 0.70106 0.135784 0.711462 0.137307 0.687263 0.129603 0.688374 0.133222 0.70106 0.137307 0.687263 0.123076 0.665027 0.129603 0.688374 0.137307 0.687263 0.1174679 0.641466 0.137307 0.653036 0.137307 0.617009 0.1174679 0.641466 0.123076 0.665027 0.137307 0.653036 0.108987 0.593917 0.137307 0.617009 0.137307 0.579613 0.112773 0.617746 0.1174679 0.641466 0.137307 0.617009 0.108987 0.593917 0.112773 0.617746 0.137307 0.617009 0.102269 0.564014 0.137307 0.579613 0.137307 0.541295 0.10226 0.593917 0.137307 0.579613 0.102269 0.564014 0.108987 0.593917 0.137307 0.579613 0.10226 0.593917 0.170877 0.502513 0.137307 0.502513 0.137307 0.541295 0.102269 0.533414 0.137307 0.541295 0.137307 0.502513 0.102269 0.564014 0.137307 0.541295 0.102269 0.533414 0.176518 0.458116 0.137307 0.502513 0.170877 0.502513 0.13285 0.502513 0.102269 0.533414 0.137307 0.502513 0.137307 0.462262 0.13285 0.502513 0.137307 0.502513 0.176518 0.458116 0.137307 0.462262 0.137307 0.502513 0.133746 0.593917 0.133843 0.709795 0.134904 0.715756 0.1929309 0.677247 0.133843 0.709795 0.132122 0.704745 0.133746 0.593917 0.132122 0.704745 0.133843 0.709795 0.135545 0.593917 0.134904 0.715756 0.135567 0.72102 0.133746 0.593917 0.134904 0.715756 0.135545 0.593917 0.135545 0.593917 0.135567 0.72102 0.135808 0.725569 0.1356199 0.593917 0.135808 0.725569 0.135582 0.729344 0.135545 0.593917 0.135808 0.725569 0.1356199 0.593917 0.1356199 0.593917 0.135582 0.729344 0.134834 0.732217 0.133969 0.593917 0.134834 0.732217 0.133544 0.734003 0.1356199 0.593917 0.134834 0.732217 0.133969 0.593917 0.133969 0.593917 0.133544 0.734003 0.131757 0.734598 0.130721 0.593917 0.131757 0.734598 0.129513 0.733977 0.133969 0.593917 0.131757 0.734598 0.130721 0.593917 0.130721 0.593917 0.129513 0.733977 0.12686 0.732148 0.102269 0.71223 0.123953 0.729214 0.12686 0.732148 0.1261309 0.593917 0.12686 0.732148 0.123953 0.729214 0.130721 0.593917 0.12686 0.732148 0.1261309 0.593917 0.102269 0.71223 0.120956 0.725375 0.123953 0.729214 0.1261309 0.593917 0.123953 0.729214 0.120956 0.725375 0.102269 0.71223 0.117928 0.720758 0.120956 0.725375 0.120564 0.593917 0.120956 0.725375 0.117928 0.720758 0.1261309 0.593917 0.120956 0.725375 0.120564 0.593917 0.102269 0.71223 0.114899 0.715419 0.117928 0.720758 0.120564 0.593917 0.117928 0.720758 0.114899 0.715419 0.102269 0.71223 0.1118929 0.709382 0.114899 0.715419 0.1144559 0.593917 0.114899 0.715419 0.1118929 0.709382 0.120564 0.593917 0.114899 0.715419 0.1144559 0.593917 0.102269 0.71223 0.108929 0.702626 0.1118929 0.709382 0.111668 0.593917 0.1118929 0.709382 0.108929 0.702626 0.1144559 0.593917 0.1118929 0.709382 0.111668 0.593917 0.102269 0.71223 0.10201 0.684878 0.108929 0.702626 0.08523297 0.630358 0.108929 0.702626 0.10201 0.684878 0.08104395 0.612151 0.108929 0.702626 0.08523297 0.630358 0.07754099 0.593917 0.108929 0.702626 0.08104395 0.612151 0.108929 0.593917 0.108929 0.702626 0.07754099 0.593917 0.111668 0.593917 0.108929 0.702626 0.108929 0.593917 0.07184296 0.669106 0.10201 0.684878 0.102269 0.71223 0.08523297 0.630358 0.10201 0.684878 0.09566998 0.666688 0.07184296 0.644669 0.09566998 0.666688 0.10201 0.684878 0.07184296 0.669106 0.07184296 0.644669 0.10201 0.684878 0.07184296 0.691448 0.102269 0.71223 0.102269 0.737057 0.07184296 0.691448 0.07184296 0.669106 0.102269 0.71223 0.07184296 0.711414 0.102269 0.737057 0.102269 0.758907 0.07184296 0.711414 0.07184296 0.691448 0.102269 0.737057 0.07184296 0.728753 0.102269 0.758907 0.102269 0.777503 0.07184296 0.728753 0.07184296 0.711414 0.102269 0.758907 0.07184296 0.743247 0.102269 0.777503 0.102269 0.792608 0.07184296 0.743247 0.07184296 0.728753 0.102269 0.777503 0.07184296 0.754713 0.102269 0.792608 0.102269 0.804033 0.07184296 0.754713 0.07184296 0.743247 0.102269 0.792608 0.07184296 0.763008 0.102269 0.804033 0.102269 0.81163 0.07184296 0.763008 0.07184296 0.754713 0.102269 0.804033 0.07184296 0.768027 0.102269 0.81163 0.102269 0.815305 0.07184296 0.768027 0.07184296 0.763008 0.102269 0.81163 0.07184296 0.769707 0.102269 0.815305 0.102269 0.815009 0.07184296 0.769707 0.07184296 0.768027 0.102269 0.815305 0.07184296 0.768027 0.102269 0.815009 0.102269 0.810748 0.07184296 0.768027 0.07184296 0.769707 0.102269 0.815009 0.07184296 0.763008 0.102269 0.810748 0.102269 0.802575 0.07184296 0.763008 0.07184296 0.768027 0.102269 0.810748 0.07184296 0.754713 0.102269 0.802575 0.102269 0.790593 0.07184296 0.754713 0.07184296 0.763008 0.102269 0.802575 0.07184296 0.743247 0.102269 0.790593 0.102269 0.774955 0.07184296 0.743247 0.07184296 0.754713 0.102269 0.790593 0.07184296 0.728753 0.102269 0.774955 0.102269 0.75586 0.07184296 0.728753 0.07184296 0.743247 0.102269 0.774955 0.07184296 0.711414 0.102269 0.75586 0.102269 0.733549 0.07184296 0.711414 0.07184296 0.728753 0.102269 0.75586 0.121406 0.726856 0.102269 0.708306 0.102269 0.733549 0.07184296 0.691448 0.102269 0.733549 0.102269 0.708306 0.1250399 0.731902 0.121406 0.726856 0.102269 0.733549 0.1282989 0.735499 0.1250399 0.731902 0.102269 0.733549 0.131083 0.737728 0.1282989 0.735499 0.102269 0.733549 0.133369 0.738755 0.131083 0.737728 0.102269 0.733549 0.07184296 0.691448 0.07184296 0.711414 0.102269 0.733549 0.104504 0.688374 0.102187 0.680477 0.102269 0.708306 0.07184296 0.669106 0.102269 0.708306 0.102187 0.680477 0.108897 0.701351 0.104504 0.688374 0.102269 0.708306 0.113265 0.711838 0.108897 0.701351 0.102269 0.708306 0.117463 0.72024 0.113265 0.711838 0.102269 0.708306 0.121406 0.726856 0.117463 0.72024 0.102269 0.708306 0.07184296 0.669106 0.07184296 0.691448 0.102269 0.708306 0.104504 0.593917 0.102187 0.680477 0.104504 0.688374 0.07184296 0.644669 0.07184296 0.669106 0.102187 0.680477 0.09795796 0.664956 0.07184296 0.644669 0.102187 0.680477 0.104504 0.593917 0.09795796 0.664956 0.102187 0.680477 0.104504 0.593917 0.104504 0.688374 0.108897 0.701351 0.112614 0.593917 0.108897 0.701351 0.113265 0.711838 0.108369 0.593917 0.108897 0.701351 0.112614 0.593917 0.104504 0.593917 0.108897 0.701351 0.108369 0.593917 0.117053 0.593917 0.113265 0.711838 0.117463 0.72024 0.112614 0.593917 0.113265 0.711838 0.117053 0.593917 0.117053 0.593917 0.117463 0.72024 0.121406 0.726856 0.122979 0.593917 0.121406 0.726856 0.1250399 0.731902 0.117053 0.593917 0.121406 0.726856 0.122979 0.593917 0.122979 0.593917 0.1250399 0.731902 0.1282989 0.735499 0.128408 0.593917 0.1282989 0.735499 0.131083 0.737728 0.122979 0.593917 0.1282989 0.735499 0.128408 0.593917 0.132943 0.593917 0.131083 0.737728 0.133369 0.738755 0.128408 0.593917 0.131083 0.737728 0.132943 0.593917 0.132943 0.593917 0.133369 0.738755 0.135227 0.738746 0.136246 0.593917 0.135227 0.738746 0.13673 0.737689 0.132943 0.593917 0.135227 0.738746 0.136246 0.593917 0.07184296 0.644669 0.08523297 0.630358 0.09566998 0.666688 0.07184296 0.618444 0.08104395 0.612151 0.08523297 0.630358 0.07184296 0.644669 0.07184296 0.618444 0.08523297 0.630358 0.07184296 0.590762 0.07754099 0.593917 0.08104395 0.612151 0.07184296 0.618444 0.07184296 0.590762 0.08104395 0.612151 0.09152597 0.593917 0.07754099 0.593917 0.08438795 0.593917 0.07184296 0.590762 0.08438795 0.593917 0.07754099 0.593917 0.108929 0.593917 0.07754099 0.593917 0.09152597 0.593917 0.07184296 0.561969 0.09152597 0.593917 0.08438795 0.593917 0.07184296 0.590762 0.07184296 0.561969 0.08438795 0.593917 0.07184296 0.561969 0.08737695 0.571361 0.09152597 0.593917 0.183551 0.569057 0.09152597 0.593917 0.08737695 0.571361 0.09399598 0.593917 0.09152597 0.593917 0.183551 0.569057 0.09399598 0.593917 0.09646695 0.593917 0.108929 0.593917 0.108929 0.593917 0.09152597 0.593917 0.09399598 0.593917 0.07184296 0.561969 0.08439797 0.548561 0.08737695 0.571361 0.179844 0.547083 0.08737695 0.571361 0.08439797 0.548561 0.179844 0.547083 0.183551 0.569057 0.08737695 0.571361 0.07184296 0.532429 0.08260297 0.525588 0.08439797 0.548561 0.1776199 0.524918 0.08439797 0.548561 0.08260297 0.525588 0.07184296 0.561969 0.07184296 0.532429 0.08439797 0.548561 0.1776199 0.524918 0.179844 0.547083 0.08439797 0.548561 0.07184296 0.502513 0.08200299 0.502513 0.08260297 0.525588 0.1776199 0.524918 0.08260297 0.525588 0.08200299 0.502513 0.07184296 0.532429 0.07184296 0.502513 0.08260297 0.525588 0.07184296 0.472597 0.08200299 0.502513 0.07184296 0.502513 0.07184296 0.472597 0.08233696 0.485294 0.08200299 0.502513 0.176868 0.502513 0.08200299 0.502513 0.08233696 0.485294 0.1776199 0.524918 0.08200299 0.502513 0.176868 0.502513 0.057473 0.502513 0.07184296 0.502513 0.07184296 0.532429 0.04641199 0.478118 0.07184296 0.502513 0.057473 0.502513 0.04641199 0.478118 0.07184296 0.472597 0.07184296 0.502513 0.04641199 0.527367 0.07184296 0.532429 0.07184296 0.561969 0.04641199 0.502513 0.057473 0.502513 0.07184296 0.532429 0.04641199 0.527367 0.04641199 0.502513 0.07184296 0.532429 0.04641199 0.551896 0.07184296 0.561969 0.07184296 0.590762 0.04641199 0.551896 0.04641199 0.527367 0.07184296 0.561969 0.04641199 0.575781 0.07184296 0.590762 0.07184296 0.618444 0.04641199 0.575781 0.04641199 0.551896 0.07184296 0.590762 0.04641199 0.598709 0.07184296 0.618444 0.07184296 0.644669 0.04641199 0.598709 0.04641199 0.575781 0.07184296 0.618444 0.04641199 0.620382 0.07184296 0.644669 0.07184296 0.669106 0.04641199 0.620382 0.04641199 0.598709 0.07184296 0.644669 0.04641199 0.640516 0.07184296 0.669106 0.07184296 0.691448 0.04641199 0.640516 0.04641199 0.620382 0.07184296 0.669106 0.04641199 0.658848 0.07184296 0.691448 0.07184296 0.711414 0.04641199 0.658848 0.04641199 0.640516 0.07184296 0.691448 0.04641199 0.675139 0.07184296 0.711414 0.07184296 0.728753 0.04641199 0.675139 0.04641199 0.658848 0.07184296 0.711414 0.04641199 0.689177 0.07184296 0.728753 0.07184296 0.743247 0.04641199 0.689177 0.04641199 0.675139 0.07184296 0.728753 0.04641199 0.700778 0.07184296 0.743247 0.07184296 0.754713 0.04641199 0.700778 0.04641199 0.689177 0.07184296 0.743247 0.04641199 0.709791 0.07184296 0.754713 0.07184296 0.763008 0.04641199 0.709791 0.04641199 0.700778 0.07184296 0.754713 0.04641199 0.716098 0.07184296 0.763008 0.07184296 0.768027 0.04641199 0.716098 0.04641199 0.709791 0.07184296 0.763008 0.04642999 0.719656 0.07184296 0.768027 0.07184296 0.769707 0.04642999 0.719656 0.04641199 0.716098 0.07184296 0.768027 0.05509197 0.738736 0.07184296 0.769707 0.07184296 0.768027 0.04658895 0.720022 0.04642999 0.719656 0.07184296 0.769707 0.04955095 0.726717 0.04658895 0.720022 0.07184296 0.769707 0.05187696 0.731839 0.04955095 0.726717 0.07184296 0.769707 0.05356895 0.735491 0.05187696 0.731839 0.07184296 0.769707 0.05462598 0.737747 0.05356895 0.735491 0.07184296 0.769707 0.05510795 0.738769 0.05462598 0.737747 0.07184296 0.769707 0.05509197 0.738736 0.05510795 0.738769 0.07184296 0.769707 0.04641199 0.716095 0.07184296 0.768027 0.07184296 0.763008 0.05457895 0.737647 0.05509197 0.738736 0.07184296 0.768027 0.05349296 0.735329 0.05457895 0.737647 0.07184296 0.768027 0.05178296 0.731634 0.05349296 0.735329 0.07184296 0.768027 0.04945296 0.726499 0.05178296 0.731634 0.07184296 0.768027 0.04649698 0.71981 0.04945296 0.726499 0.07184296 0.768027 0.389797 0.873461 0.389781 0.873461 0.3879 0.873461 0.04641199 0.716095 0.04649698 0.71981 0.07184296 0.768027 0.04641199 0.709788 0.07184296 0.763008 0.07184296 0.754713 0.04641199 0.709788 0.04641199 0.716095 0.07184296 0.763008 0.04641199 0.700774 0.07184296 0.754713 0.07184296 0.743247 0.04641199 0.700774 0.04641199 0.709788 0.07184296 0.754713 0.04641199 0.689173 0.07184296 0.743247 0.07184296 0.728753 0.04641199 0.689173 0.04641199 0.700774 0.07184296 0.743247 0.04641199 0.675135 0.07184296 0.728753 0.07184296 0.711414 0.04641199 0.675135 0.04641199 0.689173 0.07184296 0.728753 0.04641199 0.658844 0.07184296 0.711414 0.07184296 0.691448 0.04641199 0.658844 0.04641199 0.675135 0.07184296 0.711414 0.04641199 0.640512 0.07184296 0.691448 0.07184296 0.669106 0.04641199 0.640512 0.04641199 0.658844 0.07184296 0.691448 0.04641199 0.620378 0.07184296 0.669106 0.07184296 0.644669 0.04641199 0.620378 0.04641199 0.640512 0.07184296 0.669106 0.09234696 0.641371 0.07184296 0.618444 0.07184296 0.644669 0.04641199 0.598706 0.07184296 0.644669 0.07184296 0.618444 0.09795796 0.664956 0.09234696 0.641371 0.07184296 0.644669 0.04641199 0.598706 0.04641199 0.620378 0.07184296 0.644669 0.08765995 0.617673 0.07184296 0.590762 0.07184296 0.618444 0.04641199 0.575779 0.07184296 0.618444 0.07184296 0.590762 0.09234696 0.641371 0.08765995 0.617673 0.07184296 0.618444 0.04641199 0.575779 0.04641199 0.598706 0.07184296 0.618444 0.10226 0.593917 0.07184296 0.561969 0.07184296 0.590762 0.04641199 0.551895 0.07184296 0.590762 0.07184296 0.561969 0.09603798 0.593917 0.10226 0.593917 0.07184296 0.590762 0.08388698 0.593917 0.09603798 0.593917 0.07184296 0.590762 0.08765995 0.617673 0.08388698 0.593917 0.07184296 0.590762 0.04641199 0.551895 0.04641199 0.575779 0.07184296 0.590762 0.102269 0.564014 0.07184296 0.532429 0.07184296 0.561969 0.04641199 0.527366 0.07184296 0.561969 0.07184296 0.532429 0.10226 0.593917 0.102269 0.564014 0.07184296 0.561969 0.04641199 0.527366 0.04641199 0.551895 0.07184296 0.561969 0.09890699 0.502513 0.07184296 0.502513 0.07184296 0.532429 0.04641199 0.527366 0.07184296 0.532429 0.07184296 0.502513 0.102268 0.502513 0.09890699 0.502513 0.07184296 0.532429 0.102269 0.533414 0.102268 0.502513 0.07184296 0.532429 0.102269 0.564014 0.102269 0.533414 0.07184296 0.532429 0.102268 0.467274 0.07184296 0.502513 0.09890699 0.502513 0.069458 0.502513 0.04641199 0.527366 0.07184296 0.502513 0.07184296 0.472597 0.069458 0.502513 0.07184296 0.502513 0.07184296 0.472597 0.07184296 0.502513 0.102268 0.467274 0.102268 0.467274 0.09890699 0.502513 0.102268 0.502513 0.13285 0.502513 0.102268 0.502513 0.102269 0.533414 0.137307 0.462262 0.102268 0.502513 0.13285 0.502513 0.137307 0.462262 0.102268 0.467274 0.102268 0.502513 0.104504 0.593917 0.10226 0.593917 0.09603798 0.593917 0.108369 0.593917 0.108987 0.593917 0.10226 0.593917 0.104504 0.593917 0.108369 0.593917 0.10226 0.593917 0.104504 0.593917 0.09603798 0.593917 0.08388698 0.593917 0.104504 0.593917 0.08388698 0.593917 0.08765995 0.617673 0.104504 0.593917 0.08765995 0.617673 0.09234696 0.641371 0.104504 0.593917 0.09234696 0.641371 0.09795796 0.664956 0.04641199 0.478118 0.057473 0.502513 0.04641199 0.502513 0.03706097 0.502513 0.04641199 0.502513 0.04641199 0.527367 0.026295 0.483945 0.04641199 0.502513 0.03706097 0.502513 0.026295 0.483945 0.04641199 0.478118 0.04641199 0.502513 0.026295 0.538685 0.04641199 0.527367 0.04641199 0.551896 0.026295 0.502513 0.03706097 0.502513 0.04641199 0.527367 0.026295 0.520709 0.026295 0.502513 0.04641199 0.527367 0.026295 0.538685 0.026295 0.520709 0.04641199 0.527367 0.026295 0.556225 0.04641199 0.551896 0.04641199 0.575781 0.026295 0.556225 0.026295 0.538685 0.04641199 0.551896 0.026295 0.573116 0.04641199 0.575781 0.04641199 0.598709 0.026295 0.573116 0.026295 0.556225 0.04641199 0.575781 0.026295 0.589154 0.04641199 0.598709 0.04641199 0.620382 0.026295 0.589154 0.026295 0.573116 0.04641199 0.598709 0.026295 0.604146 0.04641199 0.620382 0.04641199 0.640516 0.026295 0.604146 0.026295 0.589154 0.04641199 0.620382 0.026295 0.617911 0.04641199 0.640516 0.04641199 0.658848 0.026295 0.617911 0.026295 0.604146 0.04641199 0.640516 0.026295 0.630283 0.04641199 0.658848 0.04641199 0.675139 0.026295 0.630283 0.026295 0.617911 0.04641199 0.658848 0.026295 0.641111 0.04641199 0.675139 0.04641199 0.689177 0.026295 0.641111 0.026295 0.630283 0.04641199 0.675139 0.026295 0.650266 0.04641199 0.689177 0.04641199 0.700778 0.026295 0.650266 0.026295 0.641111 0.04641199 0.689177 0.026295 0.657637 0.04641199 0.700778 0.04641199 0.709791 0.026295 0.657637 0.026295 0.650266 0.04641199 0.700778 0.026295 0.663134 0.04641199 0.709791 0.04641199 0.716098 0.026295 0.663134 0.026295 0.657637 0.04641199 0.709791 0.04297995 0.711573 0.04641199 0.716098 0.04642999 0.719656 0.02609199 0.66606 0.026295 0.663134 0.04641199 0.716098 0.03871798 0.701132 0.02609199 0.66606 0.04641199 0.716098 0.04297995 0.711573 0.03871798 0.701132 0.04641199 0.716098 0.04549199 0.593917 0.04642999 0.719656 0.04658895 0.720022 0.04549199 0.593917 0.04297995 0.711573 0.04642999 0.719656 0.04549199 0.593917 0.04658895 0.720022 0.04955095 0.726717 0.05005198 0.593917 0.04955095 0.726717 0.05187696 0.731839 0.04549199 0.593917 0.04955095 0.726717 0.05005198 0.593917 0.05327898 0.593917 0.05187696 0.731839 0.05356895 0.735491 0.05005198 0.593917 0.05187696 0.731839 0.05327898 0.593917 0.05327898 0.593917 0.05356895 0.735491 0.05462598 0.737747 0.05494999 0.593917 0.05462598 0.737747 0.05510795 0.738769 0.05327898 0.593917 0.05462598 0.737747 0.05494999 0.593917 0.05494999 0.593917 0.05510795 0.738769 0.05509197 0.738736 0.05492496 0.593917 0.05509197 0.738736 0.05457895 0.737647 0.05494999 0.593917 0.05509197 0.738736 0.05492496 0.593917 0.05492496 0.593917 0.05457895 0.737647 0.05349296 0.735329 0.05320894 0.593917 0.05349296 0.735329 0.05178296 0.731634 0.05492496 0.593917 0.05349296 0.735329 0.05320894 0.593917 0.049959 0.593917 0.05178296 0.731634 0.04945296 0.726499 0.05320894 0.593917 0.05178296 0.731634 0.049959 0.593917 0.049959 0.593917 0.04945296 0.726499 0.04649698 0.71981 0.395398 0.873461 0.395314 0.873461 0.389797 0.873461 0.04290497 0.711393 0.04649698 0.71981 0.04641199 0.716095 0.04541999 0.593917 0.04649698 0.71981 0.04290497 0.711393 0.049959 0.593917 0.04649698 0.71981 0.04541999 0.593917 0.026295 0.663134 0.04641199 0.716095 0.04641199 0.709788 0.03867197 0.701017 0.04290497 0.711393 0.04641199 0.716095 0.03380799 0.68838 0.03867197 0.701017 0.04641199 0.716095 0.02609199 0.66606 0.03380799 0.68838 0.04641199 0.716095 0.026295 0.663134 0.02609199 0.66606 0.04641199 0.716095 0.026295 0.657637 0.04641199 0.709788 0.04641199 0.700774 0.026295 0.657637 0.026295 0.663134 0.04641199 0.709788 0.026295 0.650266 0.04641199 0.700774 0.04641199 0.689173 0.026295 0.650266 0.026295 0.657637 0.04641199 0.700774 0.026295 0.641111 0.04641199 0.689173 0.04641199 0.675135 0.026295 0.641111 0.026295 0.650266 0.04641199 0.689173 0.026295 0.630283 0.04641199 0.675135 0.04641199 0.658844 0.026295 0.630283 0.026295 0.641111 0.04641199 0.675135 0.026295 0.617911 0.04641199 0.658844 0.04641199 0.640512 0.026295 0.617911 0.026295 0.630283 0.04641199 0.658844 0.026295 0.604146 0.04641199 0.640512 0.04641199 0.620378 0.026295 0.604146 0.026295 0.617911 0.04641199 0.640512 0.026295 0.589154 0.04641199 0.620378 0.04641199 0.598706 0.026295 0.589154 0.026295 0.604146 0.04641199 0.620378 0.026295 0.573116 0.04641199 0.598706 0.04641199 0.575779 0.026295 0.573116 0.026295 0.589154 0.04641199 0.598706 0.026295 0.556225 0.04641199 0.575779 0.04641199 0.551895 0.026295 0.556225 0.026295 0.573116 0.04641199 0.575779 0.026295 0.538685 0.04641199 0.551895 0.04641199 0.527366 0.026295 0.538685 0.026295 0.556225 0.04641199 0.551895 0.069458 0.502513 0.04641199 0.502513 0.04641199 0.527366 0.026295 0.520709 0.04641199 0.527366 0.04641199 0.502513 0.026295 0.520709 0.026295 0.538685 0.04641199 0.527366 0.07184296 0.472597 0.04641199 0.502513 0.069458 0.502513 0.026295 0.520709 0.04641199 0.502513 0.04486095 0.502513 0.04641199 0.478118 0.04486095 0.502513 0.04641199 0.502513 0.04641199 0.478118 0.04641199 0.502513 0.07184296 0.472597 0.026295 0.483945 0.03706097 0.502513 0.026295 0.502513 0.02096897 0.502513 0.026295 0.502513 0.026295 0.520709 0.01174396 0.490006 0.026295 0.502513 0.02096897 0.502513 0.01174396 0.490006 0.026295 0.483945 0.026295 0.502513 0.01174396 0.515118 0.026295 0.520709 0.026295 0.538685 0.01174396 0.502513 0.02096897 0.502513 0.026295 0.520709 0.01174396 0.515118 0.01174396 0.502513 0.026295 0.520709 0.01174396 0.527563 0.026295 0.538685 0.026295 0.556225 0.01174396 0.527563 0.01174396 0.515118 0.026295 0.538685 0.01174396 0.539687 0.026295 0.556225 0.026295 0.573116 0.01174396 0.539687 0.01174396 0.527563 0.026295 0.556225 0.01174396 0.551337 0.026295 0.573116 0.026295 0.589154 0.01174396 0.551337 0.01174396 0.539687 0.026295 0.573116 0.01174396 0.562362 0.026295 0.589154 0.026295 0.604146 0.01174396 0.562362 0.01174396 0.551337 0.026295 0.589154 0.01174396 0.572624 0.026295 0.604146 0.026295 0.617911 0.01174396 0.572624 0.01174396 0.562362 0.026295 0.604146 0.01174396 0.581989 0.026295 0.617911 0.026295 0.630283 0.01174396 0.581989 0.01174396 0.572624 0.026295 0.617911 0.01174396 0.59034 0.026295 0.630283 0.026295 0.641111 0.01174396 0.59034 0.01174396 0.581989 0.026295 0.630283 0.01174396 0.597569 0.026295 0.641111 0.026295 0.650266 0.01174396 0.597569 0.01174396 0.59034 0.026295 0.641111 0.01174396 0.603583 0.026295 0.650266 0.026295 0.657637 0.01174396 0.603583 0.01174396 0.597569 0.026295 0.650266 0.01174396 0.608306 0.026295 0.657637 0.026295 0.663134 0.01174396 0.608306 0.01174396 0.603583 0.026295 0.657637 0.01156699 0.611129 0.026295 0.663134 0.02609199 0.66606 0.01156699 0.611129 0.01174396 0.608306 0.026295 0.663134 0.03871798 0.701132 0.03380799 0.68838 0.02609199 0.66606 0.03380799 0.593917 0.02609199 0.66606 0.03380799 0.68838 0.01817697 0.639111 0.01156699 0.611129 0.02609199 0.66606 0.03380799 0.593917 0.01817697 0.639111 0.02609199 0.66606 0.03380799 0.593917 0.03380799 0.68838 0.03871798 0.701132 0.03991299 0.593917 0.03871798 0.701132 0.04297995 0.711573 0.03380799 0.593917 0.03871798 0.701132 0.03991299 0.593917 0.03991299 0.593917 0.04297995 0.711573 0.04549199 0.593917 0.01174396 0.490006 0.02096897 0.502513 0.01174396 0.502513 0.009357988 0.502513 0.01174396 0.502513 0.01174396 0.515118 0.002941966 0.496223 0.01174396 0.502513 0.009357988 0.502513 0.002941966 0.496223 0.01174396 0.490006 0.01174396 0.502513 0.002941966 0.515014 0.01174396 0.515118 0.01174396 0.527563 0.002941966 0.502513 0.009357988 0.502513 0.01174396 0.515118 0.002941966 0.508803 0.002941966 0.502513 0.01174396 0.515118 0.002941966 0.515014 0.002941966 0.508803 0.01174396 0.515118 0.002941966 0.521068 0.01174396 0.527563 0.01174396 0.539687 0.002941966 0.521068 0.002941966 0.515014 0.01174396 0.527563 0.002941966 0.526888 0.01174396 0.539687 0.01174396 0.551337 0.002941966 0.526888 0.002941966 0.521068 0.01174396 0.539687 0.002941966 0.532402 0.01174396 0.551337 0.01174396 0.562362 0.002941966 0.532402 0.002941966 0.526888 0.01174396 0.551337 0.002941966 0.53754 0.01174396 0.562362 0.01174396 0.572624 0.002941966 0.53754 0.002941966 0.532402 0.01174396 0.562362 0.002941966 0.542238 0.01174396 0.572624 0.01174396 0.581989 0.002941966 0.542238 0.002941966 0.53754 0.01174396 0.572624 0.002941966 0.546436 0.01174396 0.581989 0.01174396 0.59034 0.002941966 0.546436 0.002941966 0.542238 0.01174396 0.581989 0.002941966 0.550081 0.01174396 0.59034 0.01174396 0.597569 0.002941966 0.550081 0.002941966 0.546436 0.01174396 0.59034 0.002941966 0.553129 0.01174396 0.597569 0.01174396 0.603583 0.002941966 0.553129 0.002941966 0.550081 0.01174396 0.597569 0.002941966 0.555539 0.01174396 0.603583 0.01174396 0.608306 0.002941966 0.555539 0.002941966 0.553129 0.01174396 0.603583 0.008322954 0.593917 0.01174396 0.608306 0.01156699 0.611129 0.008322954 0.593917 0.002941966 0.555539 0.01174396 0.608306 0.03380799 0.593917 0.01156699 0.611129 0.01817697 0.639111 0.03380799 0.593917 0.008322954 0.593917 0.01156699 0.611129 0.002941966 0.496223 0.009357988 0.502513 0.002941966 0.502513 0.002344965 0.502513 0.002941966 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.502513 0.002344965 0.502513 0.002941966 0.496223 0.002941966 0.502513 0 0.502513 0 0.502513 0.002941966 0.508803 0.002941966 0.515014 0 0.502513 0.002344965 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.515014 0.002941966 0.521068 0 0.502513 0.002941966 0.521068 0.002941966 0.526888 0 0.502513 0.002941966 0.526888 0.002941966 0.532402 0 0.502513 0.002941966 0.532402 0.002941966 0.53754 0 0.502513 0.002941966 0.53754 0.002941966 0.542238 0 0.502513 0.002941966 0.542238 0.002941966 0.546436 0 0.502513 0.002941966 0.546436 0.002941966 0.550081 0 0.502513 0.002941966 0.550081 0.002941966 0.553129 0 0.502513 0.002941966 0.553129 0.002941966 0.555539 0.008322954 0.593917 0.002941966 0.557283 0.002941966 0.555539 0 0.502513 0.002941966 0.555539 0.002941966 0.557283 0.008048951 0.593917 0.002941966 0.558339 0.002941966 0.557283 0 0.502513 0.002941966 0.557283 0.002941966 0.558339 0.008322954 0.593917 0.008048951 0.593917 0.002941966 0.557283 0.007829964 0.593917 0.002941966 0.558692 0.002941966 0.558339 0 0.502513 0.002941966 0.558339 0.002941966 0.558692 0.007884979 0.593917 0.007829964 0.593917 0.002941966 0.558339 0.008048951 0.593917 0.007884979 0.593917 0.002941966 0.558339 0.007884979 0.593917 0.002941966 0.558339 0.002941966 0.558692 0 0.502513 0.002941966 0.558692 0.002941966 0.558339 0.007829964 0.593917 0.007884979 0.593917 0.002941966 0.558692 0.008048951 0.593917 0.002941966 0.557283 0.002941966 0.558339 0 0.502513 0.002941966 0.558339 0.002941966 0.557283 0.007884979 0.593917 0.008048951 0.593917 0.002941966 0.558339 0.01174396 0.608306 0.002941966 0.555539 0.002941966 0.557283 0 0.502513 0.002941966 0.557283 0.002941966 0.555539 0.008322954 0.593917 0.01174396 0.608306 0.002941966 0.557283 0.008048951 0.593917 0.008322954 0.593917 0.002941966 0.557283 0.01174396 0.603583 0.002941966 0.553129 0.002941966 0.555539 0 0.502513 0.002941966 0.555539 0.002941966 0.553129 0.01174396 0.608306 0.01174396 0.603583 0.002941966 0.555539 0.01174396 0.597569 0.002941966 0.550081 0.002941966 0.553129 0 0.502513 0.002941966 0.553129 0.002941966 0.550081 0.01174396 0.603583 0.01174396 0.597569 0.002941966 0.553129 0.01174396 0.59034 0.002941966 0.546436 0.002941966 0.550081 0 0.502513 0.002941966 0.550081 0.002941966 0.546436 0.01174396 0.597569 0.01174396 0.59034 0.002941966 0.550081 0.01174396 0.581989 0.002941966 0.542238 0.002941966 0.546436 0 0.502513 0.002941966 0.546436 0.002941966 0.542238 0.01174396 0.59034 0.01174396 0.581989 0.002941966 0.546436 0.01174396 0.572624 0.002941966 0.53754 0.002941966 0.542238 0 0.502513 0.002941966 0.542238 0.002941966 0.53754 0.01174396 0.581989 0.01174396 0.572624 0.002941966 0.542238 0.01174396 0.562362 0.002941966 0.532402 0.002941966 0.53754 0 0.502513 0.002941966 0.53754 0.002941966 0.532402 0.01174396 0.572624 0.01174396 0.562362 0.002941966 0.53754 0.01174396 0.551337 0.002941966 0.526888 0.002941966 0.532402 0 0.502513 0.002941966 0.532402 0.002941966 0.526888 0.01174396 0.562362 0.01174396 0.551337 0.002941966 0.532402 0.01174396 0.539687 0.002941966 0.521068 0.002941966 0.526888 0 0.502513 0.002941966 0.526888 0.002941966 0.521068 0.01174396 0.551337 0.01174396 0.539687 0.002941966 0.526888 0.01174396 0.527563 0.002941966 0.515014 0.002941966 0.521068 0 0.502513 0.002941966 0.521068 0.002941966 0.515014 0.01174396 0.539687 0.01174396 0.527563 0.002941966 0.521068 0.01174396 0.515118 0.002941966 0.508803 0.002941966 0.515014 0 0.502513 0.002941966 0.515014 0.002941966 0.508803 0.01174396 0.527563 0.01174396 0.515118 0.002941966 0.515014 0.01135295 0.502513 0.002941966 0.502513 0.002941966 0.508803 0 0.502513 0.002941966 0.508803 0.002941966 0.502513 0.01174396 0.502513 0.01135295 0.502513 0.002941966 0.508803 0.01174396 0.515118 0.01174396 0.502513 0.002941966 0.508803 0.01174396 0.490006 0.002941966 0.502513 0.01135295 0.502513 0.002846956 0.502513 0 0.502513 0.002941966 0.502513 0.002941966 0.496223 0.002846956 0.502513 0.002941966 0.502513 0.002941966 0.496223 0.002941966 0.502513 0.01174396 0.490006 0.01174396 0.490006 0.01135295 0.502513 0.01174396 0.502513 0.02541399 0.502513 0.01174396 0.502513 0.01174396 0.515118 0.026295 0.483945 0.01174396 0.502513 0.02541399 0.502513 0.01174396 0.490006 0.01174396 0.502513 0.026295 0.483945 0.026295 0.538685 0.01174396 0.515118 0.01174396 0.527563 0.026295 0.520709 0.01174396 0.515118 0.026295 0.538685 0.026295 0.502513 0.01174396 0.515118 0.026295 0.520709 0.02541399 0.502513 0.01174396 0.515118 0.026295 0.502513 0.026295 0.556225 0.01174396 0.527563 0.01174396 0.539687 0.026295 0.538685 0.01174396 0.527563 0.026295 0.556225 0.026295 0.573116 0.01174396 0.539687 0.01174396 0.551337 0.026295 0.556225 0.01174396 0.539687 0.026295 0.573116 0.026295 0.589154 0.01174396 0.551337 0.01174396 0.562362 0.026295 0.573116 0.01174396 0.551337 0.026295 0.589154 0.026295 0.604146 0.01174396 0.562362 0.01174396 0.572624 0.026295 0.589154 0.01174396 0.562362 0.026295 0.604146 0.026295 0.617911 0.01174396 0.572624 0.01174396 0.581989 0.026295 0.604146 0.01174396 0.572624 0.026295 0.617911 0.026295 0.630283 0.01174396 0.581989 0.01174396 0.59034 0.026295 0.617911 0.01174396 0.581989 0.026295 0.630283 0.026295 0.641111 0.01174396 0.59034 0.01174396 0.597569 0.026295 0.630283 0.01174396 0.59034 0.026295 0.641111 0.026295 0.650266 0.01174396 0.597569 0.01174396 0.603583 0.026295 0.641111 0.01174396 0.597569 0.026295 0.650266 0.026295 0.657637 0.01174396 0.603583 0.01174396 0.608306 0.026295 0.650266 0.01174396 0.603583 0.026295 0.657637 0.008322954 0.593917 0.01156699 0.611129 0.01174396 0.608306 0.026295 0.663134 0.01174396 0.608306 0.01156699 0.611129 0.026295 0.657637 0.01174396 0.608306 0.026295 0.663134 0.03380799 0.68838 0.01156699 0.611129 0.008322954 0.593917 0.02609199 0.66606 0.01156699 0.611129 0.03380799 0.68838 0.01817697 0.639111 0.01156699 0.611129 0.02609199 0.66606 0.01817697 0.639111 0.026295 0.663134 0.01156699 0.611129 0.008322954 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.03380799 0.593917 0.008322954 0.593917 0.008322954 0.593917 0.03380799 0.593917 0.03380799 0.68838 0.008322954 0.593917 0.03380799 0.593917 0.03380799 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.008322954 0.593917 0.008048951 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.007884979 0.593917 0.007829964 0.593917 0.008048951 0.593917 0.007884979 0.593917 0.007884979 0.593917 0.002941966 0.496223 0 0.502513 0.002846956 0.502513 0.002941966 0.490012 0 0.502513 0.002941966 0.496223 0.002941966 0.483958 0 0.502513 0.002941966 0.490012 0.002941966 0.478138 0 0.502513 0.002941966 0.483958 0.002941966 0.472624 0 0.502513 0.002941966 0.478138 0.002941966 0.467486 0 0.502513 0.002941966 0.472624 0.002941966 0.462789 0 0.502513 0.002941966 0.467486 0.002941966 0.458591 0 0.502513 0.002941966 0.462789 0.002941966 0.454945 0 0.502513 0.002941966 0.458591 0.002941966 0.451898 0 0.502513 0.002941966 0.454945 0.002941966 0.449487 0 0.502513 0.002941966 0.451898 0.002941966 0.447743 0 0.502513 0.002941966 0.449487 0.002941966 0.446687 0 0.502513 0.002941966 0.447743 0.002941966 0.446334 0 0.502513 0.002941966 0.446687 0.002941966 0.446687 0 0.502513 0.002941966 0.446334 0.002941966 0.447743 0 0.502513 0.002941966 0.446687 0.002941966 0.449487 0 0.502513 0.002941966 0.447743 0.002941966 0.451898 0 0.502513 0.002941966 0.449487 0.002941966 0.454945 0 0.502513 0.002941966 0.451898 0.002941966 0.458591 0 0.502513 0.002941966 0.454945 0.002941966 0.462789 0 0.502513 0.002941966 0.458591 0.002941966 0.467486 0 0.502513 0.002941966 0.462789 0.002941966 0.472624 0 0.502513 0.002941966 0.467486 0.002941966 0.478138 0 0.502513 0.002941966 0.472624 0.002941966 0.483958 0 0.502513 0.002941966 0.478138 0.002941966 0.490012 0 0.502513 0.002941966 0.483958 0.002941966 0.496223 0 0.502513 0.002941966 0.490012 0.469011 0.502513 0.469011 0.55703 0.507956 0.502513 0.521562 0.44543 0.469011 0.502513 0.507956 0.502513 0.520866 0.873461 0.521124 0.999734 0.509391 0.999542 0.520866 0.873461 0.529869 0.873461 0.521124 0.999734 0.50904 0.873461 0.509391 0.999542 0.495215 0.999309 0.50904 0.873461 0.520866 0.873461 0.509391 0.999542 0.494872 0.873461 0.495215 0.999309 0.479343 0.999049 0.494872 0.873461 0.50904 0.873461 0.495215 0.999309 0.47908 0.873461 0.479343 0.999049 0.469055 0.99888 0.47908 0.873461 0.494872 0.873461 0.479343 0.999049 0.462654 0.998775 0.469055 0.99888 0.469012 0.987435 0.47908 0.873461 0.469055 0.99888 0.462654 0.998775 0.469011 0.445198 0.456258 0.502513 0.469011 0.502513 0.521562 0.44543 0.469011 0.445198 0.469011 0.502513 0.462456 0.873461 0.462654 0.998775 0.445986 0.998501 0.462456 0.873461 0.47908 0.873461 0.462654 0.998775 0.445823 0.873461 0.445986 0.998501 0.430159 0.998241 0.445823 0.873461 0.462456 0.873461 0.445986 0.998501 0.430024 0.873461 0.445823 0.873461 0.430159 0.998241 0.133904 0.593917 0.135784 0.711462 0.133222 0.70106 0.136866 0.593917 0.135784 0.711462 0.133904 0.593917 0.133904 0.593917 0.133222 0.70106 0.129603 0.688374 0.1174679 0.641466 0.129603 0.688374 0.123076 0.665027 0.112773 0.617746 0.129603 0.688374 0.1174679 0.641466 0.108987 0.593917 0.129603 0.688374 0.112773 0.617746 0.129603 0.593917 0.129603 0.688374 0.108987 0.593917 0.133904 0.593917 0.129603 0.688374 0.129603 0.593917 0.128408 0.593917 0.129603 0.593917 0.108987 0.593917 0.122979 0.593917 0.128408 0.593917 0.108987 0.593917 0.117053 0.593917 0.122979 0.593917 0.108987 0.593917 0.112614 0.593917 0.117053 0.593917 0.108987 0.593917 0.108369 0.593917 0.112614 0.593917 0.108987 0.593917 0.026295 0.502513 0.026295 0.520709 0.04486095 0.502513 0.04641199 0.478118 0.026295 0.502513 0.04486095 0.502513 0.03988796 0.593917 0.04290497 0.711393 0.03867197 0.701017 0.04541999 0.593917 0.04290497 0.711393 0.03988796 0.593917 0.03988796 0.593917 0.03867197 0.701017 0.03380799 0.68838 0.03988796 0.593917 0.03380799 0.68838 0.03380799 0.593917 0.01817697 0.639111 0.02609199 0.66606 0.026295 0.663134 0.026295 0.483945 0.02541399 0.502513 0.026295 0.502513 0.026295 0.483945 0.026295 0.502513 0.04641199 0.478118 0.591918 0.593917 0.638549 0.593917 0.624886 0.593917 0.794366 0.553923 0.624886 0.593917 0.638549 0.593917 0.591233 0.593917 0.632282 0.593917 0.638549 0.593917 0.632282 0.676804 0.638549 0.593917 0.632282 0.593917 0.590785 0.593917 0.591233 0.593917 0.638549 0.593917 0.591918 0.593917 0.590785 0.593917 0.638549 0.593917 0.79572 0.570943 0.794366 0.553923 0.638549 0.593917 0.635928 0.635169 0.79572 0.570943 0.638549 0.593917 0.635928 0.635169 0.638549 0.593917 0.632282 0.676804 0.593202 0.593917 0.630928 0.593917 0.632282 0.593917 0.632282 0.676804 0.632282 0.593917 0.630928 0.593917 0.591233 0.593917 0.593202 0.593917 0.632282 0.593917 0.596544 0.593917 0.629178 0.593917 0.630928 0.593917 0.630413 0.690992 0.630928 0.593917 0.629178 0.593917 0.593202 0.593917 0.596544 0.593917 0.630928 0.593917 0.632282 0.676804 0.630928 0.593917 0.630413 0.690992 0.596544 0.593917 0.627006 0.593917 0.629178 0.593917 0.6279 0.703709 0.629178 0.593917 0.627006 0.593917 0.630413 0.690992 0.629178 0.593917 0.6279 0.703709 0.601023 0.593917 0.62449 0.593917 0.627006 0.593917 0.624824 0.715193 0.627006 0.593917 0.62449 0.593917 0.596544 0.593917 0.601023 0.593917 0.627006 0.593917 0.6279 0.703709 0.627006 0.593917 0.624824 0.715193 0.601023 0.593917 0.621679 0.593917 0.62449 0.593917 0.624824 0.715193 0.62449 0.593917 0.621679 0.593917 0.606326 0.593917 0.618636 0.593917 0.621679 0.593917 0.601023 0.593917 0.606326 0.593917 0.621679 0.593917 0.606326 0.593917 0.615453 0.593917 0.618636 0.593917 0.606326 0.593917 0.6121 0.593917 0.615453 0.593917 0.896309 0.502513 0.792617 0.502513 0.792811 0.519637 0.896628 0.473634 0.792819 0.485066 0.792617 0.502513 0.896309 0.502513 0.896628 0.473634 0.792617 0.502513 0.896628 0.531392 0.792811 0.519637 0.793395 0.536821 0.896628 0.531392 0.896309 0.502513 0.792811 0.519637 0.896628 0.531392 0.793395 0.536821 0.794366 0.553923 0.897565 0.559898 0.794366 0.553923 0.79572 0.570943 0.897565 0.559898 0.896628 0.531392 0.794366 0.553923 0.635928 0.635169 0.797451 0.58783 0.79572 0.570943 0.897565 0.559898 0.79572 0.570943 0.797451 0.58783 0.635928 0.635169 0.799552 0.604573 0.797451 0.58783 0.816638 0.593917 0.797451 0.58783 0.799552 0.604573 0.899065 0.587673 0.797451 0.58783 0.816638 0.593917 0.899065 0.587673 0.897565 0.559898 0.797451 0.58783 0.632282 0.676804 0.802016 0.621149 0.799552 0.604573 0.815643 0.613145 0.799552 0.604573 0.802016 0.621149 0.635928 0.635169 0.632282 0.676804 0.799552 0.604573 0.815643 0.613145 0.816638 0.593917 0.799552 0.604573 0.6279 0.703709 0.804827 0.637482 0.802016 0.621149 0.814466 0.631592 0.802016 0.621149 0.804827 0.637482 0.630413 0.690992 0.6279 0.703709 0.802016 0.621149 0.632282 0.676804 0.630413 0.690992 0.802016 0.621149 0.814466 0.631592 0.815643 0.613145 0.802016 0.621149 0.813114 0.64918 0.804827 0.637482 0.807968 0.653536 0.6279 0.703709 0.624824 0.715193 0.804827 0.637482 0.813114 0.64918 0.814466 0.631592 0.804827 0.637482 0.811462 0.66749 0.807968 0.653536 0.811395 0.669147 0.811462 0.66749 0.811596 0.665829 0.807968 0.653536 0.813114 0.64918 0.807968 0.653536 0.811596 0.665829 0.811596 0.593917 0.811395 0.669147 0.811389 0.670394 0.811462 0.66749 0.811395 0.669147 0.811596 0.593917 0.750018 0.704868 0.811411 0.671626 0.811389 0.670394 0.811596 0.593917 0.811389 0.670394 0.811411 0.671626 0.688625 0.738111 0.750018 0.704868 0.811389 0.670394 0.812058 0.677897 0.811411 0.671626 0.750018 0.704868 0.811616 0.593917 0.811411 0.671626 0.812058 0.677897 0.811616 0.593917 0.811596 0.593917 0.811411 0.671626 0.693008 0.76114 0.750018 0.704868 0.688625 0.738111 0.754457 0.724456 0.812058 0.677897 0.750018 0.704868 0.693008 0.76114 0.754457 0.724456 0.750018 0.704868 0.623954 0.256914 0.808394 0.349452 0.81191 0.333671 0.905955 0.341434 0.81191 0.333671 0.808394 0.349452 0.750351 0.300338 0.623954 0.256914 0.81191 0.333671 0.754457 0.28057 0.750351 0.300338 0.81191 0.333671 0.81583 0.317556 0.81191 0.333671 0.905955 0.341434 0.754457 0.28057 0.81191 0.333671 0.81583 0.317556 0.621909 0.273278 0.805174 0.365671 0.808394 0.349452 0.903374 0.365251 0.808394 0.349452 0.805174 0.365671 0.623954 0.256914 0.621909 0.273278 0.808394 0.349452 0.903374 0.365251 0.905955 0.341434 0.808394 0.349452 0.617463 0.315671 0.802297 0.382139 0.805174 0.365671 0.903374 0.365251 0.805174 0.365671 0.802297 0.382139 0.621909 0.273278 0.617463 0.315671 0.805174 0.365671 0.617463 0.315671 0.799772 0.398854 0.802297 0.382139 0.901037 0.390633 0.802297 0.382139 0.799772 0.398854 0.901037 0.390633 0.903374 0.365251 0.802297 0.382139 0.613945 0.360338 0.797612 0.415792 0.799772 0.398854 0.899065 0.417353 0.799772 0.398854 0.797612 0.415792 0.617463 0.315671 0.613945 0.360338 0.799772 0.398854 0.899065 0.417353 0.901037 0.390633 0.799772 0.398854 0.6114 0.406742 0.795828 0.432908 0.797612 0.415792 0.899065 0.417353 0.797612 0.415792 0.795828 0.432908 0.613945 0.360338 0.6114 0.406742 0.797612 0.415792 0.6114 0.406742 0.794429 0.450188 0.795828 0.432908 0.897565 0.445128 0.795828 0.432908 0.794429 0.450188 0.897565 0.445128 0.899065 0.417353 0.795828 0.432908 0.609859 0.454326 0.793424 0.467575 0.794429 0.450188 0.897565 0.445128 0.794429 0.450188 0.793424 0.467575 0.6114 0.406742 0.609859 0.454326 0.794429 0.450188 0.609859 0.454326 0.792819 0.485066 0.793424 0.467575 0.896628 0.473634 0.793424 0.467575 0.792819 0.485066 0.896628 0.473634 0.897565 0.445128 0.793424 0.467575 0.573463 0.446152 0.609859 0.454326 0.6114 0.406742 0.573463 0.390538 0.6114 0.406742 0.613945 0.360338 0.573463 0.446152 0.6114 0.406742 0.573463 0.390538 0.573463 0.336408 0.613945 0.360338 0.617463 0.315671 0.573463 0.390538 0.613945 0.360338 0.573463 0.336408 0.573463 0.28448 0.617463 0.315671 0.621909 0.273278 0.573463 0.336408 0.617463 0.315671 0.573463 0.28448 0.573463 0.28448 0.621909 0.273278 0.623954 0.256914 0.688792 0.267005 0.627233 0.233672 0.623954 0.256914 0.624062 0.213328 0.623954 0.256914 0.627233 0.233672 0.750351 0.300338 0.688792 0.267005 0.623954 0.256914 0.573463 0.28448 0.623954 0.256914 0.573463 0.2354429 0.624062 0.213328 0.573463 0.2354429 0.623954 0.256914 0.63156 0.207201 0.627233 0.233672 0.688792 0.267005 0.624062 0.213328 0.627233 0.233672 0.63156 0.207201 0.693009 0.2438859 0.688792 0.267005 0.750351 0.300338 0.693009 0.2438859 0.63156 0.207201 0.688792 0.267005 0.754457 0.28057 0.693009 0.2438859 0.750351 0.300338 1 0.349198 0.905955 0.341434 0.903374 0.365251 0.910149 0.308556 0.905955 0.341434 1 0.349198 0.815905 0.317259 0.81583 0.317556 0.905955 0.341434 0.820298 0.300523 0.815905 0.317259 0.905955 0.341434 0.910149 0.308556 0.820298 0.300523 0.905955 0.341434 1 0.385273 0.903374 0.365251 0.901037 0.390633 1 0.366995 1 0.349198 0.903374 0.365251 1 0.385273 1 0.366995 0.903374 0.365251 1 0.40407 0.901037 0.390633 0.899065 0.417353 1 0.40407 1 0.385273 0.901037 0.390633 1 0.42327 0.899065 0.417353 0.897565 0.445128 1 0.42327 1 0.40407 0.899065 0.417353 1 0.462565 0.897565 0.445128 0.896628 0.473634 1 0.442796 1 0.42327 0.897565 0.445128 1 0.462565 1 0.442796 0.897565 0.445128 1 0.482458 0.896628 0.473634 0.896309 0.502513 1 0.482458 1 0.462565 0.896628 0.473634 1 0.502513 1 0.482458 0.896309 0.502513 0.896628 0.531392 1 0.502513 0.896309 0.502513 1 0.351077 1 0.349198 1 0.366995 1 0.332566 0.910149 0.308556 1 0.349198 1 0.332035 1 0.332566 1 0.349198 1 0.351077 1 0.332035 1 0.349198 1 0.370938 1 0.366995 1 0.385273 1 0.370938 1 0.351077 1 0.366995 1 0.391462 1 0.385273 1 0.40407 1 0.391462 1 0.370938 1 0.385273 1 0.412545 1 0.40407 1 0.42327 1 0.412545 1 0.391462 1 0.40407 1 0.434153 1 0.42327 1 0.442796 1 0.434153 1 0.412545 1 0.42327 1 0.456062 1 0.442796 1 0.462565 1 0.456062 1 0.434153 1 0.442796 1 0.478322 1 0.462565 1 0.482458 1 0.478322 1 0.456062 1 0.462565 1 0.500545 1 0.482458 1 0.502513 1 0.500545 1 0.478322 1 0.482458 1 0.522569 1 0.502513 0.896628 0.531392 1 0.500545 1 0.502513 1 0.522569 0.754457 0.28057 0.81583 0.317556 0.815905 0.317259 0.759019 0.261244 0.815905 0.317259 0.820298 0.300523 0.759019 0.261244 0.754457 0.28057 0.815905 0.317259 1 0.299088 0.820298 0.300523 0.910149 0.308556 0.825248 0.28348 0.759019 0.261244 0.820298 0.300523 0.825248 0.28348 0.820298 0.300523 1 0.299088 1 0.332566 1 0.316589 0.910149 0.308556 1 0.299088 0.910149 0.308556 1 0.316589 1 0.332035 1 0.316589 1 0.332566 1 0.313798 1 0.299088 1 0.316589 1 0.332035 1 0.313798 1 0.316589 0.636279 0.182569 0.63156 0.207201 0.693009 0.2438859 0.624062 0.213328 0.63156 0.207201 0.636279 0.182569 0.697618 0.221886 0.693009 0.2438859 0.754457 0.28057 0.697618 0.221886 0.636279 0.182569 0.693009 0.2438859 0.759019 0.261244 0.697618 0.221886 0.754457 0.28057 0.704674 0.193393 0.636279 0.182569 0.697618 0.221886 0.624062 0.213328 0.636279 0.182569 0.624062 0.1733 0.640054 0.1654559 0.624062 0.1733 0.636279 0.182569 0.704674 0.193393 0.640054 0.1654559 0.636279 0.182569 0.765931 0.2353529 0.697618 0.221886 0.759019 0.261244 0.765931 0.2353529 0.704674 0.193393 0.697618 0.221886 0.765931 0.2353529 0.759019 0.261244 0.825248 0.28348 0.07184296 0.472597 0.08333295 0.468165 0.08233696 0.485294 0.177636 0.479946 0.08233696 0.485294 0.08333295 0.468165 0.177636 0.479946 0.176868 0.502513 0.08233696 0.485294 0.07184296 0.443057 0.08726596 0.434374 0.08333295 0.468165 0.179884 0.457657 0.08333295 0.468165 0.08726596 0.434374 0.07184296 0.472597 0.07184296 0.443057 0.08333295 0.468165 0.179884 0.457657 0.177636 0.479946 0.08333295 0.468165 0.07184296 0.414264 0.09382796 0.400815 0.08726596 0.434374 0.183625 0.435598 0.08726596 0.434374 0.09382796 0.400815 0.07184296 0.443057 0.07184296 0.414264 0.08726596 0.434374 0.183625 0.435598 0.179884 0.457657 0.08726596 0.434374 0.07184296 0.386582 0.10216 0.370461 0.09382796 0.400815 0.18885 0.413801 0.09382796 0.400815 0.10216 0.370461 0.07184296 0.414264 0.07184296 0.386582 0.09382796 0.400815 0.18885 0.413801 0.183625 0.435598 0.09382796 0.400815 0.07184296 0.386582 0.102268 0.339397 0.10216 0.370461 0.103213 0.36715 0.10216 0.370461 0.102268 0.339397 0.18885 0.413801 0.10216 0.370461 0.103213 0.36715 0.07184296 0.360357 0.102268 0.310352 0.102268 0.339397 0.132099 0.298503 0.102268 0.339397 0.102268 0.310352 0.07184296 0.386582 0.07184296 0.360357 0.102268 0.339397 0.115783 0.333115 0.103213 0.36715 0.102268 0.339397 0.132099 0.298503 0.115783 0.333115 0.102268 0.339397 0.07184296 0.33592 0.102268 0.283748 0.102268 0.310352 0.137307 0.258698 0.102268 0.310352 0.102268 0.283748 0.07184296 0.360357 0.07184296 0.33592 0.102268 0.310352 0.136974 0.289526 0.132099 0.298503 0.102268 0.310352 0.137307 0.258698 0.136974 0.289526 0.102268 0.310352 0.07184296 0.313578 0.102268 0.259923 0.102268 0.283748 0.137307 0.2309989 0.102268 0.283748 0.102268 0.259923 0.07184296 0.33592 0.07184296 0.313578 0.102268 0.283748 0.137307 0.2309989 0.137307 0.258698 0.102268 0.283748 0.07184296 0.293612 0.102268 0.23918 0.102268 0.259923 0.137307 0.206799 0.102268 0.259923 0.102268 0.23918 0.07184296 0.313578 0.07184296 0.293612 0.102268 0.259923 0.137307 0.206799 0.137307 0.2309989 0.102268 0.259923 0.07184296 0.276273 0.102268 0.221782 0.102268 0.23918 0.137307 0.186408 0.102268 0.23918 0.102268 0.221782 0.07184296 0.293612 0.07184296 0.276273 0.102268 0.23918 0.137307 0.186408 0.137307 0.206799 0.102268 0.23918 0.07184296 0.261779 0.102268 0.207951 0.102268 0.221782 0.137307 0.170091 0.102268 0.221782 0.102268 0.207951 0.07184296 0.276273 0.07184296 0.261779 0.102268 0.221782 0.137307 0.170091 0.137307 0.186408 0.102268 0.221782 0.07184296 0.250313 0.102268 0.197861 0.102268 0.207951 0.137307 0.158057 0.102268 0.207951 0.102268 0.197861 0.07184296 0.261779 0.07184296 0.250313 0.102268 0.207951 0.137307 0.158057 0.137307 0.170091 0.102268 0.207951 0.07184296 0.242018 0.102268 0.191642 0.102268 0.197861 0.137307 0.15046 0.102268 0.197861 0.102268 0.191642 0.07184296 0.250313 0.07184296 0.242018 0.102268 0.197861 0.137307 0.15046 0.137307 0.158057 0.102268 0.197861 0.07184296 0.236999 0.102268 0.189371 0.102268 0.191642 0.137307 0.1474 0.102268 0.191642 0.102268 0.189371 0.07184296 0.242018 0.07184296 0.236999 0.102268 0.191642 0.137307 0.1474 0.137307 0.15046 0.102268 0.191642 0.07184296 0.235319 0.102268 0.191079 0.102268 0.189371 0.137307 0.1489149 0.102268 0.189371 0.102268 0.191079 0.07184296 0.236999 0.07184296 0.235319 0.102268 0.189371 0.137307 0.1489149 0.137307 0.1474 0.102268 0.189371 0.07184296 0.236999 0.102268 0.196743 0.102268 0.191079 0.137307 0.154986 0.102268 0.191079 0.102268 0.196743 0.07184296 0.235319 0.07184296 0.236999 0.102268 0.191079 0.137307 0.154986 0.137307 0.1489149 0.102268 0.191079 0.07184296 0.242018 0.102268 0.206291 0.102268 0.196743 0.137307 0.165535 0.102268 0.196743 0.102268 0.206291 0.07184296 0.236999 0.07184296 0.242018 0.102268 0.196743 0.137307 0.165535 0.137307 0.154986 0.102268 0.196743 0.07184296 0.250313 0.102268 0.219603 0.102268 0.206291 0.137307 0.180426 0.102268 0.206291 0.102268 0.219603 0.07184296 0.242018 0.07184296 0.250313 0.102268 0.206291 0.137307 0.180426 0.137307 0.165535 0.102268 0.206291 0.07184296 0.261779 0.102268 0.236508 0.102268 0.219603 0.137307 0.199466 0.102268 0.219603 0.102268 0.236508 0.07184296 0.250313 0.07184296 0.261779 0.102268 0.219603 0.137307 0.199466 0.137307 0.180426 0.102268 0.219603 0.07184296 0.276273 0.102268 0.256793 0.102268 0.236508 0.137307 0.222411 0.102268 0.236508 0.102268 0.256793 0.07184296 0.261779 0.07184296 0.276273 0.102268 0.236508 0.137307 0.222411 0.137307 0.199466 0.102268 0.236508 0.07184296 0.293612 0.102268 0.280199 0.102268 0.256793 0.137307 0.248965 0.102268 0.256793 0.102268 0.280199 0.07184296 0.276273 0.07184296 0.293612 0.102268 0.256793 0.137307 0.248965 0.137307 0.222411 0.102268 0.256793 0.07184296 0.313578 0.102268 0.30643 0.102268 0.280199 0.137307 0.278786 0.102268 0.280199 0.102268 0.30643 0.07184296 0.293612 0.07184296 0.313578 0.102268 0.280199 0.137307 0.278786 0.137307 0.248965 0.102268 0.280199 0.07184296 0.33592 0.102268 0.335151 0.102268 0.30643 0.137307 0.31149 0.102268 0.30643 0.102268 0.335151 0.07184296 0.313578 0.07184296 0.33592 0.102268 0.30643 0.137307 0.31149 0.137307 0.278786 0.102268 0.30643 0.07184296 0.360357 0.102268 0.365999 0.102268 0.335151 0.137307 0.346654 0.102268 0.335151 0.102268 0.365999 0.07184296 0.33592 0.07184296 0.360357 0.102268 0.335151 0.137307 0.346654 0.137307 0.31149 0.102268 0.335151 0.07184296 0.386582 0.102268 0.39858 0.102268 0.365999 0.137307 0.383827 0.102268 0.365999 0.102268 0.39858 0.07184296 0.360357 0.07184296 0.386582 0.102268 0.365999 0.137307 0.383827 0.137307 0.346654 0.102268 0.365999 0.07184296 0.414264 0.102268 0.432482 0.102268 0.39858 0.137307 0.422529 0.102268 0.39858 0.102268 0.432482 0.07184296 0.386582 0.07184296 0.414264 0.102268 0.39858 0.137307 0.422529 0.137307 0.383827 0.102268 0.39858 0.07184296 0.443057 0.102268 0.467274 0.102268 0.432482 0.137307 0.462262 0.102268 0.432482 0.102268 0.467274 0.07184296 0.414264 0.07184296 0.443057 0.102268 0.432482 0.137307 0.462262 0.137307 0.422529 0.102268 0.432482 0.07184296 0.443057 0.07184296 0.472597 0.102268 0.467274 0.04641199 0.478118 0.07184296 0.472597 0.07184296 0.443057 0.04641199 0.45403 0.07184296 0.443057 0.07184296 0.414264 0.04641199 0.45403 0.04641199 0.478118 0.07184296 0.443057 0.04641199 0.430551 0.07184296 0.414264 0.07184296 0.386582 0.04641199 0.430551 0.04641199 0.45403 0.07184296 0.414264 0.04641199 0.407977 0.07184296 0.386582 0.07184296 0.360357 0.04641199 0.407977 0.04641199 0.430551 0.07184296 0.386582 0.04641199 0.386592 0.07184296 0.360357 0.07184296 0.33592 0.04641199 0.386592 0.04641199 0.407977 0.07184296 0.360357 0.04641199 0.366665 0.07184296 0.33592 0.07184296 0.313578 0.04641199 0.366665 0.04641199 0.386592 0.07184296 0.33592 0.04641199 0.348447 0.07184296 0.313578 0.07184296 0.293612 0.04641199 0.348447 0.04641199 0.366665 0.07184296 0.313578 0.04641199 0.332165 0.07184296 0.293612 0.07184296 0.276273 0.04641199 0.332165 0.04641199 0.348447 0.07184296 0.293612 0.04641199 0.318026 0.07184296 0.276273 0.07184296 0.261779 0.04641199 0.318026 0.04641199 0.332165 0.07184296 0.276273 0.04641199 0.306207 0.07184296 0.261779 0.07184296 0.250313 0.04641199 0.306207 0.04641199 0.318026 0.07184296 0.261779 0.04641199 0.296857 0.07184296 0.250313 0.07184296 0.242018 0.04641199 0.296857 0.04641199 0.306207 0.07184296 0.250313 0.04641199 0.290093 0.07184296 0.242018 0.07184296 0.236999 0.04641199 0.290093 0.04641199 0.296857 0.07184296 0.242018 0.04641199 0.286 0.07184296 0.236999 0.07184296 0.235319 0.04641199 0.286 0.04641199 0.290093 0.07184296 0.236999 0.04641199 0.28463 0.07184296 0.235319 0.07184296 0.236999 0.04641199 0.28463 0.04641199 0.286 0.07184296 0.235319 0.04641199 0.286 0.07184296 0.236999 0.07184296 0.242018 0.04641199 0.286 0.04641199 0.28463 0.07184296 0.236999 0.04641199 0.290093 0.07184296 0.242018 0.07184296 0.250313 0.04641199 0.290093 0.04641199 0.286 0.07184296 0.242018 0.04641199 0.296857 0.07184296 0.250313 0.07184296 0.261779 0.04641199 0.296857 0.04641199 0.290093 0.07184296 0.250313 0.04641199 0.306207 0.07184296 0.261779 0.07184296 0.276273 0.04641199 0.306207 0.04641199 0.296857 0.07184296 0.261779 0.04641199 0.318026 0.07184296 0.276273 0.07184296 0.293612 0.04641199 0.318026 0.04641199 0.306207 0.07184296 0.276273 0.04641199 0.332165 0.07184296 0.293612 0.07184296 0.313578 0.04641199 0.332165 0.04641199 0.318026 0.07184296 0.293612 0.04641199 0.348447 0.07184296 0.313578 0.07184296 0.33592 0.04641199 0.348447 0.04641199 0.332165 0.07184296 0.313578 0.04641199 0.366665 0.07184296 0.33592 0.07184296 0.360357 0.04641199 0.366665 0.04641199 0.348447 0.07184296 0.33592 0.04641199 0.386592 0.07184296 0.360357 0.07184296 0.386582 0.04641199 0.386592 0.04641199 0.366665 0.07184296 0.360357 0.04641199 0.407977 0.07184296 0.386582 0.07184296 0.414264 0.04641199 0.407977 0.04641199 0.386592 0.07184296 0.386582 0.04641199 0.430551 0.07184296 0.414264 0.07184296 0.443057 0.04641199 0.430551 0.04641199 0.407977 0.07184296 0.414264 0.04641199 0.45403 0.07184296 0.443057 0.07184296 0.472597 0.04641199 0.45403 0.04641199 0.430551 0.07184296 0.443057 0.04641199 0.478118 0.04641199 0.45403 0.07184296 0.472597 0.1954759 0.392574 0.103213 0.36715 0.115783 0.333115 0.1954759 0.392574 0.18885 0.413801 0.103213 0.36715 0.203529 0.371874 0.115783 0.333115 0.132099 0.298503 0.203529 0.371874 0.1954759 0.392574 0.115783 0.333115 0.21288 0.351931 0.132099 0.298503 0.136974 0.289526 0.21288 0.351931 0.203529 0.371874 0.132099 0.298503 0.152923 0.263287 0.136974 0.289526 0.137307 0.258698 0.2234809 0.332846 0.136974 0.289526 0.152923 0.263287 0.2234809 0.332846 0.21288 0.351931 0.136974 0.289526 0.1764 0.231153 0.137307 0.258698 0.137307 0.2309989 0.1764 0.231153 0.152923 0.263287 0.137307 0.258698 0.176518 0.200835 0.137307 0.2309989 0.137307 0.206799 0.176518 0.200835 0.1764 0.231153 0.137307 0.2309989 0.176518 0.174342 0.137307 0.206799 0.137307 0.186408 0.176518 0.174342 0.176518 0.200835 0.137307 0.206799 0.176518 0.152055 0.137307 0.186408 0.137307 0.170091 0.176518 0.152055 0.176518 0.174342 0.137307 0.186408 0.176518 0.134261 0.137307 0.170091 0.137307 0.158057 0.176518 0.134261 0.176518 0.152055 0.137307 0.170091 0.176518 0.121187 0.137307 0.158057 0.137307 0.15046 0.176518 0.121187 0.176518 0.134261 0.137307 0.158057 0.176518 0.113003 0.137307 0.15046 0.137307 0.1474 0.176518 0.113003 0.176518 0.121187 0.137307 0.15046 0.176518 0.109811 0.137307 0.1474 0.137307 0.1489149 0.176518 0.109811 0.176518 0.113003 0.137307 0.1474 0.176518 0.111654 0.137307 0.1489149 0.137307 0.154986 0.176518 0.111654 0.176518 0.109811 0.137307 0.1489149 0.176518 0.118508 0.137307 0.154986 0.137307 0.165535 0.176518 0.118508 0.176518 0.111654 0.137307 0.154986 0.176518 0.130284 0.137307 0.165535 0.137307 0.180426 0.176518 0.130284 0.176518 0.118508 0.137307 0.165535 0.176518 0.146833 0.137307 0.180426 0.137307 0.199466 0.176518 0.146833 0.176518 0.130284 0.137307 0.180426 0.176518 0.167941 0.137307 0.199466 0.137307 0.222411 0.176518 0.167941 0.176518 0.146833 0.137307 0.199466 0.176518 0.193338 0.137307 0.222411 0.137307 0.248965 0.176518 0.193338 0.176518 0.167941 0.137307 0.222411 0.176518 0.222698 0.137307 0.248965 0.137307 0.278786 0.176518 0.222698 0.176518 0.193338 0.137307 0.248965 0.176518 0.255646 0.137307 0.278786 0.137307 0.31149 0.176518 0.255646 0.176518 0.222698 0.137307 0.278786 0.176518 0.291759 0.137307 0.31149 0.137307 0.346654 0.176518 0.291759 0.176518 0.255646 0.137307 0.31149 0.176518 0.330573 0.137307 0.346654 0.137307 0.383827 0.176518 0.330573 0.176518 0.291759 0.137307 0.346654 0.176518 0.371591 0.137307 0.383827 0.137307 0.422529 0.176518 0.371591 0.176518 0.330573 0.137307 0.383827 0.176518 0.414288 0.137307 0.422529 0.137307 0.462262 0.176518 0.414288 0.176518 0.371591 0.137307 0.422529 0.176518 0.458116 0.176518 0.414288 0.137307 0.462262 0.235328 0.314611 0.152923 0.263287 0.1764 0.231153 0.235328 0.314611 0.2234809 0.332846 0.152923 0.263287 0.178434 0.228655 0.1764 0.231153 0.176518 0.200835 0.24841 0.297265 0.1764 0.231153 0.178434 0.228655 0.24841 0.297265 0.235328 0.314611 0.1764 0.231153 0.21941 0.1554819 0.176518 0.200835 0.176518 0.174342 0.208652 0.195729 0.178434 0.228655 0.176518 0.200835 0.219151 0.18586 0.208652 0.195729 0.176518 0.200835 0.21941 0.1554819 0.219151 0.18586 0.176518 0.200835 0.21941 0.129518 0.176518 0.174342 0.176518 0.152055 0.21941 0.129518 0.21941 0.1554819 0.176518 0.174342 0.21941 0.108493 0.176518 0.152055 0.176518 0.134261 0.21941 0.108493 0.21941 0.129518 0.176518 0.152055 0.21941 0.09268498 0.176518 0.134261 0.176518 0.121187 0.21941 0.09268498 0.21941 0.108493 0.176518 0.134261 0.21941 0.082304 0.176518 0.121187 0.176518 0.113003 0.21941 0.082304 0.21941 0.09268498 0.176518 0.121187 0.21941 0.07748496 0.176518 0.113003 0.176518 0.109811 0.21941 0.07748496 0.21941 0.082304 0.176518 0.113003 0.21941 0.07829499 0.176518 0.109811 0.176518 0.111654 0.21941 0.07829499 0.21941 0.07748496 0.176518 0.109811 0.21941 0.08472096 0.176518 0.111654 0.176518 0.118508 0.21941 0.08472096 0.21941 0.07829499 0.176518 0.111654 0.21941 0.09667897 0.176518 0.118508 0.176518 0.130284 0.21941 0.09667897 0.21941 0.08472096 0.176518 0.118508 0.21941 0.11401 0.176518 0.130284 0.176518 0.146833 0.21941 0.11401 0.21941 0.09667897 0.176518 0.130284 0.21941 0.1364859 0.176518 0.146833 0.176518 0.167941 0.21941 0.1364859 0.21941 0.11401 0.176518 0.146833 0.21941 0.163807 0.176518 0.167941 0.176518 0.193338 0.21941 0.163807 0.21941 0.1364859 0.176518 0.167941 0.21941 0.195613 0.176518 0.193338 0.176518 0.222698 0.21941 0.195613 0.21941 0.163807 0.176518 0.193338 0.21941 0.231483 0.176518 0.222698 0.176518 0.255646 0.21941 0.231483 0.21941 0.195613 0.176518 0.222698 0.21941 0.270941 0.176518 0.255646 0.176518 0.291759 0.21941 0.270941 0.21941 0.231483 0.176518 0.255646 0.21941 0.313465 0.176518 0.291759 0.176518 0.330573 0.21941 0.313465 0.21941 0.270941 0.176518 0.291759 0.21941 0.358493 0.176518 0.330573 0.176518 0.371591 0.21941 0.358493 0.21941 0.313465 0.176518 0.330573 0.21941 0.405427 0.176518 0.371591 0.176518 0.414288 0.21941 0.405427 0.21941 0.358493 0.176518 0.371591 0.21941 0.453646 0.176518 0.414288 0.176518 0.458116 0.21941 0.453646 0.21941 0.405427 0.176518 0.414288 0.262704 0.280832 0.178434 0.228655 0.208652 0.195729 0.262704 0.280832 0.24841 0.297265 0.178434 0.228655 0.277977 0.265611 0.208652 0.195729 0.219151 0.18586 0.277977 0.265611 0.262704 0.280832 0.208652 0.195729 0.2433969 0.165594 0.219151 0.18586 0.21941 0.1554819 0.294268 0.251571 0.219151 0.18586 0.2433969 0.165594 0.294268 0.251571 0.277977 0.265611 0.219151 0.18586 0.265444 0.12053 0.21941 0.1554819 0.21941 0.129518 0.265201 0.149987 0.2433969 0.165594 0.21941 0.1554819 0.265444 0.12053 0.265201 0.149987 0.21941 0.1554819 0.265444 0.095676 0.21941 0.129518 0.21941 0.108493 0.265444 0.095676 0.265444 0.12053 0.21941 0.129518 0.265444 0.07596397 0.21941 0.108493 0.21941 0.09268498 0.265444 0.07596397 0.265444 0.095676 0.21941 0.108493 0.265444 0.06164395 0.21941 0.09268498 0.21941 0.082304 0.265444 0.06164395 0.265444 0.07596397 0.21941 0.09268498 0.265444 0.05289697 0.21941 0.082304 0.21941 0.07748496 0.265444 0.05289697 0.265444 0.06164395 0.21941 0.082304 0.265444 0.04983198 0.21941 0.07748496 0.21941 0.07829499 0.265444 0.04983198 0.265444 0.05289697 0.21941 0.07748496 0.265444 0.05248898 0.21941 0.07829499 0.21941 0.08472096 0.265444 0.05248898 0.265444 0.04983198 0.21941 0.07829499 0.265444 0.060835 0.21941 0.08472096 0.21941 0.09667897 0.265444 0.060835 0.265444 0.05248898 0.21941 0.08472096 0.265444 0.074763 0.21941 0.09667897 0.21941 0.11401 0.265444 0.074763 0.265444 0.060835 0.21941 0.09667897 0.265444 0.09409797 0.21941 0.11401 0.21941 0.1364859 0.265444 0.09409797 0.265444 0.074763 0.21941 0.11401 0.265444 0.118595 0.21941 0.1364859 0.21941 0.163807 0.265444 0.118595 0.265444 0.09409797 0.21941 0.1364859 0.265444 0.147944 0.21941 0.163807 0.21941 0.195613 0.265444 0.147944 0.265444 0.118595 0.21941 0.163807 0.265444 0.181776 0.21941 0.195613 0.21941 0.231483 0.265444 0.181776 0.265444 0.147944 0.21941 0.195613 0.265444 0.2196609 0.21941 0.231483 0.21941 0.270941 0.265444 0.2196609 0.265444 0.181776 0.21941 0.231483 0.265444 0.261122 0.21941 0.270941 0.21941 0.313465 0.265444 0.261122 0.265444 0.2196609 0.21941 0.270941 0.265444 0.305634 0.21941 0.313465 0.21941 0.358493 0.265444 0.305634 0.265444 0.261122 0.21941 0.313465 0.265444 0.352634 0.21941 0.358493 0.21941 0.405427 0.265444 0.352634 0.265444 0.305634 0.21941 0.358493 0.265444 0.401529 0.21941 0.405427 0.21941 0.453646 0.265444 0.401529 0.265444 0.352634 0.21941 0.405427 0.265444 0.4517 0.265444 0.401529 0.21941 0.453646 0.31139 0.238842 0.2433969 0.165594 0.265201 0.149987 0.31139 0.238842 0.294268 0.251571 0.2433969 0.165594 0.282272 0.1392779 0.265201 0.149987 0.265444 0.12053 0.31139 0.238842 0.265201 0.149987 0.282272 0.1392779 0.314043 0.09367996 0.265444 0.12053 0.265444 0.095676 0.313889 0.12255 0.282272 0.1392779 0.265444 0.12053 0.314043 0.09367996 0.313889 0.12255 0.265444 0.12053 0.314043 0.069628 0.265444 0.095676 0.265444 0.07596397 0.314043 0.069628 0.314043 0.09367996 0.265444 0.095676 0.314043 0.05087 0.265444 0.07596397 0.265444 0.06164395 0.314043 0.05087 0.314043 0.069628 0.265444 0.07596397 0.314043 0.03763699 0.265444 0.06164395 0.265444 0.05289697 0.314043 0.03763699 0.314043 0.05087 0.265444 0.06164395 0.314043 0.03008997 0.265444 0.05289697 0.265444 0.04983198 0.314043 0.03008997 0.314043 0.03763699 0.265444 0.05289697 0.314043 0.02832198 0.265444 0.04983198 0.265444 0.05248898 0.314043 0.02832198 0.314043 0.03008997 0.265444 0.04983198 0.314043 0.03235495 0.265444 0.05248898 0.265444 0.060835 0.314043 0.03235495 0.314043 0.02832198 0.265444 0.05248898 0.314043 0.04213798 0.265444 0.060835 0.265444 0.074763 0.314043 0.04213798 0.314043 0.03235495 0.265444 0.060835 0.314043 0.05755299 0.265444 0.074763 0.265444 0.09409797 0.314043 0.05755299 0.314043 0.04213798 0.265444 0.074763 0.314043 0.07841098 0.265444 0.09409797 0.265444 0.118595 0.314043 0.07841098 0.314043 0.05755299 0.265444 0.09409797 0.314043 0.104456 0.265444 0.118595 0.265444 0.147944 0.314043 0.104456 0.314043 0.07841098 0.265444 0.118595 0.314043 0.135371 0.265444 0.147944 0.265444 0.181776 0.314043 0.135371 0.314043 0.104456 0.265444 0.147944 0.314043 0.170776 0.265444 0.181776 0.265444 0.2196609 0.314043 0.170776 0.314043 0.135371 0.265444 0.181776 0.314043 0.2102389 0.265444 0.2196609 0.265444 0.261122 0.314043 0.2102389 0.314043 0.170776 0.265444 0.2196609 0.314043 0.253278 0.265444 0.261122 0.265444 0.305634 0.314043 0.253278 0.314043 0.2102389 0.265444 0.261122 0.314043 0.299365 0.265444 0.305634 0.265444 0.352634 0.314043 0.299365 0.314043 0.253278 0.265444 0.305634 0.314043 0.347937 0.265444 0.352634 0.265444 0.401529 0.314043 0.347937 0.314043 0.299365 0.265444 0.352634 0.314043 0.3984 0.265444 0.401529 0.265444 0.4517 0.314043 0.3984 0.314043 0.347937 0.265444 0.401529 0.314043 0.450136 0.314043 0.3984 0.265444 0.4517 0.329326 0.227455 0.282272 0.1392779 0.313889 0.12255 0.329326 0.227455 0.31139 0.238842 0.282272 0.1392779 0.324664 0.117693 0.313889 0.12255 0.314043 0.09367996 0.347971 0.217454 0.313889 0.12255 0.324664 0.117693 0.347971 0.217454 0.329326 0.227455 0.313889 0.12255 0.364596 0.07322597 0.314043 0.09367996 0.314043 0.069628 0.364535 0.103118 0.324664 0.117693 0.314043 0.09367996 0.364596 0.07322597 0.364535 0.103118 0.314043 0.09367996 0.364596 0.04892295 0.314043 0.069628 0.314043 0.05087 0.364596 0.04892295 0.364596 0.07322597 0.314043 0.069628 0.364596 0.03063297 0.314043 0.05087 0.314043 0.03763699 0.364596 0.03063297 0.364596 0.04892295 0.314043 0.05087 0.364596 0.01859998 0.314043 0.03763699 0.314043 0.03008997 0.364596 0.01859998 0.364596 0.03063297 0.314043 0.03763699 0.364596 0.01298296 0.314043 0.03008997 0.314043 0.02832198 0.364596 0.01298296 0.364596 0.01859998 0.314043 0.03008997 0.364596 0.01385599 0.314043 0.02832198 0.314043 0.03235495 0.364596 0.01385599 0.364596 0.01298296 0.314043 0.02832198 0.364596 0.02120798 0.314043 0.03235495 0.314043 0.04213798 0.364596 0.02120798 0.364596 0.01385599 0.314043 0.03235495 0.364596 0.03494095 0.314043 0.04213798 0.314043 0.05755299 0.364596 0.03494095 0.364596 0.02120798 0.314043 0.04213798 0.364596 0.054874 0.314043 0.05755299 0.314043 0.07841098 0.364596 0.054874 0.364596 0.03494095 0.314043 0.05755299 0.364596 0.08074098 0.314043 0.07841098 0.314043 0.104456 0.364596 0.08074098 0.364596 0.054874 0.314043 0.07841098 0.364596 0.112201 0.314043 0.104456 0.314043 0.135371 0.364596 0.112201 0.364596 0.08074098 0.314043 0.104456 0.364596 0.148835 0.314043 0.135371 0.314043 0.170776 0.364596 0.148835 0.364596 0.112201 0.314043 0.135371 0.364596 0.190159 0.314043 0.170776 0.314043 0.2102389 0.364596 0.190159 0.364596 0.148835 0.314043 0.170776 0.364596 0.235624 0.314043 0.2102389 0.314043 0.253278 0.364596 0.235624 0.364596 0.190159 0.314043 0.2102389 0.364596 0.284627 0.314043 0.253278 0.314043 0.299365 0.364596 0.284627 0.364596 0.235624 0.314043 0.253278 0.364596 0.33652 0.314043 0.299365 0.314043 0.347937 0.364596 0.33652 0.364596 0.284627 0.314043 0.299365 0.364596 0.390613 0.314043 0.347937 0.314043 0.3984 0.364596 0.390613 0.364596 0.33652 0.314043 0.347937 0.364596 0.44619 0.314043 0.3984 0.314043 0.450136 0.364596 0.44619 0.364596 0.390613 0.314043 0.3984 0.367186 0.208925 0.324664 0.117693 0.364535 0.103118 0.367186 0.208925 0.347971 0.217454 0.324664 0.117693 0.36979 0.101575 0.364535 0.103118 0.364596 0.07322597 0.386977 0.201854 0.364535 0.103118 0.36979 0.101575 0.386977 0.201854 0.367186 0.208925 0.364535 0.103118 0.416469 0.06176096 0.364596 0.07322597 0.364596 0.04892295 0.41647 0.09148496 0.36979 0.101575 0.364596 0.07322597 0.416469 0.06176096 0.41647 0.09148496 0.364596 0.07322597 0.416469 0.03780394 0.364596 0.04892295 0.364596 0.03063297 0.416469 0.03780394 0.416469 0.06176096 0.364596 0.04892295 0.416469 0.01993095 0.364596 0.03063297 0.364596 0.01859998 0.416469 0.01993095 0.416469 0.03780394 0.364596 0.03063297 0.416469 0.008375942 0.364596 0.01859998 0.364596 0.01298296 0.416469 0.008375942 0.416469 0.01993095 0.364596 0.01859998 0.416469 0.003288984 0.364596 0.01298296 0.364596 0.01385599 0.416469 0.003288984 0.416469 0.008375942 0.364596 0.01298296 0.416469 0.004736959 0.364596 0.01385599 0.364596 0.02120798 0.416469 0.004736959 0.416469 0.003288984 0.364596 0.01385599 0.416469 0.01270198 0.364596 0.02120798 0.364596 0.03494095 0.416469 0.01270198 0.416469 0.004736959 0.364596 0.02120798 0.416469 0.02707898 0.364596 0.03494095 0.364596 0.054874 0.416469 0.02707898 0.416469 0.01270198 0.364596 0.03494095 0.416469 0.04767894 0.364596 0.054874 0.364596 0.08074098 0.416469 0.04767894 0.416469 0.02707898 0.364596 0.054874 0.416469 0.074234 0.364596 0.08074098 0.364596 0.112201 0.416469 0.074234 0.416469 0.04767894 0.364596 0.08074098 0.416469 0.106395 0.364596 0.112201 0.364596 0.148835 0.416469 0.106395 0.416469 0.074234 0.364596 0.112201 0.416469 0.143742 0.364596 0.148835 0.364596 0.190159 0.416469 0.143742 0.416469 0.106395 0.364596 0.148835 0.416469 0.1857849 0.364596 0.190159 0.364596 0.235624 0.416469 0.1857849 0.416469 0.143742 0.364596 0.190159 0.416469 0.231975 0.364596 0.235624 0.364596 0.284627 0.416469 0.231975 0.416469 0.1857849 0.364596 0.235624 0.416469 0.281706 0.364596 0.284627 0.364596 0.33652 0.416469 0.281706 0.416469 0.231975 0.364596 0.284627 0.416469 0.334328 0.364596 0.33652 0.364596 0.390613 0.416469 0.334328 0.416469 0.281706 0.364596 0.33652 0.416469 0.389151 0.364596 0.390613 0.364596 0.44619 0.416469 0.389151 0.416469 0.334328 0.364596 0.390613 0.416469 0.445459 0.416469 0.389151 0.364596 0.44619 0.407116 0.196327 0.36979 0.101575 0.41647 0.09148496 0.407116 0.196327 0.386977 0.201854 0.36979 0.101575 0.46459 0.08758598 0.41647 0.09148496 0.416469 0.06176096 0.448343 0.189913 0.41647 0.09148496 0.46459 0.08758598 0.427649 0.192333 0.407116 0.196327 0.41647 0.09148496 0.448343 0.189913 0.427649 0.192333 0.41647 0.09148496 0.469011 0.05796897 0.416469 0.06176096 0.416469 0.03780394 0.469017 0.08754998 0.46459 0.08758598 0.416469 0.06176096 0.469011 0.05796897 0.469017 0.08754998 0.416469 0.06176096 0.469011 0.03410297 0.416469 0.03780394 0.416469 0.01993095 0.469011 0.03410297 0.469011 0.05796897 0.416469 0.03780394 0.469011 0.01634597 0.416469 0.01993095 0.416469 0.008375942 0.469011 0.01634597 0.469011 0.03410297 0.416469 0.01993095 0.469011 0.004927992 0.416469 0.008375942 0.416469 0.003288984 0.469011 0.004927992 0.469011 0.01634597 0.416469 0.008375942 0.469011 0 0.416469 0.003288984 0.416469 0.004736959 0.469011 0 0.469011 0.004927992 0.416469 0.003288984 0.469011 0.001624941 0.416469 0.004736959 0.416469 0.01270198 0.469011 0.001624941 0.469011 0 0.416469 0.004736959 0.469011 0.009781956 0.416469 0.01270198 0.416469 0.02707898 0.469011 0.009781956 0.469011 0.001624941 0.416469 0.01270198 0.469011 0.02436399 0.416469 0.02707898 0.416469 0.04767894 0.469011 0.02436399 0.469011 0.009781956 0.416469 0.02707898 0.469011 0.04518198 0.416469 0.04767894 0.416469 0.074234 0.469011 0.04518198 0.469011 0.02436399 0.416469 0.04767894 0.469011 0.07196396 0.416469 0.074234 0.416469 0.106395 0.469011 0.07196396 0.469011 0.04518198 0.416469 0.074234 0.469011 0.10436 0.416469 0.106395 0.416469 0.143742 0.469011 0.10436 0.469011 0.07196396 0.416469 0.106395 0.469011 0.1419489 0.416469 0.143742 0.416469 0.1857849 0.469011 0.1419489 0.469011 0.10436 0.416469 0.143742 0.469011 0.18424 0.416469 0.1857849 0.416469 0.231975 0.469011 0.18424 0.469011 0.1419489 0.416469 0.1857849 0.469011 0.230681 0.416469 0.231975 0.416469 0.281706 0.469011 0.230681 0.469011 0.18424 0.416469 0.231975 0.469011 0.280668 0.416469 0.281706 0.416469 0.334328 0.469011 0.280668 0.469011 0.230681 0.416469 0.281706 0.469011 0.333547 0.416469 0.334328 0.416469 0.389151 0.469011 0.333547 0.469011 0.280668 0.416469 0.334328 0.469011 0.38863 0.416469 0.389151 0.416469 0.445459 0.469011 0.38863 0.469011 0.333547 0.416469 0.389151 0.469011 0.445198 0.469011 0.38863 0.416469 0.445459 0.469192 0.189079 0.46459 0.08758598 0.469017 0.08754998 0.469192 0.189079 0.448343 0.189913 0.46459 0.08758598 0.521562 0.06167697 0.469017 0.08754998 0.469011 0.05796897 0.521562 0.06167697 0.512554 0.09008496 0.469017 0.08754998 0.490055 0.189828 0.469017 0.08754998 0.512554 0.09008496 0.490055 0.189828 0.469192 0.189079 0.469017 0.08754998 0.521562 0.03769296 0.469011 0.05796897 0.469011 0.03410297 0.521562 0.03769296 0.521562 0.06167697 0.469011 0.05796897 0.521562 0.01979595 0.469011 0.03410297 0.469011 0.01634597 0.521562 0.01979595 0.521562 0.03769296 0.469011 0.03410297 0.521562 0.008218944 0.469011 0.01634597 0.469011 0.004927992 0.521562 0.008218944 0.521562 0.01979595 0.469011 0.01634597 0.521562 0.003115952 0.469011 0.004927992 0.469011 0 0.521562 0.003115952 0.521562 0.008218944 0.469011 0.004927992 0.521562 0.004550993 0.469011 0 0.469011 0.001624941 0.521562 0.004550993 0.521562 0.003115952 0.469011 0 0.521562 0.01250797 0.469011 0.001624941 0.469011 0.009781956 0.521562 0.01250797 0.521562 0.004550993 0.469011 0.001624941 0.521562 0.02688097 0.469011 0.009781956 0.469011 0.02436399 0.521562 0.02688097 0.521562 0.01250797 0.469011 0.009781956 0.521562 0.04748195 0.469011 0.02436399 0.469011 0.04518198 0.521562 0.04748195 0.521562 0.02688097 0.469011 0.02436399 0.521562 0.07404196 0.469011 0.04518198 0.469011 0.07196396 0.521562 0.07404196 0.521562 0.04748195 0.469011 0.04518198 0.521562 0.106213 0.469011 0.07196396 0.469011 0.10436 0.521562 0.106213 0.521562 0.07404196 0.469011 0.07196396 0.521562 0.143573 0.469011 0.10436 0.469011 0.1419489 0.521562 0.143573 0.521562 0.106213 0.469011 0.10436 0.521562 0.185633 0.469011 0.1419489 0.469011 0.18424 0.521562 0.185633 0.521562 0.143573 0.469011 0.1419489 0.521562 0.2318429 0.469011 0.18424 0.469011 0.230681 0.521562 0.2318429 0.521562 0.185633 0.469011 0.18424 0.521562 0.281597 0.469011 0.230681 0.469011 0.280668 0.521562 0.281597 0.521562 0.2318429 0.469011 0.230681 0.521562 0.334244 0.469011 0.280668 0.469011 0.333547 0.521562 0.334244 0.521562 0.281597 0.469011 0.280668 0.521562 0.389094 0.469011 0.333547 0.469011 0.38863 0.521562 0.389094 0.521562 0.334244 0.469011 0.333547 0.521562 0.44543 0.469011 0.38863 0.469011 0.445198 0.521562 0.44543 0.521562 0.389094 0.469011 0.38863 0.521562 0.06167697 0.521583 0.091273 0.512554 0.09008496 0.490055 0.189828 0.512554 0.09008496 0.521583 0.091273 0.573463 0.07289397 0.521583 0.091273 0.521562 0.06167697 0.573463 0.07289397 0.559955 0.09893399 0.521583 0.091273 0.510792 0.192171 0.521583 0.091273 0.559955 0.09893399 0.510792 0.192171 0.490055 0.189828 0.521583 0.091273 0.573463 0.04857999 0.521562 0.06167697 0.521562 0.03769296 0.573463 0.04857999 0.573463 0.07289397 0.521562 0.06167697 0.573463 0.03028297 0.521562 0.03769296 0.521562 0.01979595 0.573463 0.03028297 0.573463 0.04857999 0.521562 0.03769296 0.573463 0.01824599 0.521562 0.01979595 0.521562 0.008218944 0.573463 0.01824599 0.573463 0.03028297 0.521562 0.01979595 0.573463 0.01262897 0.521562 0.008218944 0.521562 0.003115952 0.573463 0.01262897 0.573463 0.01824599 0.521562 0.008218944 0.573463 0.01350694 0.521562 0.003115952 0.521562 0.004550993 0.573463 0.01350694 0.573463 0.01262897 0.521562 0.003115952 0.573463 0.020868 0.521562 0.004550993 0.521562 0.01250797 0.573463 0.020868 0.573463 0.01350694 0.521562 0.004550993 0.573463 0.03461396 0.521562 0.01250797 0.521562 0.02688097 0.573463 0.03461396 0.573463 0.020868 0.521562 0.01250797 0.573463 0.05456298 0.521562 0.02688097 0.521562 0.04748195 0.573463 0.05456298 0.573463 0.03461396 0.521562 0.02688097 0.573463 0.08045095 0.521562 0.04748195 0.521562 0.07404196 0.573463 0.08045095 0.573463 0.05456298 0.521562 0.04748195 0.573463 0.111933 0.521562 0.07404196 0.521562 0.106213 0.573463 0.111933 0.573463 0.08045095 0.521562 0.07404196 0.573463 0.148594 0.521562 0.106213 0.521562 0.143573 0.573463 0.148594 0.573463 0.111933 0.521562 0.106213 0.573463 0.189947 0.521562 0.143573 0.521562 0.185633 0.573463 0.189947 0.573463 0.148594 0.521562 0.143573 0.573463 0.2354429 0.521562 0.185633 0.521562 0.2318429 0.573463 0.2354429 0.573463 0.189947 0.521562 0.185633 0.573463 0.28448 0.521562 0.2318429 0.521562 0.281597 0.573463 0.28448 0.573463 0.2354429 0.521562 0.2318429 0.573463 0.336408 0.521562 0.281597 0.521562 0.334244 0.573463 0.336408 0.573463 0.28448 0.521562 0.281597 0.573463 0.390538 0.521562 0.334244 0.521562 0.389094 0.573463 0.390538 0.573463 0.336408 0.521562 0.334244 0.573463 0.446152 0.521562 0.389094 0.521562 0.44543 0.573463 0.446152 0.573463 0.390538 0.521562 0.389094 0.573463 0.07289397 0.57351 0.102682 0.559955 0.09893399 0.531396 0.196096 0.559955 0.09893399 0.57351 0.102682 0.531396 0.196096 0.510792 0.192171 0.559955 0.09893399 0.624062 0.09294098 0.57351 0.102682 0.573463 0.07289397 0.624062 0.09294098 0.606009 0.114015 0.57351 0.102682 0.551631 0.201575 0.57351 0.102682 0.606009 0.114015 0.551631 0.201575 0.531396 0.196096 0.57351 0.102682 0.624062 0.06880098 0.573463 0.07289397 0.573463 0.04857999 0.624062 0.06880098 0.624062 0.09294098 0.573463 0.07289397 0.624062 0.05002397 0.573463 0.04857999 0.573463 0.03028297 0.624062 0.05002397 0.624062 0.06880098 0.573463 0.04857999 0.624062 0.03684198 0.573463 0.03028297 0.573463 0.01824599 0.624062 0.03684198 0.624062 0.05002397 0.573463 0.03028297 0.624062 0.02941995 0.573463 0.01824599 0.573463 0.01262897 0.624062 0.02941995 0.624062 0.03684198 0.573463 0.01824599 0.624062 0.027848 0.573463 0.01262897 0.573463 0.01350694 0.624062 0.027848 0.624062 0.02941995 0.573463 0.01262897 0.624062 0.03214496 0.573463 0.01350694 0.573463 0.020868 0.624062 0.03214496 0.624062 0.027848 0.573463 0.01350694 0.624062 0.04225999 0.573463 0.020868 0.573463 0.03461396 0.624062 0.04225999 0.624062 0.03214496 0.573463 0.020868 0.624062 0.05806595 0.573463 0.03461396 0.573463 0.05456298 0.624062 0.05806595 0.624062 0.04225999 0.573463 0.03461396 0.624062 0.079369 0.573463 0.05456298 0.573463 0.08045095 0.624062 0.079369 0.624062 0.05806595 0.573463 0.05456298 0.624062 0.105904 0.573463 0.08045095 0.573463 0.111933 0.624062 0.105904 0.624062 0.079369 0.573463 0.08045095 0.624062 0.137345 0.573463 0.111933 0.573463 0.148594 0.624062 0.137345 0.624062 0.105904 0.573463 0.111933 0.624062 0.1733 0.573463 0.148594 0.573463 0.189947 0.624062 0.1733 0.624062 0.137345 0.573463 0.148594 0.624062 0.213328 0.573463 0.189947 0.573463 0.2354429 0.624062 0.213328 0.624062 0.1733 0.573463 0.189947 0.624062 0.09294098 0.624173 0.121877 0.606009 0.114015 0.571543 0.208617 0.606009 0.114015 0.624173 0.121877 0.571543 0.208617 0.551631 0.201575 0.606009 0.114015 0.672724 0.118915 0.624173 0.121877 0.624062 0.09294098 0.672724 0.118915 0.649875 0.13504 0.624173 0.121877 0.590891 0.2171429 0.624173 0.121877 0.649875 0.13504 0.590891 0.2171429 0.571543 0.208617 0.624173 0.121877 0.672724 0.09359097 0.624062 0.09294098 0.624062 0.06880098 0.672724 0.09359097 0.672724 0.118915 0.624062 0.09294098 0.672724 0.073731 0.624062 0.06880098 0.624062 0.05002397 0.672724 0.073731 0.672724 0.09359097 0.624062 0.06880098 0.672724 0.05959999 0.624062 0.05002397 0.624062 0.03684198 0.672724 0.05959999 0.672724 0.073731 0.624062 0.05002397 0.672724 0.05138695 0.624062 0.03684198 0.624062 0.02941995 0.672724 0.05138695 0.672724 0.05959999 0.624062 0.03684198 0.672724 0.04920095 0.624062 0.02941995 0.624062 0.027848 0.672724 0.04920095 0.672724 0.05138695 0.624062 0.02941995 0.672724 0.05307096 0.624062 0.027848 0.624062 0.03214496 0.672724 0.05307096 0.672724 0.04920095 0.624062 0.027848 0.672724 0.06294697 0.624062 0.03214496 0.624062 0.04225999 0.672724 0.06294697 0.672724 0.05307096 0.624062 0.03214496 0.672724 0.06294697 0.624062 0.04225999 0.624062 0.05806595 0.672698 0.07869499 0.624062 0.05806595 0.624062 0.079369 0.672698 0.07869499 0.672724 0.06294697 0.624062 0.05806595 0.661396 0.098576 0.624062 0.079369 0.624062 0.105904 0.670826 0.08136296 0.672698 0.07869499 0.624062 0.079369 0.66606 0.08925199 0.670826 0.08136296 0.624062 0.079369 0.661396 0.098576 0.66606 0.08925199 0.624062 0.079369 0.652412 0.121392 0.624062 0.105904 0.624062 0.137345 0.656835 0.109297 0.661396 0.098576 0.624062 0.105904 0.652412 0.121392 0.656835 0.109297 0.624062 0.105904 0.644001 0.149514 0.624062 0.137345 0.624062 0.1733 0.648123 0.134808 0.652412 0.121392 0.624062 0.137345 0.644001 0.149514 0.648123 0.134808 0.624062 0.137345 0.640054 0.1654559 0.644001 0.149514 0.624062 0.1733 0.672724 0.118915 0.672887 0.149052 0.649875 0.13504 0.60968 0.2271659 0.649875 0.13504 0.672887 0.149052 0.60968 0.2271659 0.590891 0.2171429 0.649875 0.13504 0.718839 0.155048 0.672887 0.149052 0.672724 0.118915 0.718839 0.155048 0.690835 0.161611 0.672887 0.149052 0.62776 0.2386 0.672887 0.149052 0.690835 0.161611 0.62776 0.2386 0.60968 0.2271659 0.672887 0.149052 0.718839 0.129548 0.672724 0.118915 0.672724 0.09359097 0.718839 0.129548 0.718839 0.155048 0.672724 0.118915 0.718839 0.108757 0.672724 0.09359097 0.672724 0.073731 0.718839 0.108757 0.718839 0.129548 0.672724 0.09359097 0.718839 0.09293699 0.672724 0.073731 0.672724 0.05959999 0.718839 0.09293699 0.718839 0.108757 0.672724 0.073731 0.718845 0.08228898 0.672724 0.05959999 0.672724 0.05138695 0.718845 0.08228898 0.718839 0.09293699 0.672724 0.05959999 0.710349 0.07168 0.672724 0.05138695 0.672724 0.04920095 0.715306 0.077286 0.718845 0.08228898 0.672724 0.05138695 0.710349 0.07168 0.715306 0.077286 0.672724 0.05138695 0.700467 0.06511598 0.672724 0.04920095 0.672724 0.05307096 0.705418 0.067649 0.710349 0.07168 0.672724 0.04920095 0.700467 0.06511598 0.705418 0.067649 0.672724 0.04920095 0.690497 0.064538 0.672724 0.05307096 0.672724 0.06294697 0.695491 0.06407898 0.700467 0.06511598 0.672724 0.05307096 0.690497 0.064538 0.695491 0.06407898 0.672724 0.05307096 0.680571 0.06997096 0.672724 0.06294697 0.672698 0.07869499 0.685525 0.06650799 0.690497 0.064538 0.672724 0.06294697 0.680571 0.06997096 0.685525 0.06650799 0.672724 0.06294697 0.736859 0.116113 0.672698 0.07869499 0.670826 0.08136296 0.736859 0.116113 0.680571 0.06997096 0.672698 0.07869499 0.728491 0.129417 0.670826 0.08136296 0.66606 0.08925199 0.728491 0.129417 0.736859 0.116113 0.670826 0.08136296 0.728491 0.129417 0.66606 0.08925199 0.661396 0.098576 0.72024 0.14689 0.661396 0.098576 0.656835 0.109297 0.72024 0.14689 0.728491 0.129417 0.661396 0.098576 0.72024 0.14689 0.656835 0.109297 0.652412 0.121392 0.712256 0.168301 0.652412 0.121392 0.648123 0.134808 0.712256 0.168301 0.72024 0.14689 0.652412 0.121392 0.712256 0.168301 0.648123 0.134808 0.644001 0.149514 0.704674 0.193393 0.644001 0.149514 0.640054 0.1654559 0.704674 0.193393 0.712256 0.168301 0.644001 0.149514 0.718839 0.155048 0.719071 0.184704 0.690835 0.161611 0.645017 0.251398 0.690835 0.161611 0.719071 0.184704 0.645017 0.251398 0.62776 0.2386 0.690835 0.161611 0.754333 0.190326 0.719071 0.184704 0.718839 0.155048 0.757788 0.2089689 0.728136 0.193109 0.719071 0.184704 0.661432 0.265526 0.719071 0.184704 0.728136 0.193109 0.754333 0.190326 0.757788 0.2089689 0.719071 0.184704 0.661432 0.265526 0.645017 0.251398 0.719071 0.184704 0.750668 0.172748 0.718839 0.155048 0.718839 0.129548 0.750668 0.172748 0.754333 0.190326 0.718839 0.155048 0.742735 0.141025 0.718839 0.129548 0.718839 0.108757 0.746788 0.156288 0.750668 0.172748 0.718839 0.129548 0.742735 0.141025 0.746788 0.156288 0.718839 0.129548 0.734111 0.114279 0.718839 0.108757 0.718839 0.09293699 0.738502 0.127003 0.742735 0.141025 0.718839 0.108757 0.734111 0.114279 0.738502 0.127003 0.718839 0.108757 0.724921 0.09292 0.718839 0.09293699 0.718845 0.08228898 0.729586 0.102907 0.734111 0.114279 0.718839 0.09293699 0.724921 0.09292 0.729586 0.102907 0.718839 0.09293699 0.774461 0.118588 0.718845 0.08228898 0.715306 0.077286 0.720161 0.08437097 0.724921 0.09292 0.718845 0.08228898 0.774461 0.118588 0.720161 0.08437097 0.718845 0.08228898 0.768104 0.1084 0.715306 0.077286 0.710349 0.07168 0.768104 0.1084 0.774461 0.118588 0.715306 0.077286 0.760989 0.103177 0.710349 0.07168 0.705418 0.067649 0.760989 0.103177 0.768104 0.1084 0.710349 0.07168 0.760989 0.103177 0.705418 0.067649 0.700467 0.06511598 0.753288 0.102818 0.700467 0.06511598 0.695491 0.06407898 0.753288 0.102818 0.760989 0.103177 0.700467 0.06511598 0.753288 0.102818 0.695491 0.06407898 0.690497 0.064538 0.745183 0.107184 0.690497 0.064538 0.685525 0.06650799 0.745183 0.107184 0.753288 0.102818 0.690497 0.064538 0.745183 0.107184 0.685525 0.06650799 0.680571 0.06997096 0.736859 0.116113 0.745183 0.107184 0.680571 0.06997096 0.757788 0.2089689 0.761044 0.228627 0.728136 0.193109 0.676806 0.280841 0.728136 0.193109 0.761044 0.228627 0.676806 0.280841 0.661432 0.265526 0.728136 0.193109 0.792162 0.242654 0.761044 0.228627 0.757788 0.2089689 0.691181 0.297378 0.676806 0.280841 0.761044 0.228627 0.782695 0.261627 0.691181 0.297378 0.761044 0.228627 0.792162 0.242654 0.782695 0.261627 0.761044 0.228627 0.790434 0.208712 0.757788 0.2089689 0.754333 0.190326 0.790434 0.208712 0.792162 0.242654 0.757788 0.2089689 0.790434 0.208712 0.754333 0.190326 0.750668 0.172748 0.787889 0.1790339 0.750668 0.172748 0.746788 0.156288 0.787889 0.1790339 0.790434 0.208712 0.750668 0.172748 0.787889 0.1790339 0.746788 0.156288 0.742735 0.141025 0.784405 0.15398 0.742735 0.141025 0.738502 0.127003 0.784405 0.15398 0.787889 0.1790339 0.742735 0.141025 0.784405 0.15398 0.738502 0.127003 0.734111 0.114279 0.779923 0.13379 0.734111 0.114279 0.729586 0.102907 0.779923 0.13379 0.784405 0.15398 0.734111 0.114279 0.779923 0.13379 0.729586 0.102907 0.724921 0.09292 0.774461 0.118588 0.724921 0.09292 0.720161 0.08437097 0.774461 0.118588 0.779923 0.13379 0.724921 0.09292 0.026295 0.483945 0.04641199 0.478118 0.04641199 0.45403 0.026295 0.465611 0.04641199 0.45403 0.04641199 0.430551 0.026295 0.465611 0.026295 0.483945 0.04641199 0.45403 0.026295 0.447741 0.04641199 0.430551 0.04641199 0.407977 0.026295 0.447741 0.026295 0.465611 0.04641199 0.430551 0.026295 0.430559 0.04641199 0.407977 0.04641199 0.386592 0.026295 0.430559 0.026295 0.447741 0.04641199 0.407977 0.026295 0.414283 0.04641199 0.386592 0.04641199 0.366665 0.026295 0.414283 0.026295 0.430559 0.04641199 0.386592 0.026295 0.399116 0.04641199 0.366665 0.04641199 0.348447 0.026295 0.399116 0.026295 0.414283 0.04641199 0.366665 0.026295 0.385249 0.04641199 0.348447 0.04641199 0.332165 0.026295 0.385249 0.026295 0.399116 0.04641199 0.348447 0.026295 0.372857 0.04641199 0.332165 0.04641199 0.318026 0.026295 0.372857 0.026295 0.385249 0.04641199 0.332165 0.026295 0.362095 0.04641199 0.318026 0.04641199 0.306207 0.026295 0.362095 0.026295 0.372857 0.04641199 0.318026 0.026295 0.353099 0.04641199 0.306207 0.04641199 0.296857 0.026295 0.353099 0.026295 0.362095 0.04641199 0.306207 0.026295 0.345982 0.04641199 0.296857 0.04641199 0.290093 0.026295 0.345982 0.026295 0.353099 0.04641199 0.296857 0.026295 0.340834 0.04641199 0.290093 0.04641199 0.286 0.026295 0.340834 0.026295 0.345982 0.04641199 0.290093 0.026295 0.337719 0.04641199 0.286 0.04641199 0.28463 0.026295 0.337719 0.026295 0.340834 0.04641199 0.286 0.026295 0.336676 0.04641199 0.28463 0.04641199 0.286 0.026295 0.336676 0.026295 0.337719 0.04641199 0.28463 0.026295 0.337719 0.04641199 0.286 0.04641199 0.290093 0.026295 0.337719 0.026295 0.336676 0.04641199 0.286 0.026295 0.340834 0.04641199 0.290093 0.04641199 0.296857 0.026295 0.340834 0.026295 0.337719 0.04641199 0.290093 0.026295 0.345982 0.04641199 0.296857 0.04641199 0.306207 0.026295 0.345982 0.026295 0.340834 0.04641199 0.296857 0.026295 0.353099 0.04641199 0.306207 0.04641199 0.318026 0.026295 0.353099 0.026295 0.345982 0.04641199 0.306207 0.026295 0.362095 0.04641199 0.318026 0.04641199 0.332165 0.026295 0.362095 0.026295 0.353099 0.04641199 0.318026 0.026295 0.372857 0.04641199 0.332165 0.04641199 0.348447 0.026295 0.372857 0.026295 0.362095 0.04641199 0.332165 0.026295 0.385249 0.04641199 0.348447 0.04641199 0.366665 0.026295 0.385249 0.026295 0.372857 0.04641199 0.348447 0.026295 0.399116 0.04641199 0.366665 0.04641199 0.386592 0.026295 0.399116 0.026295 0.385249 0.04641199 0.366665 0.026295 0.414283 0.04641199 0.386592 0.04641199 0.407977 0.026295 0.414283 0.026295 0.399116 0.04641199 0.386592 0.026295 0.430559 0.04641199 0.407977 0.04641199 0.430551 0.026295 0.430559 0.026295 0.414283 0.04641199 0.407977 0.026295 0.447741 0.04641199 0.430551 0.04641199 0.45403 0.026295 0.447741 0.026295 0.430559 0.04641199 0.430551 0.026295 0.465611 0.04641199 0.45403 0.04641199 0.478118 0.026295 0.465611 0.026295 0.447741 0.04641199 0.45403 0.026295 0.483945 0.026295 0.465611 0.04641199 0.478118 0.01174396 0.490006 0.026295 0.483945 0.026295 0.465611 0.01174396 0.477655 0.026295 0.465611 0.026295 0.447741 0.01174396 0.477655 0.01174396 0.490006 0.026295 0.465611 0.01174396 0.465618 0.026295 0.447741 0.026295 0.430559 0.01174396 0.465618 0.01174396 0.477655 0.026295 0.447741 0.01174396 0.454044 0.026295 0.430559 0.026295 0.414283 0.01174396 0.454044 0.01174396 0.465618 0.026295 0.430559 0.01174396 0.44308 0.026295 0.414283 0.026295 0.399116 0.01174396 0.44308 0.01174396 0.454044 0.026295 0.414283 0.01174396 0.432864 0.026295 0.399116 0.026295 0.385249 0.01174396 0.432864 0.01174396 0.44308 0.026295 0.399116 0.01174396 0.423523 0.026295 0.385249 0.026295 0.372857 0.01174396 0.423523 0.01174396 0.432864 0.026295 0.385249 0.01174396 0.415176 0.026295 0.372857 0.026295 0.362095 0.01174396 0.415176 0.01174396 0.423523 0.026295 0.372857 0.01174396 0.407926 0.026295 0.362095 0.026295 0.353099 0.01174396 0.407926 0.01174396 0.415176 0.026295 0.362095 0.01174396 0.401867 0.026295 0.353099 0.026295 0.345982 0.01174396 0.401867 0.01174396 0.407926 0.026295 0.353099 0.01174396 0.397073 0.026295 0.345982 0.026295 0.340834 0.01174396 0.397073 0.01174396 0.401867 0.026295 0.345982 0.01174396 0.393605 0.026295 0.340834 0.026295 0.337719 0.01174396 0.393605 0.01174396 0.397073 0.026295 0.340834 0.01174396 0.391507 0.026295 0.337719 0.026295 0.336676 0.01174396 0.391507 0.01174396 0.393605 0.026295 0.337719 0.01174396 0.390804 0.026295 0.336676 0.026295 0.337719 0.01174396 0.390804 0.01174396 0.391507 0.026295 0.336676 0.01174396 0.391507 0.026295 0.337719 0.026295 0.340834 0.01174396 0.391507 0.01174396 0.390804 0.026295 0.337719 0.01174396 0.393605 0.026295 0.340834 0.026295 0.345982 0.01174396 0.393605 0.01174396 0.391507 0.026295 0.340834 0.01174396 0.397073 0.026295 0.345982 0.026295 0.353099 0.01174396 0.397073 0.01174396 0.393605 0.026295 0.345982 0.01174396 0.401867 0.026295 0.353099 0.026295 0.362095 0.01174396 0.401867 0.01174396 0.397073 0.026295 0.353099 0.01174396 0.407926 0.026295 0.362095 0.026295 0.372857 0.01174396 0.407926 0.01174396 0.401867 0.026295 0.362095 0.01174396 0.415176 0.026295 0.372857 0.026295 0.385249 0.01174396 0.415176 0.01174396 0.407926 0.026295 0.372857 0.01174396 0.423523 0.026295 0.385249 0.026295 0.399116 0.01174396 0.423523 0.01174396 0.415176 0.026295 0.385249 0.01174396 0.432864 0.026295 0.399116 0.026295 0.414283 0.01174396 0.432864 0.01174396 0.423523 0.026295 0.399116 0.01174396 0.44308 0.026295 0.414283 0.026295 0.430559 0.01174396 0.44308 0.01174396 0.432864 0.026295 0.414283 0.01174396 0.454044 0.026295 0.430559 0.026295 0.447741 0.01174396 0.454044 0.01174396 0.44308 0.026295 0.430559 0.01174396 0.465618 0.026295 0.447741 0.026295 0.465611 0.01174396 0.465618 0.01174396 0.454044 0.026295 0.447741 0.01174396 0.477655 0.026295 0.465611 0.026295 0.483945 0.01174396 0.477655 0.01174396 0.465618 0.026295 0.465611 0.01174396 0.490006 0.01174396 0.477655 0.026295 0.483945 0.002941966 0.496223 0.01174396 0.490006 0.01174396 0.477655 0.002941966 0.490012 0.01174396 0.477655 0.01174396 0.465618 0.002941966 0.490012 0.002941966 0.496223 0.01174396 0.477655 0.002941966 0.483958 0.01174396 0.465618 0.01174396 0.454044 0.002941966 0.483958 0.002941966 0.490012 0.01174396 0.465618 0.002941966 0.478138 0.01174396 0.454044 0.01174396 0.44308 0.002941966 0.478138 0.002941966 0.483958 0.01174396 0.454044 0.002941966 0.472624 0.01174396 0.44308 0.01174396 0.432864 0.002941966 0.472624 0.002941966 0.478138 0.01174396 0.44308 0.002941966 0.467486 0.01174396 0.432864 0.01174396 0.423523 0.002941966 0.467486 0.002941966 0.472624 0.01174396 0.432864 0.002941966 0.462789 0.01174396 0.423523 0.01174396 0.415176 0.002941966 0.462789 0.002941966 0.467486 0.01174396 0.423523 0.002941966 0.458591 0.01174396 0.415176 0.01174396 0.407926 0.002941966 0.458591 0.002941966 0.462789 0.01174396 0.415176 0.002941966 0.454945 0.01174396 0.407926 0.01174396 0.401867 0.002941966 0.454945 0.002941966 0.458591 0.01174396 0.407926 0.002941966 0.451898 0.01174396 0.401867 0.01174396 0.397073 0.002941966 0.451898 0.002941966 0.454945 0.01174396 0.401867 0.002941966 0.449487 0.01174396 0.397073 0.01174396 0.393605 0.002941966 0.449487 0.002941966 0.451898 0.01174396 0.397073 0.002941966 0.447743 0.01174396 0.393605 0.01174396 0.391507 0.002941966 0.447743 0.002941966 0.449487 0.01174396 0.393605 0.002941966 0.446687 0.01174396 0.391507 0.01174396 0.390804 0.002941966 0.446687 0.002941966 0.447743 0.01174396 0.391507 0.002941966 0.446334 0.01174396 0.390804 0.01174396 0.391507 0.002941966 0.446334 0.002941966 0.446687 0.01174396 0.390804 0.002941966 0.446687 0.01174396 0.391507 0.01174396 0.393605 0.002941966 0.446687 0.002941966 0.446334 0.01174396 0.391507 0.002941966 0.447743 0.01174396 0.393605 0.01174396 0.397073 0.002941966 0.447743 0.002941966 0.446687 0.01174396 0.393605 0.002941966 0.449487 0.01174396 0.397073 0.01174396 0.401867 0.002941966 0.449487 0.002941966 0.447743 0.01174396 0.397073 0.002941966 0.451898 0.01174396 0.401867 0.01174396 0.407926 0.002941966 0.451898 0.002941966 0.449487 0.01174396 0.401867 0.002941966 0.454945 0.01174396 0.407926 0.01174396 0.415176 0.002941966 0.454945 0.002941966 0.451898 0.01174396 0.407926 0.002941966 0.458591 0.01174396 0.415176 0.01174396 0.423523 0.002941966 0.458591 0.002941966 0.454945 0.01174396 0.415176 0.002941966 0.462789 0.01174396 0.423523 0.01174396 0.432864 0.002941966 0.462789 0.002941966 0.458591 0.01174396 0.423523 0.002941966 0.467486 0.01174396 0.432864 0.01174396 0.44308 0.002941966 0.467486 0.002941966 0.462789 0.01174396 0.432864 0.002941966 0.472624 0.01174396 0.44308 0.01174396 0.454044 0.002941966 0.472624 0.002941966 0.467486 0.01174396 0.44308 0.002941966 0.478138 0.01174396 0.454044 0.01174396 0.465618 0.002941966 0.478138 0.002941966 0.472624 0.01174396 0.454044 0.002941966 0.483958 0.01174396 0.465618 0.01174396 0.477655 0.002941966 0.483958 0.002941966 0.478138 0.01174396 0.465618 0.002941966 0.490012 0.01174396 0.477655 0.01174396 0.490006 0.002941966 0.490012 0.002941966 0.483958 0.01174396 0.477655 0.002941966 0.496223 0.002941966 0.490012 0.01174396 0.490006 0.221364 0.482277 0.176868 0.502513 0.177636 0.479946 0.22131 0.521977 0.1776199 0.524918 0.176868 0.502513 0.221364 0.482277 0.22131 0.521977 0.176868 0.502513 0.221364 0.482277 0.177636 0.479946 0.179884 0.457657 0.2269189 0.443054 0.179884 0.457657 0.183625 0.435598 0.2269189 0.443054 0.221364 0.482277 0.179884 0.457657 0.2269189 0.443054 0.183625 0.435598 0.18885 0.413801 0.237852 0.405142 0.18885 0.413801 0.1954759 0.392574 0.237852 0.405142 0.2269189 0.443054 0.18885 0.413801 0.237852 0.405142 0.1954759 0.392574 0.203529 0.371874 0.253943 0.369349 0.203529 0.371874 0.21288 0.351931 0.253943 0.369349 0.237852 0.405142 0.203529 0.371874 0.274861 0.336466 0.21288 0.351931 0.2234809 0.332846 0.274861 0.336466 0.253943 0.369349 0.21288 0.351931 0.274861 0.336466 0.2234809 0.332846 0.235328 0.314611 0.300197 0.307215 0.235328 0.314611 0.24841 0.297265 0.300197 0.307215 0.274861 0.336466 0.235328 0.314611 0.329118 0.282457 0.24841 0.297265 0.262704 0.280832 0.329118 0.282457 0.300197 0.307215 0.24841 0.297265 0.329118 0.282457 0.262704 0.280832 0.277977 0.265611 0.361204 0.262568 0.277977 0.265611 0.294268 0.251571 0.361204 0.262568 0.329118 0.282457 0.277977 0.265611 0.395916 0.247904 0.294268 0.251571 0.31139 0.238842 0.395916 0.247904 0.361204 0.262568 0.294268 0.251571 0.450942 0.236687 0.31139 0.238842 0.329326 0.227455 0.414034 0.242677 0.395916 0.247904 0.31139 0.238842 0.432383 0.2389349 0.414034 0.242677 0.31139 0.238842 0.450942 0.236687 0.432383 0.2389349 0.31139 0.238842 0.60968 0.2271659 0.329326 0.227455 0.347971 0.217454 0.62776 0.2386 0.329326 0.227455 0.60968 0.2271659 0.469751 0.235918 0.329326 0.227455 0.62776 0.2386 0.469751 0.235918 0.450942 0.236687 0.329326 0.227455 0.590891 0.2171429 0.347971 0.217454 0.367186 0.208925 0.60968 0.2271659 0.347971 0.217454 0.590891 0.2171429 0.571543 0.208617 0.367186 0.208925 0.386977 0.201854 0.590891 0.2171429 0.367186 0.208925 0.571543 0.208617 0.551631 0.201575 0.386977 0.201854 0.407116 0.196327 0.571543 0.208617 0.386977 0.201854 0.551631 0.201575 0.531396 0.196096 0.407116 0.196327 0.427649 0.192333 0.551631 0.201575 0.407116 0.196327 0.531396 0.196096 0.510792 0.192171 0.427649 0.192333 0.448343 0.189913 0.531396 0.196096 0.427649 0.192333 0.510792 0.192171 0.490055 0.189828 0.448343 0.189913 0.469192 0.189079 0.510792 0.192171 0.448343 0.189913 0.490055 0.189828 0.50689 0.238896 0.62776 0.2386 0.645017 0.251398 0.50689 0.238896 0.469751 0.235918 0.62776 0.2386 0.577939 0.262382 0.645017 0.251398 0.661432 0.265526 0.543239 0.247788 0.50689 0.238896 0.645017 0.251398 0.577939 0.262382 0.543239 0.247788 0.645017 0.251398 0.577939 0.262382 0.661432 0.265526 0.676806 0.280841 0.6101 0.282251 0.676806 0.280841 0.691181 0.297378 0.6101 0.282251 0.577939 0.262382 0.676806 0.280841 0.782695 0.261627 0.704319 0.314818 0.691181 0.297378 0.639155 0.307068 0.691181 0.297378 0.704319 0.314818 0.639155 0.307068 0.6101 0.282251 0.691181 0.297378 0.792958 0.280024 0.716196 0.333138 0.704319 0.314818 0.652449 0.321296 0.704319 0.314818 0.716196 0.333138 0.782695 0.261627 0.792958 0.280024 0.704319 0.314818 0.652449 0.321296 0.639155 0.307068 0.704319 0.314818 0.802414 0.298995 0.726806 0.352293 0.716196 0.333138 0.664644 0.336472 0.716196 0.333138 0.726806 0.352293 0.792958 0.280024 0.802414 0.298995 0.716196 0.333138 0.664644 0.336472 0.652449 0.321296 0.716196 0.333138 0.815647 0.329808 0.736147 0.372282 0.726806 0.352293 0.685683 0.36958 0.726806 0.352293 0.736147 0.372282 0.802414 0.298995 0.815647 0.329808 0.726806 0.352293 0.685683 0.36958 0.664644 0.336472 0.726806 0.352293 0.818636 0.337669 0.744174 0.393004 0.736147 0.372282 0.685683 0.36958 0.736147 0.372282 0.744174 0.393004 0.815647 0.329808 0.818636 0.337669 0.736147 0.372282 0.831335 0.376692 0.750768 0.414218 0.744174 0.393004 0.701822 0.405616 0.744174 0.393004 0.750768 0.414218 0.818636 0.337669 0.831335 0.376692 0.744174 0.393004 0.701822 0.405616 0.685683 0.36958 0.744174 0.393004 0.838339 0.416896 0.755951 0.435969 0.750768 0.414218 0.701822 0.405616 0.750768 0.414218 0.755951 0.435969 0.831335 0.376692 0.838339 0.416896 0.750768 0.414218 0.838339 0.416896 0.759658 0.457943 0.755951 0.435969 0.712724 0.443722 0.755951 0.435969 0.759658 0.457943 0.712724 0.443722 0.701822 0.405616 0.755951 0.435969 0.842785 0.4585 0.761882 0.480108 0.759658 0.457943 0.712724 0.443722 0.759658 0.457943 0.761882 0.480108 0.838339 0.416896 0.842785 0.4585 0.759658 0.457943 0.844381 0.502513 0.762633 0.502513 0.761882 0.480108 0.718191 0.48305 0.761882 0.480108 0.762633 0.502513 0.842785 0.4585 0.844381 0.502513 0.761882 0.480108 0.718191 0.48305 0.712724 0.443722 0.761882 0.480108 0.843623 0.532838 0.762633 0.502513 0.844381 0.502513 0.761865 0.52508 0.762633 0.502513 0.843623 0.532838 0.718138 0.522749 0.762633 0.502513 0.761865 0.52508 0.718138 0.522749 0.718191 0.48305 0.762633 0.502513 1 0.500545 0.844381 0.502513 0.842785 0.4585 1 0.522699 0.843623 0.532838 0.844381 0.502513 1 0.522699 0.844381 0.502513 1 0.500545 1 0.456062 0.842785 0.4585 0.838339 0.416896 1 0.478322 0.842785 0.4585 1 0.456062 1 0.500545 0.842785 0.4585 1 0.478322 1 0.412545 0.838339 0.416896 0.831335 0.376692 1 0.434153 0.838339 0.416896 1 0.412545 1 0.456062 0.838339 0.416896 1 0.434153 0.837076 0.337754 0.831335 0.376692 0.818636 0.337669 1 0.391462 0.831335 0.376692 1 0.370938 0.837076 0.337754 1 0.370938 0.831335 0.376692 1 0.412545 0.831335 0.376692 1 0.391462 0.837076 0.337754 0.818636 0.337669 0.815647 0.329808 0.819035 0.290247 0.815647 0.329808 0.802414 0.298995 0.837076 0.337754 0.815647 0.329808 0.843886 0.300883 0.819035 0.290247 0.843886 0.300883 0.815647 0.329808 0.819035 0.290247 0.802414 0.298995 0.792958 0.280024 0.792162 0.242654 0.792958 0.280024 0.782695 0.261627 0.822294 0.254266 0.792958 0.280024 0.792162 0.242654 0.822294 0.254266 0.819035 0.290247 0.792958 0.280024 0.832029 0.593917 0.837495 0.593917 0.812115 0.593917 0.755877 0.569428 0.832029 0.593917 0.826559 0.593917 0.812115 0.593917 0.826559 0.593917 0.832029 0.593917 0.77787 0.593917 0.755877 0.569428 0.826559 0.593917 0.822537 0.625081 0.826559 0.593917 0.812115 0.682229 0.812115 0.593917 0.812115 0.682229 0.826559 0.593917 0.77787 0.593917 0.826559 0.593917 0.822537 0.625081 0.755877 0.569428 0.837495 0.593917 0.832029 0.593917 0.755877 0.569428 0.841297 0.56369 0.837495 0.593917 1 0.566683 0.837495 0.593917 0.841297 0.56369 0.812115 0.593917 0.837495 0.593917 0.848384 0.593917 0.848384 0.593917 0.859274 0.593917 0.812115 0.593917 1 0.588406 0.848384 0.593917 0.837495 0.593917 1 0.588406 0.837495 0.593917 1 0.566683 0.759618 0.547369 0.843623 0.532838 0.841297 0.56369 1 0.544743 0.841297 0.56369 0.843623 0.532838 0.755877 0.569428 0.759618 0.547369 0.841297 0.56369 1 0.566683 0.841297 0.56369 1 0.544743 0.759618 0.547369 0.761865 0.52508 0.843623 0.532838 1 0.544743 0.843623 0.532838 1 0.522699 0.718138 0.522749 0.761865 0.52508 0.759618 0.547369 0.712583 0.561973 0.759618 0.547369 0.755877 0.569428 0.712583 0.561973 0.718138 0.522749 0.759618 0.547369 0.766414 0.593917 0.750652 0.591225 0.755877 0.569428 0.712583 0.561973 0.755877 0.569428 0.750652 0.591225 0.772146 0.593917 0.766414 0.593917 0.755877 0.569428 0.77787 0.593917 0.772146 0.593917 0.755877 0.569428 0.757124 0.625156 0.744026 0.612452 0.750652 0.591225 0.701649 0.599884 0.750652 0.591225 0.744026 0.612452 0.757124 0.625156 0.750652 0.591225 0.766414 0.593917 0.701649 0.599884 0.712583 0.561973 0.750652 0.591225 0.757124 0.625156 0.735973 0.633152 0.744026 0.612452 0.701649 0.599884 0.744026 0.612452 0.735973 0.633152 0.745128 0.65543 0.726621 0.653095 0.735973 0.633152 0.685559 0.635677 0.735973 0.633152 0.726621 0.653095 0.757124 0.625156 0.745128 0.65543 0.735973 0.633152 0.685559 0.635677 0.701649 0.599884 0.735973 0.633152 0.73353 0.681538 0.716021 0.672181 0.726621 0.653095 0.664641 0.66856 0.726621 0.653095 0.716021 0.672181 0.736516 0.674599 0.73353 0.681538 0.726621 0.653095 0.740377 0.665972 0.736516 0.674599 0.726621 0.653095 0.745128 0.65543 0.740377 0.665972 0.726621 0.653095 0.664641 0.66856 0.685559 0.635677 0.726621 0.653095 0.729361 0.695677 0.704174 0.690415 0.716021 0.672181 0.664641 0.66856 0.716021 0.672181 0.704174 0.690415 0.729384 0.693908 0.729361 0.695677 0.716021 0.672181 0.730025 0.691053 0.729384 0.693908 0.716021 0.672181 0.731385 0.686967 0.730025 0.691053 0.716021 0.672181 0.73353 0.681538 0.731385 0.686967 0.716021 0.672181 0.639305 0.697812 0.704174 0.690415 0.691091 0.707761 0.729844 0.696544 0.778922 0.749673 0.704174 0.690415 0.729361 0.695677 0.729844 0.696544 0.704174 0.690415 0.639305 0.697812 0.664641 0.66856 0.704174 0.690415 0.610383 0.722569 0.691091 0.707761 0.676797 0.724194 0.610383 0.722569 0.639305 0.697812 0.691091 0.707761 0.610383 0.722569 0.676797 0.724194 0.661524 0.739415 0.578297 0.742459 0.661524 0.739415 0.645234 0.753456 0.578297 0.742459 0.610383 0.722569 0.661524 0.739415 0.543586 0.757122 0.645234 0.753456 0.628112 0.766184 0.543586 0.757122 0.578297 0.742459 0.645234 0.753456 0.48856 0.768339 0.628112 0.766184 0.610176 0.777572 0.525467 0.762349 0.543586 0.757122 0.628112 0.766184 0.507118 0.766091 0.525467 0.762349 0.628112 0.766184 0.48856 0.768339 0.507118 0.766091 0.628112 0.766184 0.329822 0.77786 0.610176 0.777572 0.591531 0.787572 0.311742 0.766426 0.610176 0.777572 0.329822 0.77786 0.469751 0.769108 0.610176 0.777572 0.311742 0.766426 0.48856 0.768339 0.610176 0.777572 0.469751 0.769108 0.348611 0.787884 0.591531 0.787572 0.572316 0.796101 0.329822 0.77786 0.591531 0.787572 0.348611 0.787884 0.367959 0.796409 0.572316 0.796101 0.552525 0.803172 0.348611 0.787884 0.572316 0.796101 0.367959 0.796409 0.387871 0.803451 0.552525 0.803172 0.532386 0.808699 0.367959 0.796409 0.552525 0.803172 0.387871 0.803451 0.408105 0.80893 0.532386 0.808699 0.511853 0.812693 0.387871 0.803451 0.532386 0.808699 0.408105 0.80893 0.42871 0.812855 0.511853 0.812693 0.491159 0.815114 0.408105 0.80893 0.511853 0.812693 0.42871 0.812855 0.449447 0.815199 0.491159 0.815114 0.47031 0.815947 0.42871 0.812855 0.491159 0.815114 0.449447 0.815199 0.432612 0.76613 0.311742 0.766426 0.294485 0.753628 0.432612 0.76613 0.469751 0.769108 0.311742 0.766426 0.361563 0.742644 0.294485 0.753628 0.27807 0.7395 0.396263 0.757238 0.432612 0.76613 0.294485 0.753628 0.361563 0.742644 0.396263 0.757238 0.294485 0.753628 0.361563 0.742644 0.27807 0.7395 0.262696 0.724185 0.329402 0.722775 0.262696 0.724185 0.2483209 0.707649 0.329402 0.722775 0.361563 0.742644 0.262696 0.724185 0.300347 0.697958 0.2483209 0.707649 0.235183 0.690209 0.300347 0.697958 0.329402 0.722775 0.2483209 0.707649 0.208483 0.68798 0.223305 0.671888 0.235183 0.690209 0.287053 0.68373 0.235183 0.690209 0.223305 0.671888 0.209724 0.691965 0.208483 0.68798 0.235183 0.690209 0.210189 0.694622 0.209724 0.691965 0.235183 0.690209 0.210002 0.696128 0.210189 0.694622 0.235183 0.690209 0.209277 0.696675 0.210002 0.696128 0.235183 0.690209 0.287053 0.68373 0.300347 0.697958 0.235183 0.690209 0.1993629 0.666499 0.212696 0.652733 0.223305 0.671888 0.274858 0.668555 0.223305 0.671888 0.212696 0.652733 0.203356 0.675439 0.1993629 0.666499 0.223305 0.671888 0.206381 0.68253 0.203356 0.675439 0.223305 0.671888 0.208483 0.68798 0.206381 0.68253 0.223305 0.671888 0.274858 0.668555 0.287053 0.68373 0.223305 0.671888 0.194373 0.65543 0.203354 0.632744 0.212696 0.652733 0.253819 0.635446 0.212696 0.652733 0.203354 0.632744 0.1993629 0.666499 0.194373 0.65543 0.212696 0.652733 0.253819 0.635446 0.274858 0.668555 0.212696 0.652733 0.1823779 0.625156 0.195327 0.612022 0.203354 0.632744 0.253819 0.635446 0.203354 0.632744 0.195327 0.612022 0.194373 0.65543 0.1823779 0.625156 0.203354 0.632744 0.173088 0.593917 0.1887339 0.590809 0.195327 0.612022 0.23768 0.59941 0.195327 0.612022 0.1887339 0.590809 0.1823779 0.625156 0.173088 0.593917 0.195327 0.612022 0.23768 0.59941 0.253819 0.635446 0.195327 0.612022 0.09646695 0.593917 0.183551 0.569057 0.1887339 0.590809 0.23768 0.59941 0.1887339 0.590809 0.183551 0.569057 0.161632 0.593917 0.09646695 0.593917 0.1887339 0.590809 0.167356 0.593917 0.1887339 0.590809 0.173088 0.593917 0.167356 0.593917 0.161632 0.593917 0.1887339 0.590809 0.226778 0.561305 0.183551 0.569057 0.179844 0.547083 0.09646695 0.593917 0.09399598 0.593917 0.183551 0.569057 0.226778 0.561305 0.23768 0.59941 0.183551 0.569057 0.226778 0.561305 0.179844 0.547083 0.1776199 0.524918 0.22131 0.521977 0.226778 0.561305 0.1776199 0.524918 0.161632 0.593917 0.106427 0.634365 0.09646695 0.593917 0.119982 0.593917 0.09646695 0.593917 0.106427 0.634365 0.119982 0.593917 0.108929 0.593917 0.09646695 0.593917 0.171077 0.626682 0.119982 0.673721 0.106427 0.634365 0.119982 0.593917 0.106427 0.634365 0.119982 0.673721 0.161632 0.593917 0.171077 0.626682 0.106427 0.634365 0.1833209 0.65829 0.125511 0.687615 0.119982 0.673721 0.119982 0.593917 0.119982 0.673721 0.125511 0.687615 0.171077 0.626682 0.1833209 0.65829 0.119982 0.673721 0.1833209 0.65829 0.130129 0.699442 0.125511 0.687615 0.125651 0.593917 0.125511 0.687615 0.130129 0.699442 0.119982 0.593917 0.125511 0.687615 0.125651 0.593917 0.188288 0.668764 0.132122 0.704745 0.130129 0.699442 0.13036 0.593917 0.130129 0.699442 0.132122 0.704745 0.1833209 0.65829 0.188288 0.668764 0.130129 0.699442 0.125651 0.593917 0.130129 0.699442 0.13036 0.593917 0.188288 0.668764 0.1929309 0.677247 0.132122 0.704745 0.13036 0.593917 0.132122 0.704745 0.133746 0.593917 0.739602 0.68789 0.793088 0.724745 0.778922 0.749673 0.792246 0.76015 0.778922 0.749673 0.793088 0.724745 0.736557 0.691717 0.739602 0.68789 0.778922 0.749673 0.734072 0.694352 0.736557 0.691717 0.778922 0.749673 0.732164 0.695929 0.734072 0.694352 0.778922 0.749673 0.730777 0.696624 0.732164 0.695929 0.778922 0.749673 0.729844 0.696544 0.730777 0.696624 0.778922 0.749673 0.743159 0.682767 0.796192 0.718751 0.793088 0.724745 0.821712 0.744407 0.793088 0.724745 0.796192 0.718751 0.739602 0.68789 0.743159 0.682767 0.793088 0.724745 0.792246 0.76015 0.793088 0.724745 0.821712 0.744407 0.756181 0.65829 0.811536 0.685426 0.796192 0.718751 0.811435 0.693364 0.796192 0.718751 0.811536 0.685426 0.751534 0.668135 0.756181 0.65829 0.796192 0.718751 0.747164 0.676227 0.751534 0.668135 0.796192 0.718751 0.743159 0.682767 0.747164 0.676227 0.796192 0.718751 0.81202 0.699554 0.796192 0.718751 0.811435 0.693364 0.813211 0.704175 0.796192 0.718751 0.81202 0.699554 0.814904 0.707334 0.796192 0.718751 0.813211 0.704175 0.816911 0.709131 0.796192 0.718751 0.814904 0.707334 0.818564 0.709749 0.796192 0.718751 0.816911 0.709131 0.821712 0.744407 0.796192 0.718751 0.818564 0.709749 0.768425 0.626682 0.811774 0.683933 0.811536 0.685426 0.811515 0.593917 0.811536 0.685426 0.811774 0.683933 0.756181 0.65829 0.768425 0.626682 0.811536 0.685426 0.811409 0.593917 0.811536 0.685426 0.811515 0.593917 0.811435 0.693364 0.811536 0.685426 0.811409 0.593917 0.768425 0.626682 0.812115 0.682229 0.811774 0.683933 0.811515 0.593917 0.811774 0.683933 0.812115 0.682229 0.822537 0.625081 0.812115 0.682229 0.817775 0.653891 0.768425 0.626682 0.817775 0.653891 0.812115 0.682229 0.811515 0.593917 0.812115 0.682229 0.812115 0.593917 0.768425 0.626682 0.822537 0.625081 0.817775 0.653891 0.768425 0.626682 0.77787 0.593917 0.822537 0.625081 0.756181 0.593917 0.766414 0.593917 0.772146 0.593917 0.757124 0.625156 0.766414 0.593917 0.745128 0.65543 0.745128 0.593917 0.745128 0.65543 0.766414 0.593917 0.750655 0.593917 0.745128 0.593917 0.766414 0.593917 0.753442 0.593917 0.750655 0.593917 0.766414 0.593917 0.756181 0.593917 0.753442 0.593917 0.766414 0.593917 0.756181 0.593917 0.772146 0.593917 0.77787 0.593917 0.756181 0.593917 0.77787 0.593917 0.768425 0.626682 0.756181 0.593917 0.768425 0.626682 0.756181 0.65829 0.756181 0.593917 0.756181 0.65829 0.751534 0.668135 0.750655 0.593917 0.751534 0.668135 0.747164 0.676227 0.753442 0.593917 0.751534 0.668135 0.750655 0.593917 0.756181 0.593917 0.751534 0.668135 0.753442 0.593917 0.744546 0.593917 0.747164 0.676227 0.743159 0.682767 0.750655 0.593917 0.747164 0.676227 0.744546 0.593917 0.744546 0.593917 0.743159 0.682767 0.739602 0.68789 0.738978 0.593917 0.739602 0.68789 0.736557 0.691717 0.744546 0.593917 0.739602 0.68789 0.738978 0.593917 0.734388 0.593917 0.736557 0.691717 0.734072 0.694352 0.738978 0.593917 0.736557 0.691717 0.734388 0.593917 0.734388 0.593917 0.734072 0.694352 0.732164 0.695929 0.731141 0.593917 0.732164 0.695929 0.730777 0.696624 0.734388 0.593917 0.732164 0.695929 0.731141 0.593917 0.731141 0.593917 0.730777 0.696624 0.729844 0.696544 0.72949 0.593917 0.729844 0.696544 0.729361 0.695677 0.731141 0.593917 0.729844 0.696544 0.72949 0.593917 0.72949 0.593917 0.729361 0.695677 0.729384 0.693908 0.729566 0.593917 0.729384 0.693908 0.730025 0.691053 0.72949 0.593917 0.729384 0.693908 0.729566 0.593917 0.731365 0.593917 0.730025 0.691053 0.731385 0.686967 0.729566 0.593917 0.730025 0.691053 0.731365 0.593917 0.731365 0.593917 0.731385 0.686967 0.73353 0.681538 0.734751 0.593917 0.73353 0.681538 0.736516 0.674599 0.731365 0.593917 0.73353 0.681538 0.734751 0.593917 0.73946 0.593917 0.736516 0.674599 0.740377 0.665972 0.734751 0.593917 0.736516 0.674599 0.73946 0.593917 0.73946 0.593917 0.740377 0.665972 0.745128 0.65543 0.73946 0.593917 0.745128 0.65543 0.745128 0.593917 0.194373 0.593917 0.173088 0.593917 0.1823779 0.625156 0.167356 0.593917 0.173088 0.593917 0.1833209 0.593917 0.1833209 0.593917 0.161632 0.593917 0.167356 0.593917 0.1833209 0.593917 0.173088 0.593917 0.194373 0.593917 0.194373 0.593917 0.1823779 0.625156 0.194373 0.65543 0.194373 0.593917 0.194373 0.65543 0.1993629 0.666499 0.200043 0.593917 0.1993629 0.666499 0.203356 0.675439 0.200043 0.593917 0.194373 0.593917 0.1993629 0.666499 0.204752 0.593917 0.203356 0.675439 0.206381 0.68253 0.200043 0.593917 0.203356 0.675439 0.204752 0.593917 0.208138 0.593917 0.206381 0.68253 0.208483 0.68798 0.204752 0.593917 0.206381 0.68253 0.208138 0.593917 0.208138 0.593917 0.208483 0.68798 0.209724 0.691965 0.209936 0.593917 0.209724 0.691965 0.210189 0.694622 0.208138 0.593917 0.209724 0.691965 0.209936 0.593917 0.210011 0.593917 0.210189 0.694622 0.210002 0.696128 0.209936 0.593917 0.210189 0.694622 0.210011 0.593917 0.210011 0.593917 0.210002 0.696128 0.209277 0.696675 0.20836 0.593917 0.209277 0.696675 0.208057 0.696361 0.210011 0.593917 0.209277 0.696675 0.20836 0.593917 0.20836 0.593917 0.208057 0.696361 0.206293 0.695128 0.2051129 0.593917 0.206293 0.695128 0.203889 0.692777 0.20836 0.593917 0.206293 0.695128 0.2051129 0.593917 0.2051129 0.593917 0.203889 0.692777 0.200815 0.6891 0.200523 0.593917 0.200815 0.6891 0.197138 0.68397 0.2051129 0.593917 0.200815 0.6891 0.200523 0.593917 0.194955 0.593917 0.197138 0.68397 0.1929309 0.677247 0.200523 0.593917 0.197138 0.68397 0.194955 0.593917 0.188847 0.593917 0.1929309 0.677247 0.188288 0.668764 0.194955 0.593917 0.1929309 0.677247 0.188847 0.593917 0.18606 0.593917 0.188288 0.668764 0.1833209 0.65829 0.188847 0.593917 0.188288 0.668764 0.18606 0.593917 0.161632 0.593917 0.1833209 0.65829 0.171077 0.626682 0.1833209 0.593917 0.1833209 0.65829 0.161632 0.593917 0.18606 0.593917 0.1833209 0.65829 0.1833209 0.593917 0.853365 0.593917 0.811515 0.593917 0.812115 0.593917 0.859274 0.593917 0.853365 0.593917 0.812115 0.593917 0.853365 0.593917 0.811409 0.593917 0.811515 0.593917 0.853365 0.593917 0.811807 0.593917 0.811409 0.593917 0.811435 0.693364 0.811409 0.593917 0.811807 0.593917 0.853365 0.593917 0.812682 0.593917 0.811807 0.593917 0.81202 0.699554 0.811807 0.593917 0.812682 0.593917 0.81202 0.699554 0.811435 0.693364 0.811807 0.593917 0.851226 0.593917 0.814029 0.593917 0.812682 0.593917 0.813211 0.704175 0.812682 0.593917 0.814029 0.593917 0.853365 0.593917 0.851226 0.593917 0.812682 0.593917 0.813211 0.704175 0.81202 0.699554 0.812682 0.593917 0.851226 0.593917 0.8158 0.593917 0.814029 0.593917 0.814904 0.707334 0.814029 0.593917 0.8158 0.593917 0.814904 0.707334 0.813211 0.704175 0.814029 0.593917 0.847834 0.593917 0.817969 0.593917 0.8158 0.593917 0.816911 0.709131 0.8158 0.593917 0.817969 0.593917 0.851226 0.593917 0.847834 0.593917 0.8158 0.593917 0.816911 0.709131 0.814904 0.707334 0.8158 0.593917 0.843422 0.593917 0.820476 0.593917 0.817969 0.593917 0.818564 0.709749 0.817969 0.593917 0.820476 0.593917 0.847834 0.593917 0.843422 0.593917 0.817969 0.593917 0.818564 0.709749 0.816911 0.709131 0.817969 0.593917 0.843422 0.593917 0.823276 0.593917 0.820476 0.593917 0.82174 0.709556 0.820476 0.593917 0.823276 0.593917 0.819145 0.709835 0.818564 0.709749 0.820476 0.593917 0.82174 0.709556 0.819145 0.709835 0.820476 0.593917 0.838279 0.593917 0.826296 0.593917 0.823276 0.593917 0.824868 0.708096 0.823276 0.593917 0.826296 0.593917 0.843422 0.593917 0.838279 0.593917 0.823276 0.593917 0.824868 0.708096 0.82174 0.709556 0.823276 0.593917 0.838279 0.593917 0.82944 0.593917 0.826296 0.593917 0.828482 0.705166 0.826296 0.593917 0.82944 0.593917 0.828482 0.705166 0.824868 0.708096 0.826296 0.593917 0.838279 0.593917 0.83274 0.593917 0.82944 0.593917 0.832378 0.700644 0.82944 0.593917 0.83274 0.593917 0.832378 0.700644 0.828482 0.705166 0.82944 0.593917 0.836399 0.694428 0.83274 0.593917 0.838279 0.593917 0.836399 0.694428 0.832378 0.700644 0.83274 0.593917 0.840411 0.686351 0.838279 0.593917 0.843422 0.593917 0.836399 0.694428 0.838279 0.593917 0.840411 0.686351 0.844502 0.681691 0.843422 0.593917 0.847834 0.593917 0.844502 0.681691 0.840411 0.686351 0.843422 0.593917 0.848211 0.675225 0.847834 0.593917 0.851226 0.593917 0.848211 0.675225 0.844502 0.681691 0.847834 0.593917 0.851271 0.666742 0.851226 0.593917 0.853365 0.593917 0.851271 0.666742 0.848211 0.675225 0.851226 0.593917 0.85669 0.625553 0.853365 0.593917 0.859274 0.593917 0.853365 0.655982 0.851271 0.666742 0.853365 0.593917 0.85669 0.625553 0.853365 0.655982 0.853365 0.593917 1 0.588406 0.859274 0.593917 0.848384 0.593917 1 0.609646 0.859274 0.593917 1 0.588406 0.85669 0.625553 0.859274 0.593917 1 0.609646 1 0.669842 0.840411 0.686351 0.844502 0.681691 0.841952 0.694475 0.836399 0.694428 0.840411 0.686351 1 0.688437 0.841952 0.694475 0.840411 0.686351 1 0.688437 0.840411 0.686351 1 0.669842 1 0.669842 0.844502 0.681691 0.848211 0.675225 1 0.669842 0.848211 0.675225 0.851271 0.666742 1 0.650529 0.851271 0.666742 0.853365 0.655982 1 0.669842 0.851271 0.666742 1 0.650529 1 0.650529 0.853365 0.655982 1 0.630454 0.85669 0.625553 1 0.630454 0.853365 0.655982 0.821712 0.744407 0.818564 0.709749 0.819145 0.709835 0.821712 0.744407 0.819145 0.709835 0.82174 0.709556 0.850996 0.736571 0.82174 0.709556 0.824868 0.708096 0.850996 0.736571 0.821712 0.744407 0.82174 0.709556 0.843524 0.702427 0.824868 0.708096 0.828482 0.705166 0.843524 0.702427 0.850996 0.736571 0.824868 0.708096 0.843524 0.702427 0.828482 0.705166 0.832378 0.700644 0.841952 0.694475 0.832378 0.700644 0.836399 0.694428 0.841952 0.694475 0.843524 0.702427 0.832378 0.700644 0.850996 0.736571 0.824502 0.775395 0.821712 0.744407 0.792246 0.76015 0.821712 0.744407 0.824502 0.775395 0.8583 0.766162 0.826598 0.802161 0.824502 0.775395 0.790682 0.792447 0.824502 0.775395 0.826598 0.802161 0.850996 0.736571 0.8583 0.766162 0.824502 0.775395 0.790682 0.792447 0.792246 0.76015 0.824502 0.775395 0.86481 0.790594 0.827686 0.824377 0.826598 0.802161 0.78841 0.821011 0.826598 0.802161 0.827686 0.824377 0.8583 0.766162 0.86481 0.790594 0.826598 0.802161 0.78841 0.821011 0.790682 0.792447 0.826598 0.802161 0.871946 0.816989 0.82754 0.841871 0.827686 0.824377 0.785322 0.845527 0.827686 0.824377 0.82754 0.841871 0.869978 0.809548 0.871946 0.816989 0.827686 0.824377 0.86481 0.790594 0.869978 0.809548 0.827686 0.824377 0.785322 0.845527 0.78841 0.821011 0.827686 0.824377 0.874444 0.828055 0.826047 0.854624 0.82754 0.841871 0.781356 0.865771 0.82754 0.841871 0.826047 0.854624 0.87343 0.82319 0.874444 0.828055 0.82754 0.841871 0.871946 0.816989 0.87343 0.82319 0.82754 0.841871 0.781356 0.865771 0.785322 0.845527 0.82754 0.841871 0.874778 0.833551 0.823213 0.862748 0.826047 0.854624 0.776508 0.881618 0.826047 0.854624 0.823213 0.862748 0.874895 0.831506 0.874778 0.833551 0.826047 0.854624 0.874444 0.828055 0.874895 0.831506 0.826047 0.854624 0.776508 0.881618 0.781356 0.865771 0.826047 0.854624 0.874093 0.834213 0.81914 0.866449 0.823213 0.862748 0.770834 0.89302 0.823213 0.862748 0.81914 0.866449 0.874778 0.833551 0.874093 0.834213 0.823213 0.862748 0.770834 0.89302 0.776508 0.881618 0.823213 0.862748 0.87099 0.831374 0.814001 0.865986 0.81914 0.866449 0.764433 0.899996 0.81914 0.866449 0.814001 0.865986 0.872824 0.83349 0.87099 0.831374 0.81914 0.866449 0.874093 0.834213 0.872824 0.83349 0.81914 0.866449 0.764433 0.899996 0.770834 0.89302 0.81914 0.866449 0.865622 0.822877 0.808003 0.861639 0.814001 0.865986 0.757438 0.902616 0.814001 0.865986 0.808003 0.861639 0.868586 0.827839 0.865622 0.822877 0.814001 0.865986 0.87099 0.831374 0.868586 0.827839 0.814001 0.865986 0.757438 0.902616 0.764433 0.899996 0.814001 0.865986 0.862271 0.81662 0.801369 0.853685 0.808003 0.861639 0.749999 0.900979 0.808003 0.861639 0.801369 0.853685 0.865622 0.822877 0.862271 0.81662 0.808003 0.861639 0.749999 0.900979 0.757438 0.902616 0.808003 0.861639 0.854443 0.800545 0.794312 0.842388 0.801369 0.853685 0.74227 0.895211 0.801369 0.853685 0.794312 0.842388 0.858535 0.809218 0.854443 0.800545 0.801369 0.853685 0.862271 0.81662 0.858535 0.809218 0.801369 0.853685 0.74227 0.895211 0.749999 0.900979 0.801369 0.853685 0.849978 0.790477 0.787033 0.827991 0.794312 0.842388 0.734403 0.885457 0.794312 0.842388 0.787033 0.827991 0.854443 0.800545 0.849978 0.790477 0.794312 0.842388 0.734403 0.885457 0.74227 0.895211 0.794312 0.842388 0.840312 0.766438 0.77971 0.810723 0.787033 0.827991 0.726539 0.871876 0.787033 0.827991 0.77971 0.810723 0.845223 0.779092 0.840312 0.766438 0.787033 0.827991 0.849978 0.790477 0.845223 0.779092 0.787033 0.827991 0.726539 0.871876 0.734403 0.885457 0.787033 0.827991 0.835222 0.75255 0.772507 0.790794 0.77971 0.810723 0.718812 0.854648 0.77971 0.810723 0.772507 0.790794 0.840312 0.766438 0.835222 0.75255 0.77971 0.810723 0.718812 0.854648 0.726539 0.871876 0.77971 0.810723 0.830187 0.737547 0.765567 0.768414 0.772507 0.790794 0.711343 0.833967 0.772507 0.790794 0.765567 0.768414 0.835222 0.75255 0.830187 0.737547 0.772507 0.790794 0.711343 0.833967 0.718812 0.854648 0.772507 0.790794 0.820298 0.704504 0.759019 0.743783 0.765567 0.768414 0.704244 0.810053 0.765567 0.768414 0.759019 0.743783 0.825223 0.721509 0.820298 0.704504 0.765567 0.768414 0.830187 0.737547 0.825223 0.721509 0.765567 0.768414 0.704244 0.810053 0.711343 0.833967 0.765567 0.768414 0.754457 0.724456 0.759019 0.743783 0.820298 0.704504 0.697617 0.78314 0.704244 0.810053 0.759019 0.743783 0.693008 0.76114 0.697617 0.78314 0.759019 0.743783 0.693008 0.76114 0.759019 0.743783 0.754457 0.724456 0.910149 0.69647 0.820298 0.704504 0.825223 0.721509 0.817786 0.695094 0.754457 0.724456 0.820298 0.704504 0.910149 0.69647 0.817786 0.695094 0.820298 0.704504 1 0.706099 0.825223 0.721509 0.830187 0.737547 1 0.688437 0.825223 0.721509 1 0.706099 0.910149 0.69647 0.825223 0.721509 1 0.688437 1 0.722604 0.830187 0.737547 0.835222 0.75255 1 0.706099 0.830187 0.737547 1 0.722604 1 0.737987 0.835222 0.75255 0.840312 0.766438 1 0.722604 0.835222 0.75255 1 0.737987 1 0.752187 0.840312 0.766438 0.845223 0.779092 1 0.737987 0.840312 0.766438 1 0.752187 1 0.765053 0.845223 0.779092 0.849978 0.790477 1 0.752187 0.845223 0.779092 1 0.765053 1 0.776599 0.849978 0.790477 0.854443 0.800545 1 0.765053 0.849978 0.790477 1 0.776599 1 0.786693 0.854443 0.800545 0.858535 0.809218 1 0.776599 0.854443 0.800545 1 0.786693 1 0.795347 0.858535 0.809218 0.862271 0.81662 1 0.786693 0.858535 0.809218 1 0.795347 1 0.80247 0.862271 0.81662 0.865622 0.822877 1 0.795347 0.862271 0.81662 1 0.80247 1 0.808058 0.865622 0.822877 0.868586 0.827839 1 0.80247 0.865622 0.822877 1 0.808058 1 0.812066 0.868586 0.827839 0.87099 0.831374 1 0.808058 0.868586 0.827839 1 0.812066 1 0.812066 0.87099 0.831374 0.872824 0.83349 1 0.814477 0.872824 0.83349 0.874093 0.834213 1 0.812066 0.872824 0.83349 1 0.814477 1 0.815286 0.874093 0.834213 0.874778 0.833551 1 0.814477 0.874093 0.834213 1 0.815286 1 0.814477 0.874778 0.833551 0.874895 0.831506 1 0.815286 0.874778 0.833551 1 0.814477 1 0.812065 0.874895 0.831506 0.874444 0.828055 1 0.814477 0.874895 0.831506 1 0.812065 1 0.808057 0.874444 0.828055 0.87343 0.82319 1 0.812065 0.874444 0.828055 1 0.808057 1 0.802469 0.87343 0.82319 0.871946 0.816989 1 0.808057 0.87343 0.82319 1 0.802469 1 0.795347 0.871946 0.816989 0.869978 0.809548 1 0.802469 0.871946 0.816989 1 0.795347 1 0.786692 0.869978 0.809548 0.86481 0.790594 1 0.795347 0.869978 0.809548 1 0.786692 1 0.765052 0.86481 0.790594 0.8583 0.766162 1 0.776598 0.86481 0.790594 1 0.765052 1 0.786692 0.86481 0.790594 1 0.776598 1 0.737986 0.8583 0.766162 0.850996 0.736571 1 0.752186 0.8583 0.766162 1 0.737986 1 0.765052 0.8583 0.766162 1 0.752186 1 0.706098 0.850996 0.736571 0.843524 0.702427 1 0.722604 0.850996 0.736571 1 0.706098 1 0.737986 0.850996 0.736571 1 0.722604 1 0.688437 0.843524 0.702427 0.841952 0.694475 1 0.706098 0.843524 0.702427 1 0.688437 0.754457 0.724456 0.813446 0.68263 0.812058 0.677897 0.813343 0.593917 0.812058 0.677897 0.813446 0.68263 0.813343 0.593917 0.811616 0.593917 0.812058 0.677897 0.815904 0.687765 0.815422 0.685847 0.813446 0.68263 0.813343 0.593917 0.813446 0.68263 0.815422 0.685847 0.754457 0.724456 0.815904 0.687765 0.813446 0.68263 0.817983 0.689344 0.815422 0.685847 0.815904 0.687765 0.816626 0.593917 0.813343 0.593917 0.815422 0.685847 0.817983 0.689344 0.816626 0.593917 0.815422 0.685847 0.817786 0.695094 0.815904 0.687765 0.754457 0.724456 0.820732 0.691805 0.815904 0.687765 0.817786 0.695094 0.817983 0.689344 0.815904 0.687765 0.820732 0.691805 0.826462 0.694287 0.817786 0.695094 0.829537 0.694513 0.910149 0.69647 0.829537 0.694513 0.817786 0.695094 0.82356 0.693404 0.817786 0.695094 0.826462 0.694287 0.820732 0.691805 0.817786 0.695094 0.82356 0.693404 0.811462 0.66749 0.811596 0.593917 0.811596 0.665829 0.813114 0.64918 0.811596 0.665829 0.811596 0.593917 0.853885 0.593917 0.811596 0.593917 0.811616 0.593917 0.858426 0.593917 0.811596 0.593917 0.853885 0.593917 0.837562 0.593917 0.811596 0.593917 0.858426 0.593917 0.816638 0.593917 0.811596 0.593917 0.837562 0.593917 0.815643 0.613145 0.811596 0.593917 0.816638 0.593917 0.814466 0.631592 0.811596 0.593917 0.815643 0.613145 0.813114 0.64918 0.811596 0.593917 0.814466 0.631592 0.852178 0.593917 0.811616 0.593917 0.813343 0.593917 0.853885 0.593917 0.811616 0.593917 0.852178 0.593917 0.848898 0.593917 0.813343 0.593917 0.816626 0.593917 0.852178 0.593917 0.813343 0.593917 0.848898 0.593917 0.844313 0.593917 0.816626 0.593917 0.821202 0.593917 0.820732 0.691805 0.821202 0.593917 0.816626 0.593917 0.848898 0.593917 0.816626 0.593917 0.844313 0.593917 0.817983 0.689344 0.820732 0.691805 0.816626 0.593917 0.838784 0.593917 0.821202 0.593917 0.826717 0.593917 0.826462 0.694287 0.826717 0.593917 0.821202 0.593917 0.844313 0.593917 0.821202 0.593917 0.838784 0.593917 0.82356 0.693404 0.826462 0.694287 0.821202 0.593917 0.820732 0.691805 0.82356 0.693404 0.821202 0.593917 0.838784 0.593917 0.826717 0.593917 0.83274 0.593917 0.829537 0.694513 0.83274 0.593917 0.826717 0.593917 0.826462 0.694287 0.829537 0.694513 0.826717 0.593917 0.83635 0.692688 0.838784 0.593917 0.83274 0.593917 0.832837 0.694023 0.83635 0.692688 0.83274 0.593917 0.829537 0.694513 0.832837 0.694023 0.83274 0.593917 0.843764 0.686813 0.844313 0.593917 0.838784 0.593917 0.840032 0.690341 0.843764 0.686813 0.838784 0.593917 0.83635 0.692688 0.840032 0.690341 0.838784 0.593917 0.847336 0.681984 0.848898 0.593917 0.844313 0.593917 0.843764 0.686813 0.847336 0.681984 0.844313 0.593917 0.850505 0.675752 0.852178 0.593917 0.848898 0.593917 0.847336 0.681984 0.850505 0.675752 0.848898 0.593917 0.853885 0.662112 0.853885 0.593917 0.852178 0.593917 0.853521 0.665051 0.853885 0.662112 0.852178 0.593917 0.852966 0.667966 0.853521 0.665051 0.852178 0.593917 0.850505 0.675752 0.852966 0.667966 0.852178 0.593917 0.858426 0.593917 0.853885 0.593917 0.853885 0.662112 0.903374 0.639776 0.853885 0.662112 0.853521 0.665051 0.85752 0.612009 0.858426 0.593917 0.853885 0.662112 0.855244 0.646172 0.853885 0.662112 0.903374 0.639776 0.856458 0.629449 0.853885 0.662112 0.855244 0.646172 0.85752 0.612009 0.853885 0.662112 0.856458 0.629449 0.903374 0.639776 0.853521 0.665051 0.852966 0.667966 0.910149 0.69647 0.852966 0.667966 0.850505 0.675752 0.905955 0.663592 0.903374 0.639776 0.852966 0.667966 0.910149 0.69647 0.905955 0.663592 0.852966 0.667966 0.910149 0.69647 0.850505 0.675752 0.847336 0.681984 0.910149 0.69647 0.847336 0.681984 0.843764 0.686813 0.910149 0.69647 0.843764 0.686813 0.840032 0.690341 0.910149 0.69647 0.840032 0.690341 0.83635 0.692688 0.910149 0.69647 0.83635 0.692688 0.832837 0.694023 0.910149 0.69647 0.832837 0.694023 0.829537 0.694513 0.899065 0.587673 0.837562 0.593917 0.858426 0.593917 0.85752 0.612009 0.899065 0.587673 0.858426 0.593917 0.899065 0.587673 0.816638 0.593917 0.837562 0.593917 1 0.542461 0.896628 0.531392 0.897565 0.559898 1 0.542461 1 0.522569 0.896628 0.531392 1 0.56223 0.897565 0.559898 0.899065 0.587673 1 0.56223 1 0.542461 0.897565 0.559898 0.85752 0.612009 0.901037 0.614393 0.899065 0.587673 1 0.581756 0.899065 0.587673 0.901037 0.614393 1 0.581756 1 0.56223 0.899065 0.587673 0.856458 0.629449 0.903374 0.639776 0.901037 0.614393 1 0.619753 0.901037 0.614393 0.903374 0.639776 0.85752 0.612009 0.856458 0.629449 0.901037 0.614393 1 0.600956 1 0.581756 0.901037 0.614393 1 0.619753 1 0.600956 0.901037 0.614393 1 0.638031 0.903374 0.639776 0.905955 0.663592 0.856458 0.629449 0.855244 0.646172 0.903374 0.639776 1 0.638031 1 0.619753 0.903374 0.639776 1 0.655828 1 0.638031 0.905955 0.663592 1 0.672461 1 0.655828 0.905955 0.663592 1 0.672461 0.905955 0.663592 1 0.688437 0.910149 0.69647 1 0.688437 0.905955 0.663592 1 0.522699 1 0.522569 1 0.542461 1 0.522699 1 0.500545 1 0.522569 1 0.544743 1 0.542461 1 0.56223 1 0.544743 1 0.522699 1 0.542461 1 0.566683 1 0.56223 1 0.581756 1 0.566683 1 0.544743 1 0.56223 1 0.588406 1 0.581756 1 0.600956 1 0.588406 1 0.566683 1 0.581756 1 0.609646 1 0.600956 1 0.619753 1 0.609646 1 0.588406 1 0.600956 1 0.630454 1 0.619753 1 0.638031 1 0.630454 1 0.609646 1 0.619753 1 0.650529 1 0.638031 1 0.655828 1 0.650529 1 0.630454 1 0.638031 1 0.669842 1 0.650529 1 0.655828 1 0.672461 1 0.669842 1 0.655828 1 0.296579 1 0.282713 1 0.299088 0.830249 0.267332 1 0.299088 1 0.282713 1 0.313798 1 0.296579 1 0.299088 0.830249 0.267332 0.825248 0.28348 1 0.299088 1 0.280339 1 0.267434 1 0.282713 0.835326 0.252169 1 0.282713 1 0.267434 1 0.296579 1 0.280339 1 0.282713 0.835326 0.252169 0.830249 0.267332 1 0.282713 1 0.265261 1 0.253271 1 0.267434 0.840502 0.238082 1 0.267434 1 0.253271 1 0.280339 1 0.265261 1 0.267434 0.840502 0.238082 0.835326 0.252169 1 0.267434 1 0.251357 1 0.240434 1 0.253271 0.845536 0.225181 1 0.253271 1 0.240434 1 0.265261 1 0.251357 1 0.253271 0.845536 0.225181 0.840502 0.238082 1 0.253271 1 0.238714 1 0.228901 1 0.240434 0.850415 0.213499 1 0.240434 1 0.228901 1 0.251357 1 0.238714 1 0.240434 0.850415 0.213499 0.845536 0.225181 1 0.240434 1 0.2274309 1 0.218791 1 0.228901 0.85505 0.203182 1 0.228901 1 0.218791 1 0.238714 1 0.2274309 1 0.228901 0.85505 0.203182 0.850415 0.213499 1 0.228901 1 0.217501 1 0.210156 1 0.218791 0.859223 0.194376 1 0.218791 1 0.210156 1 0.2274309 1 0.217501 1 0.218791 0.859223 0.194376 0.85505 0.203182 1 0.218791 1 0.209053 1 0.202994 1 0.210156 0.862989 0.187034 1 0.210156 1 0.202994 1 0.217501 1 0.209053 1 0.210156 0.862989 0.187034 0.859223 0.194376 1 0.210156 1 0.202063 1 0.19734 1 0.202994 0.866287 0.1810089 1 0.202994 1 0.19734 1 0.209053 1 0.202063 1 0.202994 0.866287 0.1810089 0.862989 0.187034 1 0.202994 1 0.196622 1 0.1931959 1 0.19734 0.869131 0.176309 1 0.19734 1 0.1931959 1 0.202063 1 0.196622 1 0.19734 0.869131 0.176309 0.866287 0.1810089 1 0.19734 1 0.1927379 1 0.190667 1 0.1931959 0.871459 0.173049 1 0.1931959 1 0.190667 1 0.196622 1 0.1927379 1 0.1931959 0.871459 0.173049 0.869131 0.176309 1 0.1931959 1 0.190436 1 0.18975 1 0.190667 0.873169 0.171244 1 0.190667 1 0.18975 1 0.1927379 1 0.190436 1 0.190667 0.873169 0.171244 0.871459 0.173049 1 0.190667 0.874293 0.170841 1 0.18975 1 0.190436 0.874293 0.170841 0.873169 0.171244 1 0.18975 0.874858 0.171805 1 0.190436 1 0.1927379 0.874858 0.171805 0.874293 0.170841 1 0.190436 0.874852 0.174093 1 0.1927379 1 0.196622 0.874852 0.174093 0.874858 0.171805 1 0.1927379 0.873276 0.182592 1 0.196622 1 0.202063 0.874314 0.177687 0.874852 0.174093 1 0.196622 0.873276 0.182592 0.874314 0.177687 1 0.196622 0.873276 0.182592 1 0.202063 1 0.209053 0.869759 0.196326 1 0.209053 1 0.217501 0.869759 0.196326 0.873276 0.182592 1 0.209053 0.869759 0.196326 1 0.217501 1 0.2274309 0.864527 0.215445 1 0.2274309 1 0.238714 0.864527 0.215445 0.869759 0.196326 1 0.2274309 0.864527 0.215445 1 0.238714 1 0.251357 0.858161 0.2392899 1 0.251357 1 0.265261 0.858161 0.2392899 0.864527 0.215445 1 0.251357 0.858161 0.2392899 1 0.265261 1 0.280339 0.851119 0.267802 1 0.280339 1 0.296579 0.851119 0.267802 0.858161 0.2392899 1 0.280339 0.851119 0.267802 1 0.296579 1 0.313798 0.843886 0.300883 1 0.313798 1 0.332035 0.843886 0.300883 0.851119 0.267802 1 0.313798 0.837076 0.337754 1 0.332035 1 0.351077 0.837076 0.337754 0.843886 0.300883 1 0.332035 0.837076 0.337754 1 0.351077 1 0.370938 0.85669 0.625553 1 0.609646 1 0.630454 1 0.688437 1 0.688437 1 0.669842 1 0.672461 1 0.688437 1 0.669842 1 0.706099 1 0.706098 1 0.688437 1 0.688437 1 0.706099 1 0.688437 1 0.722604 1 0.722604 1 0.706098 1 0.706099 1 0.722604 1 0.706098 1 0.737987 1 0.737986 1 0.722604 1 0.722604 1 0.737987 1 0.722604 1 0.737987 1 0.752186 1 0.737986 1 0.752187 1 0.765052 1 0.752186 1 0.737987 1 0.752187 1 0.752186 1 0.765053 1 0.776598 1 0.765052 1 0.752187 1 0.765053 1 0.765052 1 0.776599 1 0.786692 1 0.776598 1 0.765053 1 0.776599 1 0.776598 1 0.786693 1 0.795347 1 0.786692 1 0.776599 1 0.786693 1 0.786692 1 0.795347 1 0.802469 1 0.795347 1 0.786693 1 0.795347 1 0.795347 1 0.808058 1 0.808057 1 0.802469 1 0.80247 1 0.808058 1 0.802469 1 0.795347 1 0.80247 1 0.802469 1 0.812066 1 0.812065 1 0.808057 1 0.808058 1 0.812066 1 0.808057 1 0.814477 1 0.814477 1 0.812065 1 0.812066 1 0.814477 1 0.812065 1 0.814477 1 0.815286 1 0.814477 0.765931 0.2353529 0.825248 0.28348 0.830249 0.267332 0.77327 0.2119719 0.830249 0.267332 0.835326 0.252169 0.765931 0.2353529 0.830249 0.267332 0.77327 0.2119719 0.77327 0.2119719 0.835326 0.252169 0.840502 0.238082 0.780885 0.191338 0.840502 0.238082 0.845536 0.225181 0.77327 0.2119719 0.840502 0.238082 0.780885 0.191338 0.788604 0.173695 0.845536 0.225181 0.850415 0.213499 0.780885 0.191338 0.845536 0.225181 0.788604 0.173695 0.788604 0.173695 0.850415 0.213499 0.85505 0.203182 0.796235 0.1592929 0.85505 0.203182 0.859223 0.194376 0.788604 0.173695 0.85505 0.203182 0.796235 0.1592929 0.803561 0.148403 0.859223 0.194376 0.862989 0.187034 0.796235 0.1592929 0.859223 0.194376 0.803561 0.148403 0.803561 0.148403 0.862989 0.187034 0.866287 0.1810089 0.810343 0.141317 0.866287 0.1810089 0.869131 0.176309 0.803561 0.148403 0.866287 0.1810089 0.810343 0.141317 0.816325 0.1383489 0.869131 0.176309 0.871459 0.173049 0.810343 0.141317 0.869131 0.176309 0.816325 0.1383489 0.816325 0.1383489 0.871459 0.173049 0.873169 0.171244 0.821252 0.139828 0.873169 0.171244 0.874293 0.170841 0.816325 0.1383489 0.873169 0.171244 0.821252 0.139828 0.821252 0.139828 0.874293 0.170841 0.874858 0.171805 0.824897 0.146073 0.874858 0.171805 0.874852 0.174093 0.821252 0.139828 0.874858 0.171805 0.824897 0.146073 0.824897 0.146073 0.874852 0.174093 0.874314 0.177687 0.827093 0.157361 0.874314 0.177687 0.873276 0.182592 0.824897 0.146073 0.874314 0.177687 0.827093 0.157361 0.827784 0.173876 0.873276 0.182592 0.869759 0.196326 0.827093 0.157361 0.873276 0.182592 0.827784 0.173876 0.827045 0.195658 0.869759 0.196326 0.864527 0.215445 0.827784 0.173876 0.869759 0.196326 0.827045 0.195658 0.825101 0.222566 0.864527 0.215445 0.858161 0.2392899 0.827045 0.195658 0.864527 0.215445 0.825101 0.222566 0.822294 0.254266 0.858161 0.2392899 0.851119 0.267802 0.825101 0.222566 0.858161 0.2392899 0.822294 0.254266 0.819035 0.290247 0.851119 0.267802 0.843886 0.300883 0.822294 0.254266 0.851119 0.267802 0.819035 0.290247 0.825101 0.222566 0.792162 0.242654 0.790434 0.208712 0.825101 0.222566 0.822294 0.254266 0.792162 0.242654 0.827045 0.195658 0.790434 0.208712 0.787889 0.1790339 0.827045 0.195658 0.825101 0.222566 0.790434 0.208712 0.827784 0.173876 0.787889 0.1790339 0.784405 0.15398 0.827784 0.173876 0.827045 0.195658 0.787889 0.1790339 0.827093 0.157361 0.784405 0.15398 0.779923 0.13379 0.827093 0.157361 0.827784 0.173876 0.784405 0.15398 0.824897 0.146073 0.779923 0.13379 0.774461 0.118588 0.824897 0.146073 0.827093 0.157361 0.779923 0.13379 0.821252 0.139828 0.774461 0.118588 0.768104 0.1084 0.821252 0.139828 0.824897 0.146073 0.774461 0.118588 0.816325 0.1383489 0.768104 0.1084 0.760989 0.103177 0.816325 0.1383489 0.821252 0.139828 0.768104 0.1084 0.810343 0.141317 0.760989 0.103177 0.753288 0.102818 0.810343 0.141317 0.816325 0.1383489 0.760989 0.103177 0.803561 0.148403 0.753288 0.102818 0.745183 0.107184 0.803561 0.148403 0.810343 0.141317 0.753288 0.102818 0.796235 0.1592929 0.745183 0.107184 0.736859 0.116113 0.796235 0.1592929 0.803561 0.148403 0.745183 0.107184 0.788604 0.173695 0.736859 0.116113 0.728491 0.129417 0.788604 0.173695 0.796235 0.1592929 0.736859 0.116113 0.780885 0.191338 0.728491 0.129417 0.72024 0.14689 0.780885 0.191338 0.788604 0.173695 0.728491 0.129417 0.77327 0.2119719 0.72024 0.14689 0.712256 0.168301 0.77327 0.2119719 0.780885 0.191338 0.72024 0.14689 0.765931 0.2353529 0.712256 0.168301 0.704674 0.193393 0.765931 0.2353529 0.77327 0.2119719 0.712256 0.168301 0.469751 0.769108 0.469751 0.769108 0.432612 0.76613 0.50689 0.76613 0.48856 0.768339 0.469751 0.769108 0.50689 0.76613 0.469751 0.769108 0.469751 0.769108 0.432383 0.766091 0.432612 0.76613 0.396263 0.757238 0.450942 0.768339 0.469751 0.769108 0.432612 0.76613 0.432383 0.766091 0.450942 0.768339 0.432612 0.76613 0.395916 0.757122 0.396263 0.757238 0.361563 0.742644 0.414034 0.762349 0.432383 0.766091 0.396263 0.757238 0.395916 0.757122 0.414034 0.762349 0.396263 0.757238 0.361204 0.742459 0.361563 0.742644 0.329402 0.722775 0.361204 0.742459 0.395916 0.757122 0.361563 0.742644 0.329118 0.722569 0.329402 0.722775 0.300347 0.697958 0.329118 0.722569 0.361204 0.742459 0.329402 0.722775 0.300197 0.697812 0.300347 0.697958 0.287053 0.68373 0.300197 0.697812 0.329118 0.722569 0.300347 0.697958 0.274861 0.66856 0.287053 0.68373 0.274858 0.668555 0.274861 0.66856 0.300197 0.697812 0.287053 0.68373 0.253943 0.635677 0.274858 0.668555 0.253819 0.635446 0.253943 0.635677 0.274861 0.66856 0.274858 0.668555 0.237852 0.599884 0.253819 0.635446 0.23768 0.59941 0.237852 0.599884 0.253943 0.635677 0.253819 0.635446 0.2269189 0.561973 0.23768 0.59941 0.226778 0.561305 0.2269189 0.561973 0.237852 0.599884 0.23768 0.59941 0.221364 0.522749 0.226778 0.561305 0.22131 0.521977 0.221364 0.522749 0.2269189 0.561973 0.226778 0.561305 0.22131 0.48305 0.22131 0.521977 0.221364 0.482277 0.22131 0.48305 0.221364 0.522749 0.22131 0.521977 0.226778 0.443722 0.221364 0.482277 0.2269189 0.443054 0.226778 0.443722 0.22131 0.48305 0.221364 0.482277 0.23768 0.405616 0.2269189 0.443054 0.237852 0.405142 0.23768 0.405616 0.226778 0.443722 0.2269189 0.443054 0.253819 0.36958 0.237852 0.405142 0.253943 0.369349 0.253819 0.36958 0.23768 0.405616 0.237852 0.405142 0.274858 0.336472 0.253943 0.369349 0.274861 0.336466 0.274858 0.336472 0.253819 0.36958 0.253943 0.369349 0.287053 0.321296 0.274861 0.336466 0.300197 0.307215 0.287053 0.321296 0.274858 0.336472 0.274861 0.336466 0.300347 0.307068 0.300197 0.307215 0.329118 0.282457 0.300347 0.307068 0.287053 0.321296 0.300197 0.307215 0.329402 0.282251 0.329118 0.282457 0.361204 0.262568 0.329402 0.282251 0.300347 0.307068 0.329118 0.282457 0.361563 0.262382 0.361204 0.262568 0.395916 0.247904 0.361563 0.262382 0.329402 0.282251 0.361204 0.262568 0.396263 0.247788 0.395916 0.247904 0.414034 0.242677 0.396263 0.247788 0.361563 0.262382 0.395916 0.247904 0.396263 0.247788 0.414034 0.242677 0.432383 0.2389349 0.432612 0.238896 0.432383 0.2389349 0.450942 0.236687 0.432612 0.238896 0.396263 0.247788 0.432383 0.2389349 0.432612 0.238896 0.450942 0.236687 0.469751 0.235918 0.469751 0.235918 0.469751 0.235918 0.50689 0.238896 0.469751 0.235918 0.432612 0.238896 0.469751 0.235918 0.507118 0.2389349 0.50689 0.238896 0.543239 0.247788 0.48856 0.236687 0.469751 0.235918 0.50689 0.238896 0.507118 0.2389349 0.48856 0.236687 0.50689 0.238896 0.543586 0.247904 0.543239 0.247788 0.577939 0.262382 0.525467 0.242677 0.507118 0.2389349 0.543239 0.247788 0.543586 0.247904 0.525467 0.242677 0.543239 0.247788 0.578297 0.262568 0.577939 0.262382 0.6101 0.282251 0.578297 0.262568 0.543586 0.247904 0.577939 0.262382 0.610383 0.282457 0.6101 0.282251 0.639155 0.307068 0.610383 0.282457 0.578297 0.262568 0.6101 0.282251 0.639305 0.307215 0.639155 0.307068 0.652449 0.321296 0.639305 0.307215 0.610383 0.282457 0.639155 0.307068 0.664641 0.336466 0.652449 0.321296 0.664644 0.336472 0.664641 0.336466 0.639305 0.307215 0.652449 0.321296 0.685559 0.369349 0.664644 0.336472 0.685683 0.36958 0.685559 0.369349 0.664641 0.336466 0.664644 0.336472 0.701649 0.405142 0.685683 0.36958 0.701822 0.405616 0.701649 0.405142 0.685559 0.369349 0.685683 0.36958 0.712583 0.443054 0.701822 0.405616 0.712724 0.443722 0.712583 0.443054 0.701649 0.405142 0.701822 0.405616 0.718138 0.482277 0.712724 0.443722 0.718191 0.48305 0.718138 0.482277 0.712583 0.443054 0.712724 0.443722 0.718191 0.521977 0.718191 0.48305 0.718138 0.522749 0.718191 0.521977 0.718138 0.482277 0.718191 0.48305 0.712724 0.561305 0.718138 0.522749 0.712583 0.561973 0.712724 0.561305 0.718191 0.521977 0.718138 0.522749 0.701822 0.59941 0.712583 0.561973 0.701649 0.599884 0.701822 0.59941 0.712724 0.561305 0.712583 0.561973 0.685683 0.635446 0.701649 0.599884 0.685559 0.635677 0.685683 0.635446 0.701822 0.59941 0.701649 0.599884 0.664644 0.668555 0.685559 0.635677 0.664641 0.66856 0.664644 0.668555 0.685683 0.635446 0.685559 0.635677 0.652449 0.68373 0.664641 0.66856 0.639305 0.697812 0.652449 0.68373 0.664644 0.668555 0.664641 0.66856 0.639155 0.697958 0.639305 0.697812 0.610383 0.722569 0.639155 0.697958 0.652449 0.68373 0.639305 0.697812 0.6101 0.722775 0.610383 0.722569 0.578297 0.742459 0.6101 0.722775 0.639155 0.697958 0.610383 0.722569 0.577939 0.742644 0.578297 0.742459 0.543586 0.757122 0.577939 0.742644 0.6101 0.722775 0.578297 0.742459 0.543239 0.757238 0.543586 0.757122 0.525467 0.762349 0.543239 0.757238 0.577939 0.742644 0.543586 0.757122 0.543239 0.757238 0.525467 0.762349 0.507118 0.766091 0.50689 0.76613 0.507118 0.766091 0.48856 0.768339 0.50689 0.76613 0.543239 0.757238 0.507118 0.766091 0.50689 0.76613 0.469751 0.769108 0.450942 0.768339 0.50689 0.76613 0.450942 0.768339 0.432383 0.766091 0.50689 0.76613 0.432383 0.766091 0.414034 0.762349 0.543239 0.757238 0.414034 0.762349 0.395916 0.757122 0.50689 0.76613 0.414034 0.762349 0.543239 0.757238 0.577939 0.742644 0.395916 0.757122 0.361204 0.742459 0.543239 0.757238 0.395916 0.757122 0.577939 0.742644 0.6101 0.722775 0.361204 0.742459 0.329118 0.722569 0.577939 0.742644 0.361204 0.742459 0.6101 0.722775 0.639155 0.697958 0.329118 0.722569 0.300197 0.697812 0.6101 0.722775 0.329118 0.722569 0.639155 0.697958 0.652449 0.68373 0.300197 0.697812 0.274861 0.66856 0.639155 0.697958 0.300197 0.697812 0.652449 0.68373 0.664644 0.668555 0.274861 0.66856 0.253943 0.635677 0.652449 0.68373 0.274861 0.66856 0.664644 0.668555 0.685683 0.635446 0.253943 0.635677 0.237852 0.599884 0.664644 0.668555 0.253943 0.635677 0.685683 0.635446 0.701822 0.59941 0.237852 0.599884 0.2269189 0.561973 0.685683 0.635446 0.237852 0.599884 0.701822 0.59941 0.712724 0.561305 0.2269189 0.561973 0.221364 0.522749 0.701822 0.59941 0.2269189 0.561973 0.712724 0.561305 0.718191 0.521977 0.221364 0.522749 0.22131 0.48305 0.712724 0.561305 0.221364 0.522749 0.718191 0.521977 0.718138 0.482277 0.22131 0.48305 0.226778 0.443722 0.718191 0.521977 0.22131 0.48305 0.718138 0.482277 0.712583 0.443054 0.226778 0.443722 0.23768 0.405616 0.718138 0.482277 0.226778 0.443722 0.712583 0.443054 0.701649 0.405142 0.23768 0.405616 0.253819 0.36958 0.712583 0.443054 0.23768 0.405616 0.701649 0.405142 0.685559 0.369349 0.253819 0.36958 0.274858 0.336472 0.701649 0.405142 0.253819 0.36958 0.685559 0.369349 0.664641 0.336466 0.274858 0.336472 0.287053 0.321296 0.685559 0.369349 0.274858 0.336472 0.664641 0.336466 0.639305 0.307215 0.287053 0.321296 0.300347 0.307068 0.664641 0.336466 0.287053 0.321296 0.639305 0.307215 0.610383 0.282457 0.300347 0.307068 0.329402 0.282251 0.639305 0.307215 0.300347 0.307068 0.610383 0.282457 0.578297 0.262568 0.329402 0.282251 0.361563 0.262382 0.610383 0.282457 0.329402 0.282251 0.578297 0.262568 0.543586 0.247904 0.361563 0.262382 0.396263 0.247788 0.578297 0.262568 0.361563 0.262382 0.543586 0.247904 0.525467 0.242677 0.396263 0.247788 0.432612 0.238896 0.543586 0.247904 0.396263 0.247788 0.525467 0.242677 0.48856 0.236687 0.432612 0.238896 0.469751 0.235918 0.507118 0.2389349 0.432612 0.238896 0.48856 0.236687 0.525467 0.242677 0.432612 0.238896 0.507118 0.2389349 0.119982 0.593917 0.111668 0.593917 0.108929 0.593917 0.119982 0.593917 0.1144559 0.593917 0.111668 0.593917 0.119982 0.593917 0.120564 0.593917 0.1144559 0.593917 0.125651 0.593917 0.1261309 0.593917 0.120564 0.593917 0.119982 0.593917 0.125651 0.593917 0.120564 0.593917 0.13036 0.593917 0.130721 0.593917 0.1261309 0.593917 0.125651 0.593917 0.13036 0.593917 0.1261309 0.593917 0.133746 0.593917 0.133969 0.593917 0.130721 0.593917 0.13036 0.593917 0.133746 0.593917 0.130721 0.593917 0.135545 0.593917 0.1356199 0.593917 0.133969 0.593917 0.133746 0.593917 0.135545 0.593917 0.133969 0.593917 0.744546 0.593917 0.73946 0.593917 0.745128 0.593917 0.750655 0.593917 0.744546 0.593917 0.745128 0.593917 0.738978 0.593917 0.734751 0.593917 0.73946 0.593917 0.744546 0.593917 0.738978 0.593917 0.73946 0.593917 0.734388 0.593917 0.731365 0.593917 0.734751 0.593917 0.738978 0.593917 0.734388 0.593917 0.734751 0.593917 0.731141 0.593917 0.729566 0.593917 0.731365 0.593917 0.734388 0.593917 0.731141 0.593917 0.731365 0.593917 0.731141 0.593917 0.72949 0.593917 0.729566 0.593917 0.18606 0.593917 0.1833209 0.593917 0.194373 0.593917 0.188847 0.593917 0.18606 0.593917 0.194373 0.593917 0.194955 0.593917 0.188847 0.593917 0.194373 0.593917 0.200043 0.593917 0.194955 0.593917 0.194373 0.593917 0.200043 0.593917 0.200523 0.593917 0.194955 0.593917 0.204752 0.593917 0.2051129 0.593917 0.200523 0.593917 0.200043 0.593917 0.204752 0.593917 0.200523 0.593917 0.208138 0.593917 0.20836 0.593917 0.2051129 0.593917 0.204752 0.593917 0.208138 0.593917 0.2051129 0.593917 0.209936 0.593917 0.210011 0.593917 0.20836 0.593917 0.208138 0.593917 0.209936 0.593917 0.20836 0.593917 0.30722 0.593917 0.348716 0.593917 0.347584 0.593917 0.30722 0.593917 0.348269 0.593917 0.348716 0.593917 0.30722 0.593917 0.3463 0.593917 0.348269 0.593917 0.310324 0.593917 0.342959 0.593917 0.3463 0.593917 0.308574 0.593917 0.310324 0.593917 0.3463 0.593917 0.30722 0.593917 0.308574 0.593917 0.3463 0.593917 0.315012 0.593917 0.338479 0.593917 0.342959 0.593917 0.312496 0.593917 0.315012 0.593917 0.342959 0.593917 0.310324 0.593917 0.312496 0.593917 0.342959 0.593917 0.320866 0.593917 0.333177 0.593917 0.338479 0.593917 0.317823 0.593917 0.320866 0.593917 0.338479 0.593917 0.315012 0.593917 0.317823 0.593917 0.338479 0.593917 0.324049 0.593917 0.327402 0.593917 0.333177 0.593917 0.320866 0.593917 0.324049 0.593917 0.333177 0.593917 0.132943 0.593917 0.133904 0.593917 0.129603 0.593917 0.128408 0.593917 0.132943 0.593917 0.129603 0.593917 0.136246 0.593917 0.136866 0.593917 0.133904 0.593917 0.132943 0.593917 0.136246 0.593917 0.133904 0.593917 0.138074 0.593917 0.138289 0.593917 0.136866 0.593917 0.136246 0.593917 0.138074 0.593917 0.136866 0.593917 0.03991299 0.593917 0.03988796 0.593917 0.03380799 0.593917 0.03380799 0.593917 0.03991299 0.593917 0.03380799 0.593917 0.03991299 0.593917 0.04541999 0.593917 0.03988796 0.593917 0.04549199 0.593917 0.049959 0.593917 0.04541999 0.593917 0.03991299 0.593917 0.04549199 0.593917 0.04541999 0.593917 0.05005198 0.593917 0.05320894 0.593917 0.049959 0.593917 0.04549199 0.593917 0.05005198 0.593917 0.049959 0.593917 0.05327898 0.593917 0.05492496 0.593917 0.05320894 0.593917 0.05005198 0.593917 0.05327898 0.593917 0.05320894 0.593917 0.05327898 0.593917 0.05494999 0.593917 0.05492496 0.593917 0.535486 0.873461 0.537367 0.873461 0.53547 0.873461 0.529953 0.873461 0.53547 0.873461 0.529869 0.873461 0.535486 0.873461 0.53547 0.873461 0.529953 0.873461 0.521065 0.873461 0.529869 0.873461 0.520866 0.873461 0.529953 0.873461 0.529869 0.873461 0.521065 0.873461 0.509356 0.873461 0.520866 0.873461 0.50904 0.873461 0.521065 0.873461 0.520866 0.873461 0.509356 0.873461 0.495243 0.873461 0.50904 0.873461 0.494872 0.873461 0.509356 0.873461 0.50904 0.873461 0.495243 0.873461 0.479444 0.873461 0.494872 0.873461 0.47908 0.873461 0.495243 0.873461 0.494872 0.873461 0.479444 0.873461 0.462811 0.873461 0.47908 0.873461 0.462456 0.873461 0.479444 0.873461 0.47908 0.873461 0.462811 0.873461 0.446187 0.873461 0.462456 0.873461 0.445823 0.873461 0.462811 0.873461 0.462456 0.873461 0.446187 0.873461 0.430395 0.873461 0.445823 0.873461 0.430024 0.873461 0.446187 0.873461 0.445823 0.873461 0.430395 0.873461 0.416227 0.873461 0.430024 0.873461 0.415911 0.873461 0.430395 0.873461 0.430024 0.873461 0.416227 0.873461 0.404401 0.873461 0.415911 0.873461 0.404202 0.873461 0.416227 0.873461 0.415911 0.873461 0.404401 0.873461 0.395398 0.873461 0.404202 0.873461 0.395314 0.873461 0.404401 0.873461 0.404202 0.873461 0.395398 0.873461 0.389797 0.873461 0.395314 0.873461 0.389781 0.873461 - - - - - - - - - - - - - - -

0 0 0 1 1 1 2 2 2 3 3 3 4 4 4 5 5 5 6 6 6 0 0 7 2 2 8 7 7 9 6 6 10 2 2 11 8 8 12 7 7 13 2 2 14 9 9 15 10 9 16 11 9 17 12 10 18 13 11 19 1 1 20 3 3 21 5 5 22 14 12 23 0 0 24 12 10 25 1 1 26 15 13 27 16 14 28 13 11 29 17 15 30 18 16 31 19 17 32 12 10 33 15 13 34 13 11 35 15 13 36 20 18 37 16 14 38 21 19 39 19 17 40 22 20 41 17 15 42 19 17 43 21 19 44 15 13 45 23 21 46 20 18 47 24 22 48 22 20 49 25 23 50 21 19 51 22 20 52 24 22 53 26 24 54 27 25 55 23 21 56 28 26 57 25 23 58 29 27 59 15 13 60 26 24 61 23 21 62 24 22 63 25 23 64 28 26 65 26 24 66 30 28 67 27 25 68 28 26 69 29 27 70 31 29 71 26 24 72 32 30 73 30 28 74 33 31 75 31 29 76 34 32 77 28 26 78 31 29 79 33 31 80 26 24 81 35 33 82 32 30 83 33 31 84 34 32 85 36 34 86 26 24 87 37 35 88 35 33 89 38 36 90 36 34 91 39 37 92 33 31 93 36 34 94 38 36 95 26 24 96 40 38 97 37 35 98 41 39 99 39 37 100 42 40 101 38 36 102 39 37 103 41 39 104 43 41 105 44 42 106 40 38 107 41 39 108 42 40 109 45 43 110 26 24 111 43 41 112 40 38 113 43 41 114 46 44 115 44 42 116 47 45 117 45 43 118 48 46 119 41 39 120 45 43 121 47 45 122 43 41 123 49 47 124 46 44 125 50 48 126 48 46 127 51 49 128 47 45 129 48 46 130 50 48 131 43 41 132 52 50 133 49 47 134 53 51 135 51 49 136 54 52 137 50 48 138 51 49 139 53 51 140 55 53 141 56 54 142 57 55 143 53 51 144 54 52 145 58 56 146 59 57 147 58 56 148 54 52 149 55 53 150 60 58 151 56 54 152 61 59 153 56 54 154 60 58 155 26 24 156 62 60 157 43 41 158 63 61 159 43 41 160 62 60 161 64 62 162 57 55 163 65 63 164 64 62 165 55 53 166 57 55 167 66 64 168 67 65 169 62 60 170 68 66 171 62 60 172 67 65 173 26 24 174 66 64 175 62 60 176 68 66 177 63 61 178 62 60 179 69 67 180 70 68 181 67 65 182 71 69 183 67 65 184 70 68 185 66 64 186 69 67 187 67 65 188 72 70 189 68 66 190 67 65 191 71 69 192 72 70 193 67 65 194 73 71 195 74 72 196 70 68 197 75 73 198 70 68 199 74 72 200 69 67 201 73 71 202 70 68 203 76 74 204 71 69 205 70 68 206 75 73 207 76 74 208 70 68 209 77 75 210 78 76 211 74 72 212 79 77 213 74 72 214 78 76 215 73 71 216 77 75 217 74 72 218 80 78 219 75 73 220 74 72 221 79 77 222 80 78 223 74 72 224 81 79 225 82 80 226 78 76 227 83 81 228 78 76 229 82 80 230 77 75 231 81 79 232 78 76 233 84 82 234 79 77 235 78 76 236 83 81 237 84 82 238 78 76 239 85 83 240 86 84 241 82 80 242 87 85 243 82 80 244 86 84 245 81 79 246 85 83 247 82 80 248 88 86 249 83 81 250 82 80 251 89 87 252 88 86 253 82 80 254 87 85 255 89 87 256 82 80 257 90 88 258 91 89 259 86 84 260 87 85 261 86 84 262 91 89 263 85 83 264 90 88 265 86 84 266 92 90 267 93 91 268 91 89 269 94 92 270 91 89 271 93 91 272 90 88 273 92 90 274 91 89 275 94 92 276 87 85 277 91 89 278 95 93 279 96 94 280 93 91 281 97 95 282 93 91 283 96 94 284 92 90 285 95 93 286 93 91 287 97 95 288 94 92 289 93 91 290 98 96 291 99 97 292 96 94 293 100 98 294 96 94 295 99 97 296 95 93 297 98 96 298 96 94 299 100 98 300 97 95 301 96 94 302 101 99 303 102 100 304 99 97 305 103 101 306 99 97 307 102 100 308 98 96 309 101 99 310 99 97 311 103 101 312 100 98 313 99 97 314 104 102 315 105 103 316 102 100 317 106 104 318 102 100 319 105 103 320 101 99 321 104 102 322 102 100 323 106 104 324 103 101 325 102 100 326 107 105 327 108 106 328 105 103 329 109 107 330 105 103 331 108 106 332 104 102 333 107 105 334 105 103 335 109 107 336 106 104 337 105 103 338 110 108 339 111 109 340 108 106 341 112 110 342 108 106 343 111 109 344 113 111 345 110 108 346 108 106 347 107 105 348 113 111 349 108 106 350 112 110 351 109 107 352 108 106 353 114 112 354 115 113 355 116 114 356 117 115 357 112 110 358 111 109 359 114 112 360 118 116 361 115 113 362 119 117 363 116 114 364 120 118 365 119 117 366 114 112 367 116 114 368 121 119 369 113 111 370 107 105 371 122 120 372 120 118 373 123 121 374 122 120 375 119 117 376 120 118 377 124 122 378 107 105 379 104 102 380 125 123 381 121 119 382 107 105 383 126 124 384 125 123 385 107 105 386 124 122 387 126 124 388 107 105 389 127 125 390 104 102 391 101 99 392 127 125 393 124 122 394 104 102 395 128 126 396 101 99 397 98 96 398 128 126 399 127 125 400 101 99 401 129 127 402 98 96 403 95 93 404 129 127 405 128 126 406 98 96 407 130 128 408 95 93 409 92 90 410 131 129 411 129 127 412 95 93 413 130 128 414 131 129 415 95 93 416 132 130 417 92 90 418 90 88 419 133 131 420 130 128 421 92 90 422 134 132 423 133 131 424 92 90 425 135 133 426 134 132 427 92 90 428 132 130 429 135 133 430 92 90 431 136 134 432 90 88 433 85 83 434 136 134 435 132 130 436 90 88 437 137 135 438 85 83 439 81 79 440 137 135 441 136 134 442 85 83 443 138 136 444 81 79 445 77 75 446 138 136 447 137 135 448 81 79 449 139 137 450 77 75 451 73 71 452 139 137 453 138 136 454 77 75 455 140 138 456 73 71 457 69 67 458 140 138 459 139 137 460 73 71 461 141 139 462 69 67 463 66 64 464 141 139 465 140 138 466 69 67 467 142 140 468 66 64 469 26 24 470 142 140 471 141 139 472 66 64 473 143 141 474 26 24 475 15 13 476 143 141 477 142 140 478 26 24 479 144 142 480 15 13 481 12 10 482 144 142 483 143 141 484 15 13 485 145 143 486 12 10 487 0 0 488 145 143 489 144 142 490 12 10 491 146 144 492 0 0 493 6 6 494 146 144 495 145 143 496 0 0 497 147 145 498 148 146 499 6 6 500 149 147 501 6 6 502 148 146 503 7 7 504 147 145 505 6 6 506 149 147 507 146 144 508 6 6 509 150 148 510 151 149 511 152 150 512 153 151 513 149 147 514 148 146 515 154 152 516 155 153 517 151 149 518 154 152 519 151 149 520 150 148 521 156 154 522 157 155 523 158 156 524 159 157 525 160 158 526 161 159 527 162 160 528 160 158 529 159 157 530 8 8 531 163 161 532 7 7 533 164 162 534 158 156 535 165 163 536 166 164 537 156 154 538 158 156 539 164 162 540 166 164 541 158 156 542 9 9 543 167 9 544 10 9 545 9 9 546 168 9 547 167 9 548 169 165 549 165 163 550 170 166 551 169 165 552 164 162 553 165 163 554 171 167 555 172 168 556 173 169 557 174 170 558 64 62 559 65 63 560 175 171 561 174 170 562 65 63 563 171 167 564 176 172 565 172 168 566 177 173 567 173 169 568 178 174 569 171 167 570 173 169 571 177 173 572 179 175 573 180 176 574 181 177 575 182 178 576 181 177 577 183 179 578 179 175 579 181 177 580 182 178 581 182 178 582 183 179 583 184 180 584 185 181 585 184 180 586 186 182 587 182 178 588 184 180 589 185 181 590 185 181 591 186 182 592 187 183 593 188 184 594 187 183 595 189 185 596 185 181 597 187 183 598 188 184 599 188 184 600 189 185 601 190 186 602 191 187 603 190 186 604 192 188 605 188 184 606 190 186 607 191 187 608 191 187 609 192 188 610 193 189 611 194 190 612 89 87 613 87 85 614 195 191 615 193 189 616 196 192 617 191 187 618 193 189 619 195 191 620 197 193 621 87 85 622 94 92 623 197 193 624 194 190 625 87 85 626 198 194 627 94 92 628 97 95 629 199 195 630 197 193 631 94 92 632 198 194 633 199 195 634 94 92 635 200 196 636 97 95 637 100 98 638 201 197 639 198 194 640 97 95 641 200 196 642 201 197 643 97 95 644 202 198 645 100 98 646 103 101 647 203 199 648 200 196 649 100 98 650 202 198 651 203 199 652 100 98 653 204 200 654 103 101 655 106 104 656 205 201 657 202 198 658 103 101 659 204 200 660 205 201 661 103 101 662 206 202 663 106 104 664 109 107 665 206 202 666 204 200 667 106 104 668 207 203 669 109 107 670 112 110 671 207 203 672 206 202 673 109 107 674 117 115 675 208 204 676 112 110 677 209 205 678 112 110 679 208 204 680 209 205 681 207 203 682 112 110 683 210 206 684 211 207 685 118 116 686 212 208 687 209 205 688 208 204 689 213 209 690 214 210 691 211 207 692 210 206 693 213 209 694 211 207 695 114 112 696 210 206 697 118 116 698 215 211 699 196 192 700 216 212 701 195 191 702 196 192 703 215 211 704 215 211 705 216 212 706 217 213 707 218 214 708 217 213 709 219 215 710 215 211 711 217 213 712 218 214 713 218 214 714 219 215 715 220 216 716 221 217 717 220 216 718 222 218 719 218 214 720 220 216 721 221 217 722 223 219 723 222 218 724 224 220 725 221 217 726 222 218 727 223 219 728 223 219 729 224 220 730 225 221 731 223 219 732 225 221 733 226 222 734 227 223 735 205 201 736 204 200 737 228 224 738 226 222 739 229 225 740 223 219 741 226 222 742 228 224 743 230 226 744 204 200 745 206 202 746 231 227 747 227 223 748 204 200 749 230 226 750 231 227 751 204 200 752 232 228 753 206 202 754 207 203 755 233 229 756 230 226 757 206 202 758 232 228 759 233 229 760 206 202 761 234 230 762 207 203 763 209 205 764 235 231 765 232 228 766 207 203 767 234 230 768 235 231 769 207 203 770 212 208 771 236 232 772 209 205 773 237 233 774 209 205 775 236 232 776 238 234 777 234 230 778 209 205 779 237 233 780 238 234 781 209 205 782 239 235 783 240 236 784 214 210 785 241 237 786 237 233 787 236 232 788 242 238 789 241 237 790 236 232 791 243 239 792 244 240 793 240 236 794 239 235 795 243 239 796 240 236 797 213 209 798 239 235 799 214 210 800 228 224 801 229 225 802 245 241 803 246 242 804 245 241 805 247 243 806 228 224 807 245 241 808 246 242 809 246 242 810 247 243 811 248 244 812 249 245 813 248 244 814 250 246 815 246 242 816 248 244 817 249 245 818 249 245 819 250 246 820 251 247 821 252 248 822 251 247 823 253 249 824 249 245 825 251 247 826 252 248 827 254 250 828 253 249 829 255 251 830 252 248 831 253 249 832 254 250 833 254 250 834 255 251 835 256 252 836 257 253 837 256 252 838 258 254 839 254 250 840 256 252 841 257 253 842 242 238 843 259 255 844 241 237 845 257 253 846 258 254 847 260 256 848 261 257 849 262 258 850 244 240 851 263 259 852 264 260 853 262 258 854 265 261 855 262 258 856 264 260 857 261 257 858 263 259 859 262 258 860 266 262 861 260 256 862 267 263 863 257 253 864 260 256 865 266 262 866 243 239 867 261 257 868 244 240 869 268 264 870 123 121 871 269 265 872 268 264 873 122 120 874 123 121 875 270 266 876 125 123 877 126 124 878 271 267 879 269 265 880 272 268 881 271 267 882 268 264 883 269 265 884 273 269 885 126 124 886 124 122 887 274 270 888 270 266 889 126 124 890 275 271 891 274 270 892 126 124 893 273 269 894 275 271 895 126 124 896 276 272 897 124 122 898 127 125 899 276 272 900 273 269 901 124 122 902 277 273 903 127 125 904 128 126 905 277 273 906 276 272 907 127 125 908 278 274 909 128 126 910 129 127 911 279 275 912 277 273 913 128 126 914 280 276 915 279 275 916 128 126 917 281 277 918 280 276 919 128 126 920 282 278 921 281 277 922 128 126 923 278 274 924 282 278 925 128 126 926 283 279 927 284 280 928 285 281 929 283 279 930 286 282 931 284 280 932 287 283 933 285 281 934 288 284 935 287 283 936 283 279 937 285 281 938 289 285 939 288 284 940 290 286 941 289 285 942 287 283 943 288 284 944 291 287 945 292 288 946 293 289 947 289 285 948 290 286 949 294 290 950 295 291 951 293 289 952 296 292 953 295 291 954 291 287 955 293 289 956 297 293 957 296 292 958 298 294 959 297 293 960 295 291 961 296 292 962 299 295 963 132 130 964 136 134 965 297 293 966 298 294 967 300 296 968 301 297 969 136 134 970 137 135 971 302 298 972 299 295 973 136 134 974 303 299 975 302 298 976 136 134 977 304 300 978 303 299 979 136 134 980 305 301 981 304 300 982 136 134 983 301 297 984 305 301 985 136 134 986 306 302 987 137 135 988 138 136 989 306 302 990 301 297 991 137 135 992 307 303 993 138 136 994 139 137 995 307 303 996 306 302 997 138 136 998 308 304 999 139 137 1000 140 138 1001 308 304 1002 307 303 1003 139 137 1004 309 305 1005 140 138 1006 141 139 1007 309 305 1008 308 304 1009 140 138 1010 310 306 1011 141 139 1012 142 140 1013 310 306 1014 309 305 1015 141 139 1016 311 307 1017 142 140 1018 143 141 1019 311 307 1020 310 306 1021 142 140 1022 312 308 1023 143 141 1024 144 142 1025 312 308 1026 311 307 1027 143 141 1028 313 309 1029 144 142 1030 145 143 1031 313 309 1032 312 308 1033 144 142 1034 314 310 1035 145 143 1036 146 144 1037 314 310 1038 313 309 1039 145 143 1040 315 311 1041 146 144 1042 149 147 1043 315 311 1044 314 310 1045 146 144 1046 153 151 1047 316 312 1048 149 147 1049 317 313 1050 149 147 1051 316 312 1052 317 313 1053 315 311 1054 149 147 1055 154 152 1056 318 314 1057 155 153 1058 317 313 1059 316 312 1060 319 315 1061 320 316 1062 321 317 1063 318 314 1064 154 152 1065 320 316 1066 318 314 1067 322 318 1068 272 268 1069 323 319 1070 322 318 1071 271 267 1072 272 268 1073 324 320 1074 323 319 1075 325 321 1076 324 320 1077 322 318 1078 323 319 1079 326 322 1080 275 271 1081 273 269 1082 326 322 1083 327 323 1084 275 271 1085 328 324 1086 325 321 1087 329 325 1088 328 324 1089 324 320 1090 325 321 1091 330 326 1092 273 269 1093 276 272 1094 330 326 1095 326 322 1096 273 269 1097 331 327 1098 276 272 1099 277 273 1100 331 327 1101 330 326 1102 276 272 1103 332 328 1104 277 273 1105 279 275 1106 332 328 1107 331 327 1108 277 273 1109 333 329 1110 334 330 1111 335 331 1112 336 332 1113 332 328 1114 279 275 1115 333 329 1116 337 333 1117 334 330 1118 338 334 1119 335 331 1120 339 335 1121 338 334 1122 333 329 1123 335 331 1124 340 336 1125 339 335 1126 341 337 1127 340 336 1128 338 334 1129 339 335 1130 342 338 1131 341 337 1132 286 282 1133 342 338 1134 340 336 1135 341 337 1136 283 279 1137 342 338 1138 286 282 1139 326 322 1140 343 339 1141 327 323 1142 328 324 1143 329 325 1144 344 340 1145 345 341 1146 343 339 1147 326 322 1148 346 342 1149 344 340 1150 347 343 1151 346 342 1152 328 324 1153 344 340 1154 348 344 1155 326 322 1156 330 326 1157 349 345 1158 345 341 1159 326 322 1160 348 344 1161 349 345 1162 326 322 1163 350 346 1164 330 326 1165 331 327 1166 350 346 1167 348 344 1168 330 326 1169 351 347 1170 331 327 1171 332 328 1172 351 347 1173 350 346 1174 331 327 1175 352 348 1176 353 349 1177 332 328 1178 354 350 1179 332 328 1180 353 349 1181 355 351 1182 352 348 1183 332 328 1184 336 332 1185 355 351 1186 332 328 1187 354 350 1188 351 347 1189 332 328 1190 356 352 1191 357 353 1192 358 354 1193 359 355 1194 354 350 1195 353 349 1196 356 352 1197 360 356 1198 357 353 1199 361 357 1200 358 354 1201 362 358 1202 361 357 1203 356 352 1204 358 354 1205 363 359 1206 362 358 1207 337 333 1208 363 359 1209 361 357 1210 362 358 1211 333 329 1212 363 359 1213 337 333 1214 364 360 1215 347 343 1216 365 361 1217 364 360 1218 346 342 1219 347 343 1220 366 362 1221 349 345 1222 348 344 1223 366 362 1224 367 363 1225 349 345 1226 368 364 1227 365 361 1228 369 365 1229 368 364 1230 364 360 1231 365 361 1232 370 366 1233 348 344 1234 350 346 1235 370 366 1236 366 362 1237 348 344 1238 371 367 1239 350 346 1240 351 347 1241 371 367 1242 370 366 1243 350 346 1244 372 368 1245 351 347 1246 354 350 1247 372 368 1248 371 367 1249 351 347 1250 373 369 1251 374 370 1252 354 350 1253 375 371 1254 354 350 1255 374 370 1256 376 372 1257 373 369 1258 354 350 1259 359 355 1260 376 372 1261 354 350 1262 375 371 1263 372 368 1264 354 350 1265 377 373 1266 378 374 1267 374 370 1268 379 375 1269 374 370 1270 378 374 1271 380 376 1272 377 373 1273 374 370 1274 381 377 1275 380 376 1276 374 370 1277 382 378 1278 381 377 1279 374 370 1280 373 369 1281 382 378 1282 374 370 1283 379 375 1284 375 371 1285 374 370 1286 383 379 1287 384 380 1288 378 374 1289 385 381 1290 378 374 1291 384 380 1292 386 382 1293 383 379 1294 378 374 1295 387 383 1296 386 382 1297 378 374 1298 377 373 1299 387 383 1300 378 374 1301 385 381 1302 379 375 1303 378 374 1304 388 384 1305 389 385 1306 384 380 1307 390 386 1308 384 380 1309 389 385 1310 383 379 1311 388 384 1312 384 380 1313 390 386 1314 385 381 1315 384 380 1316 391 387 1317 392 388 1318 389 385 1319 393 389 1320 389 385 1321 392 388 1322 388 384 1323 391 387 1324 389 385 1325 393 389 1326 390 386 1327 389 385 1328 394 390 1329 395 391 1330 392 388 1331 396 392 1332 392 388 1333 395 391 1334 391 387 1335 394 390 1336 392 388 1337 396 392 1338 393 389 1339 392 388 1340 397 393 1341 398 394 1342 395 391 1343 399 395 1344 395 391 1345 398 394 1346 394 390 1347 397 393 1348 395 391 1349 399 395 1350 396 392 1351 395 391 1352 400 396 1353 401 397 1354 398 394 1355 402 398 1356 398 394 1357 401 397 1358 397 393 1359 400 396 1360 398 394 1361 402 398 1362 399 395 1363 398 394 1364 403 399 1365 404 400 1366 401 397 1367 405 401 1368 401 397 1369 404 400 1370 400 396 1371 403 399 1372 401 397 1373 405 401 1374 402 398 1375 401 397 1376 406 402 1377 407 403 1378 404 400 1379 408 404 1380 404 400 1381 407 403 1382 403 399 1383 406 402 1384 404 400 1385 408 404 1386 405 401 1387 404 400 1388 409 405 1389 410 406 1390 407 403 1391 411 407 1392 407 403 1393 410 406 1394 406 402 1395 409 405 1396 407 403 1397 412 408 1398 408 404 1399 407 403 1400 413 409 1401 412 408 1402 407 403 1403 414 410 1404 413 409 1405 407 403 1406 411 407 1407 414 410 1408 407 403 1409 415 411 1410 416 412 1411 410 406 1412 417 413 1413 410 406 1414 416 412 1415 409 405 1416 415 411 1417 410 406 1418 418 414 1419 411 407 1420 410 406 1421 419 415 1422 418 414 1423 410 406 1424 420 416 1425 419 415 1426 410 406 1427 421 417 1428 420 416 1429 410 406 1430 417 413 1431 421 417 1432 410 406 1433 422 418 1434 423 419 1435 416 412 1436 424 420 1437 416 412 1438 423 419 1439 415 411 1440 422 418 1441 416 412 1442 425 421 1443 417 413 1444 416 412 1445 426 422 1446 425 421 1447 416 412 1448 424 420 1449 426 422 1450 416 412 1451 427 423 1452 428 424 1453 423 419 1454 429 425 1455 423 419 1456 428 424 1457 422 418 1458 427 423 1459 423 419 1460 429 425 1461 424 420 1462 423 419 1463 430 426 1464 431 427 1465 428 424 1466 432 428 1467 428 424 1468 431 427 1469 433 429 1470 430 426 1471 428 424 1472 434 430 1473 433 429 1474 428 424 1475 427 423 1476 434 430 1477 428 424 1478 435 431 1479 429 425 1480 428 424 1481 436 432 1482 435 431 1483 428 424 1484 432 428 1485 436 432 1486 428 424 1487 437 433 1488 438 434 1489 439 435 1490 440 436 1491 432 428 1492 431 427 1493 441 437 1494 442 438 1495 438 434 1496 437 433 1497 441 437 1498 438 434 1499 437 433 1500 439 435 1501 443 439 1502 444 440 1503 433 429 1504 434 430 1505 445 441 1506 443 439 1507 446 442 1508 445 441 1509 437 433 1510 443 439 1511 315 311 1512 434 430 1513 427 423 1514 317 313 1515 434 430 1516 315 311 1517 447 443 1518 434 430 1519 317 313 1520 444 440 1521 434 430 1522 447 443 1523 314 310 1524 427 423 1525 422 418 1526 315 311 1527 427 423 1528 314 310 1529 313 309 1530 422 418 1531 415 411 1532 314 310 1533 422 418 1534 313 309 1535 312 308 1536 415 411 1537 409 405 1538 313 309 1539 415 411 1540 312 308 1541 311 307 1542 409 405 1543 406 402 1544 312 308 1545 409 405 1546 311 307 1547 310 306 1548 406 402 1549 403 399 1550 311 307 1551 406 402 1552 310 306 1553 309 305 1554 403 399 1555 400 396 1556 310 306 1557 403 399 1558 309 305 1559 308 304 1560 400 396 1561 397 393 1562 309 305 1563 400 396 1564 308 304 1565 307 303 1566 397 393 1567 394 390 1568 308 304 1569 397 393 1570 307 303 1571 306 302 1572 394 390 1573 391 387 1574 307 303 1575 394 390 1576 306 302 1577 301 297 1578 391 387 1579 388 384 1580 306 302 1581 391 387 1582 301 297 1583 448 444 1584 388 384 1585 383 379 1586 449 445 1587 301 297 1588 388 384 1589 450 446 1590 449 445 1591 388 384 1592 448 444 1593 450 446 1594 388 384 1595 451 447 1596 452 448 1597 453 449 1598 451 447 1599 454 450 1600 452 448 1601 455 451 1602 453 449 1603 456 452 1604 455 451 1605 451 447 1606 453 449 1607 457 453 1608 456 452 1609 458 454 1610 457 453 1611 455 451 1612 456 452 1613 459 455 1614 458 454 1615 460 456 1616 461 457 1617 457 453 1618 458 454 1619 459 455 1620 461 457 1621 458 454 1622 459 455 1623 460 456 1624 462 458 1625 463 459 1626 464 460 1627 465 461 1628 466 462 1629 459 455 1630 462 458 1631 467 463 1632 465 461 1633 468 464 1634 467 463 1635 463 459 1636 465 461 1637 469 465 1638 468 464 1639 470 466 1640 469 465 1641 467 463 1642 468 464 1643 471 467 1644 470 466 1645 360 356 1646 471 467 1647 469 465 1648 470 466 1649 356 352 1650 471 467 1651 360 356 1652 366 362 1653 472 468 1654 367 363 1655 473 469 1656 369 365 1657 474 470 1658 473 469 1659 368 364 1660 369 365 1661 475 471 1662 472 468 1663 366 362 1664 475 471 1665 476 472 1666 472 468 1667 477 473 1668 474 470 1669 478 474 1670 477 473 1671 473 469 1672 474 470 1673 479 475 1674 366 362 1675 370 366 1676 479 475 1677 475 471 1678 366 362 1679 480 476 1680 370 366 1681 371 367 1682 480 476 1683 479 475 1684 370 366 1685 481 477 1686 371 367 1687 372 368 1688 481 477 1689 480 476 1690 371 367 1691 482 478 1692 372 368 1693 375 371 1694 482 478 1695 481 477 1696 372 368 1697 483 479 1698 375 371 1699 379 375 1700 483 479 1701 482 478 1702 375 371 1703 484 480 1704 379 375 1705 385 381 1706 484 480 1707 483 479 1708 379 375 1709 485 481 1710 385 381 1711 390 386 1712 485 481 1713 484 480 1714 385 381 1715 486 482 1716 390 386 1717 393 389 1718 486 482 1719 485 481 1720 390 386 1721 487 483 1722 393 389 1723 396 392 1724 487 483 1725 486 482 1726 393 389 1727 487 483 1728 396 392 1729 399 395 1730 488 484 1731 399 395 1732 402 398 1733 488 484 1734 487 483 1735 399 395 1736 489 485 1737 402 398 1738 405 401 1739 489 485 1740 488 484 1741 402 398 1742 490 486 1743 405 401 1744 408 404 1745 490 486 1746 489 485 1747 405 401 1748 491 487 1749 408 404 1750 412 408 1751 491 487 1752 490 486 1753 408 404 1754 492 488 1755 493 489 1756 412 408 1757 494 490 1758 412 408 1759 493 489 1760 495 491 1761 492 488 1762 412 408 1763 496 492 1764 495 491 1765 412 408 1766 497 493 1767 496 492 1768 412 408 1769 498 494 1770 497 493 1771 412 408 1772 413 409 1773 498 494 1774 412 408 1775 494 490 1776 491 487 1777 412 408 1778 499 495 1779 500 496 1780 501 497 1781 502 498 1782 494 490 1783 493 489 1784 503 499 1785 504 500 1786 500 496 1787 503 499 1788 500 496 1789 499 495 1790 505 501 1791 501 497 1792 506 502 1793 499 495 1794 501 497 1795 505 501 1796 507 503 1797 506 502 1798 508 504 1799 505 501 1800 506 502 1801 507 503 1802 509 505 1803 508 504 1804 510 506 1805 507 503 1806 508 504 1807 509 505 1808 511 507 1809 510 506 1810 512 508 1811 509 505 1812 510 506 1813 511 507 1814 511 507 1815 512 508 1816 513 509 1817 514 510 1818 513 509 1819 515 511 1820 511 507 1821 513 509 1822 514 510 1823 516 512 1824 515 511 1825 517 513 1826 514 510 1827 515 511 1828 516 512 1829 516 512 1830 517 513 1831 518 514 1832 519 515 1833 518 514 1834 520 516 1835 516 512 1836 518 514 1837 519 515 1838 519 515 1839 520 516 1840 521 517 1841 522 518 1842 521 517 1843 523 519 1844 519 515 1845 521 517 1846 522 518 1847 524 520 1848 523 519 1849 525 521 1850 522 518 1851 523 519 1852 524 520 1853 526 522 1854 525 521 1855 527 523 1856 524 520 1857 525 521 1858 526 522 1859 526 522 1860 527 523 1861 528 524 1862 529 525 1863 530 526 1864 531 527 1865 532 528 1866 530 526 1867 529 525 1868 526 522 1869 528 524 1870 533 529 1871 534 9 1872 535 9 1873 536 9 1874 537 9 1875 535 9 1876 534 9 1877 538 9 1878 535 9 1879 537 9 1880 539 530 1881 436 432 1882 432 428 1883 540 531 1884 436 432 1885 539 530 1886 440 436 1887 541 532 1888 432 428 1889 539 530 1890 432 428 1891 541 532 1892 441 437 1893 542 533 1894 442 438 1895 543 534 1896 539 530 1897 541 532 1898 544 535 1899 545 536 1900 542 533 1901 441 437 1902 544 535 1903 542 533 1904 475 471 1905 546 537 1906 476 472 1907 547 538 1908 478 474 1909 548 539 1910 547 538 1911 477 473 1912 478 474 1913 549 540 1914 546 537 1915 475 471 1916 549 540 1917 550 541 1918 546 537 1919 551 542 1920 548 539 1921 552 543 1922 551 542 1923 547 538 1924 548 539 1925 553 544 1926 475 471 1927 479 475 1928 553 544 1929 549 540 1930 475 471 1931 554 545 1932 479 475 1933 480 476 1934 554 545 1935 553 544 1936 479 475 1937 555 546 1938 480 476 1939 481 477 1940 555 546 1941 554 545 1942 480 476 1943 556 547 1944 481 477 1945 482 478 1946 556 547 1947 555 546 1948 481 477 1949 557 548 1950 482 478 1951 483 479 1952 557 548 1953 556 547 1954 482 478 1955 558 549 1956 483 479 1957 484 480 1958 558 549 1959 557 548 1960 483 479 1961 559 550 1962 484 480 1963 485 481 1964 559 550 1965 558 549 1966 484 480 1967 560 551 1968 485 481 1969 486 482 1970 560 551 1971 559 550 1972 485 481 1973 561 552 1974 486 482 1975 487 483 1976 561 552 1977 560 551 1978 486 482 1979 562 553 1980 487 483 1981 488 484 1982 562 553 1983 561 552 1984 487 483 1985 563 554 1986 488 484 1987 489 485 1988 563 554 1989 562 553 1990 488 484 1991 564 555 1992 489 485 1993 490 486 1994 564 555 1995 563 554 1996 489 485 1997 565 556 1998 490 486 1999 491 487 2000 565 556 2001 564 555 2002 490 486 2003 566 557 2004 491 487 2005 494 490 2006 566 557 2007 565 556 2008 491 487 2009 502 498 2010 567 558 2011 494 490 2012 568 559 2013 494 490 2014 567 558 2015 568 559 2016 566 557 2017 494 490 2018 569 560 2019 570 561 2020 567 558 2021 571 562 2022 567 558 2023 570 561 2024 572 563 2025 569 560 2026 567 558 2027 502 498 2028 572 563 2029 567 558 2030 571 562 2031 568 559 2032 567 558 2033 573 564 2034 574 565 2035 570 561 2036 575 566 2037 570 561 2038 574 565 2039 569 560 2040 573 564 2041 570 561 2042 575 566 2043 571 562 2044 570 561 2045 540 531 2046 539 530 2047 574 565 2048 576 567 2049 574 565 2050 539 530 2051 573 564 2052 540 531 2053 574 565 2054 576 567 2055 575 566 2056 574 565 2057 543 534 2058 577 568 2059 539 530 2060 576 567 2061 539 530 2062 577 568 2063 544 535 2064 578 569 2065 545 536 2066 579 570 2067 576 567 2068 577 568 2069 580 571 2070 581 572 2071 578 569 2072 544 535 2073 580 571 2074 578 569 2075 582 573 2076 583 574 2077 584 575 2078 585 9 2079 538 9 2080 537 9 2081 582 573 2082 584 575 2083 586 576 2084 587 577 2085 588 578 2086 589 579 2087 590 580 2088 589 579 2089 504 500 2090 591 581 2091 589 579 2092 590 580 2093 587 577 2094 589 579 2095 591 581 2096 590 580 2097 504 500 2098 503 499 2099 549 540 2100 592 582 2101 550 541 2102 593 583 2103 552 543 2104 594 584 2105 593 583 2106 551 542 2107 552 543 2108 595 585 2109 592 582 2110 549 540 2111 595 585 2112 596 586 2113 592 582 2114 597 587 2115 594 584 2116 598 588 2117 597 587 2118 593 583 2119 594 584 2120 599 589 2121 549 540 2122 553 544 2123 599 589 2124 595 585 2125 549 540 2126 600 590 2127 553 544 2128 554 545 2129 600 590 2130 599 589 2131 553 544 2132 601 591 2133 554 545 2134 555 546 2135 601 591 2136 600 590 2137 554 545 2138 602 592 2139 555 546 2140 556 547 2141 602 592 2142 601 591 2143 555 546 2144 603 593 2145 556 547 2146 557 548 2147 603 593 2148 602 592 2149 556 547 2150 604 594 2151 557 548 2152 558 549 2153 604 594 2154 603 593 2155 557 548 2156 605 595 2157 558 549 2158 559 550 2159 605 595 2160 604 594 2161 558 549 2162 606 596 2163 559 550 2164 560 551 2165 606 596 2166 605 595 2167 559 550 2168 607 597 2169 560 551 2170 561 552 2171 607 597 2172 606 596 2173 560 551 2174 608 598 2175 561 552 2176 562 553 2177 608 598 2178 607 597 2179 561 552 2180 609 599 2181 562 553 2182 563 554 2183 609 599 2184 608 598 2185 562 553 2186 610 600 2187 563 554 2188 564 555 2189 610 600 2190 609 599 2191 563 554 2192 611 601 2193 564 555 2194 565 556 2195 611 601 2196 610 600 2197 564 555 2198 612 602 2199 565 556 2200 566 557 2201 612 602 2202 611 601 2203 565 556 2204 613 603 2205 566 557 2206 568 559 2207 613 603 2208 612 602 2209 566 557 2210 614 604 2211 568 559 2212 571 562 2213 614 604 2214 613 603 2215 568 559 2216 615 605 2217 571 562 2218 575 566 2219 615 605 2220 614 604 2221 571 562 2222 616 606 2223 575 566 2224 576 567 2225 616 606 2226 615 605 2227 575 566 2228 579 570 2229 617 607 2230 576 567 2231 618 608 2232 576 567 2233 617 607 2234 618 608 2235 616 606 2236 576 567 2237 580 571 2238 619 609 2239 581 572 2240 620 610 2241 618 608 2242 617 607 2243 621 611 2244 622 612 2245 619 609 2246 580 571 2247 621 611 2248 619 609 2249 595 585 2250 623 613 2251 596 586 2252 624 614 2253 598 588 2254 625 615 2255 624 614 2256 597 587 2257 598 588 2258 595 585 2259 626 616 2260 623 613 2261 627 617 2262 625 615 2263 628 618 2264 627 617 2265 624 614 2266 625 615 2267 629 619 2268 626 616 2269 595 585 2270 630 620 2271 631 621 2272 626 616 2273 632 622 2274 628 618 2275 633 623 2276 629 619 2277 630 620 2278 626 616 2279 632 622 2280 627 617 2281 628 618 2282 634 624 2283 595 585 2284 599 589 2285 634 624 2286 629 619 2287 595 585 2288 635 625 2289 599 589 2290 600 590 2291 635 625 2292 634 624 2293 599 589 2294 636 626 2295 600 590 2296 601 591 2297 636 626 2298 635 625 2299 600 590 2300 637 627 2301 601 591 2302 602 592 2303 637 627 2304 636 626 2305 601 591 2306 638 628 2307 602 592 2308 603 593 2309 638 628 2310 637 627 2311 602 592 2312 639 629 2313 603 593 2314 604 594 2315 639 629 2316 638 628 2317 603 593 2318 640 630 2319 604 594 2320 605 595 2321 640 630 2322 639 629 2323 604 594 2324 641 631 2325 605 595 2326 606 596 2327 641 631 2328 640 630 2329 605 595 2330 642 632 2331 606 596 2332 607 597 2333 642 632 2334 641 631 2335 606 596 2336 643 633 2337 607 597 2338 608 598 2339 643 633 2340 642 632 2341 607 597 2342 644 634 2343 608 598 2344 609 599 2345 644 634 2346 643 633 2347 608 598 2348 645 635 2349 609 599 2350 610 600 2351 645 635 2352 644 634 2353 609 599 2354 646 636 2355 610 600 2356 611 601 2357 646 636 2358 645 635 2359 610 600 2360 647 637 2361 611 601 2362 612 602 2363 647 637 2364 646 636 2365 611 601 2366 648 638 2367 612 602 2368 613 603 2369 649 639 2370 647 637 2371 612 602 2372 650 640 2373 649 639 2374 612 602 2375 651 641 2376 650 640 2377 612 602 2378 648 638 2379 651 641 2380 612 602 2381 652 642 2382 613 603 2383 614 604 2384 653 643 2385 648 638 2386 613 603 2387 652 642 2388 653 643 2389 613 603 2390 654 644 2391 614 604 2392 615 605 2393 654 644 2394 652 642 2395 614 604 2396 655 645 2397 615 605 2398 616 606 2399 655 645 2400 654 644 2401 615 605 2402 656 646 2403 616 606 2404 618 608 2405 656 646 2406 655 645 2407 616 606 2408 620 610 2409 657 647 2410 618 608 2411 658 648 2412 618 608 2413 657 647 2414 658 648 2415 656 646 2416 618 608 2417 621 611 2418 659 649 2419 622 612 2420 660 650 2421 658 648 2422 657 647 2423 661 651 2424 662 652 2425 659 649 2426 621 611 2427 661 651 2428 659 649 2429 630 620 2430 663 653 2431 631 621 2432 664 654 2433 633 623 2434 665 655 2435 664 654 2436 632 622 2437 633 623 2438 666 656 2439 663 653 2440 630 620 2441 667 657 2442 668 658 2443 663 653 2444 669 659 2445 665 655 2446 670 660 2447 666 656 2448 667 657 2449 663 653 2450 671 661 2451 664 654 2452 665 655 2453 672 662 2454 671 661 2455 665 655 2456 673 663 2457 672 662 2458 665 655 2459 674 664 2460 673 663 2461 665 655 2462 675 665 2463 674 664 2464 665 655 2465 669 659 2466 675 665 2467 665 655 2468 676 666 2469 630 620 2470 629 619 2471 677 667 2472 666 656 2473 630 620 2474 678 668 2475 677 667 2476 630 620 2477 679 669 2478 678 668 2479 630 620 2480 680 670 2481 679 669 2482 630 620 2483 681 671 2484 680 670 2485 630 620 2486 682 672 2487 681 671 2488 630 620 2489 683 673 2490 682 672 2491 630 620 2492 684 674 2493 683 673 2494 630 620 2495 676 666 2496 684 674 2497 630 620 2498 685 675 2499 629 619 2500 634 624 2501 685 675 2502 676 666 2503 629 619 2504 686 676 2505 634 624 2506 635 625 2507 686 676 2508 685 675 2509 634 624 2510 687 677 2511 635 625 2512 636 626 2513 687 677 2514 686 676 2515 635 625 2516 688 678 2517 636 626 2518 637 627 2519 688 678 2520 687 677 2521 636 626 2522 689 679 2523 637 627 2524 638 628 2525 689 679 2526 688 678 2527 637 627 2528 690 680 2529 638 628 2530 639 629 2531 690 680 2532 689 679 2533 638 628 2534 691 681 2535 639 629 2536 640 630 2537 691 681 2538 690 680 2539 639 629 2540 692 682 2541 640 630 2542 641 631 2543 692 682 2544 691 681 2545 640 630 2546 693 683 2547 641 631 2548 642 632 2549 693 683 2550 692 682 2551 641 631 2552 694 684 2553 642 632 2554 643 633 2555 694 684 2556 693 683 2557 642 632 2558 695 685 2559 643 633 2560 644 634 2561 695 685 2562 694 684 2563 643 633 2564 696 686 2565 644 634 2566 645 635 2567 696 686 2568 695 685 2569 644 634 2570 696 686 2571 645 635 2572 646 636 2573 697 687 2574 646 636 2575 647 637 2576 698 688 2577 696 686 2578 646 636 2579 699 689 2580 698 688 2581 646 636 2582 700 690 2583 699 689 2584 646 636 2585 697 687 2586 700 690 2587 646 636 2588 701 691 2589 702 692 2590 703 693 2591 701 691 2592 704 694 2593 702 692 2594 705 695 2595 703 693 2596 706 696 2597 701 691 2598 703 693 2599 705 695 2600 707 697 2601 706 696 2602 708 698 2603 705 695 2604 706 696 2605 707 697 2606 707 697 2607 708 698 2608 709 699 2609 707 697 2610 709 699 2611 710 700 2612 711 701 2613 653 643 2614 652 642 2615 712 702 2616 710 700 2617 713 703 2618 707 697 2619 710 700 2620 712 702 2621 714 704 2622 652 642 2623 654 644 2624 715 705 2625 711 701 2626 652 642 2627 716 706 2628 715 705 2629 652 642 2630 714 704 2631 716 706 2632 652 642 2633 717 707 2634 654 644 2635 655 645 2636 717 707 2637 714 704 2638 654 644 2639 718 708 2640 655 645 2641 656 646 2642 719 709 2643 717 707 2644 655 645 2645 718 708 2646 719 709 2647 655 645 2648 720 710 2649 656 646 2650 658 648 2651 721 711 2652 656 646 2653 720 710 2654 718 708 2655 656 646 2656 721 711 2657 660 650 2658 722 712 2659 658 648 2660 723 713 2661 658 648 2662 722 712 2663 720 710 2664 658 648 2665 723 713 2666 661 651 2667 724 714 2668 662 652 2669 725 715 2670 723 713 2671 722 712 2672 726 716 2673 727 717 2674 724 714 2675 661 651 2676 726 716 2677 724 714 2678 728 718 2679 729 719 2680 730 720 2681 669 659 2682 670 660 2683 731 721 2684 728 718 2685 732 722 2686 729 719 2687 733 723 2688 730 720 2689 734 724 2690 728 718 2691 730 720 2692 733 723 2693 733 723 2694 734 724 2695 735 725 2696 736 726 2697 735 725 2698 737 727 2699 733 723 2700 735 725 2701 736 726 2702 736 726 2703 737 727 2704 738 728 2705 739 729 2706 738 728 2707 740 730 2708 736 726 2709 738 728 2710 739 729 2711 739 729 2712 740 730 2713 741 731 2714 742 732 2715 741 731 2716 743 733 2717 739 729 2718 741 731 2719 742 732 2720 742 732 2721 743 733 2722 744 734 2723 684 674 2724 745 735 2725 683 673 2726 746 736 2727 744 734 2728 747 737 2729 742 732 2730 744 734 2731 746 736 2732 684 674 2733 748 738 2734 745 735 2735 746 736 2736 747 737 2737 749 739 2738 684 674 2739 750 740 2740 748 738 2741 751 741 2742 749 739 2743 752 742 2744 746 736 2745 749 739 2746 751 741 2747 684 674 2748 753 743 2749 750 740 2750 751 741 2751 752 742 2752 754 744 2753 684 674 2754 755 745 2755 753 743 2756 756 746 2757 754 744 2758 757 747 2759 751 741 2760 754 744 2761 756 746 2762 684 674 2763 758 748 2764 755 745 2765 759 749 2766 757 747 2767 760 750 2768 756 746 2769 757 747 2770 759 749 2771 684 674 2772 761 751 2773 758 748 2774 762 752 2775 763 753 2776 764 754 2777 765 755 2778 763 753 2779 762 752 2780 766 756 2781 763 753 2782 765 755 2783 767 757 2784 763 753 2785 766 756 2786 759 749 2787 760 750 2788 768 758 2789 769 759 2790 761 751 2791 684 674 2792 762 752 2793 764 754 2794 770 760 2795 771 761 2796 772 762 2797 761 751 2798 769 759 2799 771 761 2800 761 751 2801 773 763 2802 684 674 2803 676 666 2804 773 763 2805 769 759 2806 684 674 2807 774 764 2808 676 666 2809 685 675 2810 774 764 2811 773 763 2812 676 666 2813 775 765 2814 685 675 2815 686 676 2816 775 765 2817 774 764 2818 685 675 2819 776 766 2820 686 676 2821 687 677 2822 776 766 2823 775 765 2824 686 676 2825 777 767 2826 687 677 2827 688 678 2828 777 767 2829 776 766 2830 687 677 2831 778 768 2832 688 678 2833 689 679 2834 778 768 2835 777 767 2836 688 678 2837 779 769 2838 689 679 2839 690 680 2840 779 769 2841 778 768 2842 689 679 2843 780 770 2844 690 680 2845 691 681 2846 780 770 2847 779 769 2848 690 680 2849 781 771 2850 691 681 2851 692 682 2852 781 771 2853 780 770 2854 691 681 2855 782 772 2856 692 682 2857 693 683 2858 782 772 2859 781 771 2860 692 682 2861 783 773 2862 693 683 2863 694 684 2864 783 773 2865 782 772 2866 693 683 2867 784 774 2868 694 684 2869 695 685 2870 784 774 2871 783 773 2872 694 684 2873 785 775 2874 695 685 2875 696 686 2876 785 775 2877 784 774 2878 695 685 2879 786 776 2880 696 686 2881 698 688 2882 786 776 2883 785 775 2884 696 686 2885 787 777 2886 788 778 2887 698 688 2888 789 779 2889 698 688 2890 788 778 2891 790 780 2892 787 777 2893 698 688 2894 791 781 2895 790 780 2896 698 688 2897 792 782 2898 791 781 2899 698 688 2900 699 689 2901 792 782 2902 698 688 2903 789 779 2904 786 776 2905 698 688 2906 793 783 2907 794 784 2908 788 778 2909 795 785 2910 788 778 2911 794 784 2912 796 786 2913 793 783 2914 788 778 2915 797 787 2916 796 786 2917 788 778 2918 798 788 2919 797 787 2920 788 778 2921 787 777 2922 798 788 2923 788 778 2924 795 785 2925 789 779 2926 788 778 2927 799 789 2928 800 790 2929 801 791 2930 802 792 2931 795 785 2932 794 784 2933 803 793 2934 802 792 2935 794 784 2936 799 789 2937 804 794 2938 800 790 2939 805 795 2940 806 796 2941 807 797 2942 808 798 2943 807 797 2944 809 799 2945 810 800 2946 807 797 2947 808 798 2948 805 795 2949 807 797 2950 810 800 2951 811 801 2952 809 799 2953 812 802 2954 808 798 2955 809 799 2956 811 801 2957 811 801 2958 812 802 2959 813 803 2960 814 804 2961 813 803 2962 815 805 2963 811 801 2964 813 803 2965 814 804 2966 814 804 2967 815 805 2968 816 806 2969 817 807 2970 816 806 2971 818 808 2972 814 804 2973 816 806 2974 817 807 2975 819 809 2976 818 808 2977 820 810 2978 817 807 2979 818 808 2980 819 809 2981 819 809 2982 820 810 2983 821 811 2984 701 691 2985 821 811 2986 704 694 2987 819 809 2988 821 811 2989 701 691 2990 771 761 2991 822 812 2992 772 762 2993 823 813 2994 824 814 2995 822 812 2996 771 761 2997 823 813 2998 822 812 2999 825 815 3000 826 816 3001 824 814 3002 823 813 3003 825 815 3004 824 814 3005 827 9 3006 828 9 3007 829 9 3008 825 815 3009 830 817 3010 826 816 3011 831 9 3012 828 9 3013 827 9 3014 832 818 3015 833 819 3016 830 817 3017 825 815 3018 832 818 3019 830 817 3020 832 818 3021 834 820 3022 833 819 3023 835 821 3024 836 822 3025 837 823 3026 838 824 3027 836 822 3028 835 821 3029 839 9 3030 840 9 3031 831 9 3032 831 9 3033 827 9 3034 839 9 3035 832 818 3036 841 825 3037 834 820 3038 842 826 3039 837 823 3040 843 827 3041 842 826 3042 835 821 3043 837 823 3044 844 828 3045 845 829 3046 841 825 3047 846 830 3048 843 827 3049 847 831 3050 832 818 3051 844 828 3052 841 825 3053 846 830 3054 842 826 3055 843 827 3056 848 832 3057 849 833 3058 845 829 3059 846 830 3060 847 831 3061 850 834 3062 844 828 3063 848 832 3064 845 829 3065 851 835 3066 852 836 3067 853 837 3068 851 835 3069 854 838 3070 852 836 3071 855 839 3072 856 840 3073 857 841 3074 846 830 3075 850 834 3076 858 842 3077 859 843 3078 848 832 3079 844 828 3080 860 844 3081 853 837 3082 861 845 3083 860 844 3084 851 835 3085 853 837 3086 862 846 3087 844 828 3088 832 818 3089 863 847 3090 859 843 3091 844 828 3092 862 846 3093 863 847 3094 844 828 3095 864 848 3096 832 818 3097 825 815 3098 864 848 3099 862 846 3100 832 818 3101 865 849 3102 825 815 3103 823 813 3104 865 849 3105 864 848 3106 825 815 3107 866 850 3108 823 813 3109 771 761 3110 866 850 3111 865 849 3112 823 813 3113 867 851 3114 771 761 3115 769 759 3116 867 851 3117 866 850 3118 771 761 3119 868 852 3120 769 759 3121 773 763 3122 868 852 3123 867 851 3124 769 759 3125 869 853 3126 773 763 3127 774 764 3128 869 853 3129 868 852 3130 773 763 3131 870 854 3132 774 764 3133 775 765 3134 870 854 3135 869 853 3136 774 764 3137 871 855 3138 775 765 3139 776 766 3140 871 855 3141 870 854 3142 775 765 3143 872 856 3144 776 766 3145 777 767 3146 872 856 3147 871 855 3148 776 766 3149 873 857 3150 777 767 3151 778 768 3152 873 857 3153 872 856 3154 777 767 3155 874 858 3156 778 768 3157 779 769 3158 874 858 3159 873 857 3160 778 768 3161 875 859 3162 779 769 3163 780 770 3164 875 859 3165 874 858 3166 779 769 3167 876 860 3168 780 770 3169 781 771 3170 877 861 3171 875 859 3172 780 770 3173 878 862 3174 877 861 3175 780 770 3176 879 863 3177 878 862 3178 780 770 3179 880 864 3180 879 863 3181 780 770 3182 881 865 3183 880 864 3184 780 770 3185 882 866 3186 881 865 3187 780 770 3188 876 860 3189 882 866 3190 780 770 3191 883 867 3192 781 771 3193 782 772 3194 884 868 3195 876 860 3196 781 771 3197 885 869 3198 884 868 3199 781 771 3200 886 870 3201 885 869 3202 781 771 3203 887 871 3204 886 870 3205 781 771 3206 888 872 3207 887 871 3208 781 771 3209 889 9 3210 890 9 3211 891 9 3212 883 867 3213 888 872 3214 781 771 3215 892 873 3216 782 772 3217 783 773 3218 892 873 3219 883 867 3220 782 772 3221 893 874 3222 783 773 3223 784 774 3224 893 874 3225 892 873 3226 783 773 3227 894 875 3228 784 774 3229 785 775 3230 894 875 3231 893 874 3232 784 774 3233 895 876 3234 785 775 3235 786 776 3236 895 876 3237 894 875 3238 785 775 3239 896 877 3240 786 776 3241 789 779 3242 896 877 3243 895 876 3244 786 776 3245 897 878 3246 789 779 3247 795 785 3248 897 878 3249 896 877 3250 789 779 3251 898 879 3252 795 785 3253 802 792 3254 898 879 3255 897 878 3256 795 785 3257 899 880 3258 900 881 3259 802 792 3260 901 882 3261 802 792 3262 900 881 3263 803 793 3264 899 880 3265 802 792 3266 901 882 3267 898 879 3268 802 792 3269 902 883 3270 903 884 3271 900 881 3272 904 885 3273 900 881 3274 903 884 3275 899 880 3276 902 883 3277 900 881 3278 904 885 3279 901 882 3280 900 881 3281 721 711 3282 905 886 3283 903 884 3284 906 887 3285 903 884 3286 905 886 3287 907 888 3288 721 711 3289 903 884 3290 908 889 3291 907 888 3292 903 884 3293 902 883 3294 908 889 3295 903 884 3296 906 887 3297 904 885 3298 903 884 3299 720 710 3300 909 890 3301 905 886 3302 910 891 3303 905 886 3304 909 890 3305 721 711 3306 720 710 3307 905 886 3308 910 891 3309 906 887 3310 905 886 3311 911 892 3312 912 893 3313 909 890 3314 910 891 3315 909 890 3316 912 893 3317 913 894 3318 911 892 3319 909 890 3320 723 713 3321 913 894 3322 909 890 3323 720 710 3324 723 713 3325 909 890 3326 914 895 3327 915 896 3328 916 897 3329 917 898 3330 910 891 3331 912 893 3332 918 899 3333 919 900 3334 915 896 3335 918 899 3336 915 896 3337 914 895 3338 914 895 3339 916 897 3340 920 901 3341 725 715 3342 913 894 3343 723 713 3344 726 716 3345 920 901 3346 727 717 3347 726 716 3348 914 895 3349 920 901 3350 921 9 3351 922 9 3352 923 9 3353 924 9 3354 925 9 3355 922 9 3356 921 9 3357 924 9 3358 922 9 3359 921 9 3360 923 9 3361 926 9 3362 799 789 3363 927 902 3364 928 903 3365 799 789 3366 928 903 3367 929 904 3368 799 789 3369 929 904 3370 804 794 3371 860 844 3372 861 845 3373 930 905 3374 931 906 3375 863 847 3376 862 846 3377 932 907 3378 930 905 3379 933 908 3380 932 907 3381 860 844 3382 930 905 3383 934 909 3384 862 846 3385 864 848 3386 935 910 3387 931 906 3388 862 846 3389 936 911 3390 935 910 3391 862 846 3392 934 909 3393 936 911 3394 862 846 3395 937 912 3396 864 848 3397 865 849 3398 937 912 3399 934 909 3400 864 848 3401 938 913 3402 865 849 3403 866 850 3404 938 913 3405 937 912 3406 865 849 3407 939 914 3408 866 850 3409 867 851 3410 939 914 3411 938 913 3412 866 850 3413 940 915 3414 867 851 3415 868 852 3416 940 915 3417 939 914 3418 867 851 3419 941 916 3420 868 852 3421 869 853 3422 941 916 3423 940 915 3424 868 852 3425 942 917 3426 869 853 3427 870 854 3428 942 917 3429 941 916 3430 869 853 3431 943 918 3432 870 854 3433 871 855 3434 943 918 3435 942 917 3436 870 854 3437 944 919 3438 871 855 3439 872 856 3440 944 919 3441 943 918 3442 871 855 3443 945 920 3444 872 856 3445 873 857 3446 945 920 3447 944 919 3448 872 856 3449 946 921 3450 873 857 3451 874 858 3452 946 921 3453 945 920 3454 873 857 3455 947 922 3456 874 858 3457 875 859 3458 948 923 3459 946 921 3460 874 858 3461 949 924 3462 948 923 3463 874 858 3464 947 922 3465 949 924 3466 874 858 3467 950 925 3468 951 926 3469 952 927 3470 950 925 3471 953 928 3472 951 926 3473 950 925 3474 952 927 3475 954 929 3476 955 930 3477 954 929 3478 956 931 3479 950 925 3480 954 929 3481 955 930 3482 957 932 3483 956 931 3484 958 933 3485 955 930 3486 956 931 3487 957 932 3488 957 932 3489 958 933 3490 959 934 3491 960 935 3492 959 934 3493 961 936 3494 957 932 3495 959 934 3496 960 935 3497 960 935 3498 961 936 3499 962 937 3500 963 938 3501 962 937 3502 964 939 3503 960 935 3504 962 937 3505 963 938 3506 963 938 3507 964 939 3508 965 940 3509 966 941 3510 965 940 3511 967 942 3512 963 938 3513 965 940 3514 966 941 3515 968 943 3516 967 942 3517 969 944 3518 966 941 3519 967 942 3520 968 943 3521 968 943 3522 969 944 3523 970 945 3524 971 946 3525 972 947 3526 889 9 3527 973 948 3528 888 872 3529 883 867 3530 974 949 3531 970 945 3532 975 950 3533 968 943 3534 970 945 3535 974 949 3536 976 951 3537 883 867 3538 892 873 3539 977 952 3540 973 948 3541 883 867 3542 978 953 3543 977 952 3544 883 867 3545 979 954 3546 978 953 3547 883 867 3548 976 951 3549 979 954 3550 883 867 3551 980 955 3552 892 873 3553 893 874 3554 980 955 3555 976 951 3556 892 873 3557 981 956 3558 893 874 3559 894 875 3560 981 956 3561 980 955 3562 893 874 3563 982 957 3564 894 875 3565 895 876 3566 982 957 3567 981 956 3568 894 875 3569 983 958 3570 895 876 3571 896 877 3572 983 958 3573 982 957 3574 895 876 3575 984 959 3576 896 877 3577 897 878 3578 984 959 3579 983 958 3580 896 877 3581 985 960 3582 897 878 3583 898 879 3584 985 960 3585 984 959 3586 897 878 3587 986 961 3588 898 879 3589 901 882 3590 986 961 3591 985 960 3592 898 879 3593 987 962 3594 901 882 3595 904 885 3596 987 962 3597 986 961 3598 901 882 3599 988 963 3600 904 885 3601 906 887 3602 988 963 3603 987 962 3604 904 885 3605 989 964 3606 906 887 3607 910 891 3608 989 964 3609 988 963 3610 906 887 3611 917 898 3612 990 965 3613 910 891 3614 991 966 3615 910 891 3616 990 965 3617 991 966 3618 989 964 3619 910 891 3620 918 899 3621 992 967 3622 919 900 3623 991 966 3624 990 965 3625 993 968 3626 994 969 3627 995 970 3628 992 967 3629 994 969 3630 992 967 3631 918 899 3632 932 907 3633 933 908 3634 996 971 3635 997 972 3636 935 910 3637 936 911 3638 998 973 3639 996 971 3640 999 974 3641 998 973 3642 932 907 3643 996 971 3644 1000 975 3645 936 911 3646 934 909 3647 1001 976 3648 997 972 3649 936 911 3650 1000 975 3651 1001 976 3652 936 911 3653 1002 977 3654 934 909 3655 937 912 3656 1002 977 3657 1000 975 3658 934 909 3659 1003 978 3660 937 912 3661 938 913 3662 1003 978 3663 1002 977 3664 937 912 3665 1004 979 3666 938 913 3667 939 914 3668 1004 979 3669 1003 978 3670 938 913 3671 1005 980 3672 939 914 3673 940 915 3674 1005 980 3675 1004 979 3676 939 914 3677 1006 981 3678 940 915 3679 941 916 3680 1006 981 3681 1005 980 3682 940 915 3683 1007 982 3684 941 916 3685 942 917 3686 1007 982 3687 1006 981 3688 941 916 3689 1008 983 3690 942 917 3691 943 918 3692 1008 983 3693 1007 982 3694 942 917 3695 1009 984 3696 943 918 3697 944 919 3698 1009 984 3699 1008 983 3700 943 918 3701 1010 985 3702 944 919 3703 945 920 3704 1010 985 3705 1009 984 3706 944 919 3707 1011 986 3708 945 920 3709 946 921 3710 1011 986 3711 1010 985 3712 945 920 3713 1012 987 3714 946 921 3715 948 923 3716 1012 987 3717 1011 986 3718 946 921 3719 949 924 3720 1013 988 3721 948 923 3722 1014 989 3723 1015 989 3724 1016 989 3725 1017 990 3726 1012 987 3727 948 923 3728 1014 989 3729 1018 989 3730 1015 989 3731 1019 991 3732 1020 992 3733 1021 993 3734 1022 994 3735 1021 993 3736 953 928 3737 1019 991 3738 1021 993 3739 1022 994 3740 1022 994 3741 953 928 3742 950 925 3743 998 973 3744 999 974 3745 1023 995 3746 1024 996 3747 1001 976 3748 1000 975 3749 1025 997 3750 1023 995 3751 1026 998 3752 1025 997 3753 998 973 3754 1023 995 3755 1027 999 3756 1000 975 3757 1002 977 3758 1028 1000 3759 1024 996 3760 1000 975 3761 1029 1001 3762 1028 1000 3763 1000 975 3764 1027 999 3765 1029 1001 3766 1000 975 3767 1030 1002 3768 1002 977 3769 1003 978 3770 1030 1002 3771 1027 999 3772 1002 977 3773 1031 1003 3774 1003 978 3775 1004 979 3776 1031 1003 3777 1030 1002 3778 1003 978 3779 1032 1004 3780 1004 979 3781 1005 980 3782 1032 1004 3783 1031 1003 3784 1004 979 3785 1033 1005 3786 1005 980 3787 1006 981 3788 1033 1005 3789 1032 1004 3790 1005 980 3791 1034 1006 3792 1006 981 3793 1007 982 3794 1034 1006 3795 1033 1005 3796 1006 981 3797 1035 1007 3798 1007 982 3799 1008 983 3800 1035 1007 3801 1034 1006 3802 1007 982 3803 1036 1008 3804 1008 983 3805 1009 984 3806 1036 1008 3807 1035 1007 3808 1008 983 3809 1037 1009 3810 1009 984 3811 1010 985 3812 1037 1009 3813 1036 1008 3814 1009 984 3815 1038 1010 3816 1010 985 3817 1011 986 3818 1038 1010 3819 1037 1009 3820 1010 985 3821 1039 1011 3822 1011 986 3823 1012 987 3824 1039 1011 3825 1038 1010 3826 1011 986 3827 1014 989 3828 1040 989 3829 1018 989 3830 1014 989 3831 1041 989 3832 1040 989 3833 1025 997 3834 1026 998 3835 1042 1012 3836 1043 1013 3837 1028 1000 3838 1029 1001 3839 1044 1014 3840 1042 1012 3841 1045 1015 3842 1025 997 3843 1042 1012 3844 1044 1014 3845 1046 1016 3846 1029 1001 3847 1027 999 3848 1046 1016 3849 1043 1013 3850 1029 1001 3851 1046 1016 3852 1027 999 3853 1030 1002 3854 1046 1016 3855 1030 1002 3856 1031 1003 3857 1046 1016 3858 1031 1003 3859 1032 1004 3860 1046 1016 3861 1032 1004 3862 1033 1005 3863 1046 1016 3864 1033 1005 3865 1034 1006 3866 1046 1016 3867 1034 1006 3868 1035 1007 3869 1046 1016 3870 1035 1007 3871 1036 1008 3872 1046 1016 3873 1036 1008 3874 1037 1009 3875 1046 1016 3876 1037 1009 3877 1038 1010 3878 1039 1011 3879 1047 1017 3880 1038 1010 3881 1046 1016 3882 1038 1010 3883 1047 1017 3884 1048 1018 3885 1049 1019 3886 1047 1017 3887 1046 1016 3888 1047 1017 3889 1049 1019 3890 1039 1011 3891 1048 1018 3892 1047 1017 3893 1050 1020 3894 1051 1021 3895 1049 1019 3896 1046 1016 3897 1049 1019 3898 1051 1021 3899 1052 1022 3900 1050 1020 3901 1049 1019 3902 1048 1018 3903 1052 1022 3904 1049 1019 3905 1053 1023 3906 1054 1024 3907 1051 1021 3908 1046 1016 3909 1051 1021 3910 1054 1024 3911 1050 1020 3912 1053 1023 3913 1051 1021 3914 1055 1025 3915 1056 1026 3916 1054 1024 3917 1046 1016 3918 1054 1024 3919 1056 1026 3920 1053 1023 3921 1055 1025 3922 1054 1024 3923 1057 1027 3924 1058 1028 3925 1056 1026 3926 1046 1016 3927 1056 1026 3928 1058 1028 3929 1059 1029 3930 1057 1027 3931 1056 1026 3932 1055 1025 3933 1059 1029 3934 1056 1026 3935 1060 1030 3936 1061 1031 3937 1058 1028 3938 1046 1016 3939 1058 1028 3940 1061 1031 3941 1057 1027 3942 1060 1030 3943 1058 1028 3944 1062 1032 3945 1063 1033 3946 1061 1031 3947 1046 1016 3948 1061 1031 3949 1063 1033 3950 1060 1030 3951 1062 1032 3952 1061 1031 3953 1064 1034 3954 1065 1035 3955 1063 1033 3956 1046 1016 3957 1063 1033 3958 1065 1035 3959 1062 1032 3960 1064 1034 3961 1063 1033 3962 1066 1036 3963 1067 1037 3964 1065 1035 3965 1046 1016 3966 1065 1035 3967 1067 1037 3968 1064 1034 3969 1066 1036 3970 1065 1035 3971 1068 1038 3972 1069 1039 3973 1067 1037 3974 1046 1016 3975 1067 1037 3976 1069 1039 3977 1066 1036 3978 1068 1038 3979 1067 1037 3980 1070 1040 3981 1071 1041 3982 1069 1039 3983 1046 1016 3984 1069 1039 3985 1071 1041 3986 1068 1038 3987 1070 1040 3988 1069 1039 3989 1072 1042 3990 1073 1043 3991 1071 1041 3992 1046 1016 3993 1071 1041 3994 1073 1043 3995 1070 1040 3996 1072 1042 3997 1071 1041 3998 1074 1044 3999 1075 1045 4000 1073 1043 4001 1046 1016 4002 1073 1043 4003 1075 1045 4004 1072 1042 4005 1074 1044 4006 1073 1043 4007 1076 1046 4008 1077 1047 4009 1075 1045 4010 1046 1016 4011 1075 1045 4012 1077 1047 4013 1074 1044 4014 1076 1046 4015 1075 1045 4016 1078 1048 4017 1079 1049 4018 1077 1047 4019 1046 1016 4020 1077 1047 4021 1079 1049 4022 1076 1046 4023 1078 1048 4024 1077 1047 4025 1080 1050 4026 1081 1051 4027 1079 1049 4028 1046 1016 4029 1079 1049 4030 1081 1051 4031 1082 1052 4032 1080 1050 4033 1079 1049 4034 1078 1048 4035 1082 1052 4036 1079 1049 4037 1083 1053 4038 1084 1054 4039 1085 1055 4040 1086 1056 4041 1046 1016 4042 1081 1051 4043 1087 1057 4044 1088 1058 4045 1084 1054 4046 1087 1057 4047 1084 1054 4048 1083 1053 4049 1083 1053 4050 1085 1055 4051 1089 1059 4052 1090 1060 4053 1082 1052 4054 1078 1048 4055 1091 1061 4056 1089 1059 4057 1092 1062 4058 1083 1053 4059 1089 1059 4060 1091 1061 4061 989 964 4062 1078 1048 4063 1076 1046 4064 991 966 4065 1078 1048 4066 989 964 4067 1093 1063 4068 1078 1048 4069 991 966 4070 1090 1060 4071 1078 1048 4072 1093 1063 4073 988 963 4074 1076 1046 4075 1074 1044 4076 989 964 4077 1076 1046 4078 988 963 4079 987 962 4080 1074 1044 4081 1072 1042 4082 988 963 4083 1074 1044 4084 987 962 4085 986 961 4086 1072 1042 4087 1070 1040 4088 987 962 4089 1072 1042 4090 986 961 4091 985 960 4092 1070 1040 4093 1068 1038 4094 986 961 4095 1070 1040 4096 985 960 4097 984 959 4098 1068 1038 4099 1066 1036 4100 985 960 4101 1068 1038 4102 984 959 4103 983 958 4104 1066 1036 4105 1064 1034 4106 984 959 4107 1066 1036 4108 983 958 4109 982 957 4110 1064 1034 4111 1062 1032 4112 983 958 4113 1064 1034 4114 982 957 4115 981 956 4116 1062 1032 4117 1060 1030 4118 982 957 4119 1062 1032 4120 981 956 4121 980 955 4122 1060 1030 4123 1057 1027 4124 981 956 4125 1060 1030 4126 980 955 4127 1059 1029 4128 1094 1064 4129 1057 1027 4130 976 951 4131 1057 1027 4132 1094 1064 4133 980 955 4134 1057 1027 4135 976 951 4136 1095 1065 4137 1096 1066 4138 1097 1067 4139 1098 1068 4140 1096 1066 4141 1095 1065 4142 1099 1068 4143 1096 1066 4144 1098 1068 4145 1100 1069 4146 976 951 4147 1094 1064 4148 1101 9 4149 1102 9 4150 1103 9 4151 1104 9 4152 1102 9 4153 1101 9 4154 1105 1068 4155 1095 1065 4156 1097 1067 4157 1104 9 4158 1106 9 4159 1102 9 4160 1107 9 4161 1103 9 4162 1108 9 4163 1101 9 4164 1103 9 4165 1107 9 4166 1109 9 4167 1108 9 4168 1110 9 4169 1107 9 4170 1108 9 4171 1109 9 4172 1087 1057 4173 1044 1014 4174 1088 1058 4175 1111 1070 4176 1044 1014 4177 1087 1057 4178 1112 1071 4179 1044 1014 4180 1111 1070 4181 1113 1072 4182 1044 1014 4183 1112 1071 4184 1114 1073 4185 1044 1014 4186 1113 1072 4187 1115 1074 4188 1044 1014 4189 1114 1073 4190 1116 1075 4191 1044 1014 4192 1115 1074 4193 1117 1076 4194 1044 1014 4195 1116 1075 4196 1118 1077 4197 1044 1014 4198 1117 1076 4199 1119 1078 4200 1044 1014 4201 1118 1077 4202 1120 1079 4203 1044 1014 4204 1119 1078 4205 1121 1080 4206 1044 1014 4207 1120 1079 4208 1122 1081 4209 1044 1014 4210 1121 1080 4211 1123 1082 4212 1044 1014 4213 1122 1081 4214 1124 1083 4215 1044 1014 4216 1123 1082 4217 1125 1084 4218 1044 1014 4219 1124 1083 4220 1126 1085 4221 1044 1014 4222 1125 1084 4223 1127 1086 4224 1044 1014 4225 1126 1085 4226 1128 1087 4227 1044 1014 4228 1127 1086 4229 1129 1088 4230 1044 1014 4231 1128 1087 4232 1130 1089 4233 1044 1014 4234 1129 1088 4235 1131 1090 4236 1044 1014 4237 1130 1089 4238 1132 1091 4239 1044 1014 4240 1131 1090 4241 1133 1092 4242 1044 1014 4243 1132 1091 4244 1134 1093 4245 1044 1014 4246 1133 1092 4247 1135 1094 4248 1044 1014 4249 1134 1093 4250 1025 997 4251 1044 1014 4252 1135 1094 4253 447 443 4254 317 313 4255 319 315 4256 320 316 4257 1136 1095 4258 321 317 4259 1137 1096 4260 300 296 4261 1138 1097 4262 1137 1096 4263 297 293 4264 300 296 4265 1139 1098 4266 1138 1097 4267 1140 1099 4268 1139 1098 4269 1137 1096 4270 1138 1097 4271 1141 1100 4272 1140 1099 4273 1142 1101 4274 1141 1100 4275 1139 1098 4276 1140 1099 4277 1143 1102 4278 1142 1101 4279 1144 1103 4280 1143 1102 4281 1141 1100 4282 1142 1101 4283 449 445 4284 305 301 4285 301 297 4286 1143 1102 4287 1144 1103 4288 1145 1104 4289 445 441 4290 446 442 4291 1136 1095 4292 320 316 4293 445 441 4294 1136 1095 4295 1146 1105 4296 1145 1104 4297 1147 1106 4298 1146 1105 4299 1143 1102 4300 1145 1104 4301 1148 1107 4302 1147 1106 4303 454 450 4304 1148 1107 4305 1146 1105 4306 1147 1106 4307 451 447 4308 1148 1107 4309 454 450 4310 1149 1108 4311 713 703 4312 1150 1109 4313 712 702 4314 713 703 4315 1149 1108 4316 1149 1108 4317 1150 1109 4318 1151 1110 4319 1152 1111 4320 1153 1112 4321 1154 1113 4322 1155 1114 4323 1153 1112 4324 1152 1111 4325 1156 1115 4326 1153 1112 4327 1155 1114 4328 1157 1116 4329 1153 1112 4330 1156 1115 4331 1149 1108 4332 1151 1110 4333 1158 1117 4334 1159 9 4335 1160 9 4336 925 9 4337 1161 9 4338 1159 9 4339 925 9 4340 1162 9 4341 1161 9 4342 925 9 4343 1163 9 4344 1162 9 4345 925 9 4346 924 9 4347 1163 9 4348 925 9 4349 1093 1063 4350 991 966 4351 993 968 4352 994 969 4353 1164 1118 4354 995 970 4355 1165 1119 4356 975 950 4357 1166 1120 4358 974 949 4359 975 950 4360 1165 1119 4361 1165 1119 4362 1166 1120 4363 1167 1121 4364 1165 1119 4365 1167 1121 4366 1168 1122 4367 1100 1069 4368 979 954 4369 976 951 4370 1091 1061 4371 1092 1062 4372 1164 1118 4373 1091 1061 4374 1164 1118 4375 994 969 4376 9 9 4377 1169 9 4378 168 9 4379 169 165 4380 170 166 4381 1170 1123 4382 1171 9 4383 1172 9 4384 1169 9 4385 1173 1124 4386 1174 1125 4387 1175 1126 4388 1176 9 4389 1171 9 4390 1169 9 4391 9 9 4392 1176 9 4393 1169 9 4394 1177 1127 4395 169 165 4396 1170 1123 4397 1178 1128 4398 1177 1127 4399 1170 1123 4400 1179 1129 4401 1174 1125 4402 1173 1124 4403 1180 9 4404 1181 9 4405 1172 9 4406 1182 1130 4407 1183 1131 4408 1184 1132 4409 1171 9 4410 1180 9 4411 1172 9 4412 1185 9 4413 1186 9 4414 1181 9 4415 1187 1133 4416 1184 1132 4417 1188 1134 4418 1180 9 4419 1185 9 4420 1181 9 4421 1182 1130 4422 1184 1132 4423 1187 1133 4424 1185 9 4425 1189 9 4426 1186 9 4427 1190 1135 4428 1188 1134 4429 1191 1136 4430 1187 1133 4431 1188 1134 4432 1190 1135 4433 1192 9 4434 1193 9 4435 1189 9 4436 59 57 4437 1191 1136 4438 1194 1137 4439 1185 9 4440 1192 9 4441 1189 9 4442 1190 1135 4443 1191 1136 4444 59 57 4445 1192 9 4446 1195 9 4447 1193 9 4448 59 57 4449 1194 1137 4450 58 56 4451 1196 9 4452 1197 9 4453 1195 9 4454 1192 9 4455 1196 9 4456 1195 9 4457 1196 9 4458 1198 9 4459 1197 9 4460 1196 9 4461 1199 9 4462 1198 9 4463 1200 1138 4464 1201 1139 4465 1202 1140 4466 1203 1141 4467 1204 1142 4468 1205 1143 4469 1206 1144 4470 1203 1141 4471 1205 1143 4472 1207 1145 4473 1202 1140 4474 1208 1146 4475 1207 1145 4476 1200 1138 4477 1202 1140 4478 1207 1145 4479 1208 1146 4480 1209 1147 4481 1210 1148 4482 1209 1147 4483 1211 1149 4484 1210 1148 4485 1207 1145 4486 1209 1147 4487 1178 1128 4488 1212 1150 4489 1177 1127 4490 1210 1148 4491 1211 1149 4492 1213 1151 4493 1178 1128 4494 1214 1152 4495 1212 1150 4496 1215 1153 4497 1213 1151 4498 1216 1154 4499 1217 1155 4500 1213 1151 4501 1215 1153 4502 1217 1155 4503 1210 1148 4504 1213 1151 4505 1218 1156 4506 1219 1157 4507 1214 1152 4508 1220 1158 4509 1216 1154 4510 1221 1159 4511 1178 1128 4512 1218 1156 4513 1214 1152 4514 1220 1158 4515 1215 1153 4516 1216 1154 4517 1222 1160 4518 60 58 4519 1219 1157 4520 1223 1161 4521 1221 1159 4522 1224 1162 4523 1225 1163 4524 1222 1160 4525 1219 1157 4526 1218 1156 4527 1225 1163 4528 1219 1157 4529 1223 1161 4530 1220 1158 4531 1221 1159 4532 1226 1164 4533 1224 1162 4534 1227 1165 4535 1222 1160 4536 61 59 4537 60 58 4538 1226 1164 4539 1223 1161 4540 1224 1162 4541 1228 1166 4542 1227 1165 4543 1229 1167 4544 1228 1166 4545 1230 1168 4546 1227 1165 4547 1226 1164 4548 1227 1165 4549 1230 1168 4550 1231 1169 4551 1232 1170 4552 1233 1171 4553 1234 1172 4554 1232 1170 4555 1231 1169 4556 1235 1173 4557 1236 1174 4558 174 170 4559 1231 1169 4560 1233 1171 4561 1237 1175 4562 175 171 4563 1235 1173 4564 174 170 4565 1238 1176 4566 1239 1177 4567 1240 1178 4568 1241 1179 4569 1237 1175 4570 1242 1180 4571 1241 1179 4572 1231 1169 4573 1237 1175 4574 171 167 4575 1240 1178 4576 176 172 4577 1243 1181 4578 1238 1176 4579 1240 1178 4580 171 167 4581 1243 1181 4582 1240 1178 4583 1244 1182 4584 1245 1183 4585 1246 1184 4586 1247 1185 4587 1248 1186 4588 1249 1187 4589 1250 1188 4590 1244 1182 4591 1246 1184 4592 1251 1189 4593 1252 1190 4594 1253 1191 4595 1254 1192 4596 1255 1193 4597 1256 1194 4598 1251 1189 4599 1253 1191 4600 1257 1195 4601 1258 1196 4602 1259 1197 4603 1245 1183 4604 1260 1198 4605 1249 1187 4606 1261 1199 4607 1244 1182 4608 1258 1196 4609 1245 1183 4610 1260 1198 4611 1247 1185 4612 1249 1187 4613 1262 1200 4614 1263 1201 4615 1259 1197 4616 1260 1198 4617 1261 1199 4618 1264 1202 4619 1258 1196 4620 1262 1200 4621 1259 1197 4622 1262 1200 4623 1265 1203 4624 1263 1201 4625 1266 1204 4626 1264 1202 4627 1267 1205 4628 1266 1204 4629 1260 1198 4630 1264 1202 4631 1268 1206 4632 1269 1207 4633 1265 1203 4634 1270 1208 4635 1267 1205 4636 1271 1209 4637 1262 1200 4638 1268 1206 4639 1265 1203 4640 1270 1208 4641 1266 1204 4642 1267 1205 4643 1272 1210 4644 1273 1211 4645 1269 1207 4646 1270 1208 4647 1271 1209 4648 1274 1212 4649 1268 1206 4650 1272 1210 4651 1269 1207 4652 1272 1210 4653 1275 1213 4654 1273 1211 4655 1276 1214 4656 1274 1212 4657 1277 1215 4658 1276 1214 4659 1270 1208 4660 1274 1212 4661 162 160 4662 1278 1216 4663 1275 1213 4664 1276 1214 4665 1277 1215 4666 1279 1217 4667 1272 1210 4668 162 160 4669 1275 1213 4670 162 160 4671 159 157 4672 1278 1216 4673 1203 1141 4674 1279 1217 4675 1204 1142 4676 1203 1141 4677 1276 1214 4678 1279 1217 4679 154 152 4680 150 148 4681 1280 1218 4682 1281 1219 4683 1280 1218 4684 1282 1220 4685 154 152 4686 1280 1218 4687 1281 1219 4688 1283 1221 4689 1282 1220 4690 1284 1222 4691 1281 1219 4692 1282 1220 4693 1283 1221 4694 1285 1223 4695 1284 1222 4696 1286 1224 4697 1283 1221 4698 1284 1222 4699 1285 1223 4700 1285 1223 4701 1286 1224 4702 1287 1225 4703 1288 1226 4704 1289 1227 4705 1244 1182 4706 1290 1228 4707 1287 1225 4708 1291 1229 4709 1250 1188 4710 1288 1226 4711 1244 1182 4712 1285 1223 4713 1287 1225 4714 1292 1230 4715 1290 1228 4716 1292 1230 4717 1287 1225 4718 1293 1231 4719 1294 1232 4720 1295 1233 4721 1290 1228 4722 1291 1229 4723 1296 1234 4724 1297 1235 4725 1295 1233 4726 1252 1190 4727 1297 1235 4728 1293 1231 4729 1295 1233 4730 1251 1189 4731 1297 1235 4732 1252 1190 4733 1298 1236 4734 1247 1185 4735 1260 1198 4736 1299 1237 4737 1256 1194 4738 1300 1238 4739 1301 1239 4740 1254 1192 4741 1256 1194 4742 1302 1240 4743 1301 1239 4744 1256 1194 4745 1299 1237 4746 1302 1240 4747 1256 1194 4748 1303 1241 4749 1260 1198 4750 1266 1204 4751 1304 1242 4752 1298 1236 4753 1260 1198 4754 1303 1241 4755 1304 1242 4756 1260 1198 4757 1305 1243 4758 1266 1204 4759 1270 1208 4760 1305 1243 4761 1303 1241 4762 1266 1204 4763 1306 1244 4764 1270 1208 4765 1276 1214 4766 1306 1244 4767 1305 1243 4768 1270 1208 4769 1307 1245 4770 1276 1214 4771 1203 1141 4772 1308 1246 4773 1306 1244 4774 1276 1214 4775 1307 1245 4776 1308 1246 4777 1276 1214 4778 1309 1247 4779 1203 1141 4780 1206 1144 4781 1309 1247 4782 1307 1245 4783 1203 1141 4784 1310 1248 4785 1309 1247 4786 1206 1144 4787 1207 1145 4788 1311 1249 4789 1200 1138 4790 1312 1250 4791 1313 1251 4792 1314 1252 4793 1315 1253 4794 1299 1237 4795 1300 1238 4796 1316 1254 4797 1317 1255 4798 1313 1251 4799 1312 1250 4800 1316 1254 4801 1313 1251 4802 1318 1256 4803 1314 1252 4804 1319 1257 4805 1318 1256 4806 1312 1250 4807 1314 1252 4808 1320 1258 4809 1319 1257 4810 1321 1259 4811 1320 1258 4812 1318 1256 4813 1319 1257 4814 1322 1260 4815 1321 1259 4816 1323 1261 4817 1322 1260 4818 1320 1258 4819 1321 1259 4820 1324 1262 4821 1323 1261 4822 1325 1263 4823 1324 1262 4824 1322 1260 4825 1323 1261 4826 1326 1264 4827 1325 1263 4828 1327 1265 4829 1326 1264 4830 1324 1262 4831 1325 1263 4832 1328 1266 4833 1327 1265 4834 1329 1267 4835 1328 1266 4836 1326 1264 4837 1327 1265 4838 1330 1268 4839 1329 1267 4840 1331 1269 4841 1330 1268 4842 1328 1266 4843 1329 1267 4844 1332 1270 4845 1311 1249 4846 1207 1145 4847 1330 1268 4848 1331 1269 4849 1333 1271 4850 1251 1189 4851 1257 1195 4852 1334 1272 4853 1335 1273 4854 1334 1272 4855 1336 1274 4856 1335 1273 4857 1251 1189 4858 1334 1272 4859 1337 1275 4860 1338 1276 4861 1339 1277 4862 1340 1278 4863 1341 1279 4864 1342 1280 4865 1343 1281 4866 1338 1276 4867 1337 1275 4868 1315 1253 4869 1344 1282 4870 1299 1237 4871 1337 1275 4872 1339 1277 4873 1345 1283 4874 1316 1254 4875 1346 1284 4876 1317 1255 4877 1347 1285 4878 1348 1286 4879 1346 1284 4880 1316 1254 4881 1347 1285 4882 1346 1284 4883 1349 1287 4884 1293 1231 4885 1297 1235 4886 1290 1228 4887 1296 1234 4888 1350 1288 4889 1351 1289 4890 1297 1235 4891 1251 1189 4892 1351 1289 4893 1349 1287 4894 1297 1235 4895 1335 1273 4896 1351 1289 4897 1251 1189 4898 1352 1290 4899 1353 1291 4900 1354 1292 4901 1290 1228 4902 1350 1288 4903 1355 1293 4904 1356 1294 4905 1355 1293 4906 1350 1288 4907 1352 1290 4908 1357 1295 4909 1353 1291 4910 1358 1296 4911 1354 1292 4912 1341 1279 4913 1358 1296 4914 1352 1290 4915 1354 1292 4916 1358 1296 4917 1341 1279 4918 1340 1278 4919 851 835 4920 1359 1297 4921 854 838 4922 1360 1298 4923 857 841 4924 1361 1299 4925 1360 1298 4926 855 839 4927 857 841 4928 1362 1300 4929 1363 1301 4930 1359 1297 4931 1364 1302 4932 1361 1299 4933 1365 1303 4934 851 835 4935 1362 1300 4936 1359 1297 4937 1364 1302 4938 1360 1298 4939 1361 1299 4940 1366 1304 4941 1367 1305 4942 1363 1301 4943 1368 1306 4944 1365 1303 4945 1369 1307 4946 1362 1300 4947 1366 1304 4948 1363 1301 4949 1368 1306 4950 1364 1302 4951 1365 1303 4952 1370 1308 4953 1371 1309 4954 1367 1305 4955 1372 1310 4956 1369 1307 4957 1373 1311 4958 1366 1304 4959 1370 1308 4960 1367 1305 4961 1372 1310 4962 1368 1306 4963 1369 1307 4964 1370 1308 4965 1374 1312 4966 1371 1309 4967 1375 1313 4968 1371 1309 4969 1374 1312 4970 1372 1310 4971 1373 1311 4972 1376 1314 4973 1377 1315 4974 1378 1316 4975 1374 1312 4976 1379 1317 4977 1374 1312 4978 1378 1316 4979 1370 1308 4980 1377 1315 4981 1374 1312 4982 1380 1318 4983 1375 1313 4984 1374 1312 4985 1379 1317 4986 1380 1318 4987 1374 1312 4988 1381 1319 4989 1382 1320 4990 1378 1316 4991 1383 1321 4992 1378 1316 4993 1382 1320 4994 1377 1315 4995 1381 1319 4996 1378 1316 4997 1384 1322 4998 1379 1317 4999 1378 1316 5000 1383 1321 5001 1384 1322 5002 1378 1316 5003 1385 1323 5004 1386 1324 5005 1382 1320 5006 1387 1325 5007 1382 1320 5008 1386 1324 5009 1381 1319 5010 1385 1323 5011 1382 1320 5012 1387 1325 5013 1383 1321 5014 1382 1320 5015 1388 1326 5016 1389 1327 5017 1386 1324 5018 1390 1328 5019 1386 1324 5020 1389 1327 5021 1385 1323 5022 1388 1326 5023 1386 1324 5024 1390 1328 5025 1387 1325 5026 1386 1324 5027 1391 1329 5028 1392 1330 5029 1389 1327 5030 1393 1331 5031 1389 1327 5032 1392 1330 5033 1388 1326 5034 1391 1329 5035 1389 1327 5036 1393 1331 5037 1390 1328 5038 1389 1327 5039 1394 1332 5040 1395 1333 5041 1392 1330 5042 1396 1334 5043 1392 1330 5044 1395 1333 5045 1391 1329 5046 1394 1332 5047 1392 1330 5048 1396 1334 5049 1393 1331 5050 1392 1330 5051 1397 1335 5052 1398 1336 5053 1395 1333 5054 1399 1337 5055 1395 1333 5056 1398 1336 5057 1394 1332 5058 1397 1335 5059 1395 1333 5060 1399 1337 5061 1396 1334 5062 1395 1333 5063 1400 1338 5064 1401 1339 5065 1398 1336 5066 1402 1340 5067 1398 1336 5068 1401 1339 5069 1397 1335 5070 1400 1338 5071 1398 1336 5072 1402 1340 5073 1399 1337 5074 1398 1336 5075 1403 1341 5076 1404 1342 5077 1401 1339 5078 1405 1343 5079 1401 1339 5080 1404 1342 5081 1400 1338 5082 1403 1341 5083 1401 1339 5084 1405 1343 5085 1402 1340 5086 1401 1339 5087 1406 1344 5088 1407 1345 5089 1404 1342 5090 1408 1346 5091 1404 1342 5092 1407 1345 5093 1403 1341 5094 1406 1344 5095 1404 1342 5096 1408 1346 5097 1405 1343 5098 1404 1342 5099 1409 1347 5100 1410 1348 5101 1407 1345 5102 1411 1349 5103 1407 1345 5104 1410 1348 5105 1406 1344 5106 1409 1347 5107 1407 1345 5108 1411 1349 5109 1408 1346 5110 1407 1345 5111 1412 1350 5112 1413 1351 5113 1410 1348 5114 1414 1352 5115 1410 1348 5116 1413 1351 5117 1409 1347 5118 1412 1350 5119 1410 1348 5120 1414 1352 5121 1411 1349 5122 1410 1348 5123 1415 1353 5124 1416 1354 5125 1413 1351 5126 1417 1355 5127 1413 1351 5128 1416 1354 5129 1412 1350 5130 1415 1353 5131 1413 1351 5132 1417 1355 5133 1414 1352 5134 1413 1351 5135 1418 1356 5136 1419 1357 5137 1416 1354 5138 1420 1358 5139 1416 1354 5140 1419 1357 5141 1415 1353 5142 1418 1356 5143 1416 1354 5144 1420 1358 5145 1417 1355 5146 1416 1354 5147 1421 1359 5148 1422 1360 5149 1419 1357 5150 1423 1361 5151 1419 1357 5152 1422 1360 5153 1418 1356 5154 1421 1359 5155 1419 1357 5156 1423 1361 5157 1420 1358 5158 1419 1357 5159 1424 1362 5160 1425 1363 5161 1422 1360 5162 1426 1364 5163 1422 1360 5164 1425 1363 5165 1421 1359 5166 1424 1362 5167 1422 1360 5168 1426 1364 5169 1423 1361 5170 1422 1360 5171 1427 1365 5172 1428 1366 5173 1425 1363 5174 1429 1367 5175 1425 1363 5176 1428 1366 5177 1424 1362 5178 1427 1365 5179 1425 1363 5180 1429 1367 5181 1426 1364 5182 1425 1363 5183 1430 1368 5184 1431 1369 5185 1428 1366 5186 1432 1370 5187 1428 1366 5188 1431 1369 5189 1427 1365 5190 1430 1368 5191 1428 1366 5192 1432 1370 5193 1429 1367 5194 1428 1366 5195 1433 1371 5196 1434 1372 5197 1431 1369 5198 1435 1373 5199 1431 1369 5200 1434 1372 5201 1430 1368 5202 1433 1371 5203 1431 1369 5204 1435 1373 5205 1432 1370 5206 1431 1369 5207 1436 1374 5208 1437 1375 5209 1434 1372 5210 1438 1376 5211 1434 1372 5212 1437 1375 5213 1433 1371 5214 1436 1374 5215 1434 1372 5216 1438 1376 5217 1435 1373 5218 1434 1372 5219 1439 1377 5220 1440 1378 5221 1437 1375 5222 1441 1379 5223 1437 1375 5224 1440 1378 5225 1436 1374 5226 1439 1377 5227 1437 1375 5228 1441 1379 5229 1438 1376 5230 1437 1375 5231 1442 1380 5232 914 895 5233 1440 1378 5234 726 716 5235 1440 1378 5236 914 895 5237 1439 1377 5238 1442 1380 5239 1440 1378 5240 726 716 5241 1441 1379 5242 1440 1378 5243 1442 1380 5244 918 899 5245 914 895 5246 994 969 5247 918 899 5248 1442 1380 5249 1443 1381 5250 1442 1380 5251 1439 1377 5252 1443 1381 5253 994 969 5254 1442 1380 5255 1444 1382 5256 1439 1377 5257 1436 1374 5258 1444 1382 5259 1443 1381 5260 1439 1377 5261 1445 1383 5262 1436 1374 5263 1433 1371 5264 1445 1383 5265 1444 1382 5266 1436 1374 5267 1446 1384 5268 1433 1371 5269 1430 1368 5270 1446 1384 5271 1445 1383 5272 1433 1371 5273 1447 1385 5274 1430 1368 5275 1427 1365 5276 1447 1385 5277 1446 1384 5278 1430 1368 5279 1448 1386 5280 1427 1365 5281 1424 1362 5282 1448 1386 5283 1447 1385 5284 1427 1365 5285 1449 1387 5286 1424 1362 5287 1421 1359 5288 1449 1387 5289 1448 1386 5290 1424 1362 5291 1450 1388 5292 1421 1359 5293 1418 1356 5294 1450 1388 5295 1449 1387 5296 1421 1359 5297 1451 1389 5298 1418 1356 5299 1415 1353 5300 1451 1389 5301 1450 1388 5302 1418 1356 5303 1452 1390 5304 1415 1353 5305 1412 1350 5306 1452 1390 5307 1451 1389 5308 1415 1353 5309 1453 1391 5310 1412 1350 5311 1409 1347 5312 1453 1391 5313 1452 1390 5314 1412 1350 5315 1454 1392 5316 1409 1347 5317 1406 1344 5318 1454 1392 5319 1453 1391 5320 1409 1347 5321 1455 1393 5322 1406 1344 5323 1403 1341 5324 1455 1393 5325 1454 1392 5326 1406 1344 5327 1456 1394 5328 1403 1341 5329 1400 1338 5330 1456 1394 5331 1455 1393 5332 1403 1341 5333 1457 1395 5334 1400 1338 5335 1397 1335 5336 1457 1395 5337 1456 1394 5338 1400 1338 5339 1458 1396 5340 1397 1335 5341 1394 1332 5342 1458 1396 5343 1457 1395 5344 1397 1335 5345 1459 1397 5346 1394 1332 5347 1391 1329 5348 1459 1397 5349 1458 1396 5350 1394 1332 5351 1460 1398 5352 1391 1329 5353 1388 1326 5354 1460 1398 5355 1459 1397 5356 1391 1329 5357 1461 1399 5358 1388 1326 5359 1385 1323 5360 1461 1399 5361 1460 1398 5362 1388 1326 5363 1462 1400 5364 1385 1323 5365 1381 1319 5366 1462 1400 5367 1461 1399 5368 1385 1323 5369 1463 1401 5370 1381 1319 5371 1377 1315 5372 1463 1401 5373 1462 1400 5374 1381 1319 5375 1464 1402 5376 1377 1315 5377 1370 1308 5378 1464 1402 5379 1463 1401 5380 1377 1315 5381 1465 1403 5382 1370 1308 5383 1366 1304 5384 1465 1403 5385 1464 1402 5386 1370 1308 5387 1466 1404 5388 1366 1304 5389 1362 1300 5390 1466 1404 5391 1465 1403 5392 1366 1304 5393 1467 1405 5394 1362 1300 5395 851 835 5396 1467 1405 5397 1466 1404 5398 1362 1300 5399 860 844 5400 1467 1405 5401 851 835 5402 1468 1406 5403 1376 1314 5404 1469 1407 5405 1468 1406 5406 1372 1310 5407 1376 1314 5408 1470 1408 5409 1469 1407 5410 1471 1409 5411 1470 1408 5412 1468 1406 5413 1469 1407 5414 1472 1410 5415 1471 1409 5416 1473 1411 5417 1472 1410 5418 1470 1408 5419 1471 1409 5420 1474 1412 5421 1384 1322 5422 1383 1321 5423 1475 1413 5424 1473 1411 5425 1476 1414 5426 1475 1413 5427 1472 1410 5428 1473 1411 5429 1477 1415 5430 1383 1321 5431 1387 1325 5432 1477 1415 5433 1474 1412 5434 1383 1321 5435 1478 1416 5436 1387 1325 5437 1390 1328 5438 1478 1416 5439 1477 1415 5440 1387 1325 5441 1479 1417 5442 1390 1328 5443 1393 1331 5444 1479 1417 5445 1478 1416 5446 1390 1328 5447 1480 1418 5448 1393 1331 5449 1396 1334 5450 1480 1418 5451 1479 1417 5452 1393 1331 5453 1481 1419 5454 1396 1334 5455 1399 1337 5456 1481 1419 5457 1480 1418 5458 1396 1334 5459 1482 1420 5460 1399 1337 5461 1402 1340 5462 1482 1420 5463 1481 1419 5464 1399 1337 5465 1483 1421 5466 1402 1340 5467 1405 1343 5468 1483 1421 5469 1482 1420 5470 1402 1340 5471 1484 1422 5472 1405 1343 5473 1408 1346 5474 1484 1422 5475 1483 1421 5476 1405 1343 5477 1485 1423 5478 1408 1346 5479 1411 1349 5480 1485 1423 5481 1484 1422 5482 1408 1346 5483 1486 1424 5484 1411 1349 5485 1414 1352 5486 1486 1424 5487 1485 1423 5488 1411 1349 5489 1487 1425 5490 1414 1352 5491 1417 1355 5492 1487 1425 5493 1486 1424 5494 1414 1352 5495 1488 1426 5496 1417 1355 5497 1420 1358 5498 1488 1426 5499 1487 1425 5500 1417 1355 5501 1489 1427 5502 1420 1358 5503 1423 1361 5504 1489 1427 5505 1488 1426 5506 1420 1358 5507 1490 1428 5508 1423 1361 5509 1426 1364 5510 1490 1428 5511 1489 1427 5512 1423 1361 5513 1491 1429 5514 1426 1364 5515 1429 1367 5516 1491 1429 5517 1490 1428 5518 1426 1364 5519 1492 1430 5520 1429 1367 5521 1432 1370 5522 1492 1430 5523 1491 1429 5524 1429 1367 5525 1493 1431 5526 1432 1370 5527 1435 1373 5528 1493 1431 5529 1492 1430 5530 1432 1370 5531 1494 1432 5532 1435 1373 5533 1438 1376 5534 1494 1432 5535 1493 1431 5536 1435 1373 5537 1495 1433 5538 1438 1376 5539 1441 1379 5540 1495 1433 5541 1494 1432 5542 1438 1376 5543 1496 1434 5544 1441 1379 5545 726 716 5546 1496 1434 5547 1495 1433 5548 1441 1379 5549 661 651 5550 1496 1434 5551 726 716 5552 1497 1435 5553 1476 1414 5554 1498 1436 5555 1497 1435 5556 1475 1413 5557 1476 1414 5558 1499 1437 5559 1477 1415 5560 1478 1416 5561 1500 1438 5562 1498 1436 5563 1501 1439 5564 1500 1438 5565 1497 1435 5566 1498 1436 5567 1502 1440 5568 1478 1416 5569 1479 1417 5570 1503 1441 5571 1499 1437 5572 1478 1416 5573 1504 1442 5574 1503 1441 5575 1478 1416 5576 1502 1440 5577 1504 1442 5578 1478 1416 5579 1505 1443 5580 1479 1417 5581 1480 1418 5582 1505 1443 5583 1502 1440 5584 1479 1417 5585 1506 1444 5586 1480 1418 5587 1481 1419 5588 1506 1444 5589 1505 1443 5590 1480 1418 5591 1507 1445 5592 1481 1419 5593 1482 1420 5594 1507 1445 5595 1506 1444 5596 1481 1419 5597 1508 1446 5598 1482 1420 5599 1483 1421 5600 1508 1446 5601 1507 1445 5602 1482 1420 5603 1509 1447 5604 1483 1421 5605 1484 1422 5606 1509 1447 5607 1508 1446 5608 1483 1421 5609 1510 1448 5610 1484 1422 5611 1485 1423 5612 1510 1448 5613 1509 1447 5614 1484 1422 5615 1511 1449 5616 1485 1423 5617 1486 1424 5618 1511 1449 5619 1510 1448 5620 1485 1423 5621 1512 1450 5622 1486 1424 5623 1487 1425 5624 1512 1450 5625 1511 1449 5626 1486 1424 5627 1513 1451 5628 1487 1425 5629 1488 1426 5630 1513 1451 5631 1512 1450 5632 1487 1425 5633 1514 1452 5634 1488 1426 5635 1489 1427 5636 1514 1452 5637 1513 1451 5638 1488 1426 5639 1515 1453 5640 1489 1427 5641 1490 1428 5642 1515 1453 5643 1514 1452 5644 1489 1427 5645 1516 1454 5646 1490 1428 5647 1491 1429 5648 1516 1454 5649 1515 1453 5650 1490 1428 5651 1517 1455 5652 1491 1429 5653 1492 1430 5654 1517 1455 5655 1516 1454 5656 1491 1429 5657 1518 1456 5658 1492 1430 5659 1493 1431 5660 1518 1456 5661 1517 1455 5662 1492 1430 5663 1519 1457 5664 1493 1431 5665 1494 1432 5666 1519 1457 5667 1518 1456 5668 1493 1431 5669 1520 1458 5670 1494 1432 5671 1495 1433 5672 1520 1458 5673 1519 1457 5674 1494 1432 5675 1521 1459 5676 1495 1433 5677 1496 1434 5678 1521 1459 5679 1520 1458 5680 1495 1433 5681 621 611 5682 1496 1434 5683 661 651 5684 621 611 5685 1521 1459 5686 1496 1434 5687 1522 1460 5688 1501 1439 5689 1523 1461 5690 1522 1460 5691 1500 1438 5692 1501 1439 5693 1524 1462 5694 1523 1461 5695 1525 1463 5696 1524 1462 5697 1522 1460 5698 1523 1461 5699 1526 1464 5700 1504 1442 5701 1502 1440 5702 1527 1465 5703 1525 1463 5704 1528 1466 5705 1527 1465 5706 1524 1462 5707 1525 1463 5708 1529 1467 5709 1502 1440 5710 1505 1443 5711 1530 1468 5712 1526 1464 5713 1502 1440 5714 1529 1467 5715 1530 1468 5716 1502 1440 5717 1531 1469 5718 1505 1443 5719 1506 1444 5720 1531 1469 5721 1529 1467 5722 1505 1443 5723 1532 1470 5724 1506 1444 5725 1507 1445 5726 1532 1470 5727 1531 1469 5728 1506 1444 5729 1533 1471 5730 1507 1445 5731 1508 1446 5732 1533 1471 5733 1532 1470 5734 1507 1445 5735 1534 1472 5736 1508 1446 5737 1509 1447 5738 1534 1472 5739 1533 1471 5740 1508 1446 5741 1535 1473 5742 1509 1447 5743 1510 1448 5744 1535 1473 5745 1534 1472 5746 1509 1447 5747 1536 1474 5748 1510 1448 5749 1511 1449 5750 1536 1474 5751 1535 1473 5752 1510 1448 5753 1537 1475 5754 1511 1449 5755 1512 1450 5756 1537 1475 5757 1536 1474 5758 1511 1449 5759 1538 1476 5760 1512 1450 5761 1513 1451 5762 1538 1476 5763 1537 1475 5764 1512 1450 5765 1539 1477 5766 1513 1451 5767 1514 1452 5768 1539 1477 5769 1538 1476 5770 1513 1451 5771 1540 1478 5772 1514 1452 5773 1515 1453 5774 1540 1478 5775 1539 1477 5776 1514 1452 5777 1541 1479 5778 1515 1453 5779 1516 1454 5780 1541 1479 5781 1540 1478 5782 1515 1453 5783 1542 1480 5784 1516 1454 5785 1517 1455 5786 1542 1480 5787 1541 1479 5788 1516 1454 5789 1543 1481 5790 1517 1455 5791 1518 1456 5792 1543 1481 5793 1542 1480 5794 1517 1455 5795 1544 1482 5796 1518 1456 5797 1519 1457 5798 1544 1482 5799 1543 1481 5800 1518 1456 5801 1545 1483 5802 1519 1457 5803 1520 1458 5804 1545 1483 5805 1544 1482 5806 1519 1457 5807 1546 1484 5808 1520 1458 5809 1521 1459 5810 1546 1484 5811 1545 1483 5812 1520 1458 5813 1547 1485 5814 1521 1459 5815 621 611 5816 1547 1485 5817 1546 1484 5818 1521 1459 5819 580 571 5820 1547 1485 5821 621 611 5822 1548 1486 5823 1528 1466 5824 1549 1487 5825 1548 1486 5826 1527 1465 5827 1528 1466 5828 1550 1488 5829 1530 1468 5830 1529 1467 5831 1548 1486 5832 1549 1487 5833 1551 1489 5834 1552 1490 5835 1529 1467 5836 1531 1469 5837 1553 1491 5838 1550 1488 5839 1529 1467 5840 1552 1490 5841 1553 1491 5842 1529 1467 5843 1554 1492 5844 1531 1469 5845 1532 1470 5846 1554 1492 5847 1552 1490 5848 1531 1469 5849 1555 1493 5850 1532 1470 5851 1533 1471 5852 1555 1493 5853 1554 1492 5854 1532 1470 5855 1556 1494 5856 1533 1471 5857 1534 1472 5858 1556 1494 5859 1555 1493 5860 1533 1471 5861 1557 1495 5862 1534 1472 5863 1535 1473 5864 1557 1495 5865 1556 1494 5866 1534 1472 5867 1558 1496 5868 1535 1473 5869 1536 1474 5870 1558 1496 5871 1557 1495 5872 1535 1473 5873 1559 1497 5874 1536 1474 5875 1537 1475 5876 1559 1497 5877 1558 1496 5878 1536 1474 5879 1560 1498 5880 1537 1475 5881 1538 1476 5882 1560 1498 5883 1559 1497 5884 1537 1475 5885 1561 1499 5886 1538 1476 5887 1539 1477 5888 1561 1499 5889 1560 1498 5890 1538 1476 5891 1562 1500 5892 1539 1477 5893 1540 1478 5894 1562 1500 5895 1561 1499 5896 1539 1477 5897 1563 1501 5898 1540 1478 5899 1541 1479 5900 1563 1501 5901 1562 1500 5902 1540 1478 5903 1564 1502 5904 1541 1479 5905 1542 1480 5906 1564 1502 5907 1563 1501 5908 1541 1479 5909 1565 1503 5910 1542 1480 5911 1543 1481 5912 1565 1503 5913 1564 1502 5914 1542 1480 5915 1566 1504 5916 1543 1481 5917 1544 1482 5918 1566 1504 5919 1565 1503 5920 1543 1481 5921 1567 1505 5922 1544 1482 5923 1545 1483 5924 1567 1505 5925 1566 1504 5926 1544 1482 5927 1568 1506 5928 1545 1483 5929 1546 1484 5930 1568 1506 5931 1567 1505 5932 1545 1483 5933 1569 1507 5934 1546 1484 5935 1547 1485 5936 1569 1507 5937 1568 1506 5938 1546 1484 5939 1570 1508 5940 1547 1485 5941 580 571 5942 1570 1508 5943 1569 1507 5944 1547 1485 5945 544 535 5946 1570 1508 5947 580 571 5948 1571 1509 5949 1551 1489 5950 1572 1510 5951 1571 1509 5952 1548 1486 5953 1551 1489 5954 1573 1511 5955 1553 1491 5956 1552 1490 5957 1574 1512 5958 1572 1510 5959 1575 1513 5960 1574 1512 5961 1571 1509 5962 1572 1510 5963 1576 1514 5964 1552 1490 5965 1554 1492 5966 1577 1515 5967 1573 1511 5968 1552 1490 5969 1576 1514 5970 1577 1515 5971 1552 1490 5972 1578 1516 5973 1554 1492 5974 1555 1493 5975 1578 1516 5976 1576 1514 5977 1554 1492 5978 1579 1517 5979 1555 1493 5980 1556 1494 5981 1579 1517 5982 1578 1516 5983 1555 1493 5984 1580 1518 5985 1556 1494 5986 1557 1495 5987 1580 1518 5988 1579 1517 5989 1556 1494 5990 1581 1519 5991 1557 1495 5992 1558 1496 5993 1581 1519 5994 1580 1518 5995 1557 1495 5996 1582 1520 5997 1558 1496 5998 1559 1497 5999 1582 1520 6000 1581 1519 6001 1558 1496 6002 1583 1521 6003 1559 1497 6004 1560 1498 6005 1583 1521 6006 1582 1520 6007 1559 1497 6008 1584 1522 6009 1560 1498 6010 1561 1499 6011 1584 1522 6012 1583 1521 6013 1560 1498 6014 1585 1523 6015 1561 1499 6016 1562 1500 6017 1585 1523 6018 1584 1522 6019 1561 1499 6020 1586 1524 6021 1562 1500 6022 1563 1501 6023 1586 1524 6024 1585 1523 6025 1562 1500 6026 1587 1525 6027 1563 1501 6028 1564 1502 6029 1587 1525 6030 1586 1524 6031 1563 1501 6032 1588 1526 6033 1564 1502 6034 1565 1503 6035 1588 1526 6036 1587 1525 6037 1564 1502 6038 1589 1527 6039 1565 1503 6040 1566 1504 6041 1589 1527 6042 1588 1526 6043 1565 1503 6044 1590 1528 6045 1566 1504 6046 1567 1505 6047 1590 1528 6048 1589 1527 6049 1566 1504 6050 1591 1529 6051 1567 1505 6052 1568 1506 6053 1591 1529 6054 1590 1528 6055 1567 1505 6056 1592 1530 6057 1568 1506 6058 1569 1507 6059 1592 1530 6060 1591 1529 6061 1568 1506 6062 1593 1531 6063 1569 1507 6064 1570 1508 6065 1593 1531 6066 1592 1530 6067 1569 1507 6068 441 437 6069 1570 1508 6070 544 535 6071 441 437 6072 1593 1531 6073 1570 1508 6074 1594 1532 6075 1575 1513 6076 1595 1533 6077 1594 1532 6078 1574 1512 6079 1575 1513 6080 1596 1534 6081 1577 1515 6082 1576 1514 6083 1597 1535 6084 1595 1533 6085 1598 1536 6086 1597 1535 6087 1594 1532 6088 1595 1533 6089 1599 1537 6090 1576 1514 6091 1578 1516 6092 1600 1538 6093 1596 1534 6094 1576 1514 6095 1599 1537 6096 1600 1538 6097 1576 1514 6098 1601 1539 6099 1578 1516 6100 1579 1517 6101 1601 1539 6102 1599 1537 6103 1578 1516 6104 1602 1540 6105 1579 1517 6106 1580 1518 6107 1602 1540 6108 1601 1539 6109 1579 1517 6110 1603 1541 6111 1580 1518 6112 1581 1519 6113 1603 1541 6114 1602 1540 6115 1580 1518 6116 1604 1542 6117 1581 1519 6118 1582 1520 6119 1604 1542 6120 1603 1541 6121 1581 1519 6122 1605 1543 6123 1582 1520 6124 1583 1521 6125 1605 1543 6126 1604 1542 6127 1582 1520 6128 1606 1544 6129 1583 1521 6130 1584 1522 6131 1606 1544 6132 1605 1543 6133 1583 1521 6134 1607 1545 6135 1584 1522 6136 1585 1523 6137 1607 1545 6138 1606 1544 6139 1584 1522 6140 1608 1546 6141 1585 1523 6142 1586 1524 6143 1608 1546 6144 1607 1545 6145 1585 1523 6146 1609 1547 6147 1586 1524 6148 1587 1525 6149 1609 1547 6150 1608 1546 6151 1586 1524 6152 1610 1548 6153 1587 1525 6154 1588 1526 6155 1610 1548 6156 1609 1547 6157 1587 1525 6158 1611 1549 6159 1588 1526 6160 1589 1527 6161 1611 1549 6162 1610 1548 6163 1588 1526 6164 1612 1550 6165 1589 1527 6166 1590 1528 6167 1612 1550 6168 1611 1549 6169 1589 1527 6170 1613 1551 6171 1590 1528 6172 1591 1529 6173 1613 1551 6174 1612 1550 6175 1590 1528 6176 1614 1552 6177 1591 1529 6178 1592 1530 6179 1614 1552 6180 1613 1551 6181 1591 1529 6182 1615 1553 6183 1592 1530 6184 1593 1531 6185 1615 1553 6186 1614 1552 6187 1592 1530 6188 1616 1554 6189 1593 1531 6190 441 437 6191 1616 1554 6192 1615 1553 6193 1593 1531 6194 437 433 6195 1616 1554 6196 441 437 6197 1617 1555 6198 1598 1536 6199 1618 1556 6200 1617 1555 6201 1597 1535 6202 1598 1536 6203 1619 1557 6204 1600 1538 6205 1599 1537 6206 1620 1558 6207 1618 1556 6208 1621 1559 6209 1622 1560 6210 1617 1555 6211 1618 1556 6212 1620 1558 6213 1622 1560 6214 1618 1556 6215 1623 1561 6216 1599 1537 6217 1601 1539 6218 1624 1562 6219 1619 1557 6220 1599 1537 6221 1623 1561 6222 1624 1562 6223 1599 1537 6224 1625 1563 6225 1601 1539 6226 1602 1540 6227 1625 1563 6228 1623 1561 6229 1601 1539 6230 1626 1564 6231 1602 1540 6232 1603 1541 6233 1626 1564 6234 1625 1563 6235 1602 1540 6236 1627 1565 6237 1603 1541 6238 1604 1542 6239 1627 1565 6240 1626 1564 6241 1603 1541 6242 1628 1566 6243 1604 1542 6244 1605 1543 6245 1628 1566 6246 1627 1565 6247 1604 1542 6248 1629 1567 6249 1605 1543 6250 1606 1544 6251 1629 1567 6252 1628 1566 6253 1605 1543 6254 1630 1568 6255 1606 1544 6256 1607 1545 6257 1630 1568 6258 1629 1567 6259 1606 1544 6260 1631 1569 6261 1607 1545 6262 1608 1546 6263 1631 1569 6264 1630 1568 6265 1607 1545 6266 1632 1570 6267 1608 1546 6268 1609 1547 6269 1632 1570 6270 1631 1569 6271 1608 1546 6272 1633 1571 6273 1609 1547 6274 1610 1548 6275 1633 1571 6276 1632 1570 6277 1609 1547 6278 1634 1572 6279 1610 1548 6280 1611 1549 6281 1634 1572 6282 1633 1571 6283 1610 1548 6284 1635 1573 6285 1611 1549 6286 1612 1550 6287 1635 1573 6288 1634 1572 6289 1611 1549 6290 1636 1574 6291 1612 1550 6292 1613 1551 6293 1636 1574 6294 1635 1573 6295 1612 1550 6296 1637 1575 6297 1613 1551 6298 1614 1552 6299 1637 1575 6300 1636 1574 6301 1613 1551 6302 1638 1576 6303 1614 1552 6304 1615 1553 6305 1638 1576 6306 1637 1575 6307 1614 1552 6308 1639 1577 6309 1615 1553 6310 1616 1554 6311 1639 1577 6312 1638 1576 6313 1615 1553 6314 1640 1578 6315 1616 1554 6316 437 433 6317 1640 1578 6318 1639 1577 6319 1616 1554 6320 445 441 6321 1640 1578 6322 437 433 6323 1641 1579 6324 1621 1559 6325 1642 1580 6326 1641 1579 6327 1620 1558 6328 1621 1559 6329 1643 1581 6330 1624 1562 6331 1623 1561 6332 1643 1581 6333 1644 1582 6334 1624 1562 6335 1645 1583 6336 1642 1580 6337 1646 1584 6338 1645 1583 6339 1641 1579 6340 1642 1580 6341 1647 1585 6342 1623 1561 6343 1625 1563 6344 1647 1585 6345 1643 1581 6346 1623 1561 6347 1648 1586 6348 1625 1563 6349 1626 1564 6350 1648 1586 6351 1647 1585 6352 1625 1563 6353 1649 1587 6354 1626 1564 6355 1627 1565 6356 1649 1587 6357 1648 1586 6358 1626 1564 6359 1650 1588 6360 1627 1565 6361 1628 1566 6362 1650 1588 6363 1649 1587 6364 1627 1565 6365 1651 1589 6366 1628 1566 6367 1629 1567 6368 1651 1589 6369 1650 1588 6370 1628 1566 6371 1652 1590 6372 1629 1567 6373 1630 1568 6374 1652 1590 6375 1651 1589 6376 1629 1567 6377 1653 1591 6378 1630 1568 6379 1631 1569 6380 1653 1591 6381 1652 1590 6382 1630 1568 6383 1654 1592 6384 1631 1569 6385 1632 1570 6386 1654 1592 6387 1653 1591 6388 1631 1569 6389 1655 1593 6390 1632 1570 6391 1633 1571 6392 1655 1593 6393 1654 1592 6394 1632 1570 6395 1656 1594 6396 1633 1571 6397 1634 1572 6398 1656 1594 6399 1655 1593 6400 1633 1571 6401 1657 1595 6402 1634 1572 6403 1635 1573 6404 1657 1595 6405 1656 1594 6406 1634 1572 6407 1658 1596 6408 1635 1573 6409 1636 1574 6410 1658 1596 6411 1657 1595 6412 1635 1573 6413 1659 1597 6414 1636 1574 6415 1637 1575 6416 1659 1597 6417 1658 1596 6418 1636 1574 6419 1660 1598 6420 1637 1575 6421 1638 1576 6422 1660 1598 6423 1659 1597 6424 1637 1575 6425 1661 1599 6426 1638 1576 6427 1639 1577 6428 1661 1599 6429 1660 1598 6430 1638 1576 6431 1662 1600 6432 1639 1577 6433 1640 1578 6434 1662 1600 6435 1661 1599 6436 1639 1577 6437 320 316 6438 1640 1578 6439 445 441 6440 320 316 6441 1662 1600 6442 1640 1578 6443 1643 1581 6444 1663 1601 6445 1644 1582 6446 1645 1583 6447 1646 1584 6448 1664 1602 6449 1665 1603 6450 1663 1601 6451 1643 1581 6452 1665 1603 6453 1666 1604 6454 1663 1601 6455 1667 1605 6456 1664 1602 6457 1668 1606 6458 1667 1605 6459 1645 1583 6460 1664 1602 6461 1669 1607 6462 1643 1581 6463 1647 1585 6464 1669 1607 6465 1665 1603 6466 1643 1581 6467 1670 1608 6468 1647 1585 6469 1648 1586 6470 1670 1608 6471 1669 1607 6472 1647 1585 6473 1671 1609 6474 1648 1586 6475 1649 1587 6476 1671 1609 6477 1670 1608 6478 1648 1586 6479 1672 1610 6480 1649 1587 6481 1650 1588 6482 1672 1610 6483 1671 1609 6484 1649 1587 6485 1673 1611 6486 1650 1588 6487 1651 1589 6488 1673 1611 6489 1672 1610 6490 1650 1588 6491 1674 1612 6492 1651 1589 6493 1652 1590 6494 1674 1612 6495 1673 1611 6496 1651 1589 6497 1675 1613 6498 1652 1590 6499 1653 1591 6500 1675 1613 6501 1674 1612 6502 1652 1590 6503 1676 1614 6504 1653 1591 6505 1654 1592 6506 1676 1614 6507 1675 1613 6508 1653 1591 6509 1677 1615 6510 1654 1592 6511 1655 1593 6512 1677 1615 6513 1676 1614 6514 1654 1592 6515 1678 1616 6516 1655 1593 6517 1656 1594 6518 1678 1616 6519 1677 1615 6520 1655 1593 6521 1679 1617 6522 1656 1594 6523 1657 1595 6524 1679 1617 6525 1678 1616 6526 1656 1594 6527 1680 1618 6528 1657 1595 6529 1658 1596 6530 1680 1618 6531 1679 1617 6532 1657 1595 6533 1292 1230 6534 1658 1596 6535 1659 1597 6536 1292 1230 6537 1680 1618 6538 1658 1596 6539 1285 1223 6540 1659 1597 6541 1660 1598 6542 1285 1223 6543 1292 1230 6544 1659 1597 6545 1283 1221 6546 1660 1598 6547 1661 1599 6548 1283 1221 6549 1285 1223 6550 1660 1598 6551 1281 1219 6552 1661 1599 6553 1662 1600 6554 1281 1219 6555 1283 1221 6556 1661 1599 6557 154 152 6558 1662 1600 6559 320 316 6560 154 152 6561 1281 1219 6562 1662 1600 6563 1665 1603 6564 1681 1619 6565 1666 1604 6566 1682 1620 6567 1668 1606 6568 1683 1621 6569 1682 1620 6570 1667 1605 6571 1668 1606 6572 1684 1622 6573 1681 1619 6574 1665 1603 6575 1684 1622 6576 1685 1623 6577 1681 1619 6578 1686 1624 6579 1683 1621 6580 1687 1625 6581 1686 1624 6582 1682 1620 6583 1683 1621 6584 1688 1626 6585 1665 1603 6586 1669 1607 6587 1688 1626 6588 1684 1622 6589 1665 1603 6590 1689 1627 6591 1669 1607 6592 1670 1608 6593 1689 1627 6594 1688 1626 6595 1669 1607 6596 1690 1628 6597 1670 1608 6598 1671 1609 6599 1690 1628 6600 1689 1627 6601 1670 1608 6602 1691 1629 6603 1671 1609 6604 1672 1610 6605 1691 1629 6606 1690 1628 6607 1671 1609 6608 1692 1630 6609 1672 1610 6610 1673 1611 6611 1692 1630 6612 1691 1629 6613 1672 1610 6614 1693 1631 6615 1673 1611 6616 1674 1612 6617 1693 1631 6618 1692 1630 6619 1673 1611 6620 1694 1632 6621 1674 1612 6622 1675 1613 6623 1694 1632 6624 1693 1631 6625 1674 1612 6626 1695 1633 6627 1675 1613 6628 1676 1614 6629 1695 1633 6630 1694 1632 6631 1675 1613 6632 1696 1634 6633 1676 1614 6634 1677 1615 6635 1696 1634 6636 1695 1633 6637 1676 1614 6638 1697 1635 6639 1677 1615 6640 1678 1616 6641 1697 1635 6642 1696 1634 6643 1677 1615 6644 1698 1636 6645 1678 1616 6646 1679 1617 6647 1698 1636 6648 1697 1635 6649 1678 1616 6650 1355 1293 6651 1679 1617 6652 1680 1618 6653 1355 1293 6654 1698 1636 6655 1679 1617 6656 1290 1228 6657 1680 1618 6658 1292 1230 6659 1290 1228 6660 1355 1293 6661 1680 1618 6662 1684 1622 6663 1699 1637 6664 1685 1623 6665 1700 1638 6666 1687 1625 6667 1701 1639 6668 1700 1638 6669 1686 1624 6670 1687 1625 6671 1702 1640 6672 1699 1637 6673 1684 1622 6674 1702 1640 6675 1703 1641 6676 1699 1637 6677 1704 1642 6678 1701 1639 6679 1705 1643 6680 1704 1642 6681 1700 1638 6682 1701 1639 6683 1706 1644 6684 1684 1622 6685 1688 1626 6686 1706 1644 6687 1702 1640 6688 1684 1622 6689 1707 1645 6690 1688 1626 6691 1689 1627 6692 1707 1645 6693 1706 1644 6694 1688 1626 6695 1708 1646 6696 1689 1627 6697 1690 1628 6698 1708 1646 6699 1707 1645 6700 1689 1627 6701 1709 1647 6702 1690 1628 6703 1691 1629 6704 1709 1647 6705 1708 1646 6706 1690 1628 6707 1710 1648 6708 1691 1629 6709 1692 1630 6710 1710 1648 6711 1709 1647 6712 1691 1629 6713 1711 1649 6714 1692 1630 6715 1693 1631 6716 1711 1649 6717 1710 1648 6718 1692 1630 6719 1712 1650 6720 1693 1631 6721 1694 1632 6722 1712 1650 6723 1711 1649 6724 1693 1631 6725 1712 1650 6726 1694 1632 6727 1695 1633 6728 1713 1651 6729 1695 1633 6730 1696 1634 6731 1713 1651 6732 1712 1650 6733 1695 1633 6734 1714 1652 6735 1696 1634 6736 1697 1635 6737 1715 1653 6738 1713 1651 6739 1696 1634 6740 1716 1654 6741 1715 1653 6742 1696 1634 6743 1714 1652 6744 1716 1654 6745 1696 1634 6746 1717 1655 6747 1697 1635 6748 1698 1636 6749 1718 1656 6750 1714 1652 6751 1697 1635 6752 1717 1655 6753 1718 1656 6754 1697 1635 6755 1719 1657 6756 1698 1636 6757 1355 1293 6758 1720 1658 6759 1717 1655 6760 1698 1636 6761 1719 1657 6762 1720 1658 6763 1698 1636 6764 1356 1294 6765 1719 1657 6766 1355 1293 6767 1702 1640 6768 1721 1659 6769 1703 1641 6770 1722 1660 6771 1705 1643 6772 1723 1661 6773 1722 1660 6774 1704 1642 6775 1705 1643 6776 1724 1662 6777 1721 1659 6778 1702 1640 6779 1724 1662 6780 1725 1663 6781 1721 1659 6782 1726 1664 6783 1723 1661 6784 1727 1665 6785 1726 1664 6786 1722 1660 6787 1723 1661 6788 1728 1666 6789 1702 1640 6790 1706 1644 6791 1728 1666 6792 1724 1662 6793 1702 1640 6794 1729 1667 6795 1706 1644 6796 1707 1645 6797 1729 1667 6798 1728 1666 6799 1706 1644 6800 1730 1668 6801 1707 1645 6802 1708 1646 6803 1730 1668 6804 1729 1667 6805 1707 1645 6806 1731 1669 6807 1708 1646 6808 1709 1647 6809 1731 1669 6810 1730 1668 6811 1708 1646 6812 1732 1670 6813 1709 1647 6814 1710 1648 6815 1733 1671 6816 1731 1669 6817 1709 1647 6818 1732 1670 6819 1733 1671 6820 1709 1647 6821 1734 1672 6822 1710 1648 6823 1711 1649 6824 1735 1673 6825 1732 1670 6826 1710 1648 6827 1734 1672 6828 1735 1673 6829 1710 1648 6830 1736 1674 6831 1711 1649 6832 1712 1650 6833 1737 1675 6834 1734 1672 6835 1711 1649 6836 1736 1674 6837 1737 1675 6838 1711 1649 6839 1738 1676 6840 1712 1650 6841 1713 1651 6842 1739 1677 6843 1736 1674 6844 1712 1650 6845 1738 1676 6846 1739 1677 6847 1712 1650 6848 1740 1678 6849 1741 1679 6850 1742 1680 6851 1740 1678 6852 1743 1681 6853 1741 1679 6854 1744 1682 6855 1742 1680 6856 1745 1683 6857 1744 1682 6858 1740 1678 6859 1742 1680 6860 1744 1682 6861 1745 1683 6862 1746 1684 6863 1747 1685 6864 1746 1684 6865 1748 1686 6866 1747 1685 6867 1744 1682 6868 1746 1684 6869 1747 1685 6870 1748 1686 6871 1749 1687 6872 1750 1688 6873 1749 1687 6874 1751 1689 6875 1750 1688 6876 1747 1685 6877 1749 1687 6878 1750 1688 6879 1751 1689 6880 1752 1690 6881 1352 1290 6882 1752 1690 6883 1357 1295 6884 1352 1290 6885 1750 1688 6886 1752 1690 6887 1724 1662 6888 1753 1691 6889 1725 1663 6890 1754 1692 6891 1727 1665 6892 1755 1693 6893 1754 1692 6894 1726 1664 6895 1727 1665 6896 1756 1694 6897 1753 1691 6898 1724 1662 6899 1757 1695 6900 1758 1696 6901 1753 1691 6902 1759 1697 6903 1755 1693 6904 1760 1698 6905 1756 1694 6906 1757 1695 6907 1753 1691 6908 1759 1697 6909 1754 1692 6910 1755 1693 6911 1761 1699 6912 1724 1662 6913 1728 1666 6914 1761 1699 6915 1756 1694 6916 1724 1662 6917 1762 1700 6918 1728 1666 6919 1729 1667 6920 1763 1701 6921 1761 1699 6922 1728 1666 6923 1762 1700 6924 1763 1701 6925 1728 1666 6926 1764 1702 6927 1729 1667 6928 1730 1668 6929 1765 1703 6930 1762 1700 6931 1729 1667 6932 1764 1702 6933 1765 1703 6934 1729 1667 6935 1766 1704 6936 1730 1668 6937 1731 1669 6938 1767 1705 6939 1764 1702 6940 1730 1668 6941 1766 1704 6942 1767 1705 6943 1730 1668 6944 1768 1706 6945 1769 1707 6946 1770 1708 6947 1771 1709 6948 1766 1704 6949 1731 1669 6950 1768 1706 6951 1772 1710 6952 1769 1707 6953 1773 1711 6954 1770 1708 6955 1774 1712 6956 1773 1711 6957 1768 1706 6958 1770 1708 6959 1775 1713 6960 1774 1712 6961 1776 1714 6962 1775 1713 6963 1773 1711 6964 1774 1712 6965 1775 1713 6966 1776 1714 6967 1777 1715 6968 1778 1716 6969 1777 1715 6970 1779 1717 6971 1778 1716 6972 1775 1713 6973 1777 1715 6974 1778 1716 6975 1779 1717 6976 1780 1718 6977 1781 1719 6978 1780 1718 6979 1782 1720 6980 1781 1719 6981 1778 1716 6982 1780 1718 6983 1781 1719 6984 1782 1720 6985 1743 1681 6986 1740 1678 6987 1781 1719 6988 1743 1681 6989 1757 1695 6990 1783 1721 6991 1758 1696 6992 1784 1722 6993 1760 1698 6994 1785 1723 6995 1784 1722 6996 1759 1697 6997 1760 1698 6998 1786 1724 6999 1787 1725 7000 1788 1726 7001 1789 1727 7002 1784 1722 7003 1785 1723 7004 1790 1728 7005 1789 1727 7006 1785 1723 7007 1786 1724 7008 1791 1729 7009 1787 1725 7010 1792 1730 7011 1788 1726 7012 1793 1731 7013 1792 1730 7014 1786 1724 7015 1788 1726 7016 1792 1730 7017 1793 1731 7018 1794 1732 7019 1795 1733 7020 1794 1732 7021 1796 1734 7022 1795 1733 7023 1792 1730 7024 1794 1732 7025 1795 1733 7026 1796 1734 7027 1797 1735 7028 1798 1736 7029 1797 1735 7030 1799 1737 7031 1798 1736 7032 1795 1733 7033 1797 1735 7034 1798 1736 7035 1799 1737 7036 1800 1738 7037 1801 1739 7038 1800 1738 7039 1802 1740 7040 1801 1739 7041 1798 1736 7042 1800 1738 7043 1801 1739 7044 1802 1740 7045 1803 1741 7046 1768 1706 7047 1803 1741 7048 1772 1710 7049 1768 1706 7050 1801 1739 7051 1803 1741 7052 1091 1061 7053 994 969 7054 1443 1381 7055 1804 1742 7056 1443 1381 7057 1444 1382 7058 1804 1742 7059 1091 1061 7060 1443 1381 7061 1805 1743 7062 1444 1382 7063 1445 1383 7064 1805 1743 7065 1804 1742 7066 1444 1382 7067 1806 1744 7068 1445 1383 7069 1446 1384 7070 1806 1744 7071 1805 1743 7072 1445 1383 7073 1807 1745 7074 1446 1384 7075 1447 1385 7076 1807 1745 7077 1806 1744 7078 1446 1384 7079 1808 1746 7080 1447 1385 7081 1448 1386 7082 1808 1746 7083 1807 1745 7084 1447 1385 7085 1809 1747 7086 1448 1386 7087 1449 1387 7088 1809 1747 7089 1808 1746 7090 1448 1386 7091 1810 1748 7092 1449 1387 7093 1450 1388 7094 1810 1748 7095 1809 1747 7096 1449 1387 7097 1811 1749 7098 1450 1388 7099 1451 1389 7100 1811 1749 7101 1810 1748 7102 1450 1388 7103 1812 1750 7104 1451 1389 7105 1452 1390 7106 1812 1750 7107 1811 1749 7108 1451 1389 7109 1813 1751 7110 1452 1390 7111 1453 1391 7112 1813 1751 7113 1812 1750 7114 1452 1390 7115 1814 1752 7116 1453 1391 7117 1454 1392 7118 1814 1752 7119 1813 1751 7120 1453 1391 7121 1815 1753 7122 1454 1392 7123 1455 1393 7124 1815 1753 7125 1814 1752 7126 1454 1392 7127 1816 1754 7128 1455 1393 7129 1456 1394 7130 1816 1754 7131 1815 1753 7132 1455 1393 7133 1817 1755 7134 1456 1394 7135 1457 1395 7136 1817 1755 7137 1816 1754 7138 1456 1394 7139 1818 1756 7140 1457 1395 7141 1458 1396 7142 1818 1756 7143 1817 1755 7144 1457 1395 7145 1819 1757 7146 1458 1396 7147 1459 1397 7148 1819 1757 7149 1818 1756 7150 1458 1396 7151 1820 1758 7152 1459 1397 7153 1460 1398 7154 1820 1758 7155 1819 1757 7156 1459 1397 7157 1821 1759 7158 1460 1398 7159 1461 1399 7160 1821 1759 7161 1820 1758 7162 1460 1398 7163 1822 1760 7164 1461 1399 7165 1462 1400 7166 1822 1760 7167 1821 1759 7168 1461 1399 7169 1823 1761 7170 1462 1400 7171 1463 1401 7172 1823 1761 7173 1822 1760 7174 1462 1400 7175 1824 1762 7176 1463 1401 7177 1464 1402 7178 1824 1762 7179 1823 1761 7180 1463 1401 7181 1825 1763 7182 1464 1402 7183 1465 1403 7184 1825 1763 7185 1824 1762 7186 1464 1402 7187 1826 1764 7188 1465 1403 7189 1466 1404 7190 1826 1764 7191 1825 1763 7192 1465 1403 7193 1827 1765 7194 1466 1404 7195 1467 1405 7196 1827 1765 7197 1826 1764 7198 1466 1404 7199 1828 1766 7200 1467 1405 7201 860 844 7202 1828 1766 7203 1827 1765 7204 1467 1405 7205 932 907 7206 1828 1766 7207 860 844 7208 1083 1053 7209 1091 1061 7210 1804 1742 7211 1829 1767 7212 1804 1742 7213 1805 1743 7214 1829 1767 7215 1083 1053 7216 1804 1742 7217 1830 1768 7218 1805 1743 7219 1806 1744 7220 1830 1768 7221 1829 1767 7222 1805 1743 7223 1831 1769 7224 1806 1744 7225 1807 1745 7226 1831 1769 7227 1830 1768 7228 1806 1744 7229 1832 1770 7230 1807 1745 7231 1808 1746 7232 1832 1770 7233 1831 1769 7234 1807 1745 7235 1833 1771 7236 1808 1746 7237 1809 1747 7238 1833 1771 7239 1832 1770 7240 1808 1746 7241 1834 1772 7242 1809 1747 7243 1810 1748 7244 1834 1772 7245 1833 1771 7246 1809 1747 7247 1835 1773 7248 1810 1748 7249 1811 1749 7250 1835 1773 7251 1834 1772 7252 1810 1748 7253 1836 1774 7254 1811 1749 7255 1812 1750 7256 1836 1774 7257 1835 1773 7258 1811 1749 7259 1837 1775 7260 1812 1750 7261 1813 1751 7262 1837 1775 7263 1836 1774 7264 1812 1750 7265 1838 1776 7266 1813 1751 7267 1814 1752 7268 1838 1776 7269 1837 1775 7270 1813 1751 7271 1839 1777 7272 1814 1752 7273 1815 1753 7274 1839 1777 7275 1838 1776 7276 1814 1752 7277 1840 1778 7278 1815 1753 7279 1816 1754 7280 1840 1778 7281 1839 1777 7282 1815 1753 7283 1841 1779 7284 1816 1754 7285 1817 1755 7286 1841 1779 7287 1840 1778 7288 1816 1754 7289 1842 1780 7290 1817 1755 7291 1818 1756 7292 1842 1780 7293 1841 1779 7294 1817 1755 7295 1843 1781 7296 1818 1756 7297 1819 1757 7298 1843 1781 7299 1842 1780 7300 1818 1756 7301 1844 1782 7302 1819 1757 7303 1820 1758 7304 1844 1782 7305 1843 1781 7306 1819 1757 7307 1845 1783 7308 1820 1758 7309 1821 1759 7310 1845 1783 7311 1844 1782 7312 1820 1758 7313 1846 1784 7314 1821 1759 7315 1822 1760 7316 1846 1784 7317 1845 1783 7318 1821 1759 7319 1847 1785 7320 1822 1760 7321 1823 1761 7322 1847 1785 7323 1846 1784 7324 1822 1760 7325 1848 1786 7326 1823 1761 7327 1824 1762 7328 1848 1786 7329 1847 1785 7330 1823 1761 7331 1849 1787 7332 1824 1762 7333 1825 1763 7334 1849 1787 7335 1848 1786 7336 1824 1762 7337 1850 1788 7338 1825 1763 7339 1826 1764 7340 1850 1788 7341 1849 1787 7342 1825 1763 7343 1851 1789 7344 1826 1764 7345 1827 1765 7346 1851 1789 7347 1850 1788 7348 1826 1764 7349 1852 1790 7350 1827 1765 7351 1828 1766 7352 1852 1790 7353 1851 1789 7354 1827 1765 7355 1853 1791 7356 1828 1766 7357 932 907 7358 1853 1791 7359 1852 1790 7360 1828 1766 7361 998 973 7362 1853 1791 7363 932 907 7364 1087 1057 7365 1083 1053 7366 1829 1767 7367 1111 1070 7368 1829 1767 7369 1830 1768 7370 1111 1070 7371 1087 1057 7372 1829 1767 7373 1112 1071 7374 1830 1768 7375 1831 1769 7376 1112 1071 7377 1111 1070 7378 1830 1768 7379 1113 1072 7380 1831 1769 7381 1832 1770 7382 1113 1072 7383 1112 1071 7384 1831 1769 7385 1114 1073 7386 1832 1770 7387 1833 1771 7388 1114 1073 7389 1113 1072 7390 1832 1770 7391 1115 1074 7392 1833 1771 7393 1834 1772 7394 1115 1074 7395 1114 1073 7396 1833 1771 7397 1116 1075 7398 1834 1772 7399 1835 1773 7400 1116 1075 7401 1115 1074 7402 1834 1772 7403 1117 1076 7404 1835 1773 7405 1836 1774 7406 1117 1076 7407 1116 1075 7408 1835 1773 7409 1118 1077 7410 1836 1774 7411 1837 1775 7412 1118 1077 7413 1117 1076 7414 1836 1774 7415 1119 1078 7416 1837 1775 7417 1838 1776 7418 1119 1078 7419 1118 1077 7420 1837 1775 7421 1120 1079 7422 1838 1776 7423 1839 1777 7424 1120 1079 7425 1119 1078 7426 1838 1776 7427 1121 1080 7428 1839 1777 7429 1840 1778 7430 1121 1080 7431 1120 1079 7432 1839 1777 7433 1122 1081 7434 1840 1778 7435 1841 1779 7436 1122 1081 7437 1121 1080 7438 1840 1778 7439 1123 1082 7440 1841 1779 7441 1842 1780 7442 1123 1082 7443 1122 1081 7444 1841 1779 7445 1124 1083 7446 1842 1780 7447 1843 1781 7448 1124 1083 7449 1123 1082 7450 1842 1780 7451 1125 1084 7452 1843 1781 7453 1844 1782 7454 1125 1084 7455 1124 1083 7456 1843 1781 7457 1126 1085 7458 1844 1782 7459 1845 1783 7460 1126 1085 7461 1125 1084 7462 1844 1782 7463 1127 1086 7464 1845 1783 7465 1846 1784 7466 1127 1086 7467 1126 1085 7468 1845 1783 7469 1128 1087 7470 1846 1784 7471 1847 1785 7472 1128 1087 7473 1127 1086 7474 1846 1784 7475 1129 1088 7476 1847 1785 7477 1848 1786 7478 1129 1088 7479 1128 1087 7480 1847 1785 7481 1130 1089 7482 1848 1786 7483 1849 1787 7484 1130 1089 7485 1129 1088 7486 1848 1786 7487 1131 1090 7488 1849 1787 7489 1850 1788 7490 1131 1090 7491 1130 1089 7492 1849 1787 7493 1132 1091 7494 1850 1788 7495 1851 1789 7496 1132 1091 7497 1131 1090 7498 1850 1788 7499 1133 1092 7500 1851 1789 7501 1852 1790 7502 1133 1092 7503 1132 1091 7504 1851 1789 7505 1134 1093 7506 1852 1790 7507 1853 1791 7508 1134 1093 7509 1133 1092 7510 1852 1790 7511 1135 1094 7512 1853 1791 7513 998 973 7514 1135 1094 7515 1134 1093 7516 1853 1791 7517 1025 997 7518 1135 1094 7519 998 973 7520 1854 1792 7521 1855 1068 7522 1856 1793 7523 1857 1068 7524 1858 1794 7525 1855 1068 7526 1854 1792 7527 1857 1068 7528 1855 1068 7529 1854 1792 7530 1856 1793 7531 1859 1795 7532 1860 1796 7533 1859 1795 7534 1861 1068 7535 1860 1796 7536 1854 1792 7537 1859 1795 7538 1860 1796 7539 1861 1068 7540 1862 1797 7541 1863 1798 7542 1862 1797 7543 1864 1799 7544 1863 1798 7545 1860 1796 7546 1862 1797 7547 1863 1798 7548 1864 1799 7549 1865 1800 7550 1866 1801 7551 1865 1800 7552 1867 1802 7553 1866 1801 7554 1863 1798 7555 1865 1800 7556 1868 1803 7557 1867 1802 7558 1869 1068 7559 1868 1803 7560 1866 1801 7561 1867 1802 7562 1868 1803 7563 1869 1068 7564 1870 1804 7565 1871 1805 7566 1870 1804 7567 1872 1806 7568 1871 1805 7569 1868 1803 7570 1870 1804 7571 1873 1807 7572 1872 1806 7573 1874 1808 7574 1873 1807 7575 1871 1805 7576 1872 1806 7577 1873 1807 7578 1874 1808 7579 1875 1809 7580 1876 1810 7581 1875 1809 7582 1877 1811 7583 1876 1810 7584 1873 1807 7585 1875 1809 7586 1878 1812 7587 1877 1811 7588 1879 1068 7589 1878 1812 7590 1876 1810 7591 1877 1811 7592 1880 1068 7593 1879 1068 7594 1881 1813 7595 1882 1068 7596 1878 1812 7597 1879 1068 7598 1883 1068 7599 1882 1068 7600 1879 1068 7601 1880 1068 7602 1883 1068 7603 1879 1068 7604 1884 1814 7605 1881 1813 7606 1885 1815 7607 1886 1816 7608 1881 1813 7609 1884 1814 7610 1887 1068 7611 1881 1813 7612 1886 1816 7613 1887 1068 7614 1880 1068 7615 1881 1813 7616 1888 1817 7617 1885 1815 7618 1889 1818 7619 1884 1814 7620 1885 1815 7621 1888 1817 7622 1890 1819 7623 1889 1818 7624 1891 1820 7625 1888 1817 7626 1889 1818 7627 1890 1819 7628 1892 1821 7629 1891 1820 7630 1893 1068 7631 1890 1819 7632 1891 1820 7633 1892 1821 7634 1894 1068 7635 1893 1068 7636 1895 1068 7637 1892 1821 7638 1893 1068 7639 1894 1068 7640 1896 1068 7641 1895 1068 7642 1897 1068 7643 1894 1068 7644 1895 1068 7645 1896 1068 7646 1898 1068 7647 1897 1068 7648 1899 1068 7649 1896 1068 7650 1897 1068 7651 1898 1068 7652 1900 1822 7653 1886 1816 7654 1901 1823 7655 1900 1822 7656 1887 1068 7657 1886 1816 7658 1902 1824 7659 1901 1823 7660 1903 1068 7661 1904 1825 7662 1900 1822 7663 1901 1823 7664 1902 1824 7665 1904 1825 7666 1901 1823 7667 1902 1824 7668 1903 1068 7669 1905 1068 7670 1906 1068 7671 1905 1068 7672 1907 1068 7673 1906 1068 7674 1902 1824 7675 1905 1068 7676 1790 1728 7677 1908 1826 7678 1789 1727 7679 1909 1068 7680 1907 1068 7681 1910 1827 7682 1909 1068 7683 1906 1068 7684 1907 1068 7685 1911 1828 7686 1912 1829 7687 1908 1826 7688 1913 1830 7689 1910 1827 7690 1914 1831 7691 1790 1728 7692 1911 1828 7693 1908 1826 7694 1913 1830 7695 1909 1068 7696 1910 1827 7697 1915 1832 7698 1916 1833 7699 1912 1829 7700 1917 1834 7701 1914 1831 7702 1918 1835 7703 1911 1828 7704 1915 1832 7705 1912 1829 7706 1917 1834 7707 1913 1830 7708 1914 1831 7709 1919 1836 7710 1920 1837 7711 1916 1833 7712 1921 1838 7713 1918 1835 7714 1922 1839 7715 1915 1832 7716 1919 1836 7717 1916 1833 7718 1921 1838 7719 1917 1834 7720 1918 1835 7721 1923 1840 7722 1924 1841 7723 1920 1837 7724 1921 1838 7725 1922 1839 7726 1925 1842 7727 1919 1836 7728 1923 1840 7729 1920 1837 7730 1926 1843 7731 1927 1844 7732 1924 1841 7733 1928 1845 7734 1925 1842 7735 1929 1846 7736 1923 1840 7737 1926 1843 7738 1924 1841 7739 1928 1845 7740 1921 1838 7741 1925 1842 7742 1930 1847 7743 1931 1848 7744 1927 1844 7745 1928 1845 7746 1929 1846 7747 1932 1068 7748 1926 1843 7749 1930 1847 7750 1927 1844 7751 1930 1847 7752 1933 1849 7753 1931 1848 7754 1934 1850 7755 1932 1068 7756 1935 1851 7757 1934 1850 7758 1928 1845 7759 1932 1068 7760 1936 1852 7761 1937 1853 7762 1933 1849 7763 1934 1850 7764 1935 1851 7765 1938 1854 7766 1930 1847 7767 1936 1852 7768 1933 1849 7769 1939 1855 7770 1940 1856 7771 1937 1853 7772 1941 1068 7773 1938 1854 7774 1942 1068 7775 1936 1852 7776 1939 1855 7777 1937 1853 7778 1941 1068 7779 1934 1850 7780 1938 1854 7781 1943 1857 7782 1944 1858 7783 1945 1859 7784 1946 1860 7785 1944 1858 7786 1943 1857 7787 1947 1861 7788 1942 1068 7789 1948 1862 7790 1947 1861 7791 1941 1068 7792 1942 1068 7793 1949 1863 7794 1950 1864 7795 1951 1865 7796 1952 1866 7797 1953 1867 7798 1950 1864 7799 1952 1866 7800 1950 1864 7801 1949 1863 7802 1954 1868 7803 1951 1865 7804 1955 1869 7805 1956 1870 7806 1951 1865 7807 1954 1868 7808 1949 1863 7809 1951 1865 7810 1956 1870 7811 1957 1871 7812 1955 1869 7813 1958 1872 7814 1959 1873 7815 1955 1869 7816 1957 1871 7817 1954 1868 7818 1955 1869 7819 1959 1873 7820 1960 1874 7821 1961 1875 7822 1962 1876 7823 1963 1877 7824 1958 1872 7825 1964 1878 7826 1965 1879 7827 1964 1878 7828 1958 1872 7829 1957 1871 7830 1958 1872 7831 1963 1877 7832 1960 1874 7833 1962 1876 7834 1966 1880 7835 1967 1881 7836 1966 1880 7837 1968 1882 7838 1960 1874 7839 1966 1880 7840 1969 1883 7841 1967 1881 7842 1969 1883 7843 1966 1880 7844 1967 1881 7845 1968 1882 7846 1970 1884 7847 1786 1724 7848 1970 1884 7849 1791 1729 7850 1971 1885 7851 1970 1884 7852 1786 1724 7853 1971 1885 7854 1967 1881 7855 1970 1884 7856 1972 9 7857 1973 9 7858 1974 9 7859 1975 1886 7860 1976 1887 7861 1977 1888 7862 1974 9 7863 1978 9 7864 1972 9 7865 1979 1889 7866 1975 1886 7867 1977 1888 7868 1980 1890 7869 1981 1891 7870 1982 1892 7871 1983 1893 7872 1982 1892 7873 1981 1891 7874 1979 1889 7875 1977 1888 7876 1984 1894 7877 1975 1886 7878 1985 1895 7879 1976 1887 7880 1975 1886 7881 1986 1896 7882 1985 1895 7883 1987 1897 7884 1988 1898 7885 1989 1899 7886 1974 9 7887 1973 9 7888 1990 9 7889 1990 9 7890 1991 9 7891 1974 9 7892 1992 1900 7893 1993 1901 7894 1988 1898 7895 1992 1900 7896 1988 1898 7897 1987 1897 7898 1994 1902 7899 1943 1857 7900 1986 1896 7901 1995 1903 7902 1989 1899 7903 1953 1867 7904 1975 1886 7905 1994 1902 7906 1986 1896 7907 1987 1897 7908 1989 1899 7909 1995 1903 7910 1994 1902 7911 1946 1860 7912 1943 1857 7913 1995 1903 7914 1953 1867 7915 1952 1866 7916 1947 1861 7917 1948 1862 7918 1996 1904 7919 1997 1905 7920 1996 1904 7921 1998 1068 7922 1997 1905 7923 1947 1861 7924 1996 1904 7925 1999 1906 7926 2000 1907 7927 1975 1886 7928 1997 1905 7929 1998 1068 7930 2001 1908 7931 2002 1909 7932 1999 1906 7933 1975 1886 7934 1979 1889 7935 2002 1909 7936 1975 1886 7937 2003 1910 7938 2004 1911 7939 2000 1907 7940 2005 1912 7941 2001 1908 7942 2006 1913 7943 2003 1910 7944 2000 1907 7945 1999 1906 7946 2005 1912 7947 1997 1905 7948 2001 1908 7949 2003 1910 7950 2007 1914 7951 2004 1911 7952 2005 1912 7953 2006 1913 7954 2008 1915 7955 2009 1916 7956 2010 1917 7957 2007 1914 7958 2011 1918 7959 2008 1915 7960 2012 1919 7961 2003 1910 7962 2009 1916 7963 2007 1914 7964 2011 1918 7965 2005 1912 7966 2008 1915 7967 2013 1920 7968 2014 1921 7969 2010 1917 7970 2015 1922 7971 2012 1919 7972 2016 1068 7973 2017 1923 7974 2013 1920 7975 2010 1917 7976 2018 1924 7977 2017 1923 7978 2010 1917 7979 2009 1916 7980 2018 1924 7981 2010 1917 7982 2015 1922 7983 2011 1918 7984 2012 1919 7985 2019 1925 7986 264 260 7987 2014 1921 7988 2015 1922 7989 2016 1068 7990 2020 1926 7991 2021 1927 7992 2019 1925 7993 2014 1921 7994 2022 1928 7995 2021 1927 7996 2014 1921 7997 2023 1929 7998 2022 1928 7999 2014 1921 8000 2013 1920 8001 2023 1929 8002 2014 1921 8003 2024 1930 8004 2020 1926 8005 2025 1931 8006 2026 1932 8007 265 261 8008 264 260 8009 2019 1925 8010 2026 1932 8011 264 260 8012 2024 1930 8013 2015 1922 8014 2020 1926 8015 2027 1933 8016 2025 1931 8017 2028 1934 8018 2027 1933 8019 2024 1930 8020 2025 1931 8021 2027 1933 8022 2028 1934 8023 2029 1935 8024 2030 1936 8025 2029 1935 8026 2031 1937 8027 2030 1936 8028 2027 1933 8029 2029 1935 8030 2032 1938 8031 2031 1937 8032 2033 1068 8033 2032 1938 8034 2030 1936 8035 2031 1937 8036 2034 1068 8037 2033 1068 8038 2035 1939 8039 2036 1068 8040 2032 1938 8041 2033 1068 8042 2037 1068 8043 2036 1068 8044 2033 1068 8045 2034 1068 8046 2037 1068 8047 2033 1068 8048 2038 1940 8049 2035 1939 8050 2039 1941 8051 2040 1942 8052 2035 1939 8053 2038 1940 8054 2041 1068 8055 2035 1939 8056 2040 1942 8057 2034 1068 8058 2035 1939 8059 2041 1068 8060 2042 1943 8061 2039 1941 8062 2043 1944 8063 2038 1940 8064 2039 1941 8065 2042 1943 8066 2044 1945 8067 2043 1944 8068 2045 1946 8069 2042 1943 8070 2043 1944 8071 2044 1945 8072 2046 1947 8073 2045 1946 8074 2047 1068 8075 2044 1945 8076 2045 1946 8077 2046 1947 8078 2048 1068 8079 2047 1068 8080 2049 1068 8081 2046 1947 8082 2047 1068 8083 2048 1068 8084 2050 1068 8085 2049 1068 8086 2051 1068 8087 2048 1068 8088 2049 1068 8089 2050 1068 8090 2052 1068 8091 2051 1068 8092 2053 1068 8093 2050 1068 8094 2051 1068 8095 2052 1068 8096 2054 1948 8097 2040 1942 8098 2055 1949 8099 2054 1948 8100 2041 1068 8101 2040 1942 8102 2056 1950 8103 2055 1949 8104 2057 1068 8105 2058 1951 8106 2054 1948 8107 2055 1949 8108 2056 1950 8109 2058 1951 8110 2055 1949 8111 2056 1950 8112 2057 1068 8113 2059 1068 8114 2060 1068 8115 2059 1068 8116 2061 1068 8117 2060 1068 8118 2056 1950 8119 2059 1068 8120 2062 1068 8121 2061 1068 8122 2063 1952 8123 2062 1068 8124 2060 1068 8125 2061 1068 8126 2064 1953 8127 2065 1954 8128 632 622 8129 2066 1955 8130 2063 1952 8131 2067 1956 8132 2068 1957 8133 2064 1953 8134 632 622 8135 2069 1958 8136 2068 1957 8137 632 622 8138 2070 1959 8139 2069 1958 8140 632 622 8141 664 654 8142 2070 1959 8143 632 622 8144 2066 1955 8145 2062 1068 8146 2063 1952 8147 2071 1960 8148 2072 1961 8149 2065 1954 8150 2073 1962 8151 2067 1956 8152 2074 1963 8153 2075 1964 8154 2071 1960 8155 2065 1954 8156 2076 1965 8157 2075 1964 8158 2065 1954 8159 2064 1953 8160 2076 1965 8161 2065 1954 8162 2073 1962 8163 2066 1955 8164 2067 1956 8165 2077 1966 8166 2078 1967 8167 2072 1961 8168 2079 1968 8169 2074 1963 8170 2080 1969 8171 2071 1960 8172 2077 1966 8173 2072 1961 8174 2079 1968 8175 2073 1962 8176 2074 1963 8177 2081 1970 8178 2082 1971 8179 2078 1967 8180 2079 1968 8181 2080 1969 8182 2083 1972 8183 2077 1966 8184 2081 1970 8185 2078 1967 8186 2084 1973 8187 2085 1974 8188 2082 1971 8189 2086 1975 8190 2083 1972 8191 2087 1976 8192 2081 1970 8193 2084 1973 8194 2082 1971 8195 2086 1975 8196 2079 1968 8197 2083 1972 8198 2088 1977 8199 835 821 8200 2085 1974 8201 2086 1975 8202 2087 1976 8203 2089 1068 8204 2090 1978 8205 2088 1977 8206 2085 1974 8207 2091 1979 8208 2085 1974 8209 2084 1973 8210 2091 1979 8211 2090 1978 8212 2085 1974 8213 2092 1980 8214 2089 1068 8215 2093 1981 8216 2088 1977 8217 838 824 8218 835 821 8219 2092 1980 8220 2086 1975 8221 2089 1068 8222 2092 1980 8223 2093 1981 8224 1858 1794 8225 1857 1068 8226 2092 1980 8227 1858 1794 8228 2090 1978 8229 2094 1982 8230 2088 1977 8231 2095 1983 8232 2096 1984 8233 2097 1985 8234 2098 9 8235 831 9 8236 840 9 8237 2099 1986 8238 2100 1987 8239 2094 1982 8240 2095 1983 8241 2097 1985 8242 2101 1988 8243 2090 1978 8244 2099 1986 8245 2094 1982 8246 2102 1989 8247 2103 1990 8248 2100 1987 8249 2104 1991 8250 2105 1992 8251 2106 1993 8252 2099 1986 8253 2102 1989 8254 2100 1987 8255 2102 1989 8256 2107 1994 8257 2103 1990 8258 2108 1995 8259 2106 1993 8260 2109 1996 8261 2104 1991 8262 2106 1993 8263 2108 1995 8264 2110 1997 8265 731 721 8266 2107 1994 8267 2111 1998 8268 2109 1996 8269 732 722 8270 2102 1989 8271 2110 1997 8272 2107 1994 8273 2108 1995 8274 2109 1996 8275 2111 1998 8276 2110 1997 8277 669 659 8278 731 721 8279 2111 1998 8280 732 722 8281 728 718 8282 2112 1999 8283 2113 2000 8284 265 261 8285 266 262 8286 267 263 8287 2114 2001 8288 2115 2002 8289 2112 1999 8290 265 261 8291 2116 2003 8292 2115 2002 8293 265 261 8294 2117 2004 8295 2116 2003 8296 265 261 8297 2118 2005 8298 2117 2004 8299 265 261 8300 2026 1932 8301 2118 2005 8302 265 261 8303 2119 2006 8304 2120 2007 8305 2113 2000 8306 2121 2008 8307 2114 2001 8308 2122 2009 8309 2112 1999 8310 2119 2006 8311 2113 2000 8312 266 262 8313 2114 2001 8314 2121 2008 8315 2123 2010 8316 2124 2011 8317 2120 2007 8318 2125 2012 8319 2122 2009 8320 2126 2013 8321 2127 2014 8322 2123 2010 8323 2120 2007 8324 2128 2015 8325 2127 2014 8326 2120 2007 8327 2119 2006 8328 2128 2015 8329 2120 2007 8330 2129 2016 8331 2122 2009 8332 2125 2012 8333 2130 2017 8334 2122 2009 8335 2129 2016 8336 2131 2018 8337 2122 2009 8338 2130 2017 8339 2132 2019 8340 2122 2009 8341 2131 2018 8342 2133 2020 8343 2122 2009 8344 2132 2019 8345 2121 2008 8346 2122 2009 8347 2133 2020 8348 2134 2021 8349 2135 2022 8350 2124 2011 8351 2136 2023 8352 2137 2024 8353 2138 2025 8354 2123 2010 8355 2134 2021 8356 2124 2011 8357 2139 2026 8358 2137 2024 8359 2136 2023 8360 2140 2027 8361 2137 2024 8362 2139 2026 8363 2134 2021 8364 2141 2028 8365 2135 2022 8366 2136 2023 8367 2138 2025 8368 2142 2029 8369 1980 1890 8370 1982 1892 8371 2143 2030 8372 2134 2021 8373 2144 2031 8374 2141 2028 8375 2136 2023 8376 2142 2029 8377 2145 2032 8378 2134 2021 8379 1984 1894 8380 2144 2031 8381 2134 2021 8382 1979 1889 8383 1984 1894 8384 2146 9 8385 2147 9 8386 2148 9 8387 2149 2033 8388 2150 2034 8389 2151 2035 8390 2152 2036 8391 2151 2035 8392 2150 2034 8393 2153 9 8394 2154 9 8395 2147 9 8396 2155 9 8397 2153 9 8398 2147 9 8399 2146 9 8400 2155 9 8401 2147 9 8402 2146 9 8403 2148 9 8404 2156 9 8405 2157 2037 8406 2158 2038 8407 2159 2039 8408 2157 2037 8409 2159 2039 8410 2160 2040 8411 2161 2041 8412 2162 2042 8413 2163 2043 8414 2164 2044 8415 2163 2043 8416 2165 2045 8417 2166 2046 8418 2163 2043 8419 2164 2044 8420 2161 2041 8421 2163 2043 8422 2166 2046 8423 2167 2047 8424 2165 2045 8425 2168 2048 8426 2164 2044 8427 2165 2045 8428 2167 2047 8429 2167 2047 8430 2168 2048 8431 2169 2049 8432 2170 2050 8433 2169 2049 8434 2171 2051 8435 2167 2047 8436 2169 2049 8437 2170 2050 8438 2172 2052 8439 2171 2051 8440 2173 2053 8441 2170 2050 8442 2171 2051 8443 2172 2052 8444 2172 2052 8445 2173 2053 8446 2174 2054 8447 2175 2055 8448 2174 2054 8449 2176 2056 8450 2172 2052 8451 2174 2054 8452 2175 2055 8453 2175 2055 8454 2176 2056 8455 2177 2057 8456 2178 2058 8457 2177 2057 8458 2179 2059 8459 2175 2055 8460 2177 2057 8461 2178 2058 8462 2178 2058 8463 2179 2059 8464 2180 2060 8465 2181 2061 8466 2180 2060 8467 2182 2062 8468 2178 2058 8469 2180 2060 8470 2181 2061 8471 2183 2063 8472 2182 2062 8473 2184 2064 8474 2181 2061 8475 2182 2062 8476 2183 2063 8477 2183 2063 8478 2184 2064 8479 2185 2065 8480 2186 2066 8481 2185 2065 8482 2187 2067 8483 2183 2063 8484 2185 2065 8485 2186 2066 8486 2188 2068 8487 2187 2067 8488 2189 2069 8489 2186 2066 8490 2187 2067 8491 2188 2068 8492 2188 2068 8493 2189 2069 8494 2190 2070 8495 2188 2068 8496 2190 2070 8497 2191 2071 8498 2192 2072 8499 2193 2073 8500 2194 2074 8501 2195 9 8502 2196 9 8503 2197 9 8504 2197 9 8505 2198 9 8506 2195 9 8507 2197 9 8508 2196 9 8509 2199 9 8510 2192 2072 8511 2194 2074 8512 2200 2075 8513 2201 2076 8514 2202 2077 8515 2203 2078 8516 2204 2079 8517 2203 2078 8518 2205 2080 8519 2204 2079 8520 2201 2076 8521 2203 2078 8522 2206 2081 8523 2205 2080 8524 2207 2082 8525 2204 2079 8526 2205 2080 8527 2206 2081 8528 2208 2083 8529 2207 2082 8530 2209 2084 8531 2206 2081 8532 2207 2082 8533 2208 2083 8534 2208 2083 8535 2209 2084 8536 2210 2085 8537 2211 2086 8538 2210 2085 8539 2212 2087 8540 2208 2083 8541 2210 2085 8542 2211 2086 8543 2213 2088 8544 2212 2087 8545 2214 2089 8546 2211 2086 8547 2212 2087 8548 2213 2088 8549 2213 2088 8550 2214 2089 8551 2215 2090 8552 2216 2091 8553 2215 2090 8554 2217 2092 8555 2213 2088 8556 2215 2090 8557 2216 2091 8558 2216 2091 8559 2217 2092 8560 2218 2093 8561 2219 2094 8562 2218 2093 8563 2220 2095 8564 2216 2091 8565 2218 2093 8566 2219 2094 8567 2219 2094 8568 2220 2095 8569 2221 2096 8570 2222 2097 8571 2221 2096 8572 2223 2098 8573 2219 2094 8574 2221 2096 8575 2222 2097 8576 2224 2099 8577 2223 2098 8578 2225 2100 8579 2222 2097 8580 2223 2098 8581 2224 2099 8582 2226 2101 8583 2225 2100 8584 2227 2102 8585 2224 2099 8586 2225 2100 8587 2226 2101 8588 2228 2103 8589 2227 2102 8590 2229 2104 8591 2226 2101 8592 2227 2102 8593 2228 2103 8594 2230 2105 8595 2231 2106 8596 2232 2107 8597 2233 2108 8598 2231 2106 8599 2230 2105 8600 2228 2103 8601 2229 2104 8602 2234 2109 8603 2235 9 8604 2236 9 8605 1974 9 8606 1991 9 8607 2235 9 8608 1974 9 8609 2235 9 8610 2237 9 8611 2236 9 8612 2235 9 8613 2238 9 8614 2237 9 8615 2140 2027 8616 2139 2026 8617 2239 2110 8618 2235 9 8619 2240 9 8620 2238 9 8621 2241 2111 8622 2239 2110 8623 2242 2112 8624 2241 2111 8625 2140 2027 8626 2239 2110 8627 2243 9 8628 2244 9 8629 2240 9 8630 2245 2113 8631 2242 2112 8632 2246 2114 8633 2235 9 8634 2243 9 8635 2240 9 8636 2245 2113 8637 2241 2111 8638 2242 2112 8639 2243 9 8640 2247 9 8641 2244 9 8642 2248 2115 8643 2246 2114 8644 2249 2116 8645 2248 2115 8646 2245 2113 8647 2246 2114 8648 2250 9 8649 2251 9 8650 2247 9 8651 2252 2117 8652 2249 2116 8653 2253 2118 8654 2243 9 8655 2250 9 8656 2247 9 8657 2252 2117 8658 2248 2115 8659 2249 2116 8660 2254 9 8661 2255 9 8662 2251 9 8663 2256 2119 8664 2253 2118 8665 2257 2120 8666 2250 9 8667 2254 9 8668 2251 9 8669 2256 2119 8670 2252 2117 8671 2253 2118 8672 2254 9 8673 2258 9 8674 2255 9 8675 2259 2121 8676 2257 2120 8677 2260 2122 8678 2261 2123 8679 2256 2119 8680 2257 2120 8681 2259 2121 8682 2261 2123 8683 2257 2120 8684 2262 9 8685 2263 9 8686 2258 9 8687 2264 2124 8688 2260 2122 8689 2265 2125 8690 2254 9 8691 2262 9 8692 2258 9 8693 2264 2124 8694 2259 2121 8695 2260 2122 8696 2262 9 8697 2266 9 8698 2263 9 8699 2267 2126 8700 2265 2125 8701 2268 2127 8702 2267 2126 8703 2264 2124 8704 2265 2125 8705 2262 9 8706 2269 9 8707 2266 9 8708 2270 2128 8709 2268 2127 8710 2271 2129 8711 2270 2128 8712 2267 2126 8713 2268 2127 8714 2272 2130 8715 2271 2129 8716 2273 2131 8717 2272 2130 8718 2270 2128 8719 2271 2129 8720 2274 2132 8721 2273 2131 8722 2275 2133 8723 2272 2130 8724 2273 2131 8725 2274 2132 8726 2276 2134 8727 2275 2133 8728 2277 2135 8729 2276 2134 8730 2274 2132 8731 2275 2133 8732 2278 2136 8733 2277 2135 8734 2279 2137 8735 2278 2136 8736 2276 2134 8737 2277 2135 8738 2280 2138 8739 2279 2137 8740 2281 2139 8741 2280 2138 8742 2278 2136 8743 2279 2137 8744 2282 2140 8745 2283 2141 8746 2284 2142 8747 2285 2143 8748 2280 2138 8749 2281 2139 8750 2282 2140 8751 2286 2144 8752 2283 2141 8753 1992 1900 8754 2287 2145 8755 1993 1901 8756 2288 2146 8757 2287 2145 8758 1992 1900 8759 2289 2147 8760 2287 2145 8761 2288 2146 8762 2290 2148 8763 2291 2149 8764 2292 2150 8765 2293 2151 8766 2294 2152 8767 2295 2153 8768 2296 2154 8769 2297 2155 8770 2291 2149 8771 2296 2154 8772 2291 2149 8773 2290 2148 8774 2290 2148 8775 2292 2150 8776 2298 2156 8777 2290 2148 8778 2298 2156 8779 2299 2157 8780 2300 2158 8781 2299 2157 8782 2301 2159 8783 2290 2148 8784 2299 2157 8785 2300 2158 8786 2300 2158 8787 2301 2159 8788 2302 2160 8789 2289 2147 8790 2302 2160 8791 2301 2159 8792 2121 2008 8793 2133 2020 8794 2303 2161 8795 2121 2008 8796 2303 2161 8797 2304 2162 8798 2305 2163 8799 2304 2162 8800 2306 2164 8801 2305 2163 8802 2121 2008 8803 2304 2162 8804 2307 2165 8805 2306 2164 8806 2308 2166 8807 2307 2165 8808 2305 2163 8809 2306 2164 8810 2307 2165 8811 2308 2166 8812 2309 2167 8813 2293 2151 8814 2309 2167 8815 2294 2152 8816 2293 2151 8817 2307 2165 8818 2309 2167 8819 2305 2163 8820 2310 2168 8821 2121 2008 8822 266 262 8823 2121 2008 8824 2310 2168 8825 2311 2169 8826 2312 2170 8827 2310 2168 8828 257 253 8829 2310 2168 8830 2312 2170 8831 2305 2163 8832 2311 2169 8833 2310 2168 8834 257 253 8835 266 262 8836 2310 2168 8837 2313 2171 8838 2314 2172 8839 2312 2170 8840 254 250 8841 2312 2170 8842 2314 2172 8843 2311 2169 8844 2313 2171 8845 2312 2170 8846 254 250 8847 257 253 8848 2312 2170 8849 2315 2173 8850 2316 2174 8851 2314 2172 8852 252 248 8853 2314 2172 8854 2316 2174 8855 2317 2175 8856 2315 2173 8857 2314 2172 8858 2313 2171 8859 2317 2175 8860 2314 2172 8861 252 248 8862 254 250 8863 2314 2172 8864 2318 2176 8865 2319 2177 8866 2316 2174 8867 249 245 8868 2316 2174 8869 2319 2177 8870 2320 2178 8871 2318 2176 8872 2316 2174 8873 2315 2173 8874 2320 2178 8875 2316 2174 8876 249 245 8877 252 248 8878 2316 2174 8879 2321 2179 8880 2322 2180 8881 2319 2177 8882 246 242 8883 2319 2177 8884 2322 2180 8885 2323 2181 8886 2321 2179 8887 2319 2177 8888 2318 2176 8889 2323 2181 8890 2319 2177 8891 246 242 8892 249 245 8893 2319 2177 8894 2324 2182 8895 2325 2183 8896 2322 2180 8897 228 224 8898 2322 2180 8899 2325 2183 8900 2321 2179 8901 2324 2182 8902 2322 2180 8903 228 224 8904 246 242 8905 2322 2180 8906 2326 2184 8907 2327 2185 8908 2325 2183 8909 223 219 8910 2325 2183 8911 2327 2185 8912 2328 2186 8913 2326 2184 8914 2325 2183 8915 2324 2182 8916 2328 2186 8917 2325 2183 8918 223 219 8919 228 224 8920 2325 2183 8921 2329 2187 8922 2330 2188 8923 2327 2185 8924 221 217 8925 2327 2185 8926 2330 2188 8927 2331 2189 8928 2329 2187 8929 2327 2185 8930 2326 2184 8931 2331 2189 8932 2327 2185 8933 221 217 8934 223 219 8935 2327 2185 8936 2332 2190 8937 2333 2191 8938 2330 2188 8939 218 214 8940 2330 2188 8941 2333 2191 8942 2329 2187 8943 2332 2190 8944 2330 2188 8945 218 214 8946 221 217 8947 2330 2188 8948 2334 2192 8949 2335 2193 8950 2333 2191 8951 215 211 8952 2333 2191 8953 2335 2193 8954 2336 2194 8955 2334 2192 8956 2333 2191 8957 2332 2190 8958 2336 2194 8959 2333 2191 8960 215 211 8961 218 214 8962 2333 2191 8963 2337 2195 8964 2338 2196 8965 2335 2193 8966 195 191 8967 2335 2193 8968 2338 2196 8969 2334 2192 8970 2337 2195 8971 2335 2193 8972 195 191 8973 215 211 8974 2335 2193 8975 2339 2197 8976 2340 2198 8977 2338 2196 8978 191 187 8979 2338 2196 8980 2340 2198 8981 2341 2199 8982 2339 2197 8983 2338 2196 8984 2337 2195 8985 2341 2199 8986 2338 2196 8987 191 187 8988 195 191 8989 2338 2196 8990 2342 2200 8991 2343 2201 8992 2340 2198 8993 188 184 8994 2340 2198 8995 2343 2201 8996 2339 2197 8997 2342 2200 8998 2340 2198 8999 188 184 9000 191 187 9001 2340 2198 9002 2344 2202 9003 2345 2203 9004 2343 2201 9005 185 181 9006 2343 2201 9007 2345 2203 9008 2342 2200 9009 2344 2202 9010 2343 2201 9011 185 181 9012 188 184 9013 2343 2201 9014 2346 2204 9015 2347 2205 9016 2345 2203 9017 182 178 9018 2345 2203 9019 2347 2205 9020 2348 2206 9021 2346 2204 9022 2345 2203 9023 2344 2202 9024 2348 2206 9025 2345 2203 9026 182 178 9027 185 181 9028 2345 2203 9029 1243 1181 9030 2349 2207 9031 2350 2208 9032 179 175 9033 182 178 9034 2347 2205 9035 171 167 9036 177 173 9037 2349 2207 9038 171 167 9039 2349 2207 9040 1243 1181 9041 2351 2209 9042 2352 2210 9043 2353 2211 9044 2354 2212 9045 1243 1181 9046 2350 2208 9047 2355 2213 9048 2356 2214 9049 2357 2215 9050 2358 2216 9051 2353 2211 9052 2359 2217 9053 2360 2218 9054 2353 2211 9055 2358 2216 9056 2351 2209 9057 2353 2211 9058 2360 2218 9059 2361 2219 9060 2359 2217 9061 2362 2220 9062 2358 2216 9063 2359 2217 9064 2361 2219 9065 2363 2221 9066 2362 2220 9067 2364 2222 9068 2361 2219 9069 2362 2220 9070 2363 2221 9071 2365 2223 9072 2364 2222 9073 2366 2224 9074 2363 2221 9075 2364 2222 9076 2365 2223 9077 2367 2225 9078 2366 2224 9079 2368 2226 9080 2365 2223 9081 2366 2224 9082 2367 2225 9083 2369 2227 9084 2368 2226 9085 2370 2228 9086 2367 2225 9087 2368 2226 9088 2369 2227 9089 2371 2229 9090 2370 2228 9091 2372 2230 9092 2369 2227 9093 2370 2228 9094 2371 2229 9095 2373 2231 9096 2372 2230 9097 2374 2232 9098 2371 2229 9099 2372 2230 9100 2373 2231 9101 2375 2233 9102 2374 2232 9103 2376 2234 9104 2373 2231 9105 2374 2232 9106 2375 2233 9107 2377 2235 9108 2376 2234 9109 2378 2236 9110 2375 2233 9111 2376 2234 9112 2377 2235 9113 2379 2237 9114 2378 2236 9115 2380 2238 9116 2377 2235 9117 2378 2236 9118 2379 2237 9119 2379 2237 9120 2380 2238 9121 2381 2239 9122 2382 2240 9123 2381 2239 9124 2383 2241 9125 2379 2237 9126 2381 2239 9127 2382 2240 9128 2384 2242 9129 2383 2241 9130 2385 2243 9131 2382 2240 9132 2383 2241 9133 2384 2242 9134 2386 2244 9135 2385 2243 9136 2387 2245 9137 2384 2242 9138 2385 2243 9139 2386 2244 9140 2388 2246 9141 2387 2245 9142 2389 2247 9143 2386 2244 9144 2387 2245 9145 2388 2246 9146 2390 2248 9147 2389 2247 9148 2391 2249 9149 2388 2246 9150 2389 2247 9151 2390 2248 9152 2392 2250 9153 2391 2249 9154 2393 2251 9155 2390 2248 9156 2391 2249 9157 2392 2250 9158 2394 2252 9159 2393 2251 9160 2395 2253 9161 2392 2250 9162 2393 2251 9163 2394 2252 9164 2396 2254 9165 2395 2253 9166 2397 2255 9167 2394 2252 9168 2395 2253 9169 2396 2254 9170 2398 2256 9171 2397 2255 9172 2399 2257 9173 2400 2258 9174 2397 2255 9175 2398 2256 9176 2396 2254 9177 2397 2255 9178 2400 2258 9179 2401 2259 9180 2399 2257 9181 2402 2260 9182 2403 2261 9183 2399 2257 9184 2401 2259 9185 2398 2256 9186 2399 2257 9187 2403 2261 9188 2404 2262 9189 2402 2260 9190 2405 2263 9191 2406 2264 9192 2402 2260 9193 2404 2262 9194 2401 2259 9195 2402 2260 9196 2406 2264 9197 2296 2154 9198 2405 2263 9199 2297 2155 9200 2404 2262 9201 2405 2263 9202 2296 2154 9203 1243 1181 9204 2407 2265 9205 1238 1176 9206 2408 2266 9207 1242 1180 9208 2409 2267 9209 2408 2266 9210 1241 1179 9211 1242 1180 9212 2410 2268 9213 2411 2269 9214 2407 2265 9215 2408 2266 9216 2409 2267 9217 2412 2270 9218 1243 1181 9219 2410 2268 9220 2407 2265 9221 2413 2271 9222 2414 2272 9223 2415 2273 9224 2416 2274 9225 2408 2266 9226 2412 2270 9227 2417 2275 9228 2416 2274 9229 2412 2270 9230 2354 2212 9231 2410 2268 9232 1243 1181 9233 2418 2276 9234 2415 2273 9235 2356 2214 9236 2413 2271 9237 2415 2273 9238 2418 2276 9239 2419 2277 9240 2356 2214 9241 2420 2278 9242 2355 2213 9243 2420 2278 9244 2356 2214 9245 2421 2279 9246 2356 2214 9247 2419 2277 9248 2418 2276 9249 2356 2214 9250 2421 2279 9251 1234 1172 9252 1231 1169 9253 2422 2280 9254 2423 2281 9255 2424 2282 9256 2425 2283 9257 2426 9 9258 2427 9 9259 2428 9 9260 2429 9 9261 2427 9 9262 2426 9 9263 2430 9 9264 2427 9 9265 2429 9 9266 2431 9 9267 2427 9 9268 2430 9 9269 2432 2284 9270 2425 2283 9271 2433 2285 9272 2434 2286 9273 2425 2283 9274 2432 2284 9275 2423 2281 9276 2425 2283 9277 2434 2286 9278 2435 9 9279 2428 9 9280 2436 9 9281 2426 9 9282 2428 9 9283 2435 9 9284 2437 9 9285 2436 9 9286 2438 9 9287 2435 9 9288 2436 9 9289 2437 9 9290 2439 9 9291 2438 9 9292 2440 9 9293 2441 2287 9294 2442 2288 9295 2416 2274 9296 2437 9 9297 2438 9 9298 2439 9 9299 2417 2275 9300 2441 2287 9301 2416 2274 9302 2443 9 9303 2440 9 9304 2444 9 9305 2445 2289 9306 2446 2290 9307 2442 2288 9308 2439 9 9309 2440 9 9310 2443 9 9311 2447 2291 9312 2445 2289 9313 2442 2288 9314 2441 2287 9315 2447 2291 9316 2442 2288 9317 2443 9 9318 2444 9 9319 2448 9 9320 2449 2292 9321 2450 2293 9322 2446 2290 9323 2445 2289 9324 2449 2292 9325 2446 2290 9326 2451 2294 9327 2452 2295 9328 2450 2293 9329 2453 2296 9330 2451 2294 9331 2450 2293 9332 2449 2292 9333 2453 2296 9334 2450 2293 9335 2454 2297 9336 2455 2298 9337 2452 2295 9338 2456 2299 9339 2454 2297 9340 2452 2295 9341 2451 2294 9342 2456 2299 9343 2452 2295 9344 2457 2300 9345 2458 2301 9346 2455 2298 9347 2454 2297 9348 2457 2300 9349 2455 2298 9350 2459 2302 9351 2460 2303 9352 2458 2301 9353 2457 2300 9354 2459 2302 9355 2458 2301 9356 2461 2304 9357 2462 2305 9358 2460 2303 9359 2463 2306 9360 2461 2304 9361 2460 2303 9362 2464 2307 9363 2463 2306 9364 2460 2303 9365 2459 2302 9366 2464 2307 9367 2460 2303 9368 2465 2308 9369 2466 2309 9370 2467 2310 9371 2468 2311 9372 2469 2312 9373 2470 2313 9374 2471 2314 9375 2465 2308 9376 2467 2310 9377 2472 2315 9378 2469 2312 9379 2468 2311 9380 2473 2316 9381 2467 2310 9382 2474 2317 9383 2471 2314 9384 2467 2310 9385 2473 2316 9386 2468 2311 9387 2470 2313 9388 2475 2318 9389 2355 2213 9390 2476 2319 9391 2477 2320 9392 2478 2321 9393 2468 2311 9394 2475 2318 9395 2355 2213 9396 2479 2322 9397 2476 2319 9398 2355 2213 9399 2477 2320 9400 2480 2323 9401 2355 2213 9402 2480 2323 9403 2481 2324 9404 2355 2213 9405 2481 2324 9406 2482 2325 9407 2355 2213 9408 2482 2325 9409 2483 2326 9410 2355 2213 9411 2483 2326 9412 2484 2327 9413 2355 2213 9414 2484 2327 9415 2420 2278 9416 1217 1155 9417 2485 2328 9418 2486 2329 9419 2487 2330 9420 1217 1155 9421 2486 2329 9422 1217 1155 9423 1215 1153 9424 2485 2328 9425 2488 2331 9426 1207 1145 9427 1210 1148 9428 2488 2331 9429 1332 1270 9430 1207 1145 9431 2489 2332 9432 1210 1148 9433 1217 1155 9434 2489 2332 9435 2488 2331 9436 1210 1148 9437 2487 2330 9438 2490 2333 9439 1217 1155 9440 2491 2334 9441 1217 1155 9442 2490 2333 9443 2491 2334 9444 2489 2332 9445 1217 1155 9446 2492 2335 9447 2468 2311 9448 2490 2333 9449 2493 2336 9450 2490 2333 9451 2468 2311 9452 2487 2330 9453 2492 2335 9454 2490 2333 9455 2494 2337 9456 2491 2334 9457 2490 2333 9458 2493 2336 9459 2494 2337 9460 2490 2333 9461 2495 2338 9462 2468 2311 9463 2478 2321 9464 2492 2335 9465 2472 2315 9466 2468 2311 9467 2495 2338 9468 2493 2336 9469 2468 2311 9470 2496 2339 9471 2495 2338 9472 2478 2321 9473 2497 2340 9474 2498 2341 9475 2479 2322 9476 2497 2340 9477 2479 2322 9478 2499 2342 9479 2355 2213 9480 2499 2342 9481 2479 2322 9482 2500 2343 9483 1333 1271 9484 2501 2344 9485 2500 2343 9486 1330 1268 9487 1333 1271 9488 2502 2345 9489 2501 2344 9490 2503 2346 9491 2502 2345 9492 2500 2343 9493 2501 2344 9494 2504 2347 9495 2503 2346 9496 2505 2348 9497 2504 2347 9498 2502 2345 9499 2503 2346 9500 2506 2349 9501 2505 2348 9502 2507 2350 9503 2506 2349 9504 2504 2347 9505 2505 2348 9506 2508 2351 9507 2507 2350 9508 2509 2352 9509 2508 2351 9510 2506 2349 9511 2507 2350 9512 2510 2353 9513 2509 2352 9514 2511 2354 9515 2510 2353 9516 2508 2351 9517 2509 2352 9518 2512 2355 9519 2511 2354 9520 2513 2356 9521 2512 2355 9522 2510 2353 9523 2511 2354 9524 2514 2357 9525 2512 2355 9526 2513 2356 9527 2515 2358 9528 2514 2357 9529 2513 2356 9530 2516 2359 9531 2517 2360 9532 1348 1286 9533 2518 2361 9534 1337 1275 9535 2519 2362 9536 1347 1285 9537 2516 2359 9538 1348 1286 9539 2518 2361 9540 1343 1281 9541 1337 1275 9542 2520 2363 9543 2521 2364 9544 2517 2360 9545 2522 2365 9546 2519 2362 9547 2523 2366 9548 2516 2359 9549 2520 2363 9550 2517 2360 9551 2522 2365 9552 2518 2361 9553 2519 2362 9554 2524 2367 9555 2525 2368 9556 2521 2364 9557 2526 2369 9558 2523 2366 9559 2527 2370 9560 2520 2363 9561 2524 2367 9562 2521 2364 9563 2526 2369 9564 2522 2365 9565 2523 2366 9566 2528 2371 9567 2529 2372 9568 2525 2368 9569 2530 2373 9570 2527 2370 9571 2531 2374 9572 2524 2367 9573 2528 2371 9574 2525 2368 9575 2530 2373 9576 2526 2369 9577 2527 2370 9578 2532 2375 9579 2533 2376 9580 2529 2372 9581 2534 2377 9582 2531 2374 9583 2535 2378 9584 2528 2371 9585 2532 2375 9586 2529 2372 9587 2534 2377 9588 2530 2373 9589 2531 2374 9590 2536 2379 9591 2537 2380 9592 2533 2376 9593 2538 2381 9594 2535 2378 9595 2539 2382 9596 2532 2375 9597 2536 2379 9598 2533 2376 9599 2538 2381 9600 2534 2377 9601 2535 2378 9602 2540 2383 9603 2541 2384 9604 2537 2380 9605 2542 2385 9606 2539 2382 9607 2543 2386 9608 2536 2379 9609 2540 2383 9610 2537 2380 9611 2542 2385 9612 2538 2381 9613 2539 2382 9614 2544 2387 9615 2545 2388 9616 2541 2384 9617 2546 2389 9618 2543 2386 9619 2547 2390 9620 2540 2383 9621 2544 2387 9622 2541 2384 9623 2546 2389 9624 2542 2385 9625 2543 2386 9626 2548 2391 9627 2549 2392 9628 2545 2388 9629 2550 2393 9630 2547 2390 9631 2551 2394 9632 2544 2387 9633 2548 2391 9634 2545 2388 9635 2550 2393 9636 2546 2389 9637 2547 2390 9638 2552 2395 9639 2553 2396 9640 2549 2392 9641 2554 2397 9642 2551 2394 9643 2555 2398 9644 2548 2391 9645 2552 2395 9646 2549 2392 9647 2554 2397 9648 2550 2393 9649 2551 2394 9650 2556 2399 9651 2557 2399 9652 2553 2396 9653 2558 2400 9654 2555 2398 9655 2559 2401 9656 2552 2395 9657 2556 2399 9658 2553 2396 9659 2558 2400 9660 2554 2397 9661 2555 2398 9662 2560 2399 9663 2561 2399 9664 2557 2399 9665 2562 2402 9666 2559 2401 9667 2563 2403 9668 2556 2399 9669 2560 2399 9670 2557 2399 9671 2562 2402 9672 2558 2400 9673 2559 2401 9674 2564 2404 9675 2563 2403 9676 2565 2405 9677 2564 2404 9678 2562 2402 9679 2563 2403 9680 2566 2406 9681 2565 2405 9682 2567 2407 9683 2566 2406 9684 2564 2404 9685 2565 2405 9686 2568 2408 9687 2567 2407 9688 2569 2409 9689 2568 2408 9690 2566 2406 9691 2567 2407 9692 2570 2410 9693 2569 2409 9694 2571 2411 9695 2572 2412 9696 2568 2408 9697 2569 2409 9698 2570 2410 9699 2572 2412 9700 2569 2409 9701 2570 2410 9702 2571 2411 9703 2573 2413 9704 2574 2414 9705 2573 2413 9706 2575 2415 9707 2574 2414 9708 2570 2410 9709 2573 2413 9710 2574 2414 9711 2575 2415 9712 2576 2416 9713 2577 2417 9714 2576 2416 9715 2578 2418 9716 2577 2417 9717 2574 2414 9718 2576 2416 9719 2577 2417 9720 2578 2418 9721 2579 2419 9722 2580 2420 9723 2579 2419 9724 2581 2421 9725 2580 2420 9726 2577 2417 9727 2579 2419 9728 2580 2420 9729 2581 2421 9730 2582 2422 9731 2583 2423 9732 2582 2422 9733 2584 2424 9734 2583 2423 9735 2580 2420 9736 2582 2422 9737 2583 2423 9738 2584 2424 9739 2585 2425 9740 2586 2426 9741 2585 2425 9742 2587 2427 9743 2586 2426 9744 2583 2423 9745 2585 2425 9746 1965 1879 9747 2587 2427 9748 2588 2428 9749 1965 1879 9750 2586 2426 9751 2587 2427 9752 1965 1879 9753 2588 2428 9754 1964 1878 9755 2289 2147 9756 2288 2146 9757 2302 2160 9758 2589 2429 9759 2590 2430 9760 2514 2357 9761 2515 2358 9762 2589 2429 9763 2514 2357 9764 2591 2431 9765 2592 2432 9766 2590 2430 9767 2589 2429 9768 2591 2431 9769 2590 2430 9770 2593 2433 9771 2594 2434 9772 2592 2432 9773 2591 2431 9774 2593 2433 9775 2592 2432 9776 2595 2435 9777 2596 2436 9778 2594 2434 9779 2593 2433 9780 2595 2435 9781 2594 2434 9782 2595 2435 9783 2597 2437 9784 2596 2436 9785 2598 2438 9786 2599 2439 9787 2597 2437 9788 2595 2435 9789 2598 2438 9790 2597 2437 9791 2600 2440 9792 2601 2441 9793 2599 2439 9794 2598 2438 9795 2600 2440 9796 2599 2439 9797 2602 2442 9798 2603 2443 9799 2601 2441 9800 2600 2440 9801 2602 2442 9802 2601 2441 9803 2604 2444 9804 2605 2445 9805 2603 2443 9806 2602 2442 9807 2604 2444 9808 2603 2443 9809 2606 2446 9810 2607 2447 9811 2605 2445 9812 2604 2444 9813 2606 2446 9814 2605 2445 9815 2608 2448 9816 2609 2449 9817 2607 2447 9818 2610 2450 9819 2608 2448 9820 2607 2447 9821 2606 2446 9822 2610 2450 9823 2607 2447 9824 2611 2451 9825 2612 2452 9826 2609 2449 9827 2608 2448 9828 2611 2451 9829 2609 2449 9830 2613 2453 9831 2614 2454 9832 2612 2452 9833 2611 2451 9834 2613 2453 9835 2612 2452 9836 2613 2453 9837 2615 2455 9838 2614 2454 9839 1358 1296 9840 1340 1278 9841 2616 2456 9842 2617 2457 9843 2616 2456 9844 2618 2458 9845 1358 1296 9846 2616 2456 9847 2617 2457 9848 2617 2457 9849 2618 2458 9850 2619 2459 9851 2620 2460 9852 2619 2459 9853 2621 2461 9854 2617 2457 9855 2619 2459 9856 2620 2460 9857 2622 2462 9858 2621 2461 9859 2623 2463 9860 2620 2460 9861 2621 2461 9862 2622 2462 9863 2622 2462 9864 2623 2463 9865 2624 2464 9866 2625 2465 9867 2624 2464 9868 2626 2466 9869 2622 2462 9870 2624 2464 9871 2625 2465 9872 2627 2467 9873 2626 2466 9874 2628 2468 9875 2625 2465 9876 2626 2466 9877 2627 2467 9878 2627 2467 9879 2628 2468 9880 2629 2469 9881 2630 2470 9882 2629 2469 9883 2631 2471 9884 2627 2467 9885 2629 2469 9886 2630 2470 9887 2632 2472 9888 2631 2471 9889 2633 2473 9890 2630 2470 9891 2631 2471 9892 2632 2472 9893 2632 2472 9894 2633 2473 9895 2634 2474 9896 2635 2475 9897 2634 2474 9898 2636 2476 9899 2632 2472 9900 2634 2474 9901 2635 2475 9902 2635 2475 9903 2636 2476 9904 2637 2477 9905 2638 2478 9906 2637 2477 9907 2639 2479 9908 2635 2475 9909 2637 2477 9910 2638 2478 9911 2638 2478 9912 2639 2479 9913 2640 2480 9914 2641 2481 9915 2640 2480 9916 2642 2482 9917 2638 2478 9918 2640 2480 9919 2641 2481 9920 2643 2483 9921 2642 2482 9922 2644 2484 9923 2641 2481 9924 2642 2482 9925 2643 2483 9926 2645 2485 9927 2644 2484 9928 2646 2486 9929 2643 2483 9930 2644 2484 9931 2645 2485 9932 2647 2487 9933 2646 2486 9934 2648 2488 9935 2645 2485 9936 2646 2486 9937 2647 2487 9938 1971 1885 9939 2648 2488 9940 2649 2489 9941 2647 2487 9942 2648 2488 9943 1971 1885 9944 1967 1881 9945 2649 2489 9946 1969 1883 9947 1971 1885 9948 2649 2489 9949 1967 1881 9950 2647 2487 9951 1786 1724 9952 1792 1730 9953 2647 2487 9954 1971 1885 9955 1786 1724 9956 2645 2485 9957 1792 1730 9958 1795 1733 9959 2645 2485 9960 2647 2487 9961 1792 1730 9962 2643 2483 9963 1795 1733 9964 1798 1736 9965 2643 2483 9966 2645 2485 9967 1795 1733 9968 2641 2481 9969 1798 1736 9970 1801 1739 9971 2641 2481 9972 2643 2483 9973 1798 1736 9974 2638 2478 9975 1801 1739 9976 1768 1706 9977 2638 2478 9978 2641 2481 9979 1801 1739 9980 2635 2475 9981 1768 1706 9982 1773 1711 9983 2635 2475 9984 2638 2478 9985 1768 1706 9986 2632 2472 9987 1773 1711 9988 1775 1713 9989 2632 2472 9990 2635 2475 9991 1773 1711 9992 2630 2470 9993 1775 1713 9994 1778 1716 9995 2630 2470 9996 2632 2472 9997 1775 1713 9998 2627 2467 9999 1778 1716 10000 1781 1719 10001 2627 2467 10002 2630 2470 10003 1778 1716 10004 2625 2465 10005 1781 1719 10006 1740 1678 10007 2625 2465 10008 2627 2467 10009 1781 1719 10010 2622 2462 10011 1740 1678 10012 1744 1682 10013 2622 2462 10014 2625 2465 10015 1740 1678 10016 2620 2460 10017 1744 1682 10018 1747 1685 10019 2620 2460 10020 2622 2462 10021 1744 1682 10022 2617 2457 10023 1747 1685 10024 1750 1688 10025 2617 2457 10026 2620 2460 10027 1747 1685 10028 1358 1296 10029 1750 1688 10030 1352 1290 10031 1358 1296 10032 2617 2457 10033 1750 1688 10034 2650 2490 10035 2651 2491 10036 2652 2492 10037 2653 2493 10038 2654 2494 10039 2655 2495 10040 2653 2493 10041 2655 2495 10042 2656 2496 10043 2657 2497 10044 2652 2492 10045 2658 2498 10046 2659 2499 10047 2650 2490 10048 2652 2492 10049 2657 2497 10050 2659 2499 10051 2652 2492 10052 2660 2500 10053 2658 2498 10054 2661 2501 10055 2662 2502 10056 2657 2497 10057 2658 2498 10058 2660 2500 10059 2662 2502 10060 2658 2498 10061 2663 2503 10062 2661 2501 10063 2664 2504 10064 2663 2503 10065 2660 2500 10066 2661 2501 10067 2665 2505 10068 2664 2504 10069 2666 2506 10070 2665 2505 10071 2663 2503 10072 2664 2504 10073 2667 2507 10074 2666 2506 10075 2668 2508 10076 2667 2507 10077 2665 2505 10078 2666 2506 10079 2669 2509 10080 2668 2508 10081 2670 2510 10082 2669 2509 10083 2667 2507 10084 2668 2508 10085 2671 2511 10086 2670 2510 10087 2672 2512 10088 2671 2511 10089 2669 2509 10090 2670 2510 10091 2673 2513 10092 2672 2512 10093 2674 2514 10094 2673 2513 10095 2671 2511 10096 2672 2512 10097 2675 2515 10098 2674 2514 10099 2676 2516 10100 2675 2515 10101 2673 2513 10102 2674 2514 10103 2677 2517 10104 2676 2516 10105 2678 2518 10106 2677 2517 10107 2675 2515 10108 2676 2516 10109 2679 2519 10110 2678 2518 10111 2680 2520 10112 2679 2519 10113 2677 2517 10114 2678 2518 10115 2681 2521 10116 2680 2520 10117 2682 2522 10118 2681 2521 10119 2679 2519 10120 2680 2520 10121 2683 2523 10122 2682 2522 10123 2684 2524 10124 2683 2523 10125 2681 2521 10126 2682 2522 10127 2685 2525 10128 2684 2524 10129 2686 2526 10130 2685 2525 10131 2683 2523 10132 2684 2524 10133 2687 2527 10134 2686 2526 10135 2688 2528 10136 2687 2527 10137 2685 2525 10138 2686 2526 10139 2689 2529 10140 2688 2528 10141 2690 2530 10142 2689 2529 10143 2687 2527 10144 2688 2528 10145 2691 2531 10146 2690 2530 10147 2692 2532 10148 2691 2531 10149 2689 2529 10150 2690 2530 10151 2693 2533 10152 2692 2532 10153 2694 2534 10154 2693 2533 10155 2691 2531 10156 2692 2532 10157 2695 2535 10158 2694 2534 10159 2696 2536 10160 2695 2535 10161 2693 2533 10162 2694 2534 10163 2697 2537 10164 2696 2536 10165 2698 2538 10166 2697 2537 10167 2695 2535 10168 2696 2536 10169 2697 2537 10170 2698 2538 10171 2699 2539 10172 2700 2540 10173 2699 2539 10174 2701 2541 10175 2700 2540 10176 2697 2537 10177 2699 2539 10178 2700 2540 10179 2701 2541 10180 2702 2542 10181 2703 2543 10182 2704 2544 10183 2705 2545 10184 2706 2546 10185 2700 2540 10186 2702 2542 10187 2707 2547 10188 2705 2545 10189 2708 2548 10190 2709 2549 10191 2703 2543 10192 2705 2545 10193 2707 2547 10194 2709 2549 10195 2705 2545 10196 2710 2550 10197 2708 2548 10198 2711 2551 10199 2712 2552 10200 2707 2547 10201 2708 2548 10202 2710 2550 10203 2712 2552 10204 2708 2548 10205 2713 2553 10206 2711 2551 10207 2714 2554 10208 2713 2553 10209 2710 2550 10210 2711 2551 10211 2715 2555 10212 2714 2554 10213 2716 2556 10214 2715 2555 10215 2713 2553 10216 2714 2554 10217 2717 2557 10218 2716 2556 10219 2718 2558 10220 2717 2557 10221 2715 2555 10222 2716 2556 10223 2719 2559 10224 2718 2558 10225 2720 2560 10226 2719 2559 10227 2717 2557 10228 2718 2558 10229 2721 2561 10230 2720 2560 10231 2722 2562 10232 2721 2561 10233 2719 2559 10234 2720 2560 10235 2723 2563 10236 2722 2562 10237 2724 2564 10238 2723 2563 10239 2721 2561 10240 2722 2562 10241 2725 2565 10242 2724 2564 10243 2726 2566 10244 2725 2565 10245 2723 2563 10246 2724 2564 10247 2727 2567 10248 2726 2566 10249 2728 2568 10250 2727 2567 10251 2725 2565 10252 2726 2566 10253 2729 2569 10254 2728 2568 10255 2730 2570 10256 2729 2569 10257 2727 2567 10258 2728 2568 10259 2731 2571 10260 2730 2570 10261 2732 2572 10262 2731 2571 10263 2729 2569 10264 2730 2570 10265 2733 2573 10266 2732 2572 10267 2734 2574 10268 2733 2573 10269 2731 2571 10270 2732 2572 10271 2735 2575 10272 2734 2574 10273 2736 2576 10274 2735 2575 10275 2733 2573 10276 2734 2574 10277 2737 2577 10278 2736 2576 10279 2738 2578 10280 2737 2577 10281 2735 2575 10282 2736 2576 10283 2739 2579 10284 2738 2578 10285 2740 2580 10286 2739 2579 10287 2737 2577 10288 2738 2578 10289 2741 2581 10290 2740 2580 10291 2742 2582 10292 2741 2581 10293 2739 2579 10294 2740 2580 10295 2743 2583 10296 2742 2582 10297 2744 2584 10298 2743 2583 10299 2741 2581 10300 2742 2582 10301 2745 2585 10302 2744 2584 10303 2746 2586 10304 2745 2585 10305 2743 2583 10306 2744 2584 10307 2747 2587 10308 2746 2586 10309 2748 2588 10310 2747 2587 10311 2745 2585 10312 2746 2586 10313 2747 2587 10314 2748 2588 10315 2749 2589 10316 2653 2493 10317 2749 2589 10318 2654 2494 10319 2653 2493 10320 2747 2587 10321 2749 2589 10322 2750 1068 10323 2751 1068 10324 2752 1068 10325 2750 1068 10326 2752 1068 10327 2753 1068 10328 2750 1068 10329 2753 1068 10330 2754 1068 10331 2755 1068 10332 2754 1068 10333 2756 1068 10334 2750 1068 10335 2754 1068 10336 2755 1068 10337 2757 1068 10338 2756 1068 10339 2758 1068 10340 2755 1068 10341 2756 1068 10342 2757 1068 10343 2759 1068 10344 2758 1068 10345 2760 1068 10346 2757 1068 10347 2758 1068 10348 2759 1068 10349 2761 1068 10350 2760 1068 10351 2762 1068 10352 2759 1068 10353 2760 1068 10354 2761 1068 10355 2763 2590 10356 2762 1068 10357 2764 2591 10358 2761 1068 10359 2762 1068 10360 2763 2590 10361 2765 2592 10362 2764 2591 10363 2766 2593 10364 2763 2590 10365 2764 2591 10366 2765 2592 10367 2767 2594 10368 2766 2593 10369 2768 2595 10370 2765 2592 10371 2766 2593 10372 2767 2594 10373 2769 2596 10374 2768 2595 10375 2770 2597 10376 2767 2594 10377 2768 2595 10378 2769 2596 10379 2771 2598 10380 2770 2597 10381 2772 2599 10382 2769 2596 10383 2770 2597 10384 2771 2598 10385 2773 2600 10386 2772 2599 10387 2774 2601 10388 2771 2598 10389 2772 2599 10390 2773 2600 10391 2775 2602 10392 2774 2601 10393 2776 2603 10394 2773 2600 10395 2774 2601 10396 2775 2602 10397 2777 2604 10398 2776 2603 10399 2778 2605 10400 2775 2602 10401 2776 2603 10402 2777 2604 10403 2779 2606 10404 2778 2605 10405 2780 2607 10406 2777 2604 10407 2778 2605 10408 2779 2606 10409 2781 2608 10410 2780 2607 10411 2782 2609 10412 2779 2606 10413 2780 2607 10414 2781 2608 10415 2783 2610 10416 2782 2609 10417 2784 2611 10418 2781 2608 10419 2782 2609 10420 2783 2610 10421 2785 1068 10422 2784 2611 10423 2786 1068 10424 2783 2610 10425 2784 2611 10426 2785 1068 10427 2787 1068 10428 2786 1068 10429 2788 1068 10430 2785 1068 10431 2786 1068 10432 2787 1068 10433 2789 1068 10434 2788 1068 10435 2790 1068 10436 2787 1068 10437 2788 1068 10438 2789 1068 10439 2791 1068 10440 2790 1068 10441 2792 1068 10442 2789 1068 10443 2790 1068 10444 2791 1068 10445 2793 1068 10446 2792 1068 10447 2794 1068 10448 2791 1068 10449 2792 1068 10450 2793 1068 10451 2795 1068 10452 2794 1068 10453 2796 1068 10454 2797 1068 10455 2794 1068 10456 2795 1068 10457 2793 1068 10458 2794 1068 10459 2797 1068 10460 2098 9 10461 2798 9 10462 831 9 10463 2098 9 10464 2799 9 10465 2798 9 10466 2098 9 10467 2800 9 10468 2799 9 10469 2801 9 10470 2802 9 10471 2800 9 10472 2098 9 10473 2801 9 10474 2800 9 10475 2803 9 10476 2804 9 10477 2802 9 10478 2801 9 10479 2803 9 10480 2802 9 10481 2805 9 10482 2806 9 10483 2804 9 10484 2803 9 10485 2805 9 10486 2804 9 10487 2807 9 10488 2808 9 10489 2806 9 10490 2805 9 10491 2807 9 10492 2806 9 10493 2809 9 10494 2810 9 10495 2154 9 10496 2153 9 10497 2809 9 10498 2154 9 10499 2811 9 10500 2812 9 10501 2810 9 10502 2809 9 10503 2811 9 10504 2810 9 10505 2813 9 10506 2814 9 10507 2812 9 10508 2811 9 10509 2813 9 10510 2812 9 10511 2815 9 10512 2816 9 10513 2814 9 10514 2813 9 10515 2815 9 10516 2814 9 10517 2815 9 10518 2817 9 10519 2816 9 10520 2818 9 10521 2197 9 10522 2199 9 10523 2819 9 10524 2818 9 10525 2199 9 10526 2820 9 10527 2819 9 10528 2199 9 10529 2821 9 10530 2820 9 10531 2199 9 10532 2821 9 10533 2822 9 10534 2820 9 10535 2823 9 10536 2824 9 10537 2822 9 10538 2821 9 10539 2823 9 10540 2822 9 10541 2825 9 10542 2826 9 10543 2824 9 10544 2823 9 10545 2825 9 10546 2824 9 10547 2827 9 10548 2828 9 10549 2826 9 10550 2825 9 10551 2827 9 10552 2826 9 10553 585 9 10554 2829 9 10555 538 9 10556 585 9 10557 2830 9 10558 2829 9 10559 585 9 10560 2831 9 10561 2830 9 10562 2832 9 10563 2833 9 10564 2831 9 10565 2834 9 10566 2832 9 10567 2831 9 10568 585 9 10569 2834 9 10570 2831 9 10571 2835 9 10572 2836 9 10573 2833 9 10574 2837 9 10575 2835 9 10576 2833 9 10577 2832 9 10578 2837 9 10579 2833 9 10580 2838 9 10581 2839 9 10582 2836 9 10583 2840 9 10584 2838 9 10585 2836 9 10586 2835 9 10587 2840 9 10588 2836 9 10589 2841 9 10590 2842 9 10591 2839 9 10592 2838 9 10593 2841 9 10594 2839 9 10595 2843 9 10596 2844 9 10597 1160 9 10598 1159 9 10599 2843 9 10600 1160 9 10601 2845 9 10602 2846 9 10603 2844 9 10604 2843 9 10605 2845 9 10606 2844 9 10607 2847 9 10608 2848 9 10609 2846 9 10610 2845 9 10611 2847 9 10612 2846 9 10613 2849 9 10614 2850 9 10615 1106 9 10616 1104 9 10617 2849 9 10618 1106 9 10619 2849 9 10620 2851 9 10621 2850 9 10622 2852 9 10623 2853 9 10624 2851 9 10625 2849 9 10626 2852 9 10627 2851 9 10628 2854 9 10629 2855 9 10630 2853 9 10631 2852 9 10632 2854 9 10633 2853 9 10634 2856 9 10635 2857 9 10636 2855 9 10637 2854 9 10638 2856 9 10639 2855 9 10640 2856 9 10641 2858 9 10642 2857 9 10643 2859 9 10644 2860 9 10645 2861 9 10646 2862 2612 10647 2861 9 10648 2863 2613 10649 2859 9 10650 2861 9 10651 2862 2612 10652 2864 2614 10653 2863 2613 10654 2865 2615 10655 2862 2612 10656 2863 2613 10657 2864 2614 10658 2866 9 10659 2865 2615 10660 2867 9 10661 2864 2614 10662 2865 2615 10663 2866 9 10664 2868 2616 10665 2867 9 10666 2869 2617 10667 2866 9 10668 2867 9 10669 2868 2616 10670 2870 2618 10671 2869 2617 10672 2871 9 10673 2868 2616 10674 2869 2617 10675 2870 2618 10676 2872 9 10677 2871 9 10678 2873 2619 10679 2870 2618 10680 2871 9 10681 2872 9 10682 2874 2620 10683 2873 2619 10684 2875 2621 10685 2872 9 10686 2873 2619 10687 2874 2620 10688 2876 9 10689 2875 2621 10690 2877 9 10691 2874 2620 10692 2875 2621 10693 2876 9 10694 2878 9 10695 2877 9 10696 2879 9 10697 2876 9 10698 2877 9 10699 2878 9 10700 2880 2622 10701 2879 9 10702 2881 2623 10703 2878 9 10704 2879 9 10705 2880 2622 10706 971 946 10707 2881 2623 10708 972 947 10709 2880 2622 10710 2881 2623 10711 971 946 10712 889 9 10713 972 947 10714 890 9 10715

-
-
-
-
- - - - - 7.54969e-11 4.37108e-11 9.99987e-4 0 0 9.99987e-4 -4.37108e-11 -0.9174 -9.99987e-4 0 7.54969e-11 0 0 0 0 1 - - - - - - - - - - - - - -
diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl deleted file mode 100644 index 4444aa42c7e156a8999386cf27ff8d0771d0c421..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10284 zcmb7~d303e8OC2yWl>Xwpb}Y(9F~MYOhOQmxpPScg0fkl#iFuQP=pErB0-`dg;InH zib@e#0t%-t5FnsJojcdM;6Wi8trZYN*~Adp1r1xD_s*Tn^G*4uIVWd^yx;HLzvX_H z9#itiPb?TUGUcI(;~!1=&7Ve%8#!uXhwO~bT~bmfJ@&_x%ryDGezsxs=M_c4jvGsZ zFCHIbTdOw)zPWmlwWP3_rHb^swK~UoV0787yQ&&niA~1f@6{mMUxwgO)1NQsdhDxI z%jq%pGtOuCS6k6T+B)K8Y| zd8OKmqi62j*8ZBCt>x!BS~bHO!mD?oTeEu&h~w*Xt)Xq(Sl!a91GgW|v)&!o!fLtu zP=IZV90YM22>oOU+cRzG$Se?t@yQal$C^YIAxG-fXUG{#*sC1WdOT|W#Eh2fMYKCI zL4-iCM7u-tRu$QZ(H)~pu^sZdPrLbun!cTI;SLkTWB4w$Y+dgY3+r!Pej@0};nw z5S@L3C2e*d$nsZ)IIliJ9c~4I{&IN~(_0F@4n<=UDFdN>wFCr9ZeP7Iq&7+mn>nmW z1YPc?gV4{HAk|TKVl)%139A@Jb^vhC0WAuOdFVkuFmtb$TCaVE6f`wAM^YVP4<_2Gs+{5M`l#51hdx5 z^verN%UP4Rmbd}fScYy{?$;w5Gm8n+Mk%~%2ci%}dU>96CFXfj-B4isyzb6$%=49J z_61mzxB7Tq?F7NPm^O*XHdx~7C$F5m8}OtK|)+L%PGIKGoC8UsL6M|1)+tk^LZYLFh`&Hdrrf5;^L7wKvWN z>t#(Md;B@5E4D`O&s2*?F^%{7AB=yKeb>K6W8$4!|E@nJUeqk%eTjFU$oLo$ z+sSx0FjvtCQ(}kU6-#)H;*}_71H?v_@GRoF5+n2*OSlu`GooWl>?ejc&S42>;qsBs z8u~&GOE@O>R`rWqx-`wpE=$-$wjCkVtLjxxZeSZsn?$$7lHl@_J^V-dm_JJbVE>sL9m3+3>_-6t!anrSPKVtKzye`{2Ig*5G*-5E6=*( zp+kY}q0Jq(Em8-ge}&(PaW4O!at zp7%O9*WUG@6@Itvx))zfMHXV3M6`Np<1yG^T}+$A3J`ZBmV_sP(0V7;T^ovIH>Q{E zi7W$=3*vDQU%{)sLzcdyUR5Jk2@f3#bw;jOlgP^;(m-ehSr^kLq1nZ+tGR+l+KG;O z#iQ7s$dw?@AIWg1g79nLXl?gBdMNPDyga8ox4FZbu;ZZSjbKA7$hw#|2|LoeuI6g! z`aN05q~{fnVtXPjLA-KuoU6HFf=4xezbw!%^KR#k_cPFmy+I(u?gS7wcj^?V**(bF zbv)AMm(P`!GnM*)aTc$DmS zB9CHwA{Rhl4!T8g1dnR*(JhX(prLcqu}oz5Ef51i+^1emv7NF()gd|9&KXP$S z5W09@Ylm%%Tm*sM@+!!>m^KN_K{p4{Ydu)PHoCMP>9ko`QQl%sYk0K;#Qh*Na+YX+ zJ-zDna_xN9B%-xI6@!H!cofqU5Yu;A2Lk61leaRsSs-*}U`Z!rx?b&y8nY+T08!Uq zj;L2Ds6~dq8!*9|L|TE^4Wc-X;8FJ?>njIU2NIBV+)Vg3bT{DV0X~JZ?FjMnWo)qC zrjeRk&Agf?!NxHVYJ(+g&$Q7Uwa`^gv&(xQk75r+I)l)aG#>;%rSJ~NnndzJ%mwiw z2-d~4N$9^KKP4`EqJPshJ+f-^uD!o_TBj(%yCv^9N=A1gk)Mh$y%{575?*(CwTq06 z5-j1hgl8~Luf@}9ZLowpoO{~yisFd%D0gCfMxvgXx#BFCk*_{d+%XylOE@O>7G5PU z%ZU;!Vc$)!a<>oI7$w*S(+EooQEBekbpx!cl9HW1of911qj>KU*#{yY zL^24L@LoHitk6(BH}modJmBr=&%JBlE`MQ#}!xwqU;ZDbnfv2i@xitq5m=sJv~u z_t!cgP7Uwn^uT()3j}O9F&nb0zMa-G&(4T>WofSXeunRWL@IaIw=+S!0fHrbf91#L zX%hLQu&=!(?|S!^90%XeMdJ7X#N!}X;>Y3XH6tH6qB8jSw<&I;QE4{f z2>2DWP!G$mhn3vP3ba9Oe)RgQQ@<188OYUjAfU_fd)GqELw?Pz+_JNw?dXy!k3c87 z=&K;QJxXXC7W&G|Ci*o>1R}&2L%P@pN9P5<8JT7ySC-}jT@v-mLYG*>@T-6Sr)MJ! z{S6+;3vQY-!Dfl?yA|`orIBK)tI zSDr3EZ~iP|uiioA-)~ED%VJ)61kWgwZuNO{>)cw~Rj+sy&tQ|#`BDFoys*v>mhfDO z_{8(WUjJ5DE64<|3?}W*+OW=A9>p`*B(NLUjR&m=VmAo#8pVCgw8*pY=9=wE_K_yt zf;@_8Uin0dK(q#tlH4uGZ({g84r>xA_KD-L!Md0>3GAFMx+Ityi9>fUZ>_yd$9OBB z$mD_|uMm~42XxD!p{%+C65O3OUA5MJ?K#2v%5$f(ha!+Tnf zcPGOuCbTo6dpOe~<2HXB@=pLk9>tw#63vp6>>lfEcYegH+CA0JsGa~UrbTqNCT&l0 z4{6P57xruJWr1n$l%aj4r;KP{d84?O{)cdHh;(8Y5fb`ICZn;#y5 z`JuV0J#(VNyQJLkMh0pPEIDFC*(&#=$V>FG0it@ct;Q7w;&pW z;Cnc}9b`>-e-7dW5bZ#)E~ZUl$mphC9>umrPEI-(?tvX=9pd17 z7`~t3xgwI*??kW|XHk8Q;!foIGQN`&$@GaEL9m3My!?7N`jjEk9mFiyXb?y6D7Gzf zQ^bbd0t9yk-&6C`i%2^Vg*dk>!4mEa)`XS%^XATZoB*_Uc{SjBIKH35o6*YVj-DBm zUn;oWa)CW+$9{7$WHWbJ)D+ypm(`nx!d{PFGBohbY6HD2$pak zn_lURIs-yy6cap(ZHpupoD1jRi3O){mv6jy*7~%!cj>C?yAn@!Q-3Pt(9KEa0hTeIHHHkFEuGVLr zZ5Lyu=C|zp_T7x520Km@oMdoj2=kj /dev/null && pwd)" -else - _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_bash_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh script of this package -_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/package.sh" - -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts -COLCON_CURRENT_PREFIX="$_colcon_package_bash_COLCON_CURRENT_PREFIX" - -# source bash hooks -_colcon_package_bash_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.bash" - -unset COLCON_CURRENT_PREFIX - -unset _colcon_package_bash_source_script -unset _colcon_package_bash_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv deleted file mode 100644 index 760f04466e..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv +++ /dev/null @@ -1,8 +0,0 @@ -source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1 -source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv -source;share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh -source;share/moveit_resources_prbt_support/local_setup.bash -source;share/moveit_resources_prbt_support/local_setup.dsv -source;share/moveit_resources_prbt_support/local_setup.ps1 -source;share/moveit_resources_prbt_support/local_setup.sh -source;share/moveit_resources_prbt_support/local_setup.zsh diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 deleted file mode 100644 index 356c3c4dda..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1 +++ /dev/null @@ -1,116 +0,0 @@ -# generated from colcon_powershell/shell/template/package.ps1.em - -# function to append a value to a variable -# which uses colons as separators -# duplicates as well as leading separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_append_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - $_duplicate="" - # start with no values - $_all_values="" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -eq $_value) { - $_duplicate="1" - } - if ($_all_values) { - $_all_values="${_all_values};$_" - } else { - $_all_values="$_" - } - } - } - } - # append only non-duplicates - if (!$_duplicate) { - # avoid leading separator - if ($_all_values) { - $_all_values="${_all_values};${_value}" - } else { - $_all_values="${_value}" - } - } - - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -function colcon_prepend_unique_value { - param ( - $_listname, - $_value - ) - - # get values from variable - if (Test-Path Env:$_listname) { - $_values=(Get-Item env:$_listname).Value - } else { - $_values="" - } - # start with the new value - $_all_values="$_value" - # iterate over existing values in the variable - if ($_values) { - $_values.Split(";") | ForEach { - # not an empty string - if ($_) { - # not a duplicate of _value - if ($_ -ne $_value) { - # keep non-duplicate values - $_all_values="${_all_values};$_" - } - } - } - } - # export the updated variable - Set-Item env:\$_listname -Value "$_all_values" -} - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -function colcon_package_source_powershell_script { - param ( - $_colcon_package_source_powershell_script - ) - # source script with conditional trace output - if (Test-Path $_colcon_package_source_powershell_script) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_package_source_powershell_script'" - } - . "$_colcon_package_source_powershell_script" - } else { - Write-Error "not found: '$_colcon_package_source_powershell_script'" - } -} - - -# a powershell script is able to determine its own path -# the prefix is two levels up from the package specific share directory -$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName - -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1" -colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/moveit_resources_prbt_support/local_setup.ps1" - -Remove-Item Env:\COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh deleted file mode 100644 index 88c8fe8227..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh +++ /dev/null @@ -1,87 +0,0 @@ -# generated from colcon_core/shell/template/package.sh.em - -# This script extends the environment for this package. - -# function to prepend a value to a variable -# which uses colons as separators -# duplicates as well as trailing separators are avoided -# first argument: the name of the result variable -# second argument: the value to be prepended -_colcon_prepend_unique_value() { - # arguments - _listname="$1" - _value="$2" - - # get values from variable - eval _values=\"\$$_listname\" - # backup the field separator - _colcon_prepend_unique_value_IFS=$IFS - IFS=":" - # start with the new value - _all_values="$_value" - # workaround SH_WORD_SPLIT not being set in zsh - if [ "$(command -v colcon_zsh_convert_to_array)" ]; then - colcon_zsh_convert_to_array _values - fi - # iterate over existing values in the variable - for _item in $_values; do - # ignore empty strings - if [ -z "$_item" ]; then - continue - fi - # ignore duplicates of _value - if [ "$_item" = "$_value" ]; then - continue - fi - # keep non-duplicate values - _all_values="$_all_values:$_item" - done - unset _item - # restore the field separator - IFS=$_colcon_prepend_unique_value_IFS - unset _colcon_prepend_unique_value_IFS - # export the updated variable - eval export $_listname=\"$_all_values\" - unset _all_values - unset _values - - unset _value - unset _listname -} - -# since a plain shell script can't determine its own path when being sourced -# either use the provided COLCON_CURRENT_PREFIX -# or fall back to the build time prefix (if it exists) -_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support" -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then - echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 - unset _colcon_package_sh_COLCON_CURRENT_PREFIX - return 1 - fi - COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX" -fi -unset _colcon_package_sh_COLCON_CURRENT_PREFIX - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo "# . \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source sh hooks -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh" -_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.sh" - -unset _colcon_package_sh_source_script -unset COLCON_CURRENT_PREFIX - -# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml deleted file mode 100644 index 4e77f0194c..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml +++ /dev/null @@ -1,25 +0,0 @@ - - moveit_resources_prbt_support - 2.5.1 - Mechanical, kinematic and visual description - of the Pilz light weight arm PRBT. - - Alexander Gutenkunst - Christian Henkel - Hagen Slusarek - Immanuel Martini - - Apache 2.0 - - http://moveit.ros.org - https://github.com/ros-planning/moveit-resources/issues - https://github.com/ros-planning/moveit-resources - - ament_cmake - - xacro - - - ament_cmake - - diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh deleted file mode 100644 index 49f14e0f61..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh +++ /dev/null @@ -1,50 +0,0 @@ -# generated from colcon_zsh/shell/template/package.zsh.em - -# This script extends the environment for this package. - -# a zsh script is able to determine its own path if necessary -if [ -z "$COLCON_CURRENT_PREFIX" ]; then - # the prefix is two levels up from the package specific share directory - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)" -else - _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -# additional arguments: arguments to the script -_colcon_package_zsh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$@" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# function to convert array-like strings into arrays -# to workaround SH_WORD_SPLIT not being set -colcon_zsh_convert_to_array() { - local _listname=$1 - local _dollar="$" - local _split="{=" - local _to_array="(\"$_dollar$_split$_listname}\")" - eval $_listname=$_to_array -} - -# source sh script of this package -_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/package.sh" -unset convert_zsh_to_array - -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced scripts -COLCON_CURRENT_PREFIX="$_colcon_package_zsh_COLCON_CURRENT_PREFIX" - -# source zsh hooks -_colcon_package_zsh_source_script "$COLCON_CURRENT_PREFIX/share/moveit_resources_prbt_support/local_setup.zsh" - -unset COLCON_CURRENT_PREFIX - -unset _colcon_package_zsh_source_script -unset _colcon_package_zsh_COLCON_CURRENT_PREFIX diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro deleted file mode 100644 index c76e60e75f..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - fake_components/GenericSystem - ${fake_sensor_commands} - 0.0 - - - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_1']} - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_2']} - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_3']} - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_4']} - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_5']} - - - - -2.96706 - 2.96706 - - - -3.15 - 3.15 - - - - - ${initial_positions['joint_6']} - - - - diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro deleted file mode 100644 index 6654dd97d7..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro +++ /dev/null @@ -1,73 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro deleted file mode 100644 index 82d9ff13bc..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro +++ /dev/null @@ -1,465 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - - - - - prbt - gazebo_ros_control/DefaultRobotHWSim - false - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_1 - ${prefix}joint_1 - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_2 - ${prefix}joint_2 - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_3 - ${prefix}joint_3 - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_4 - ${prefix}joint_4 - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_5 - ${prefix}joint_5 - - - - - true - - - - - 100.0 - prbt/ft_sensor/joint_6 - ${prefix}joint_6 - - - - - - diff --git a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro b/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro deleted file mode 100644 index 63236f59ab..0000000000 --- a/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/install/setup.bash b/install/setup.bash deleted file mode 100644 index 4c55244159..0000000000 --- a/install/setup.bash +++ /dev/null @@ -1,31 +0,0 @@ -# generated from colcon_bash/shell/template/prefix_chain.bash.em - -# This script extends the environment with the environment of other prefix -# paths which were sourced when this file was generated as well as all packages -# contained in this prefix path. - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_chain_bash_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source chained prefixes -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script -COLCON_CURRENT_PREFIX="/opt/ros/humble" -_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash" - -# source this prefix -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script -COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)" -_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash" - -unset COLCON_CURRENT_PREFIX -unset _colcon_prefix_chain_bash_source_script diff --git a/install/setup.ps1 b/install/setup.ps1 deleted file mode 100644 index 558e9b9e62..0000000000 --- a/install/setup.ps1 +++ /dev/null @@ -1,29 +0,0 @@ -# generated from colcon_powershell/shell/template/prefix_chain.ps1.em - -# This script extends the environment with the environment of other prefix -# paths which were sourced when this file was generated as well as all packages -# contained in this prefix path. - -# function to source another script with conditional trace output -# first argument: the path of the script -function _colcon_prefix_chain_powershell_source_script { - param ( - $_colcon_prefix_chain_powershell_source_script_param - ) - # source script with conditional trace output - if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) { - if ($env:COLCON_TRACE) { - echo ". '$_colcon_prefix_chain_powershell_source_script_param'" - } - . "$_colcon_prefix_chain_powershell_source_script_param" - } else { - Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'" - } -} - -# source chained prefixes -_colcon_prefix_chain_powershell_source_script "/opt/ros/humble\local_setup.ps1" - -# source this prefix -$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent) -_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1" diff --git a/install/setup.sh b/install/setup.sh deleted file mode 100644 index 65cd424cec..0000000000 --- a/install/setup.sh +++ /dev/null @@ -1,45 +0,0 @@ -# generated from colcon_core/shell/template/prefix_chain.sh.em - -# This script extends the environment with the environment of other prefix -# paths which were sourced when this file was generated as well as all packages -# contained in this prefix path. - -# since a plain shell script can't determine its own path when being sourced -# either use the provided COLCON_CURRENT_PREFIX -# or fall back to the build time prefix (if it exists) -_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/henry/ws_moveit2/src/moveit2/install -if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then - _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" -elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then - echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2 - unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX - return 1 -fi - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_chain_sh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo "# . \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source chained prefixes -# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script -COLCON_CURRENT_PREFIX="/opt/ros/humble" -_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh" - - -# source this prefix -# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script -COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" -_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh" - -unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX -unset _colcon_prefix_chain_sh_source_script -unset COLCON_CURRENT_PREFIX diff --git a/install/setup.zsh b/install/setup.zsh deleted file mode 100644 index 990d17190a..0000000000 --- a/install/setup.zsh +++ /dev/null @@ -1,31 +0,0 @@ -# generated from colcon_zsh/shell/template/prefix_chain.zsh.em - -# This script extends the environment with the environment of other prefix -# paths which were sourced when this file was generated as well as all packages -# contained in this prefix path. - -# function to source another script with conditional trace output -# first argument: the path of the script -_colcon_prefix_chain_zsh_source_script() { - if [ -f "$1" ]; then - if [ -n "$COLCON_TRACE" ]; then - echo ". \"$1\"" - fi - . "$1" - else - echo "not found: \"$1\"" 1>&2 - fi -} - -# source chained prefixes -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script -COLCON_CURRENT_PREFIX="/opt/ros/humble" -_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh" - -# source this prefix -# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script -COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)" -_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh" - -unset COLCON_CURRENT_PREFIX -unset _colcon_prefix_chain_zsh_source_script diff --git a/log/COLCON_IGNORE b/log/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/log/build_2022-06-08_12-52-32/events.log b/log/build_2022-06-08_12-52-32/events.log deleted file mode 100644 index 41ae65df06..0000000000 --- a/log/build_2022-06-08_12-52-32/events.log +++ /dev/null @@ -1,313 +0,0 @@ -[0.000000] (-) TimerEvent: {} -[0.000915] (moveit_common) JobQueued: {'identifier': 'moveit_common', 'dependencies': OrderedDict()} -[0.000949] (moveit_configs_utils) JobQueued: {'identifier': 'moveit_configs_utils', 'dependencies': OrderedDict()} -[0.000964] (moveit_resources_prbt_support) JobQueued: {'identifier': 'moveit_resources_prbt_support', 'dependencies': OrderedDict()} -[0.000975] (moveit_core) JobQueued: {'identifier': 'moveit_core', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common')])} -[0.000989] (chomp_motion_planner) JobQueued: {'identifier': 'chomp_motion_planner', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} -[0.001002] (moveit_resources_prbt_ikfast_manipulator_plugin) JobQueued: {'identifier': 'moveit_resources_prbt_ikfast_manipulator_plugin', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} -[0.001014] (moveit_ros_occupancy_map_monitor) JobQueued: {'identifier': 'moveit_ros_occupancy_map_monitor', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} -[0.001026] (moveit_simple_controller_manager) JobQueued: {'identifier': 'moveit_simple_controller_manager', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} -[0.001038] (pilz_industrial_motion_planner_testutils) JobQueued: {'identifier': 'pilz_industrial_motion_planner_testutils', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core')])} -[0.001049] (moveit_chomp_optimizer_adapter) JobQueued: {'identifier': 'moveit_chomp_optimizer_adapter', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('chomp_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner')])} -[0.001061] (moveit_planners_chomp) JobQueued: {'identifier': 'moveit_planners_chomp', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('chomp_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner')])} -[0.001072] (moveit_plugins) JobQueued: {'identifier': 'moveit_plugins', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager')])} -[0.001084] (moveit_ros_control_interface) JobQueued: {'identifier': 'moveit_ros_control_interface', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager')])} -[0.001095] (moveit_ros_planning) JobQueued: {'identifier': 'moveit_ros_planning', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor')])} -[0.001106] (moveit_kinematics) JobQueued: {'identifier': 'moveit_kinematics', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} -[0.001211] (moveit_planners_ompl) JobQueued: {'identifier': 'moveit_planners_ompl', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} -[0.001225] (moveit_ros_perception) JobQueued: {'identifier': 'moveit_ros_perception', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} -[0.001236] (moveit_ros_robot_interaction) JobQueued: {'identifier': 'moveit_ros_robot_interaction', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} -[0.001249] (moveit_ros_warehouse) JobQueued: {'identifier': 'moveit_ros_warehouse', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning')])} -[0.001263] (moveit_ros_benchmarks) JobQueued: {'identifier': 'moveit_ros_benchmarks', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse')])} -[0.001276] (moveit_ros_move_group) JobQueued: {'identifier': 'moveit_ros_move_group', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics')])} -[0.001289] (moveit_resources_prbt_moveit_config) JobQueued: {'identifier': 'moveit_resources_prbt_moveit_config', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group')])} -[0.001312] (moveit_ros_planning_interface) JobQueued: {'identifier': 'moveit_ros_planning_interface', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group')])} -[0.001329] (moveit_hybrid_planning) JobQueued: {'identifier': 'moveit_hybrid_planning', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} -[0.001344] (moveit_resources_prbt_pg70_support) JobQueued: {'identifier': 'moveit_resources_prbt_pg70_support', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_resources_prbt_moveit_config', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config')])} -[0.001358] (moveit_ros_visualization) JobQueued: {'identifier': 'moveit_ros_visualization', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} -[0.001452] (moveit_servo) JobQueued: {'identifier': 'moveit_servo', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface')])} -[0.001467] (moveit_ros) JobQueued: {'identifier': 'moveit_ros', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_benchmarks', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization')])} -[0.001483] (moveit_setup_assistant) JobQueued: {'identifier': 'moveit_setup_assistant', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization')])} -[0.001498] (pilz_industrial_motion_planner) JobQueued: {'identifier': 'pilz_industrial_motion_planner', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_resources_prbt_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_resources_prbt_ikfast_manipulator_plugin', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('pilz_industrial_motion_planner_testutils', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner_testutils'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_resources_prbt_moveit_config', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_resources_prbt_pg70_support', '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_pg70_support')])} -[0.001528] (moveit_planners) JobQueued: {'identifier': 'moveit_planners', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner')])} -[0.001543] (moveit) JobQueued: {'identifier': 'moveit', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_configs_utils', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_plugins', '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_robot_interaction', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_benchmarks', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('moveit_ros_visualization', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization'), ('moveit_ros', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner'), ('moveit_planners', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners')])} -[0.001561] (moveit_runtime) JobQueued: {'identifier': 'moveit_runtime', 'dependencies': OrderedDict([('moveit_common', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common'), ('moveit_core', '/home/henry/ws_moveit2/src/moveit2/install/moveit_core'), ('moveit_ros_occupancy_map_monitor', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor'), ('moveit_simple_controller_manager', '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager'), ('moveit_plugins', '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins'), ('moveit_ros_planning', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning'), ('moveit_kinematics', '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics'), ('moveit_planners_ompl', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl'), ('moveit_ros_warehouse', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse'), ('moveit_ros_move_group', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group'), ('moveit_ros_planning_interface', '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface'), ('pilz_industrial_motion_planner', '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner'), ('moveit_planners', '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners')])} -[0.001585] (moveit_common) JobStarted: {'identifier': 'moveit_common'} -[0.006455] (moveit_configs_utils) JobStarted: {'identifier': 'moveit_configs_utils'} -[0.010670] (moveit_resources_prbt_support) JobStarted: {'identifier': 'moveit_resources_prbt_support'} -[0.013071] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'cmake'} -[0.013236] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_common', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.099844] (-) TimerEvent: {} -[0.179485] (moveit_common) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} -[0.179975] (moveit_common) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} -[0.180092] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'cmake'} -[0.180291] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.199936] (-) TimerEvent: {} -[0.243553] (moveit_common) StdoutLine: {'line': b'-- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake)\n'} -[0.249359] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- The C compiler identification is GNU 11.2.0\n'} -[0.288317] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- The CXX compiler identification is GNU 11.2.0\n'} -[0.295205] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compiler ABI info\n'} -[0.300014] (-) TimerEvent: {} -[0.303725] (moveit_common) StdoutLine: {'line': b"-- Added test 'copyright' to check source files copyright and LICENSE\n"} -[0.305287] (moveit_common) StdoutLine: {'line': b"-- Added test 'lint_cmake' to check CMake code style\n"} -[0.306266] (moveit_common) StdoutLine: {'line': b"-- Added test 'xmllint' to check XML markup files\n"} -[0.307667] (moveit_common) StdoutLine: {'line': b'-- Configuring done\n'} -[0.309479] (moveit_common) StdoutLine: {'line': b'-- Generating done\n'} -[0.309965] (moveit_common) StdoutLine: {'line': b'-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common\n'} -[0.311464] (moveit_common) CommandEnded: {'returncode': 0} -[0.311967] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'build'} -[0.312487] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '--build', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', '--', '-j8', '-l8'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.332509] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compiler ABI info - done\n'} -[0.333407] (moveit_common) CommandEnded: {'returncode': 0} -[0.337252] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Check for working C compiler: /usr/lib/ccache/cc - skipped\n'} -[0.337429] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compile features\n'} -[0.337639] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting C compile features - done\n'} -[0.339680] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info\n'} -[0.343763] (moveit_common) JobProgress: {'identifier': 'moveit_common', 'progress': 'install'} -[0.348811] (moveit_common) Command: {'cmd': ['/usr/bin/cmake', '--install', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_common'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.353226] (moveit_common) StdoutLine: {'line': b'-- Install configuration: "Release"\n'} -[0.353445] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common\n'} -[0.353511] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common\n'} -[0.353606] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh\n'} -[0.353695] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv\n'} -[0.353781] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh\n'} -[0.353865] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv\n'} -[0.353958] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash\n'} -[0.354022] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh\n'} -[0.354103] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh\n'} -[0.354163] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv\n'} -[0.354248] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv\n'} -[0.354345] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common\n'} -[0.354408] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake\n'} -[0.354503] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake\n'} -[0.354585] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake\n'} -[0.354639] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml\n'} -[0.354690] (moveit_common) StdoutLine: {'line': b'-- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake\n'} -[0.354744] (moveit_common) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake\n'} -[0.355708] (moveit_common) CommandEnded: {'returncode': 0} -[0.381539] (moveit_common) JobEnded: {'identifier': 'moveit_common', 'rc': 0} -[0.382980] (moveit_core) JobStarted: {'identifier': 'moveit_core'} -[0.383355] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info - done\n'} -[0.387257] (moveit_core) JobProgress: {'identifier': 'moveit_core', 'progress': 'cmake'} -[0.387420] (moveit_core) Command: {'cmd': ['/usr/bin/cmake', '/home/henry/ws_moveit2/src/moveit2/moveit_core', '-DCMAKE_BUILD_TYPE=Release', '-DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_core', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_core'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble')]), 'shell': False} -[0.392163] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped\n'} -[0.392416] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compile features\n'} -[0.392911] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Detecting CXX compile features - done\n'} -[0.394724] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} -[0.400132] (-) TimerEvent: {} -[0.435787] (moveit_core) StdoutLine: {'line': b'-- The CXX compiler identification is GNU 11.2.0\n'} -[0.442190] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info\n'} -[0.483918] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info - done\n'} -[0.488983] (moveit_core) StdoutLine: {'line': b'-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped\n'} -[0.489143] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compile features\n'} -[0.489421] (moveit_core) StdoutLine: {'line': b'-- Detecting CXX compile features - done\n'} -[0.489996] (moveit_core) StdoutLine: {'line': b'-- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake)\n'} -[0.490919] (moveit_core) StdoutLine: {'line': b'-- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake)\n'} -[0.500228] (-) TimerEvent: {} -[0.515039] (moveit_configs_utils) Command: {'cmd': ['/usr/bin/python3', 'setup.py', 'egg_info', '--egg-base', '../build/moveit_configs_utils', 'build', '--build-base', '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build', 'install', '--prefix', '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils', '--record', '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log', '--single-version-externally-managed'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils', 'env': {'LESSOPEN': '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s', 'ALTERNATE_EDITOR': '', 'USER': 'henry', 'BASHRC_NAME': 'TODO_GITHUB_USER_NAME', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib', 'LESS': '-R', 'HOME': '/home/henry', 'OLDPWD': '/home/henry/ws_moveit2/src', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'PS1': '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$', 'MANAGERPID': '1489', 'SYSTEMD_EXEC_PID': '1823', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1000/bus', 'COLORTERM': 'truecolor', 'TERMINATOR_DBUS_NAME': 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3', 'GIO_LAUNCHED_DESKTOP_FILE_PID': '40701', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'ROS_DISTRO': 'humble', 'LOGNAME': 'henry', 'JOURNAL_STREAM': '8:37404', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'henry', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'ROS_LOCALHOST_ONLY': '1', 'PATH': '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677', 'INVOCATION_ID': '3e66bc62391b49bc94f6e6cf493d6504', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1000', 'DISPLAY': ':0', 'TERMINATOR_DBUS_PATH': '/net/tenshu/Terminator2', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'IBUS_DISABLE_SNOOPER': '1', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1000/.mutter-Xwaylandauth.VETXM1', 'BASHRC_ENV': 'default', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:', 'SSH_AGENT_LAUNCHER': 'gnome-keyring', 'SSH_AUTH_SOCK': '/run/user/1000/keyring/ssh', 'ROS_DOMAIN_ID': '44', 'AMENT_PREFIX_PATH': '/opt/ros/humble', 'ROSCONSOLE_FORMAT': '${logger}: ${message}', 'SHELL': '/bin/bash', 'TERMINATOR_UUID': 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'UBUNTU_VERSION': 'jammy', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages', 'COLCON': '1', 'VTE_VERSION': '6800', 'EDITOR': '/usr/bin/nano'}, 'shell': False} -[0.526486] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} -[0.600349] (-) TimerEvent: {} -[0.603527] (moveit_core) StdoutLine: {'line': b'-- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter \n'} -[0.623968] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Configuring done\n'} -[0.625556] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Generating done\n'} -[0.626120] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support\n'} -[0.630819] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} -[0.631277] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'build'} -[0.631483] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '--build', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', '--', '-j8', '-l8'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.654855] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} -[0.665159] (moveit_resources_prbt_support) JobProgress: {'identifier': 'moveit_resources_prbt_support', 'progress': 'install'} -[0.665448] (moveit_resources_prbt_support) Command: {'cmd': ['/usr/bin/cmake', '--install', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'], 'cwd': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'env': OrderedDict([('LESSOPEN', '|${HOME}/bitchin_unix/scripts/lessfilter.sh %s'), ('ALTERNATE_EDITOR', ''), ('USER', 'henry'), ('BASHRC_NAME', 'TODO_GITHUB_USER_NAME'), ('XDG_SESSION_TYPE', 'wayland'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib'), ('LESS', '-R'), ('HOME', '/home/henry'), ('OLDPWD', '/home/henry/ws_moveit2/src'), ('DESKTOP_SESSION', 'ubuntu'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('PS1', '\\[\\033[34m\\][\\h]\\[\\033[0m\\]\\[\\033[0;32m\\]$(parse_vc_branch_and_add_brackets)\\[\\033[0m\\] \\W$'), ('MANAGERPID', '1489'), ('SYSTEMD_EXEC_PID', '1823'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('TERMINATOR_DBUS_NAME', 'net.tenshu.Terminator25ef4b219e3b005583550f2b0f9f990c3'), ('GIO_LAUNCHED_DESKTOP_FILE_PID', '40701'), ('IM_CONFIG_PHASE', '1'), ('WAYLAND_DISPLAY', 'wayland-0'), ('ROS_DISTRO', 'humble'), ('LOGNAME', 'henry'), ('JOURNAL_STREAM', '8:37404'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('USERNAME', 'henry'), ('TERM', 'xterm-256color'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '1'), ('PATH', '/usr/lib/ccache:/home/henry/.local/bin:/opt/ros/humble/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin'), ('SESSION_MANAGER', 'local/henry-picknik-laptop:@/tmp/.ICE-unix/1677,unix/henry-picknik-laptop:/tmp/.ICE-unix/1677'), ('INVOCATION_ID', '3e66bc62391b49bc94f6e6cf493d6504'), ('XDG_MENU_PREFIX', 'gnome-'), ('GNOME_SETUP_DISPLAY', ':1'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('TERMINATOR_DBUS_PATH', '/net/tenshu/Terminator2'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('IBUS_DISABLE_SNOOPER', '1'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu'), ('XAUTHORITY', '/run/user/1000/.mutter-Xwaylandauth.VETXM1'), ('BASHRC_ENV', 'default'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('ROS_DOMAIN_ID', '44'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('ROSCONSOLE_FORMAT', '${logger}: ${message}'), ('SHELL', '/bin/bash'), ('TERMINATOR_UUID', 'urn:uuid:6579dfc3-0adc-42b4-8ec1-d863cc46cf91'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('UBUNTU_VERSION', 'jammy'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu:/etc/xdg'), ('XDG_DATA_DIRS', '/usr/share/ubuntu:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('COLCON', '1'), ('VTE_VERSION', '6800'), ('EDITOR', '/usr/bin/nano'), ('CMAKE_PREFIX_PATH', '/opt/ros/humble')]), 'shell': False} -[0.667774] (moveit_configs_utils) StdoutLine: {'line': b'running egg_info\n'} -[0.668174] (moveit_configs_utils) StdoutLine: {'line': b'creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info\n'} -[0.668307] (moveit_configs_utils) StdoutLine: {'line': b'writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO\n'} -[0.668444] (moveit_configs_utils) StdoutLine: {'line': b'writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt\n'} -[0.668540] (moveit_configs_utils) StdoutLine: {'line': b'writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt\n'} -[0.668626] (moveit_configs_utils) StdoutLine: {'line': b'writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt\n'} -[0.668721] (moveit_configs_utils) StdoutLine: {'line': b'writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt\n'} -[0.668780] (moveit_configs_utils) StdoutLine: {'line': b"writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} -[0.669687] (moveit_configs_utils) StdoutLine: {'line': b"reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} -[0.670025] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Install configuration: "Release"\n'} -[0.670236] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support\n'} -[0.670349] (moveit_configs_utils) StdoutLine: {'line': b"writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt'\n"} -[0.670470] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support\n'} -[0.670565] (moveit_configs_utils) StdoutLine: {'line': b'running build\n'} -[0.670671] (moveit_configs_utils) StdoutLine: {'line': b'running build_py\n'} -[0.670738] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build\n'} -[0.670836] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib\n'} -[0.670905] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} -[0.670971] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh\n'} -[0.671061] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} -[0.671130] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv\n'} -[0.671256] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh\n'} -[0.671325] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv\n'} -[0.671430] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash\n'} -[0.671525] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh\n'} -[0.671605] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} -[0.671680] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} -[0.671740] (moveit_configs_utils) StdoutLine: {'line': b'copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils\n'} -[0.671813] (moveit_configs_utils) StdoutLine: {'line': b'running install\n'} -[0.671875] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh\n'} -[0.671970] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv\n'} -[0.672066] (moveit_configs_utils) StderrLine: {'line': b'/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools.\n'} -[0.672238] (moveit_configs_utils) StderrLine: {'line': b' warnings.warn(\n'} -[0.672313] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv\n'} -[0.672390] (moveit_configs_utils) StdoutLine: {'line': b'running install_lib\n'} -[0.672467] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support\n'} -[0.672536] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake\n'} -[0.672621] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake\n'} -[0.672684] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml\n'} -[0.672745] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} -[0.672787] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf\n'} -[0.672826] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro\n'} -[0.672887] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} -[0.672951] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro\n'} -[0.673015] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} -[0.673079] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} -[0.673143] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro\n'} -[0.673231] (moveit_configs_utils) StdoutLine: {'line': b'copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils\n'} -[0.673290] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro\n'} -[0.673347] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes\n'} -[0.673419] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl\n'} -[0.673505] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl\n'} -[0.673544] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae\n'} -[0.673579] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc\n'} -[0.673618] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae\n'} -[0.673653] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc\n'} -[0.674627] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc\n'} -[0.674733] (moveit_configs_utils) StdoutLine: {'line': b'byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc\n'} -[0.675001] (moveit_configs_utils) StdoutLine: {'line': b'running install_data\n'} -[0.675289] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index\n'} -[0.675370] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index\n'} -[0.675408] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages\n'} -[0.675467] (moveit_configs_utils) StdoutLine: {'line': b'copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages\n'} -[0.675573] (moveit_configs_utils) StdoutLine: {'line': b'copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils\n'} -[0.675661] (moveit_configs_utils) StdoutLine: {'line': b'creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.675703] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae\n'} -[0.675746] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.675839] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.675898] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.675956] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.676008] (moveit_configs_utils) StdoutLine: {'line': b'copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs\n'} -[0.676044] (moveit_configs_utils) StdoutLine: {'line': b'running install_egg_info\n'} -[0.676818] (moveit_configs_utils) StdoutLine: {'line': b'Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info\n'} -[0.676940] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl\n'} -[0.677034] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl\n'} -[0.677120] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl\n'} -[0.677206] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl\n'} -[0.677284] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl\n'} -[0.677371] (moveit_configs_utils) StdoutLine: {'line': b'running install_scripts\n'} -[0.677455] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae\n'} -[0.677981] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae\n'} -[0.678095] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae\n'} -[0.679330] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae\n'} -[0.680751] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config\n'} -[0.680856] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf\n'} -[0.680943] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml\n'} -[0.681027] (moveit_resources_prbt_support) StdoutLine: {'line': b'-- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml\n'} -[0.682226] (moveit_resources_prbt_support) CommandEnded: {'returncode': 0} -[0.690535] (moveit_configs_utils) StdoutLine: {'line': b"writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log'\n"} -[0.700849] (-) TimerEvent: {} -[0.702434] (moveit_resources_prbt_support) JobEnded: {'identifier': 'moveit_resources_prbt_support', 'rc': 0} -[0.708287] (moveit_configs_utils) CommandEnded: {'returncode': 0} -[0.712395] (moveit_configs_utils) JobEnded: {'identifier': 'moveit_configs_utils', 'rc': 0} -[0.712895] (moveit_core) StdoutLine: {'line': b'-- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so \n'} -[0.716545] (moveit_core) StdoutLine: {'line': b'-- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) \n'} -[0.716596] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_UNWIND=1\n'} -[0.716631] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BACKTRACE=0\n'} -[0.716665] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BACKTRACE_SYMBOL=0\n'} -[0.716698] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_DW=1\n'} -[0.716732] (moveit_core) StdoutLine: {'line': b'-- BACKWARD_HAS_BFD=0\n'} -[0.717183] (moveit_core) StdoutLine: {'line': b'-- Found Backward: /opt/ros/humble/share/backward_ros/cmake \n'} -[0.719696] (moveit_core) StdoutLine: {'line': b'-- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake)\n'} -[0.768961] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake)\n'} -[0.773515] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake)\n'} -[0.781666] (moveit_core) StdoutLine: {'line': b'-- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake)\n'} -[0.796664] (moveit_core) StdoutLine: {'line': b'-- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c\n'} -[0.800941] (-) TimerEvent: {} -[0.814447] (moveit_core) StdoutLine: {'line': b'-- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp\n'} -[0.870574] (moveit_core) StdoutLine: {'line': b'-- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake)\n'} -[0.873441] (moveit_core) StdoutLine: {'line': b'-- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake)\n'} -[0.901043] (-) TimerEvent: {} -[0.938296] (moveit_core) StdoutLine: {'line': b'-- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") \n'} -[0.953175] (moveit_core) StdoutLine: {'line': b'-- Found FastRTPS: /opt/ros/humble/include \n'} -[0.979657] (moveit_core) StdoutLine: {'line': b"-- Using RMW implementation 'rmw_fastrtps_cpp' as default\n"} -[1.001142] (-) TimerEvent: {} -[1.087281] (moveit_core) StdoutLine: {'line': b'-- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake)\n'} -[1.092299] (moveit_core) StdoutLine: {'line': b'-- Found Eigen3: TRUE (found version "3.4.0") \n'} -[1.094707] (moveit_core) StdoutLine: {'line': b'-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") \n'} -[1.095049] (moveit_core) StdoutLine: {'line': b"-- Checking for module 'fcl>=0.5.0'\n"} -[1.101147] (moveit_core) StdoutLine: {'line': b'-- Found fcl, version 0.7.0\n'} -[1.101216] (-) TimerEvent: {} -[1.123782] (moveit_core) StdoutLine: {'line': b'-- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") \n'} -[1.125036] (moveit_core) StdoutLine: {'line': b'-- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake)\n'} -[1.136881] (moveit_core) StdoutLine: {'line': b'-- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake)\n'} -[1.158204] (moveit_core) StdoutLine: {'line': b'-- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake)\n'} -[1.201352] (-) TimerEvent: {} -[1.301594] (-) TimerEvent: {} -[1.401854] (-) TimerEvent: {} -[1.465100] (moveit_core) StdoutLine: {'line': b'-- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake)\n'} -[1.477530] (moveit_core) StdoutLine: {'line': b'-- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake)\n'} -[1.488819] (moveit_core) StdoutLine: {'line': b'-- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake)\n'} -[1.491189] (moveit_core) StdoutLine: {'line': b'-- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake)\n'} -[1.499324] (moveit_core) StdoutLine: {'line': b'-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem \n'} -[1.501926] (-) TimerEvent: {} -[1.547713] (moveit_core) StdoutLine: {'line': b'-- library: /usr/lib/x86_64-linux-gnu/libcurl.so\n'} -[1.602141] (-) TimerEvent: {} -[1.702487] (-) TimerEvent: {} -[1.737524] (moveit_core) StdoutLine: {'line': b'-- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake)\n'} -[1.740146] (moveit_core) StdoutLine: {'line': b'-- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake)\n'} -[1.802672] (-) TimerEvent: {} -[1.903022] (-) TimerEvent: {} -[2.003394] (-) TimerEvent: {} -[2.103064] (moveit_core) StderrLine: {'line': b'\x1b[31mCMake Error at CMakeLists.txt:43 (find_package):\n'} -[2.103240] (moveit_core) StderrLine: {'line': b' By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has\n'} -[2.103284] (moveit_core) StderrLine: {'line': b' asked CMake to find a package configuration file provided by "srdfdom", but\n'} -[2.103323] (moveit_core) StderrLine: {'line': b' CMake did not find one.\n'} -[2.103359] (moveit_core) StderrLine: {'line': b'\n'} -[2.103392] (-) TimerEvent: {} -[2.103465] (moveit_core) StderrLine: {'line': b' Could not find a package configuration file provided by "srdfdom" with any\n'} -[2.103505] (moveit_core) StderrLine: {'line': b' of the following names:\n'} -[2.103541] (moveit_core) StderrLine: {'line': b'\n'} -[2.103574] (moveit_core) StderrLine: {'line': b' srdfdomConfig.cmake\n'} -[2.103608] (moveit_core) StderrLine: {'line': b' srdfdom-config.cmake\n'} -[2.103642] (moveit_core) StderrLine: {'line': b'\n'} -[2.103674] (moveit_core) StderrLine: {'line': b' Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set\n'} -[2.103708] (moveit_core) StderrLine: {'line': b' "srdfdom_DIR" to a directory containing one of the above files. If\n'} -[2.103742] (moveit_core) StderrLine: {'line': b' "srdfdom" provides a separate development package or SDK, be sure it has\n'} -[2.103775] (moveit_core) StderrLine: {'line': b' been installed.\n'} -[2.103809] (moveit_core) StderrLine: {'line': b'\n'} -[2.103842] (moveit_core) StderrLine: {'line': b'\x1b[0m\n'} -[2.103876] (moveit_core) StdoutLine: {'line': b'-- Configuring incomplete, errors occurred!\n'} -[2.103914] (moveit_core) StdoutLine: {'line': b'See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log".\n'} -[2.110082] (moveit_core) CommandEnded: {'returncode': 1} -[2.119794] (moveit_core) JobEnded: {'identifier': 'moveit_core', 'rc': 1} -[2.130499] (chomp_motion_planner) JobSkipped: {'identifier': 'chomp_motion_planner'} -[2.130544] (moveit_resources_prbt_ikfast_manipulator_plugin) JobSkipped: {'identifier': 'moveit_resources_prbt_ikfast_manipulator_plugin'} -[2.130563] (moveit_ros_occupancy_map_monitor) JobSkipped: {'identifier': 'moveit_ros_occupancy_map_monitor'} -[2.130580] (moveit_simple_controller_manager) JobSkipped: {'identifier': 'moveit_simple_controller_manager'} -[2.130595] (pilz_industrial_motion_planner_testutils) JobSkipped: {'identifier': 'pilz_industrial_motion_planner_testutils'} -[2.130610] (moveit_chomp_optimizer_adapter) JobSkipped: {'identifier': 'moveit_chomp_optimizer_adapter'} -[2.130624] (moveit_planners_chomp) JobSkipped: {'identifier': 'moveit_planners_chomp'} -[2.130638] (moveit_plugins) JobSkipped: {'identifier': 'moveit_plugins'} -[2.130652] (moveit_ros_control_interface) JobSkipped: {'identifier': 'moveit_ros_control_interface'} -[2.130665] (moveit_ros_planning) JobSkipped: {'identifier': 'moveit_ros_planning'} -[2.130679] (moveit_kinematics) JobSkipped: {'identifier': 'moveit_kinematics'} -[2.130720] (moveit_planners_ompl) JobSkipped: {'identifier': 'moveit_planners_ompl'} -[2.130735] (moveit_ros_perception) JobSkipped: {'identifier': 'moveit_ros_perception'} -[2.130750] (moveit_ros_robot_interaction) JobSkipped: {'identifier': 'moveit_ros_robot_interaction'} -[2.130764] (moveit_ros_warehouse) JobSkipped: {'identifier': 'moveit_ros_warehouse'} -[2.130777] (moveit_ros_benchmarks) JobSkipped: {'identifier': 'moveit_ros_benchmarks'} -[2.130791] (moveit_ros_move_group) JobSkipped: {'identifier': 'moveit_ros_move_group'} -[2.130805] (moveit_resources_prbt_moveit_config) JobSkipped: {'identifier': 'moveit_resources_prbt_moveit_config'} -[2.130819] (moveit_ros_planning_interface) JobSkipped: {'identifier': 'moveit_ros_planning_interface'} -[2.130833] (moveit_hybrid_planning) JobSkipped: {'identifier': 'moveit_hybrid_planning'} -[2.130846] (moveit_resources_prbt_pg70_support) JobSkipped: {'identifier': 'moveit_resources_prbt_pg70_support'} -[2.130860] (moveit_ros_visualization) JobSkipped: {'identifier': 'moveit_ros_visualization'} -[2.130874] (moveit_servo) JobSkipped: {'identifier': 'moveit_servo'} -[2.130887] (moveit_ros) JobSkipped: {'identifier': 'moveit_ros'} -[2.130901] (moveit_setup_assistant) JobSkipped: {'identifier': 'moveit_setup_assistant'} -[2.130915] (pilz_industrial_motion_planner) JobSkipped: {'identifier': 'pilz_industrial_motion_planner'} -[2.130925] (moveit_planners) JobSkipped: {'identifier': 'moveit_planners'} -[2.130936] (moveit) JobSkipped: {'identifier': 'moveit'} -[2.130946] (moveit_runtime) JobSkipped: {'identifier': 'moveit_runtime'} -[2.130957] (-) EventReactorShutdown: {} diff --git a/log/build_2022-06-08_12-52-32/logger_all.log b/log/build_2022-06-08_12-52-32/logger_all.log deleted file mode 100644 index d4c7af7b3d..0000000000 --- a/log/build_2022-06-08_12-52-32/logger_all.log +++ /dev/null @@ -1,986 +0,0 @@ -[0.181s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--mixin', 'release'] -[0.181s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=8, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=['-DCMAKE_BUILD_TYPE=Release'], cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=['release'], verb_parser=, verb_extension=, main=>, mixin_verb=('build',)) -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover -[0.199s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover -[0.199s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/henry/ws_moveit2/src/moveit2' -[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install'] -[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore' -[0.199s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install' -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg'] -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg' -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta'] -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta' -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros'] -[0.200s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros' -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python'] -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake' -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python' -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py'] -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py' -[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['ignore', 'ignore_ament_install'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ignore' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ignore_ament_install' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['colcon_pkg'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'colcon_pkg' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['colcon_meta'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'colcon_meta' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['ros'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'ros' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['cmake', 'python'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'cmake' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'python' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extensions ['python_setup_py'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(doc) by extension 'python_setup_py' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['ignore', 'ignore_ament_install'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ignore' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ignore_ament_install' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['colcon_pkg'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'colcon_pkg' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['colcon_meta'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'colcon_meta' -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extensions ['ros'] -[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(moveit) by extension 'ros' -[0.215s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit' with type 'ros.ament_cmake' and name 'moveit' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) by extensions ['ignore', 'ignore_ament_install'] -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) by extension 'ignore' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_commander) ignored -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['ignore', 'ignore_ament_install'] -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ignore' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ignore_ament_install' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['colcon_pkg'] -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'colcon_pkg' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['colcon_meta'] -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'colcon_meta' -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extensions ['ros'] -[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_common) by extension 'ros' -[0.216s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_common' with type 'ros.ament_cmake' and name 'moveit_common' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['ignore', 'ignore_ament_install'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ignore' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ignore_ament_install' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['colcon_pkg'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'colcon_pkg' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['colcon_meta'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'colcon_meta' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extensions ['ros'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_configs_utils) by extension 'ros' -[0.216s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_configs_utils' with type 'ros.ament_python' and name 'moveit_configs_utils' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['ignore', 'ignore_ament_install'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ignore' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ignore_ament_install' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['colcon_pkg'] -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'colcon_pkg' -[0.216s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['colcon_meta'] -[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'colcon_meta' -[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extensions ['ros'] -[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_core) by extension 'ros' -[0.219s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_core' with type 'ros.ament_cmake' and name 'moveit_core' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) by extensions ['ignore', 'ignore_ament_install'] -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) by extension 'ignore' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_experimental) ignored -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['ignore', 'ignore_ament_install'] -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ignore' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ignore_ament_install' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['colcon_pkg'] -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'colcon_pkg' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['colcon_meta'] -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'colcon_meta' -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extensions ['ros'] -[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_kinematics) by extension 'ros' -[0.220s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_kinematics' with type 'ros.ament_cmake' and name 'moveit_kinematics' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['ignore', 'ignore_ament_install'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ignore' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ignore_ament_install' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['colcon_pkg'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'colcon_pkg' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['colcon_meta'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'colcon_meta' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['ros'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'ros' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['cmake', 'python'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'cmake' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'python' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extensions ['python_setup_py'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners) by extension 'python_setup_py' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['ignore', 'ignore_ament_install'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ignore' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ignore_ament_install' -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['colcon_pkg'] -[0.220s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'colcon_pkg' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['colcon_meta'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'colcon_meta' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['ros'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'ros' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['cmake', 'python'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'cmake' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'python' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extensions ['python_setup_py'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp) by extension 'python_setup_py' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['ignore', 'ignore_ament_install'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ignore' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ignore_ament_install' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['colcon_pkg'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'colcon_pkg' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['colcon_meta'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'colcon_meta' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extensions ['ros'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_interface) by extension 'ros' -[0.221s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_interface' with type 'ros.ament_cmake' and name 'moveit_planners_chomp' -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['ignore', 'ignore_ament_install'] -[0.221s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ignore' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ignore_ament_install' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['colcon_pkg'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'colcon_pkg' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['colcon_meta'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'colcon_meta' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extensions ['ros'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_motion_planner) by extension 'ros' -[0.222s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_motion_planner' with type 'ros.ament_cmake' and name 'chomp_motion_planner' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['ignore', 'ignore_ament_install'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ignore' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ignore_ament_install' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['colcon_pkg'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'colcon_pkg' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['colcon_meta'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'colcon_meta' -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extensions ['ros'] -[0.222s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/chomp/chomp_optimizer_adapter) by extension 'ros' -[0.223s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/chomp/chomp_optimizer_adapter' with type 'ros.ament_cmake' and name 'moveit_chomp_optimizer_adapter' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['ignore', 'ignore_ament_install'] -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ignore' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ignore_ament_install' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['colcon_pkg'] -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'colcon_pkg' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['colcon_meta'] -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'colcon_meta' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extensions ['ros'] -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/moveit_planners) by extension 'ros' -[0.223s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/moveit_planners' with type 'ros.ament_cmake' and name 'moveit_planners' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['ignore', 'ignore_ament_install'] -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ignore' -[0.223s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ignore_ament_install' -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['colcon_pkg'] -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'colcon_pkg' -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['colcon_meta'] -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'colcon_meta' -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extensions ['ros'] -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/ompl) by extension 'ros' -[0.224s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/ompl' with type 'ros.ament_cmake' and name 'moveit_planners_ompl' -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['ignore', 'ignore_ament_install'] -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ignore' -[0.224s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ignore_ament_install' -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['colcon_pkg'] -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'colcon_pkg' -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['colcon_meta'] -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'colcon_meta' -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extensions ['ros'] -[0.225s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner) by extension 'ros' -[0.226s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/pilz_industrial_motion_planner' with type 'ros.ament_cmake' and name 'pilz_industrial_motion_planner' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['ignore', 'ignore_ament_install'] -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ignore' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ignore_ament_install' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['colcon_pkg'] -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'colcon_pkg' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['colcon_meta'] -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'colcon_meta' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extensions ['ros'] -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/pilz_industrial_motion_planner_testutils) by extension 'ros' -[0.226s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/pilz_industrial_motion_planner_testutils' with type 'ros.ament_cmake' and name 'pilz_industrial_motion_planner_testutils' -[0.226s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['ignore', 'ignore_ament_install'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ignore' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ignore_ament_install' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['colcon_pkg'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'colcon_pkg' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['colcon_meta'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'colcon_meta' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['ros'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'ros' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['cmake', 'python'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'cmake' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'python' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extensions ['python_setup_py'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs) by extension 'python_setup_py' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['ignore', 'ignore_ament_install'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ignore' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ignore_ament_install' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['colcon_pkg'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'colcon_pkg' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['colcon_meta'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'colcon_meta' -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extensions ['ros'] -[0.227s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_ikfast_manipulator_plugin) by extension 'ros' -[0.228s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_ikfast_manipulator_plugin' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_ikfast_manipulator_plugin' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['ignore', 'ignore_ament_install'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ignore' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ignore_ament_install' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['colcon_pkg'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'colcon_pkg' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['colcon_meta'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'colcon_meta' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extensions ['ros'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_moveit_config) by extension 'ros' -[0.228s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_moveit_config' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_moveit_config' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['ignore', 'ignore_ament_install'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ignore' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ignore_ament_install' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['colcon_pkg'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'colcon_pkg' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['colcon_meta'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'colcon_meta' -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extensions ['ros'] -[0.228s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_pg70_support) by extension 'ros' -[0.229s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_pg70_support' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_pg70_support' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['ignore', 'ignore_ament_install'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ignore' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ignore_ament_install' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['colcon_pkg'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'colcon_pkg' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['colcon_meta'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'colcon_meta' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extensions ['ros'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/test_configs/prbt_support) by extension 'ros' -[0.229s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_planners/test_configs/prbt_support' with type 'ros.ament_cmake' and name 'moveit_resources_prbt_support' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) by extensions ['ignore', 'ignore_ament_install'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) by extension 'ignore' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_planners/trajopt) ignored -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['ignore', 'ignore_ament_install'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ignore' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ignore_ament_install' -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['colcon_pkg'] -[0.229s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'colcon_pkg' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['colcon_meta'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'colcon_meta' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['ros'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'ros' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['cmake', 'python'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'cmake' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'python' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extensions ['python_setup_py'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins) by extension 'python_setup_py' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) by extensions ['ignore', 'ignore_ament_install'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) by extension 'ignore' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_controller_manager_example) ignored -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['ignore', 'ignore_ament_install'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ignore' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ignore_ament_install' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['colcon_pkg'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'colcon_pkg' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['colcon_meta'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'colcon_meta' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['ros'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'ros' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['cmake', 'python'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'cmake' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'python' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extensions ['python_setup_py'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager) by extension 'python_setup_py' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['ignore', 'ignore_ament_install'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ignore' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ignore_ament_install' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['colcon_pkg'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'colcon_pkg' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['colcon_meta'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'colcon_meta' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['ros'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'ros' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['cmake', 'python'] -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'cmake' -[0.230s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'python' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extensions ['python_setup_py'] -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_fake_controller_manager/src) by extension 'python_setup_py' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['ignore', 'ignore_ament_install'] -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ignore' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ignore_ament_install' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['colcon_pkg'] -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'colcon_pkg' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['colcon_meta'] -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'colcon_meta' -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extensions ['ros'] -[0.231s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_plugins) by extension 'ros' -[0.232s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_plugins' with type 'ros.ament_cmake' and name 'moveit_plugins' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['ignore', 'ignore_ament_install'] -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ignore' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ignore_ament_install' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['colcon_pkg'] -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'colcon_pkg' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['colcon_meta'] -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'colcon_meta' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extensions ['ros'] -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_ros_control_interface) by extension 'ros' -[0.232s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_ros_control_interface' with type 'ros.ament_cmake' and name 'moveit_ros_control_interface' -[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['ignore', 'ignore_ament_install'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ignore' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ignore_ament_install' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['colcon_pkg'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'colcon_pkg' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['colcon_meta'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'colcon_meta' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extensions ['ros'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_plugins/moveit_simple_controller_manager) by extension 'ros' -[0.233s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_plugins/moveit_simple_controller_manager' with type 'ros.ament_cmake' and name 'moveit_simple_controller_manager' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['ignore', 'ignore_ament_install'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ignore' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ignore_ament_install' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['colcon_pkg'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'colcon_pkg' -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['colcon_meta'] -[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'colcon_meta' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['ros'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'ros' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['cmake', 'python'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'cmake' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'python' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extensions ['python_setup_py'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros) by extension 'python_setup_py' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['ignore', 'ignore_ament_install'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ignore' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ignore_ament_install' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['colcon_pkg'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'colcon_pkg' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['colcon_meta'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'colcon_meta' -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extensions ['ros'] -[0.234s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/benchmarks) by extension 'ros' -[0.235s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/benchmarks' with type 'ros.ament_cmake' and name 'moveit_ros_benchmarks' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['ignore', 'ignore_ament_install'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ignore' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ignore_ament_install' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['colcon_pkg'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'colcon_pkg' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['colcon_meta'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'colcon_meta' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extensions ['ros'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/hybrid_planning) by extension 'ros' -[0.236s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/hybrid_planning' with type 'ros.ament_cmake' and name 'moveit_hybrid_planning' -[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) by extensions ['ignore', 'ignore_ament_install'] -[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) by extension 'ignore' -[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/manipulation) ignored -[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['ignore', 'ignore_ament_install'] -[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ignore' -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ignore_ament_install' -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['colcon_pkg'] -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'colcon_pkg' -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['colcon_meta'] -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'colcon_meta' -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extensions ['ros'] -[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/move_group) by extension 'ros' -[0.238s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/move_group' with type 'ros.ament_cmake' and name 'moveit_ros_move_group' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['ignore', 'ignore_ament_install'] -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ignore' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ignore_ament_install' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['colcon_pkg'] -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'colcon_pkg' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['colcon_meta'] -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'colcon_meta' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extensions ['ros'] -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_ros) by extension 'ros' -[0.238s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/moveit_ros' with type 'ros.ament_cmake' and name 'moveit_ros' -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['ignore', 'ignore_ament_install'] -[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ignore' -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ignore_ament_install' -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['colcon_pkg'] -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'colcon_pkg' -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['colcon_meta'] -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'colcon_meta' -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extensions ['ros'] -[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/moveit_servo) by extension 'ros' -[0.240s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/moveit_servo' with type 'ros.ament_cmake' and name 'moveit_servo' -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['ignore', 'ignore_ament_install'] -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ignore' -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ignore_ament_install' -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['colcon_pkg'] -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'colcon_pkg' -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['colcon_meta'] -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'colcon_meta' -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extensions ['ros'] -[0.240s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/occupancy_map_monitor) by extension 'ros' -[0.241s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/occupancy_map_monitor' with type 'ros.ament_cmake' and name 'moveit_ros_occupancy_map_monitor' -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['ignore', 'ignore_ament_install'] -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ignore' -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ignore_ament_install' -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['colcon_pkg'] -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'colcon_pkg' -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['colcon_meta'] -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'colcon_meta' -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extensions ['ros'] -[0.241s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/perception) by extension 'ros' -[0.242s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/perception' with type 'ros.ament_cmake' and name 'moveit_ros_perception' -[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['ignore', 'ignore_ament_install'] -[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ignore' -[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ignore_ament_install' -[0.242s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['colcon_pkg'] -[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'colcon_pkg' -[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['colcon_meta'] -[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'colcon_meta' -[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extensions ['ros'] -[0.243s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning) by extension 'ros' -[0.244s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/planning' with type 'ros.ament_cmake' and name 'moveit_ros_planning' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['ignore', 'ignore_ament_install'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ignore' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ignore_ament_install' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['colcon_pkg'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'colcon_pkg' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['colcon_meta'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'colcon_meta' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extensions ['ros'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/planning_interface) by extension 'ros' -[0.245s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/planning_interface' with type 'ros.ament_cmake' and name 'moveit_ros_planning_interface' -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['ignore', 'ignore_ament_install'] -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ignore' -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ignore_ament_install' -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['colcon_pkg'] -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'colcon_pkg' -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['colcon_meta'] -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'colcon_meta' -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extensions ['ros'] -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/robot_interaction) by extension 'ros' -[0.246s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/robot_interaction' with type 'ros.ament_cmake' and name 'moveit_ros_robot_interaction' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['ignore', 'ignore_ament_install'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ignore' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ignore_ament_install' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['colcon_pkg'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'colcon_pkg' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['colcon_meta'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'colcon_meta' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extensions ['ros'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/visualization) by extension 'ros' -[0.247s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/visualization' with type 'ros.ament_cmake' and name 'moveit_ros_visualization' -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['ignore', 'ignore_ament_install'] -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ignore' -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ignore_ament_install' -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['colcon_pkg'] -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'colcon_pkg' -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['colcon_meta'] -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'colcon_meta' -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extensions ['ros'] -[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_ros/warehouse) by extension 'ros' -[0.248s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_ros/warehouse' with type 'ros.ament_cmake' and name 'moveit_ros_warehouse' -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['ignore', 'ignore_ament_install'] -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ignore' -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ignore_ament_install' -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['colcon_pkg'] -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'colcon_pkg' -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['colcon_meta'] -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'colcon_meta' -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extensions ['ros'] -[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_runtime) by extension 'ros' -[0.249s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_runtime' with type 'ros.ament_cmake' and name 'moveit_runtime' -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['ignore', 'ignore_ament_install'] -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ignore' -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ignore_ament_install' -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['colcon_pkg'] -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'colcon_pkg' -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['colcon_meta'] -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'colcon_meta' -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extensions ['ros'] -[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(moveit_setup_assistant) by extension 'ros' -[0.250s] DEBUG:colcon.colcon_core.package_identification:Package 'moveit_setup_assistant' with type 'ros.ament_cmake' and name 'moveit_setup_assistant' -[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults -[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover -[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults -[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover -[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults -[0.267s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters -[0.267s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover -[0.268s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 304 installed packages in /opt/ros/humble -[0.269s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_target' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_clean_cache' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_clean_first' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'cmake_force_configure' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'ament_cmake_args' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'catkin_cmake_args' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_common' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.305s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_common' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_common', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_common', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_common', 'symlink_install': False, 'test_result_base': None} -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_target' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_clean_cache' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_clean_first' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'cmake_force_configure' from command line to 'False' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'ament_cmake_args' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'catkin_cmake_args' from command line to 'None' -[0.305s] Level 5:colcon.colcon_core.verb:set package 'moveit_configs_utils' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.305s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_configs_utils' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils', 'symlink_install': False, 'test_result_base': None} -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_target' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_clean_cache' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_clean_first' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'cmake_force_configure' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'ament_cmake_args' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'catkin_cmake_args' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_support' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.306s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_support' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support', 'symlink_install': False, 'test_result_base': None} -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_target' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_clean_cache' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_clean_first' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'cmake_force_configure' from command line to 'False' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'ament_cmake_args' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'catkin_cmake_args' from command line to 'None' -[0.306s] Level 5:colcon.colcon_core.verb:set package 'moveit_core' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.306s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_core' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_core', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_core', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_core', 'symlink_install': False, 'test_result_base': None} -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_target' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_clean_cache' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_clean_first' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'cmake_force_configure' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'ament_cmake_args' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'catkin_cmake_args' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'chomp_motion_planner' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.307s] DEBUG:colcon.colcon_core.verb:Building package 'chomp_motion_planner' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/chomp_motion_planner', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/chomp_motion_planner', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_motion_planner', 'symlink_install': False, 'test_result_base': None} -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_target' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_clean_cache' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_clean_first' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'cmake_force_configure' from command line to 'False' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'ament_cmake_args' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'catkin_cmake_args' from command line to 'None' -[0.307s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_ikfast_manipulator_plugin' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.307s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_ikfast_manipulator_plugin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_ikfast_manipulator_plugin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_ikfast_manipulator_plugin', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_ikfast_manipulator_plugin', 'symlink_install': False, 'test_result_base': None} -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_target' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_clean_cache' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_clean_first' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'cmake_force_configure' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'ament_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'catkin_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_occupancy_map_monitor' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.308s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_occupancy_map_monitor' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_occupancy_map_monitor', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_occupancy_map_monitor', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/occupancy_map_monitor', 'symlink_install': False, 'test_result_base': None} -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_target' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_clean_cache' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_clean_first' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'cmake_force_configure' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'ament_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'catkin_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'moveit_simple_controller_manager' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.308s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_simple_controller_manager' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_simple_controller_manager', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_simple_controller_manager', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_simple_controller_manager', 'symlink_install': False, 'test_result_base': None} -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_target' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_clean_cache' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_clean_first' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'cmake_force_configure' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'ament_cmake_args' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'catkin_cmake_args' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner_testutils' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.309s] DEBUG:colcon.colcon_core.verb:Building package 'pilz_industrial_motion_planner_testutils' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/pilz_industrial_motion_planner_testutils', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner_testutils', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner_testutils', 'symlink_install': False, 'test_result_base': None} -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_target' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_clean_cache' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_clean_first' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'cmake_force_configure' from command line to 'False' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'ament_cmake_args' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'catkin_cmake_args' from command line to 'None' -[0.309s] Level 5:colcon.colcon_core.verb:set package 'moveit_chomp_optimizer_adapter' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.309s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_chomp_optimizer_adapter' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_chomp_optimizer_adapter', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_chomp_optimizer_adapter', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_optimizer_adapter', 'symlink_install': False, 'test_result_base': None} -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_target' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_clean_cache' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_clean_first' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'cmake_force_configure' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'ament_cmake_args' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'catkin_cmake_args' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_chomp' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.310s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners_chomp' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners_chomp', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_chomp', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/chomp/chomp_interface', 'symlink_install': False, 'test_result_base': None} -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_target' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_clean_cache' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_clean_first' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'cmake_force_configure' from command line to 'False' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'ament_cmake_args' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'catkin_cmake_args' from command line to 'None' -[0.310s] Level 5:colcon.colcon_core.verb:set package 'moveit_plugins' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.310s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_plugins' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_plugins', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_plugins', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_plugins', 'symlink_install': False, 'test_result_base': None} -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_target' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_clean_cache' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_clean_first' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'cmake_force_configure' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'ament_cmake_args' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'catkin_cmake_args' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_control_interface' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.311s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_control_interface' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_control_interface', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_control_interface', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_plugins/moveit_ros_control_interface', 'symlink_install': False, 'test_result_base': None} -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_target' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_clean_cache' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_clean_first' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'cmake_force_configure' from command line to 'False' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'ament_cmake_args' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'catkin_cmake_args' from command line to 'None' -[0.311s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.311s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_planning' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_planning', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/planning', 'symlink_install': False, 'test_result_base': None} -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_target' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_clean_cache' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_clean_first' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'cmake_force_configure' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'ament_cmake_args' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'catkin_cmake_args' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_kinematics' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.312s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_kinematics' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_kinematics', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_kinematics', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_kinematics', 'symlink_install': False, 'test_result_base': None} -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_target' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_clean_cache' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_clean_first' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'cmake_force_configure' from command line to 'False' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'ament_cmake_args' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'catkin_cmake_args' from command line to 'None' -[0.312s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners_ompl' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.312s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners_ompl' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners_ompl', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners_ompl', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/ompl', 'symlink_install': False, 'test_result_base': None} -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_target' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_clean_cache' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_clean_first' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'cmake_force_configure' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'ament_cmake_args' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'catkin_cmake_args' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_perception' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.313s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_perception' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_perception', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_perception', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/perception', 'symlink_install': False, 'test_result_base': None} -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_target' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_clean_cache' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_clean_first' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'cmake_force_configure' from command line to 'False' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'ament_cmake_args' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'catkin_cmake_args' from command line to 'None' -[0.313s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_robot_interaction' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.313s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_robot_interaction' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_robot_interaction', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_robot_interaction', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/robot_interaction', 'symlink_install': False, 'test_result_base': None} -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_target' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_clean_cache' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_clean_first' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'cmake_force_configure' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'ament_cmake_args' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'catkin_cmake_args' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_warehouse' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.314s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_warehouse' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_warehouse', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_warehouse', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/warehouse', 'symlink_install': False, 'test_result_base': None} -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_target' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_clean_cache' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_clean_first' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'cmake_force_configure' from command line to 'False' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'ament_cmake_args' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'catkin_cmake_args' from command line to 'None' -[0.314s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_benchmarks' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.314s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_benchmarks' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_benchmarks', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_benchmarks', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/benchmarks', 'symlink_install': False, 'test_result_base': None} -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_target' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_clean_cache' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_clean_first' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'cmake_force_configure' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'ament_cmake_args' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'catkin_cmake_args' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_move_group' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.315s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_move_group' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_move_group', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_move_group', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/move_group', 'symlink_install': False, 'test_result_base': None} -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_target' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_clean_cache' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_clean_first' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'cmake_force_configure' from command line to 'False' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'ament_cmake_args' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'catkin_cmake_args' from command line to 'None' -[0.315s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_moveit_config' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.315s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_moveit_config' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_moveit_config', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_moveit_config', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_moveit_config', 'symlink_install': False, 'test_result_base': None} -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_target' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_clean_cache' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_clean_first' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'cmake_force_configure' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'ament_cmake_args' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'catkin_cmake_args' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_planning_interface' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.316s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_planning_interface' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_planning_interface', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_planning_interface', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/planning_interface', 'symlink_install': False, 'test_result_base': None} -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_target' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_clean_cache' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_clean_first' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'cmake_force_configure' from command line to 'False' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'ament_cmake_args' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'catkin_cmake_args' from command line to 'None' -[0.316s] Level 5:colcon.colcon_core.verb:set package 'moveit_hybrid_planning' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.316s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_hybrid_planning' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_hybrid_planning', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_hybrid_planning', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/hybrid_planning', 'symlink_install': False, 'test_result_base': None} -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_target' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_clean_cache' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_clean_first' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'cmake_force_configure' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'ament_cmake_args' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'catkin_cmake_args' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_resources_prbt_pg70_support' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.317s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_resources_prbt_pg70_support' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_pg70_support', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_pg70_support', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_pg70_support', 'symlink_install': False, 'test_result_base': None} -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_target' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_clean_cache' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_clean_first' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'cmake_force_configure' from command line to 'False' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'ament_cmake_args' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'catkin_cmake_args' from command line to 'None' -[0.317s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros_visualization' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.317s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros_visualization' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros_visualization', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros_visualization', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/visualization', 'symlink_install': False, 'test_result_base': None} -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_target' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_clean_cache' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_clean_first' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'cmake_force_configure' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'ament_cmake_args' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'catkin_cmake_args' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_servo' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.318s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_servo' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_servo', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_servo', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/moveit_servo', 'symlink_install': False, 'test_result_base': None} -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_target' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_clean_cache' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_clean_first' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'cmake_force_configure' from command line to 'False' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'ament_cmake_args' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'catkin_cmake_args' from command line to 'None' -[0.318s] Level 5:colcon.colcon_core.verb:set package 'moveit_ros' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.318s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_ros' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_ros', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_ros', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_ros/moveit_ros', 'symlink_install': False, 'test_result_base': None} -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_target' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_clean_cache' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_clean_first' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'cmake_force_configure' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'ament_cmake_args' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'catkin_cmake_args' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'moveit_setup_assistant' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.319s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_setup_assistant' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_setup_assistant', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_setup_assistant', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_setup_assistant', 'symlink_install': False, 'test_result_base': None} -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_target' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_clean_cache' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_clean_first' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'cmake_force_configure' from command line to 'False' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'ament_cmake_args' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'catkin_cmake_args' from command line to 'None' -[0.319s] Level 5:colcon.colcon_core.verb:set package 'pilz_industrial_motion_planner' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.319s] DEBUG:colcon.colcon_core.verb:Building package 'pilz_industrial_motion_planner' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/pilz_industrial_motion_planner', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/pilz_industrial_motion_planner', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/pilz_industrial_motion_planner', 'symlink_install': False, 'test_result_base': None} -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_target' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_clean_cache' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_clean_first' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'cmake_force_configure' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'ament_cmake_args' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'catkin_cmake_args' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit_planners' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.320s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_planners' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_planners', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_planners', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_planners/moveit_planners', 'symlink_install': False, 'test_result_base': None} -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_target' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_clean_cache' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_clean_first' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'cmake_force_configure' from command line to 'False' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'ament_cmake_args' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'catkin_cmake_args' from command line to 'None' -[0.320s] Level 5:colcon.colcon_core.verb:set package 'moveit' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.320s] DEBUG:colcon.colcon_core.verb:Building package 'moveit' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit', 'symlink_install': False, 'test_result_base': None} -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_args' from command line to '['-DCMAKE_BUILD_TYPE=Release']' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_target' from command line to 'None' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_clean_cache' from command line to 'False' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_clean_first' from command line to 'False' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'cmake_force_configure' from command line to 'False' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'ament_cmake_args' from command line to 'None' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'catkin_cmake_args' from command line to 'None' -[0.321s] Level 5:colcon.colcon_core.verb:set package 'moveit_runtime' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.321s] DEBUG:colcon.colcon_core.verb:Building package 'moveit_runtime' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/henry/ws_moveit2/src/moveit2/build/moveit_runtime', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': ['-DCMAKE_BUILD_TYPE=Release'], 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/henry/ws_moveit2/src/moveit2/install/moveit_runtime', 'merge_install': False, 'path': '/home/henry/ws_moveit2/src/moveit2/moveit_runtime', 'symlink_install': False, 'test_result_base': None} -[0.321s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor -[0.322s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete -[0.323s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_common' with build type 'ament_cmake' -[0.323s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_common' -[0.326s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems -[0.326s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.326s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.328s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' with build type 'ament_python' -[0.328s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_configs_utils', 'ament_prefix_path') -[0.329s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.ps1' -[0.329s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.dsv' -[0.330s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/ament_prefix_path.sh' -[0.330s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.331s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.332s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support' with build type 'ament_cmake' -[0.332s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support' -[0.332s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.332s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.340s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -[0.499s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' -[0.499s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.499s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.504s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -[0.634s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -[0.636s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -[0.656s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -[0.672s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common -[0.678s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_common) -[0.679s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common -[0.681s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake module files -[0.681s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake config files -[0.682s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_common', 'cmake_prefix_path') -[0.682s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1' -[0.682s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv' -[0.682s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh' -[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' -[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/pkgconfig/moveit_common.pc' -[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/python3.10/site-packages' -[0.683s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' -[0.684s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.ps1' -[0.684s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv' -[0.684s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.sh' -[0.685s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.bash' -[0.685s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.zsh' -[0.686s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/colcon-core/packages/moveit_common) -[0.697s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_common) -[0.698s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake module files -[0.698s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common' for CMake config files -[0.699s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_common', 'cmake_prefix_path') -[0.699s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.ps1' -[0.700s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.dsv' -[0.700s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/hook/cmake_prefix_path.sh' -[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' -[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/pkgconfig/moveit_common.pc' -[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/lib/python3.10/site-packages' -[0.701s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/bin' -[0.702s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.ps1' -[0.702s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv' -[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.sh' -[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.bash' -[0.703s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.zsh' -[0.703s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/colcon-core/packages/moveit_common) -[0.704s] INFO:colcon.colcon_ros.task.ament_cmake.build:Building ROS package in '/home/henry/ws_moveit2/src/moveit2/moveit_core' with build type 'ament_cmake' -[0.704s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/henry/ws_moveit2/src/moveit2/moveit_core' -[0.705s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.705s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.711s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core -[0.838s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed -[0.953s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -[0.954s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -[0.977s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -[0.988s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -[1.004s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_resources_prbt_support) -[1.005s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake module files -[1.005s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -[1.006s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake config files -[1.006s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_resources_prbt_support', 'cmake_prefix_path') -[1.006s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1' -[1.006s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv' -[1.007s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh' -[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' -[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/pkgconfig/moveit_resources_prbt_support.pc' -[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/python3.10/site-packages' -[1.007s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' -[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1' -[1.008s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv' -[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh' -[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash' -[1.008s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh' -[1.009s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support) -[1.020s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_resources_prbt_support) -[1.020s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake module files -[1.021s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support' for CMake config files -[1.021s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_resources_prbt_support', 'cmake_prefix_path') -[1.021s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.ps1' -[1.022s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.dsv' -[1.022s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/hook/cmake_prefix_path.sh' -[1.022s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' -[1.022s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/pkgconfig/moveit_resources_prbt_support.pc' -[1.023s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/lib/python3.10/site-packages' -[1.023s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/bin' -[1.023s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.ps1' -[1.024s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv' -[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.sh' -[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.bash' -[1.024s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.zsh' -[1.025s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/colcon-core/packages/moveit_resources_prbt_support) -[1.030s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils' for CMake module files -[1.031s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed -[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils' for CMake config files -[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib' -[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/bin' -[1.031s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/pkgconfig/moveit_configs_utils.pc' -[1.032s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages' -[1.032s] Level 1:colcon.colcon_core.shell:create_environment_hook('moveit_configs_utils', 'pythonpath') -[1.032s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.ps1' -[1.032s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.dsv' -[1.033s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/hook/pythonpath.sh' -[1.033s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/bin' -[1.033s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_configs_utils) -[1.033s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.ps1' -[1.034s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.dsv' -[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.sh' -[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.bash' -[1.034s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/package.zsh' -[1.034s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/colcon-core/packages/moveit_configs_utils) -[2.433s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core -[2.439s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(moveit_core) -[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core' for CMake module files -[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core' for CMake config files -[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/bin' -[2.440s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/lib/pkgconfig/moveit_core.pc' -[2.441s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/lib/python3.10/site-packages' -[2.441s] Level 1:colcon.colcon_core.environment:checking '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/bin' -[2.441s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.ps1' -[2.441s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.dsv' -[2.441s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.sh' -[2.442s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.bash' -[2.442s] INFO:colcon.colcon_core.shell:Creating package script '/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/moveit_core/package.zsh' -[2.442s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/henry/ws_moveit2/src/moveit2/install/moveit_core/share/colcon-core/packages/moveit_core) -[2.452s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop -[2.452s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed -[2.453s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '1' -[2.453s] DEBUG:colcon.colcon_core.event_reactor:joining thread -[2.457s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems -[2.457s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems -[2.457s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2' -[2.467s] DEBUG:colcon.colcon_core.event_reactor:joined thread -[2.468s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.ps1' -[2.469s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/henry/ws_moveit2/src/moveit2/install/_local_setup_util_ps1.py' -[2.469s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.ps1' -[2.470s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.sh' -[2.471s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/henry/ws_moveit2/src/moveit2/install/_local_setup_util_sh.py' -[2.471s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.sh' -[2.472s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.bash' -[2.473s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.bash' -[2.473s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/henry/ws_moveit2/src/moveit2/install/local_setup.zsh' -[2.474s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/henry/ws_moveit2/src/moveit2/install/setup.zsh' diff --git a/log/build_2022-06-08_12-52-32/moveit_common/command.log b/log/build_2022-06-08_12-52-32/moveit_common/command.log deleted file mode 100644 index 81f689bf6b..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_common/command.log +++ /dev/null @@ -1,6 +0,0 @@ -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stderr.log b/log/build_2022-06-08_12-52-32/moveit_common/stderr.log deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stdout.log b/log/build_2022-06-08_12-52-32/moveit_common/stdout.log deleted file mode 100644 index c29c3332f0..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_common/stdout.log +++ /dev/null @@ -1,28 +0,0 @@ --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) --- Added test 'copyright' to check source files copyright and LICENSE --- Added test 'lint_cmake' to check CMake code style --- Added test 'xmllint' to check XML markup files --- Configuring done --- Generating done --- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common --- Install configuration: "Release" --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml --- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake diff --git a/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log deleted file mode 100644 index c29c3332f0..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_common/stdout_stderr.log +++ /dev/null @@ -1,28 +0,0 @@ --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) --- Added test 'copyright' to check source files copyright and LICENSE --- Added test 'lint_cmake' to check CMake code style --- Added test 'xmllint' to check XML markup files --- Configuring done --- Generating done --- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common --- Install configuration: "Release" --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml --- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake diff --git a/log/build_2022-06-08_12-52-32/moveit_common/streams.log b/log/build_2022-06-08_12-52-32/moveit_common/streams.log deleted file mode 100644 index 999e9e267a..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_common/streams.log +++ /dev/null @@ -1,34 +0,0 @@ -[0.016s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -[0.178s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) -[0.178s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter -[0.242s] -- Found ament_lint_auto: 0.12.4 (/opt/ros/humble/share/ament_lint_auto/cmake) -[0.302s] -- Added test 'copyright' to check source files copyright and LICENSE -[0.304s] -- Added test 'lint_cmake' to check CMake code style -[0.305s] -- Added test 'xmllint' to check XML markup files -[0.306s] -- Configuring done -[0.308s] -- Generating done -[0.308s] -- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_common -[0.310s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_common -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_common -[0.311s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -[0.332s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_common -- -j8 -l8 -[0.348s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common -[0.352s] -- Install configuration: "Release" -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/package_run_dependencies/moveit_common -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/parent_prefix_path/moveit_common -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.sh -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/ament_prefix_path.dsv -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.sh -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/environment/path.dsv -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.bash -[0.352s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.sh -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.zsh -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/local_setup.dsv -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.dsv -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/ament_index/resource_index/packages/moveit_common -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_common-extras.cmake -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig.cmake -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_commonConfig-version.cmake -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/package.xml -[0.353s] -- Up-to-date: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake -[0.353s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake/moveit_package.cmake -[0.355s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_common' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_common diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log deleted file mode 100644 index 8659525b8a..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_configs_utils/command.log +++ /dev/null @@ -1,2 +0,0 @@ -Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed -Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log deleted file mode 100644 index 89805d747e..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stderr.log +++ /dev/null @@ -1,2 +0,0 @@ -/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. - warnings.warn( diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log deleted file mode 100644 index 6e86d07a99..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout.log +++ /dev/null @@ -1,46 +0,0 @@ -running egg_info -creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info -writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO -writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt -writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt -writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt -writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt -writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -running build -running build_py -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -running install -running install_lib -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc -running install_data -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -running install_egg_info -Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info -running install_scripts -writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log deleted file mode 100644 index 514c7258cb..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_configs_utils/stdout_stderr.log +++ /dev/null @@ -1,48 +0,0 @@ -running egg_info -creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info -writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO -writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt -writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt -writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt -writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt -writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -running build -running build_py -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib -creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -running install -/usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. - warnings.warn( -running install_lib -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc -byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc -running install_data -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils -creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -running install_egg_info -Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info -running install_scripts -writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' diff --git a/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log b/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log deleted file mode 100644 index afef0f1b6f..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_configs_utils/streams.log +++ /dev/null @@ -1,50 +0,0 @@ -[0.509s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed -[0.661s] running egg_info -[0.662s] creating ../build/moveit_configs_utils/moveit_configs_utils.egg-info -[0.662s] writing ../build/moveit_configs_utils/moveit_configs_utils.egg-info/PKG-INFO -[0.662s] writing dependency_links to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/dependency_links.txt -[0.662s] writing entry points to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/entry_points.txt -[0.662s] writing requirements to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/requires.txt -[0.662s] writing top-level names to ../build/moveit_configs_utils/moveit_configs_utils.egg-info/top_level.txt -[0.662s] writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -[0.663s] reading manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -[0.664s] writing manifest file '../build/moveit_configs_utils/moveit_configs_utils.egg-info/SOURCES.txt' -[0.664s] running build -[0.664s] running build_py -[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build -[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib -[0.664s] creating /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -[0.665s] copying moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -[0.665s] copying moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -[0.665s] copying moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -[0.665s] copying moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils -[0.665s] running install -[0.666s] /usr/lib/python3/dist-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools. -[0.666s] warnings.warn( -[0.666s] running install_lib -[0.666s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -[0.666s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launches.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/moveit_configs_builder.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/__init__.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -[0.667s] copying /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build/lib/moveit_configs_utils/launch_utils.py -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils -[0.667s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launches.py to launches.cpython-310.pyc -[0.667s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/moveit_configs_builder.py to moveit_configs_builder.cpython-310.pyc -[0.668s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/__init__.py to __init__.cpython-310.pyc -[0.668s] byte-compiling /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils/launch_utils.py to launch_utils.cpython-310.pyc -[0.669s] running install_data -[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index -[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index -[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -[0.669s] copying resource/moveit_configs_utils -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/ament_index/resource_index/packages -[0.669s] copying package.xml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils -[0.669s] creating /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.669s] copying default_configs/ompl_defaults.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.669s] copying default_configs/pilz_industrial_motion_planner_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.669s] copying default_configs/chomp_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.670s] copying default_configs/trajopt_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.670s] copying default_configs/ompl_planning.yaml -> /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/share/moveit_configs_utils/default_configs -[0.670s] running install_egg_info -[0.670s] Copying ../build/moveit_configs_utils/moveit_configs_utils.egg-info to /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages/moveit_configs_utils-2.5.0-py3.10.egg-info -[0.671s] running install_scripts -[0.684s] writing list of installed files to '/home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log' -[0.702s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/moveit_configs_utils' returned '0': PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ PYTHONPATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils/lib/python3.10/site-packages:${PYTHONPATH} /usr/bin/python3 setup.py egg_info --egg-base ../build/moveit_configs_utils build --build-base /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/build install --prefix /home/henry/ws_moveit2/src/moveit2/install/moveit_configs_utils --record /home/henry/ws_moveit2/src/moveit2/build/moveit_configs_utils/install.log --single-version-externally-managed diff --git a/log/build_2022-06-08_12-52-32/moveit_core/command.log b/log/build_2022-06-08_12-52-32/moveit_core/command.log deleted file mode 100644 index 263b877f02..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_core/command.log +++ /dev/null @@ -1,2 +0,0 @@ -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stderr.log b/log/build_2022-06-08_12-52-32/moveit_core/stderr.log deleted file mode 100644 index e23dc64dc5..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_core/stderr.log +++ /dev/null @@ -1,17 +0,0 @@ -CMake Error at CMakeLists.txt:43 (find_package): - By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has - asked CMake to find a package configuration file provided by "srdfdom", but - CMake did not find one. - - Could not find a package configuration file provided by "srdfdom" with any - of the following names: - - srdfdomConfig.cmake - srdfdom-config.cmake - - Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set - "srdfdom_DIR" to a directory containing one of the above files. If - "srdfdom" provides a separate development package or SDK, be sure it has - been installed. - - diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stdout.log b/log/build_2022-06-08_12-52-32/moveit_core/stdout.log deleted file mode 100644 index 47ae7f06b6..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_core/stdout.log +++ /dev/null @@ -1,47 +0,0 @@ --- The CXX compiler identification is GNU 11.2.0 --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so --- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) --- BACKWARD_HAS_UNWIND=1 --- BACKWARD_HAS_BACKTRACE=0 --- BACKWARD_HAS_BACKTRACE_SYMBOL=0 --- BACKWARD_HAS_DW=1 --- BACKWARD_HAS_BFD=0 --- Found Backward: /opt/ros/humble/share/backward_ros/cmake --- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) --- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) --- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) --- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) --- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c --- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp --- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) --- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) --- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") --- Found FastRTPS: /opt/ros/humble/include --- Using RMW implementation 'rmw_fastrtps_cpp' as default --- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) --- Found Eigen3: TRUE (found version "3.4.0") --- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") --- Checking for module 'fcl>=0.5.0' --- Found fcl, version 0.7.0 --- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") --- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) --- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) --- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) --- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) --- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) --- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) --- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) --- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem --- library: /usr/lib/x86_64-linux-gnu/libcurl.so --- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) --- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) --- Configuring incomplete, errors occurred! -See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". diff --git a/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log deleted file mode 100644 index eb621a2b67..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_core/stdout_stderr.log +++ /dev/null @@ -1,64 +0,0 @@ --- The CXX compiler identification is GNU 11.2.0 --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so --- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) --- BACKWARD_HAS_UNWIND=1 --- BACKWARD_HAS_BACKTRACE=0 --- BACKWARD_HAS_BACKTRACE_SYMBOL=0 --- BACKWARD_HAS_DW=1 --- BACKWARD_HAS_BFD=0 --- Found Backward: /opt/ros/humble/share/backward_ros/cmake --- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) --- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) --- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) --- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) --- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c --- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp --- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) --- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) --- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") --- Found FastRTPS: /opt/ros/humble/include --- Using RMW implementation 'rmw_fastrtps_cpp' as default --- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) --- Found Eigen3: TRUE (found version "3.4.0") --- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") --- Checking for module 'fcl>=0.5.0' --- Found fcl, version 0.7.0 --- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") --- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) --- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) --- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) --- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) --- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) --- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) --- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) --- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem --- library: /usr/lib/x86_64-linux-gnu/libcurl.so --- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) --- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) -CMake Error at CMakeLists.txt:43 (find_package): - By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has - asked CMake to find a package configuration file provided by "srdfdom", but - CMake did not find one. - - Could not find a package configuration file provided by "srdfdom" with any - of the following names: - - srdfdomConfig.cmake - srdfdom-config.cmake - - Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set - "srdfdom_DIR" to a directory containing one of the above files. If - "srdfdom" provides a separate development package or SDK, be sure it has - been installed. - - --- Configuring incomplete, errors occurred! -See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". diff --git a/log/build_2022-06-08_12-52-32/moveit_core/streams.log b/log/build_2022-06-08_12-52-32/moveit_core/streams.log deleted file mode 100644 index 45601f0c62..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_core/streams.log +++ /dev/null @@ -1,66 +0,0 @@ -[0.005s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core -[0.053s] -- The CXX compiler identification is GNU 11.2.0 -[0.059s] -- Detecting CXX compiler ABI info -[0.101s] -- Detecting CXX compiler ABI info - done -[0.106s] -- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped -[0.106s] -- Detecting CXX compile features -[0.106s] -- Detecting CXX compile features - done -[0.107s] -- Found moveit_common: 2.5.1 (/home/henry/ws_moveit2/src/moveit2/install/moveit_common/share/moveit_common/cmake) -[0.108s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) -[0.220s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter -[0.330s] -- Found libdw: /usr/lib/x86_64-linux-gnu/libdw.so -[0.333s] -- Could NOT find libbfd (missing: LIBBFD_LIBRARY LIBBFD_INCLUDE_DIR) -[0.333s] -- BACKWARD_HAS_UNWIND=1 -[0.333s] -- BACKWARD_HAS_BACKTRACE=0 -[0.333s] -- BACKWARD_HAS_BACKTRACE_SYMBOL=0 -[0.333s] -- BACKWARD_HAS_DW=1 -[0.333s] -- BACKWARD_HAS_BFD=0 -[0.334s] -- Found Backward: /opt/ros/humble/share/backward_ros/cmake -[0.336s] -- Found rclcpp: 16.0.1 (/opt/ros/humble/share/rclcpp/cmake) -[0.386s] -- Found rosidl_generator_c: 3.1.3 (/opt/ros/humble/share/rosidl_generator_c/cmake) -[0.390s] -- Found rosidl_adapter: 3.1.3 (/opt/ros/humble/share/rosidl_adapter/cmake) -[0.398s] -- Found rosidl_generator_cpp: 3.1.3 (/opt/ros/humble/share/rosidl_generator_cpp/cmake) -[0.413s] -- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c -[0.431s] -- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp -[0.487s] -- Found rmw_implementation_cmake: 6.1.0 (/opt/ros/humble/share/rmw_implementation_cmake/cmake) -[0.490s] -- Found rmw_fastrtps_cpp: 6.2.1 (/opt/ros/humble/share/rmw_fastrtps_cpp/cmake) -[0.555s] -- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.2") -[0.570s] -- Found FastRTPS: /opt/ros/humble/include -[0.596s] -- Using RMW implementation 'rmw_fastrtps_cpp' as default -[0.704s] -- Found eigen3_cmake_module: 0.1.1 (/opt/ros/humble/share/eigen3_cmake_module/cmake) -[0.709s] -- Found Eigen3: TRUE (found version "3.4.0") -[0.711s] -- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.2") -[0.712s] -- Checking for module 'fcl>=0.5.0' -[0.718s] -- Found fcl, version 0.7.0 -[0.741s] -- Found Bullet: /usr/lib/x86_64-linux-gnu/libBulletDynamics.so (Required is at least version "2.87") -[0.742s] -- Found angles: 1.13.0 (/opt/ros/humble/share/angles/cmake) -[0.754s] -- Found urdf: 2.6.0 (/opt/ros/humble/share/urdf/cmake) -[0.775s] -- Found tf2_eigen: 0.25.0 (/opt/ros/humble/share/tf2_eigen/cmake) -[1.082s] -- Found tf2_kdl: 0.25.0 (/opt/ros/humble/share/tf2_kdl/cmake) -[1.094s] -- Found tf2_geometry_msgs: 0.25.0 (/opt/ros/humble/share/tf2_geometry_msgs/cmake) -[1.106s] -- Found eigen_stl_containers: 1.0.0 (/opt/ros/humble/share/eigen_stl_containers/cmake) -[1.108s] -- Found geometric_shapes: 2.1.3 (/opt/ros/humble/share/geometric_shapes/cmake) -[1.116s] -- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.74.0/BoostConfig.cmake (found version "1.74.0") found components: filesystem -[1.165s] -- library: /usr/lib/x86_64-linux-gnu/libcurl.so -[1.354s] -- Found kdl_parser: 2.6.2 (/opt/ros/humble/share/kdl_parser/cmake) -[1.357s] -- Found moveit_msgs: 2.2.0 (/opt/ros/humble/share/moveit_msgs/cmake) -[1.720s] CMake Error at CMakeLists.txt:43 (find_package): -[1.720s] By not providing "Findsrdfdom.cmake" in CMAKE_MODULE_PATH this project has -[1.720s] asked CMake to find a package configuration file provided by "srdfdom", but -[1.720s] CMake did not find one. -[1.720s] -[1.720s] Could not find a package configuration file provided by "srdfdom" with any -[1.720s] of the following names: -[1.720s] -[1.720s] srdfdomConfig.cmake -[1.720s] srdfdom-config.cmake -[1.720s] -[1.720s] Add the installation prefix of "srdfdom" to CMAKE_PREFIX_PATH or set -[1.720s] "srdfdom_DIR" to a directory containing one of the above files. If -[1.720s] "srdfdom" provides a separate development package or SDK, be sure it has -[1.721s] been installed. -[1.721s] -[1.721s]  -[1.721s] -- Configuring incomplete, errors occurred! -[1.721s] See also "/home/henry/ws_moveit2/src/moveit2/build/moveit_core/CMakeFiles/CMakeOutput.log". -[1.727s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_core' returned '1': AMENT_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:${AMENT_PREFIX_PATH} CMAKE_PREFIX_PATH=/home/henry/ws_moveit2/src/moveit2/install/moveit_common:/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_core -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_core diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log deleted file mode 100644 index 114f84f6ae..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/command.log +++ /dev/null @@ -1,6 +0,0 @@ -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stderr.log deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log deleted file mode 100644 index 09c37a964b..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout.log +++ /dev/null @@ -1,57 +0,0 @@ --- The C compiler identification is GNU 11.2.0 --- The CXX compiler identification is GNU 11.2.0 --- Detecting C compiler ABI info --- Detecting C compiler ABI info - done --- Check for working C compiler: /usr/lib/ccache/cc - skipped --- Detecting C compile features --- Detecting C compile features - done --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Configuring done --- Generating done --- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support --- Install configuration: "Release" --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log deleted file mode 100644 index 09c37a964b..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/stdout_stderr.log +++ /dev/null @@ -1,57 +0,0 @@ --- The C compiler identification is GNU 11.2.0 --- The CXX compiler identification is GNU 11.2.0 --- Detecting C compiler ABI info --- Detecting C compiler ABI info - done --- Check for working C compiler: /usr/lib/ccache/cc - skipped --- Detecting C compile features --- Detecting C compile features - done --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) --- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter --- Configuring done --- Generating done --- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support --- Install configuration: "Release" --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml --- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml diff --git a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log b/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log deleted file mode 100644 index 2f5d32631e..0000000000 --- a/log/build_2022-06-08_12-52-32/moveit_resources_prbt_support/streams.log +++ /dev/null @@ -1,63 +0,0 @@ -[0.171s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -[0.239s] -- The C compiler identification is GNU 11.2.0 -[0.278s] -- The CXX compiler identification is GNU 11.2.0 -[0.285s] -- Detecting C compiler ABI info -[0.322s] -- Detecting C compiler ABI info - done -[0.327s] -- Check for working C compiler: /usr/lib/ccache/cc - skipped -[0.327s] -- Detecting C compile features -[0.327s] -- Detecting C compile features - done -[0.329s] -- Detecting CXX compiler ABI info -[0.373s] -- Detecting CXX compiler ABI info - done -[0.382s] -- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped -[0.382s] -- Detecting CXX compile features -[0.382s] -- Detecting CXX compile features - done -[0.384s] -- Found ament_cmake: 1.3.2 (/opt/ros/humble/share/ament_cmake/cmake) -[0.516s] -- Found Python3: /usr/bin/python3.10 (found version "3.10.4") found components: Interpreter -[0.613s] -- Configuring done -[0.615s] -- Generating done -[0.615s] -- Build files have been written to: /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -[0.620s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake /home/henry/ws_moveit2/src/moveit2/moveit_planners/test_configs/prbt_support -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support -[0.621s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -[0.644s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --build /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -- -j8 -l8 -[0.655s] Invoking command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support -[0.659s] -- Install configuration: "Release" -[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/package_run_dependencies/moveit_resources_prbt_support -[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/parent_prefix_path/moveit_resources_prbt_support -[0.660s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.sh -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/ament_prefix_path.dsv -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.sh -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/environment/path.dsv -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.bash -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.sh -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.zsh -[0.661s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/local_setup.dsv -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.dsv -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/ament_index/resource_index/packages/moveit_resources_prbt_support -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig.cmake -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/cmake/moveit_resources_prbt_supportConfig-version.cmake -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/package.xml -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.ros2_control.xacro -[0.662s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/simple_gripper_brackets.urdf.xacro -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt_macro.xacro -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/urdf/prbt.xacro -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.stl -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.stl -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.dae -[0.663s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/foot.dae -[0.665s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_4.dae -[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_5.stl -[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.stl -[0.666s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.stl -[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.stl -[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.stl -[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_3.dae -[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/flange.dae -[0.667s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_2.dae -[0.669s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/meshes/link_1.dae -[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config -[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/prbt_0_1.dcf -[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_driver.yaml -[0.670s] -- Installing: /home/henry/ws_moveit2/src/moveit2/install/moveit_resources_prbt_support/share/moveit_resources_prbt_support/config/manipulator_controller.yaml -[0.672s] Invoked command in '/home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support' returned '0': CMAKE_PREFIX_PATH=/opt/ros/humble PS1=\[\033[34m\][\h]\[\033[0m\]\[\033[0;32m\]$(parse_vc_branch_and_add_brackets)\[\033[0m\] \W$ /usr/bin/cmake --install /home/henry/ws_moveit2/src/moveit2/build/moveit_resources_prbt_support diff --git a/log/latest b/log/latest deleted file mode 120000 index b57d247c77..0000000000 --- a/log/latest +++ /dev/null @@ -1 +0,0 @@ -latest_build \ No newline at end of file diff --git a/log/latest_build b/log/latest_build deleted file mode 120000 index 2886a6fca1..0000000000 --- a/log/latest_build +++ /dev/null @@ -1 +0,0 @@ -build_2022-06-08_12-52-32 \ No newline at end of file From 256c020f185dd1a5f7c31cb3d95ddc3d67a74626 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 9 Jun 2022 14:51:50 -0600 Subject: [PATCH 07/43] auto formatting --- .../include/moveit/kinematics_base/kinematics_base.h | 2 +- .../planning_request_adapter.h | 2 +- .../include/moveit/planning_scene/planning_scene.h | 5 ++--- .../include/moveit/robot_state/robot_state.h | 2 +- .../cached_ik_kinematics_plugin/src/ik_cache.cpp | 3 ++- .../include/moveit/benchmarks/BenchmarkExecutor.h | 2 +- .../pick_place/src/approach_and_translate_stage.cpp | 6 +++--- .../planning_scene_monitor/planning_scene_monitor.h | 4 ++-- .../src/planning_scene_monitor.cpp | 8 ++++---- .../src/trajectory_execution_manager.cpp | 2 +- .../include/moveit/robot_interaction/interaction.h | 2 +- .../robot_interaction/test/locked_robot_state_test.cpp | 10 ++++++++-- .../src/tools/compute_default_collisions.cpp | 7 +++---- 13 files changed, 30 insertions(+), 25 deletions(-) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 953e7bdb1a..b56f9d2a56 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -151,7 +151,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase /** @brief Signature for a callback to validate an IK solution. Typically used for collision checking. */ using IKCallbackFn = std::function&, - moveit_msgs::msg::MoveItErrorCodes&)>; + moveit_msgs::msg::MoveItErrorCodes&)>; /** * @brief Given a desired pose of the end-effector, compute the joint angles to reach it diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index 0eb9500309..67aebd9d4c 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -51,7 +51,7 @@ class PlanningRequestAdapter public: using PlannerFn = std::function; + planning_interface::MotionPlanResponse&)>; PlanningRequestAdapter() { diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 09f9129f6e..2359eeb787 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -75,8 +75,7 @@ typedef std::function StateFeasibil The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the first state and end at the second state. The third argument indicates whether the check should be verbose or not. */ -using MotionFeasibilityFn = - std::function; +using MotionFeasibilityFn = std::function; /** \brief A map from object names (e.g., attached bodies, collision objects) to their colors */ using ObjectColorMap = std::map; @@ -87,7 +86,7 @@ using ObjectTypeMap = std::map { public: diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 1fdb7d8d29..d7b0a3e409 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -66,7 +66,7 @@ MOVEIT_CLASS_FORWARD(RobotState); // Defines RobotStatePtr, ConstPtr, WeakPtr.. the state is valid or not. Returns true if the state is valid. This call is allowed to modify \e robot_state (e.g., set \e joint_group_variable_values) */ typedef std::function + const double* joint_group_variable_values)> GroupStateValidityCallbackFn; /** \brief Representation of a robot's state. This includes position, diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index 03518e9aed..87183ac63e 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -73,7 +73,8 @@ void IKCache::initializeCache(const std::string& robot_id, const std::string& gr // use mutex lock for rest of initialization std::lock_guard slock(lock_); // determine cache file name - std::filesystem::path prefix(!cached_ik_path.empty() ? std::filesystem::path(cached_ik_path) : std::filesystem::current_path()); + std::filesystem::path prefix(!cached_ik_path.empty() ? std::filesystem::path(cached_ik_path) : + std::filesystem::current_path()); // create cache directory if necessary std::filesystem::create_directories(prefix); diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index a6526f1e5f..df3b5c9f8a 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -89,7 +89,7 @@ class BenchmarkExecutor /// Definition of a post-run benchmark event function. Invoked immediately after each planner calls solve(). typedef std::function + const planning_interface::MotionPlanDetailedResponse& response, PlannerRunData& run_data)> PostRunEventFunction; BenchmarkExecutor(const rclcpp::Node::SharedPtr& node, diff --git a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp index 4d04929a02..c9888ed794 100644 --- a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp +++ b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp @@ -147,9 +147,9 @@ bool executeAttachObject(const ManipulationPlanSharedDataConstPtr& shared_plan_d ok = ps->processAttachedCollisionObjectMsg(msg); } motion_plan.planning_scene_monitor_->triggerSceneUpdateEvent( - (planning_scene_monitor::PlanningSceneMonitor:: - SceneUpdateType)(planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY + - planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE)); + (planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType)( + planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY + + planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE)); return ok; } diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index d2724c8c5d..c544ee91af 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -476,7 +476,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: planning_scene::PlanningScenePtr scene_; planning_scene::PlanningSceneConstPtr scene_const_; planning_scene::PlanningScenePtr parent_scene_; /// if diffs are monitored, this is the pointer to the parent scene - std::shared_mutex scene_update_mutex_; /// mutex for stored scene + std::shared_mutex scene_update_mutex_; /// mutex for stored scene rclcpp::Time last_update_time_; /// Last time the state was updated rclcpp::Time last_robot_motion_time_; /// Last time the robot has moved @@ -548,7 +548,7 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost: /// lock access to update_callbacks_ std::recursive_mutex update_lock_; std::vector > update_callbacks_; /// List of callbacks to trigger when updates - /// are received + /// are received private: void getUpdatedFrameTransforms(std::vector& transforms); diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 60b1276243..73995711c2 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -438,10 +438,10 @@ void PlanningSceneMonitor::scenePublishingThread() } } std::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the - // transform cache to - // update while we are - // potentially changing - // attached bodies + // transform cache to + // update while we are + // potentially changing + // attached bodies scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback()); scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn()); scene_->pushDiffs(parent_scene_); diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 74e5bc431a..2976db5742 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -1282,7 +1282,7 @@ void TrajectoryExecutionManager::execute(const ExecutionCompleteCallback& callba // start the execution thread execution_complete_ = false; execution_thread_ = std::make_unique(&TrajectoryExecutionManager::executeThread, this, callback, - part_callback, auto_clear); + part_callback, auto_clear); } moveit_controller_manager::ExecutionStatus TrajectoryExecutionManager::waitForExecution() diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 13733a7039..99e6e5040b 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -99,7 +99,7 @@ typedef std::function + const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)> ProcessFeedbackFn; /// Type of function for updating marker pose for new state. diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index 608f648456..adf5021907 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -532,9 +532,15 @@ static void runThreads(int ncheck, int nset, int nmod) // wait for all threads to finish for (int i = 0; i < p; ++i) { - if (threads[i]->joinable()) {threads[i]->join();} + if (threads[i]->joinable()) + { + threads[i]->join(); + } + } + if (wthread.joinable()) + { + wthread.join(); } - if (wthread.joinable()) {wthread.join();} // clean up for (int i = 0; i < p; ++i) diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 7252672ca6..1bb4b781a6 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -51,9 +51,8 @@ namespace moveit_setup_assistant const std::unordered_map REASONS_TO_STRING = boost::assign::map_list_of(NEVER, "Never")( DEFAULT, "Default")(ADJACENT, "Adjacent")(ALWAYS, "Always")(USER, "User")(NOT_DISABLED, "Not Disabled"); -const std::unordered_map REASONS_FROM_STRING = - boost::assign::map_list_of("Never", NEVER)("Default", DEFAULT)( - "Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED); +const std::unordered_map REASONS_FROM_STRING = boost::assign::map_list_of("Never", NEVER)( + "Default", DEFAULT)("Adjacent", ADJACENT)("Always", ALWAYS)("User", USER)("Not Disabled", NOT_DISABLED); // Used for logging static const rclcpp::Logger LOGGER = rclcpp::get_logger("collision_updater"); @@ -557,7 +556,7 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce unsigned int num_disabled = 0; boost::thread_group bgroup; // create a group of threads - std::mutex lock; // used for sharing the same data structures + std::mutex lock; // used for sharing the same data structures int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have? // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " << From fff4fdde22c3f72a4c04b2d4815e947407cede28 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 9 Jun 2022 15:22:44 -0600 Subject: [PATCH 08/43] fixed clang format --- .../pick_place/src/approach_and_translate_stage.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp index c9888ed794..4d04929a02 100644 --- a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp +++ b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp @@ -147,9 +147,9 @@ bool executeAttachObject(const ManipulationPlanSharedDataConstPtr& shared_plan_d ok = ps->processAttachedCollisionObjectMsg(msg); } motion_plan.planning_scene_monitor_->triggerSceneUpdateEvent( - (planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType)( - planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY + - planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE)); + (planning_scene_monitor::PlanningSceneMonitor:: + SceneUpdateType)(planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY + + planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE)); return ok; } From 58f3828224f051b40ce0b66d217ae4335703a5d2 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 9 Jun 2022 16:14:44 -0600 Subject: [PATCH 09/43] changes solution callback empty check to work with std::function --- .../templates/ikfast61_moveit_plugin_template.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp index bf47a3f9af..b95d248e77 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp +++ b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp @@ -901,7 +901,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); // check for collisions if a callback is provided - if (!solution_callback.empty()) + if (solution_callback) { for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) { @@ -1029,7 +1029,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik getSolution(solutions, ik_seed_state, s, solution); // This solution is within joint limits, now check if in collision (if callback provided) - if (!solution_callback.empty()) + if (solution_callback) { solution_callback(ik_pose, solution, error_code); } From 190aa61aa48bd504b569767e27410f907339eeca Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Fri, 10 Jun 2022 10:03:46 -0600 Subject: [PATCH 10/43] removed unnecessary comment --- .../include/moveit/planning_scene/planning_scene.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 2359eeb787..52d7e65158 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -86,7 +86,7 @@ using ObjectTypeMap = std::map { public: From 95ce62440b47d6df78e73497039caa0ff05d7d8a Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Fri, 10 Jun 2022 13:29:01 -0600 Subject: [PATCH 11/43] removing unnecessary boost inclusions --- .../include/moveit/collision_detection/collision_common.h | 2 -- .../include/moveit/collision_detection/occupancy_map.h | 5 +---- .../include/moveit/collision_detection/world.h | 1 - .../collision_detection_fcl/src/collision_common.cpp | 1 - .../collision_distance_field/collision_env_distance_field.h | 1 - .../moveit/collision_distance_field/collision_env_hybrid.h | 2 -- .../src/collision_common_distance_field.cpp | 1 - .../include/moveit/kinematics_base/kinematics_base.h | 1 - moveit_core/planning_interface/src/planning_interface.cpp | 1 - .../planning_request_adapter/planning_request_adapter.h | 1 - .../include/moveit/planning_scene/planning_scene.h | 1 - moveit_core/planning_scene/test/test_collision_objects.cpp | 1 - moveit_core/planning_scene/test/test_planning_scene.cpp | 1 - .../include/moveit/robot_model/joint_model_group.h | 1 - moveit_core/robot_model/test/test.cpp | 1 - .../robot_state/include/moveit/robot_state/attached_body.h | 1 - moveit_core/robot_state/test/test_aabb.cpp | 1 - moveit_core/robot_state/test/test_kinematic_complex.cpp | 1 - moveit_core/utils/src/robot_model_test_utils.cpp | 1 - .../v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp | 3 --- .../include/moveit/kinematics_cache/kinematics_cache.h | 2 -- .../kinematics_constraint_aware.h | 3 --- .../kinematics_request_response.h | 3 --- .../cached_ik_kinematics_plugin.h | 1 - .../cached_ik_kinematics_plugin/src/ik_cache.cpp | 2 +- .../ompl/ompl_interface/src/detail/constraints_library.cpp | 1 - .../ompl/ompl_interface/test/test_state_space.cpp | 1 - .../pilz_industrial_motion_planner.h | 3 --- .../src/pilz_industrial_motion_planner.cpp | 3 --- .../unit_tests/src/unittest_planning_context_loaders.cpp | 3 --- .../test/unit_tests/src/unittest_trajectory_functions.cpp | 1 - .../include/moveit/benchmarks/BenchmarkExecutor.h | 1 - moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 1 - .../include/moveit/pick_place/manipulation_pipeline.h | 2 -- moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp | 1 - .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 1 - .../lazy_free_space_updater/lazy_free_space_updater.h | 1 - .../lazy_free_space_updater/src/lazy_free_space_updater.cpp | 4 ++-- moveit_ros/perception/mesh_filter/src/gl_renderer.cpp | 1 - .../include/moveit/point_containment_filter/shape_mask.h | 4 +--- .../include/moveit/semantic_world/semantic_world.h | 1 - .../kinematics_plugin_loader/kinematics_plugin_loader.h | 1 - .../src/kinematics_plugin_loader.cpp | 1 - .../include/moveit/plan_execution/plan_representation.h | 1 - .../src/evaluate_collision_checking_speed.cpp | 1 - .../moveit/planning_scene_monitor/current_state_monitor.h | 2 -- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 3 --- .../moveit/planning_scene_monitor/trajectory_monitor.h | 1 - moveit_ros/planning/rdf_loader/src/rdf_loader.cpp | 3 --- .../trajectory_execution_manager.h | 1 - .../src/wrap_python_planning_scene_interface.cpp | 1 - .../py_bindings_tools/src/roscpp_initializer.cpp | 1 - .../include/moveit/robot_interaction/interaction.h | 2 -- .../moveit/robot_interaction/kinematic_options_map.h | 2 -- .../include/moveit/robot_interaction/locked_robot_state.h | 2 -- .../include/moveit/robot_interaction/robot_interaction.h | 2 -- .../planning_scene_rviz_plugin/background_processing.hpp | 3 +-- .../rviz_plugin_render_tools/trajectory_visualization.h | 1 - moveit_setup_assistant/src/tools/collision_matrix_model.cpp | 6 +++--- .../src/tools/compute_default_collisions.cpp | 1 - moveit_setup_assistant/src/tools/moveit_config_data.cpp | 4 +--- .../src/widgets/configuration_files_widget.cpp | 4 +--- .../src/widgets/default_collisions_widget.h | 2 -- moveit_setup_assistant/src/widgets/setup_assistant_widget.h | 1 - moveit_setup_assistant/src/widgets/start_screen_widget.cpp | 3 --- moveit_setup_assistant/test/moveit_config_data_test.cpp | 2 -- 66 files changed, 11 insertions(+), 108 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 42d606d28b..c08342a360 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -36,8 +36,6 @@ #pragma once -#include -#include #include #include #include diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index adbab5e77d..746b9d2b0b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -38,13 +38,10 @@ #include -#include -#include -#include - #include #include #include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 1ae91bd64e..6c20fbe7d4 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -40,7 +40,6 @@ #include #include #include -#include #include #include #include diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index d2bbe354ff..72957d76d8 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -47,7 +47,6 @@ #include #endif -#include #include #include diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index 9aea8d645c..f66db3c555 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -41,7 +41,6 @@ #include #include #include -#include #include "rclcpp/rclcpp.hpp" namespace collision_detection diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 14d2a22a18..6e8dd80fd3 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -41,8 +41,6 @@ #include #include -#include - namespace collision_detection { /** \brief This hybrid collision environment combines FCL and a distance field. Both can be used to calculate diff --git a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp index bc5c9b187e..f66e5e9777 100644 --- a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp @@ -36,7 +36,6 @@ #include "rclcpp/rclcpp.hpp" #include -#include #if __has_include() #include #else diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index b56f9d2a56..d2d674c816 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -40,7 +40,6 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include #include #include "moveit_kinematics_base_export.h" diff --git a/moveit_core/planning_interface/src/planning_interface.cpp b/moveit_core/planning_interface/src/planning_interface.cpp index 05183f1332..dde2cf4ac3 100644 --- a/moveit_core/planning_interface/src/planning_interface.cpp +++ b/moveit_core/planning_interface/src/planning_interface.cpp @@ -35,7 +35,6 @@ /* Author: Ioan Sucan */ #include -#include #include namespace planning_interface diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index 67aebd9d4c..f9e513c097 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -39,7 +39,6 @@ #include #include #include -#include /** \brief Generic interface to adapting motion planning requests */ namespace planning_request_adapter diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 52d7e65158..446803e73c 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -52,7 +52,6 @@ #include #include #include -#include #include #include #include "rclcpp/rclcpp.hpp" diff --git a/moveit_core/planning_scene/test/test_collision_objects.cpp b/moveit_core/planning_scene/test/test_collision_objects.cpp index 69e2b9d2a5..362bb3f553 100644 --- a/moveit_core/planning_scene/test/test_collision_objects.cpp +++ b/moveit_core/planning_scene/test/test_collision_objects.cpp @@ -42,7 +42,6 @@ #include #include #include -#include #if __has_include() #include diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index 2f1cf81fed..5394ff119c 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -43,7 +43,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 34dca32763..2d811091fa 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -41,7 +41,6 @@ #include #include #include -#include #include namespace moveit diff --git a/moveit_core/robot_model/test/test.cpp b/moveit_core/robot_model/test/test.cpp index 16305cd39b..bed167fbea 100644 --- a/moveit_core/robot_model/test/test.cpp +++ b/moveit_core/robot_model/test/test.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index e5495078cd..9f3410ebf0 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -40,7 +40,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index e44189fd5d..bcb9889a9c 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #if __has_include() #include diff --git a/moveit_core/robot_state/test/test_kinematic_complex.cpp b/moveit_core/robot_state/test/test_kinematic_complex.cpp index c66f0ece6c..2c5e64dd91 100644 --- a/moveit_core/robot_state/test/test_kinematic_complex.cpp +++ b/moveit_core/robot_state/test/test_kinematic_complex.cpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index ffa868135f..5ef4eec516 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -36,7 +36,6 @@ #include "rclcpp/rclcpp.hpp" #include -#include #include #include diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp index 8ec81cb6eb..bde5c831f1 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp @@ -37,9 +37,6 @@ #include -// ROS -#include - // MoveIt #include #include diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h index c4778bdc4a..4db845c015 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h @@ -41,8 +41,6 @@ #include #include -#include - namespace kinematics_cache { class KinematicsCache diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index afec7b65d1..e1aaad147c 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -37,9 +37,6 @@ #pragma once -// System -#include - // ROS msgs #include #include diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h index 9b62740e2d..aeb1cef0e0 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h @@ -37,9 +37,6 @@ #pragma once -// System -#include - // ROS msgs #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 76d5999f97..a5cbb25833 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -42,7 +42,6 @@ #include #include #include -#include #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp index 87183ac63e..523f238e61 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp +++ b/moveit_kinematics/cached_ik_kinematics_plugin/src/ik_cache.cpp @@ -34,9 +34,9 @@ /* Author: Mark Moll */ -#include #include #include +#include #include diff --git a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp index 124009e361..1e914bdfbd 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/constraints_library.cpp @@ -35,7 +35,6 @@ /* Author: Ioan Sucan */ #include -#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp index aa9ca1ee05..5e54df17d3 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp @@ -46,7 +46,6 @@ #include #include #include -#include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_state_space"); diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index fba0463971..62745d4587 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -44,9 +44,6 @@ #include -// Boost includes -#include - namespace pilz_industrial_motion_planner { /** diff --git a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp index 798aaff123..be641ddeec 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp @@ -43,9 +43,6 @@ #include "pilz_industrial_motion_planner/cartesian_limits_aggregator.h" #include "pilz_industrial_motion_planner/joint_limits_aggregator.h" -// Boost includes -#include - #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index 8386128e3b..9c99e13fac 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -34,9 +34,6 @@ #include -// Boost includes -#include - #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index ae4e26395a..4c23218b1c 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include #include diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index df3b5c9f8a..3db074c46f 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -52,7 +52,6 @@ #include #include #include -#include namespace moveit_ros_benchmarks { diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 91760fc02b..5019d02770 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -51,7 +51,6 @@ #include #undef BOOST_ALLOW_DEPRECATED_HEADERS #include -#include #include #include #include diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index 4b71a8e9a1..fa646b6900 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -37,8 +37,6 @@ #pragma once #include -#include -#include #include #include diff --git a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp index e20d28adfb..e89a0e9c8c 100644 --- a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp +++ b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp @@ -45,7 +45,6 @@ #include #include #include -#include #include #include "unit_test_servo_calcs.hpp" diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index ae9b5dceb3..d423f814d0 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -42,7 +42,6 @@ #include #include -#include #include #include diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index 9e1663ae1a..c2686a8a02 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -37,7 +37,6 @@ #pragma once #include -#include #include #include #include diff --git a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp index 8d63097070..33ceaa05c7 100644 --- a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp +++ b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp @@ -58,11 +58,11 @@ LazyFreeSpaceUpdater::~LazyFreeSpaceUpdater() { running_ = false; { - boost::unique_lock _(update_cell_sets_lock_); + std::unique_lock _(update_cell_sets_lock_); update_condition_.notify_one(); } { - boost::unique_lock _(cell_process_lock_); + std::unique_lock _(cell_process_lock_); process_condition_.notify_one(); } update_thread_.join(); diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index fec53a26e5..c2ba57239e 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -47,7 +47,6 @@ #include #include #include -#include #include using namespace std; diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 3f45c7b074..2a40d94491 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -38,12 +38,10 @@ #include #include -#include #include #include #include - -#include +#include namespace point_containment_filter { diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 5985d2e637..082afcf729 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -41,7 +41,6 @@ #include #include #include -#include namespace shapes { diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index f259f074f6..204ab9f8fa 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -36,7 +36,6 @@ #pragma once -#include #include #include #include diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index a7fd9ed107..ec269a3fb3 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -37,7 +37,6 @@ #include #include #include -#include #include #include #include diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index a810571c6f..985ea001dd 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -39,7 +39,6 @@ #include #include #include -#include namespace plan_execution { diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index 4b0285b5a2..745fdca10c 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -38,7 +38,6 @@ #include #include #include -#include using namespace std::chrono_literals; diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index c3ae543c01..27011bfc12 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -41,8 +41,6 @@ #include #include -#include -#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index c544ee91af..063fcd7aa2 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -47,9 +47,6 @@ #include #include #include -#include -#include -#include #include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index f5afa3f512..727e437acd 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -40,7 +40,6 @@ #include #include #include -#include #include #include #include diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index 6fd5cc303d..758b1463aa 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -43,9 +43,6 @@ #include #include -// Boost -#include - // C++ #include #include diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index 54405b8ad2..e411727bcc 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -44,7 +44,6 @@ #include #include #include -#include #include #include diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp index ca26340d3c..5455bf1ff1 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp @@ -39,7 +39,6 @@ #include #include -#include #include #include diff --git a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp index 5242bf54a0..fc7f87c3e5 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp +++ b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp @@ -36,7 +36,6 @@ #include "moveit/py_bindings_tools/roscpp_initializer.h" #include "moveit/py_bindings_tools/py_conversions.h" -#include #include #include diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 99e6e5040b..18544702cc 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -40,8 +40,6 @@ #include #include #include -#include -#include namespace moveit { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 7f3c2ea72b..22bae5cf09 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -37,8 +37,6 @@ #pragma once #include -#include -#include #include "moveit_robot_interaction_export.h" diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index 1b72a6e985..eeb5d31365 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -39,8 +39,6 @@ #include #include -#include -#include namespace robot_interaction { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 79ee5dded8..925e92fd37 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -42,8 +42,6 @@ #include #include #include -#include -#include #include // This is needed for legacy code that includes robot_interaction.h but not diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp index 3f056371f5..f2d1491305 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp @@ -38,12 +38,11 @@ #include #include -#include -#include #include #include #include #include +#include namespace moveit { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 2a9d428949..566898301e 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -36,7 +36,6 @@ #pragma once -#include #include #include #include diff --git a/moveit_setup_assistant/src/tools/collision_matrix_model.cpp b/moveit_setup_assistant/src/tools/collision_matrix_model.cpp index ea38166312..eb35a20110 100644 --- a/moveit_setup_assistant/src/tools/collision_matrix_model.cpp +++ b/moveit_setup_assistant/src/tools/collision_matrix_model.cpp @@ -35,7 +35,6 @@ /* Author: Robert Haschke */ #include "collision_matrix_model.h" -#include #include #include #include @@ -43,11 +42,12 @@ #include #include #include +#include using namespace moveit_setup_assistant; /// Boost mapping of reasons for disabling a link pair to strings -static const boost::unordered_map LONG_REASONS_TO_STRING = +static const std::unordered_map LONG_REASONS_TO_STRING = boost::assign::map_list_of // clang-format off ( moveit_setup_assistant::NEVER, "Never in Collision" ) ( moveit_setup_assistant::DEFAULT, "Collision by Default" ) @@ -57,7 +57,7 @@ static const boost::unordered_map LONG_REASONS_TO_BRUSH = +static const std::unordered_map LONG_REASONS_TO_BRUSH = boost::assign::map_list_of // clang-format off ( moveit_setup_assistant::NEVER, QBrush(QColor("lightgreen")) ) ( moveit_setup_assistant::DEFAULT, QBrush(QColor("lightpink")) ) diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 1bb4b781a6..7a9990263c 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -38,7 +38,6 @@ #include #include // for statistics at end #include -#include #include namespace moveit_setup_assistant diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 238b1fde9b..b2dc526ec4 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -38,12 +38,10 @@ // Reading/Writing Files #include // For writing yaml and launch files #include -#include // for creating folders/files -#include // is_regular_file, is_directory, etc. #include #include #include -#include +#include // for creating folders/files // ROS #include diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index 575f32ea45..642c3ff3d1 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -52,9 +52,7 @@ #include "header_widget.h" // Boost -#include // for string find and replace in templates -#include // for creating folders/files -#include // is_regular_file, is_directory, etc. +#include // for string find and replace in templates // Read write files #include // For writing yaml and launch files #include diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.h b/moveit_setup_assistant/src/widgets/default_collisions_widget.h index aa1f020ce8..cc4db24aaa 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.h +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.h @@ -55,8 +55,6 @@ class QTableView; class QVBoxLayout; #ifndef Q_MOC_RUN -#include -#include #include #endif diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h index d09c530c28..a212661d28 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h @@ -59,7 +59,6 @@ class QSplitter; // Other #include // for parsing input arguments -#include #endif // Forward declarations diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index b675586fdc..d621c6f1c7 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -57,9 +57,6 @@ // C #include // for reading in urdf #include -// Boost -#include // for reading folders/files -#include // for reading folders/files // MoveIt #include diff --git a/moveit_setup_assistant/test/moveit_config_data_test.cpp b/moveit_setup_assistant/test/moveit_config_data_test.cpp index af7b72f1d9..f6eb12cc7f 100644 --- a/moveit_setup_assistant/test/moveit_config_data_test.cpp +++ b/moveit_setup_assistant/test/moveit_config_data_test.cpp @@ -40,8 +40,6 @@ #include #include #include -#include -#include #include #include #include From 79405c49d51fa49989a7475d82de352316e5f6b6 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 12:55:06 -0600 Subject: [PATCH 12/43] changed comment --- moveit_core/collision_detection/src/world.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 527c21ac99..41c2ea73c7 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -139,7 +139,7 @@ bool World::knowsTransform(const std::string& name) const for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - // name.rfind is in service of removing the call to boost::starts_with and does the same thing + // rfind searches name for object.first in the first index (returns 0 if found) if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { return object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)) != From 25bfad5aed46f15b642e0c489e6b9a486422a8ce Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 13:09:23 -0600 Subject: [PATCH 13/43] removing forward declarations --- .../robot_model/include/moveit/robot_model/robot_model.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 760711fb43..03dad78adc 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -50,6 +50,8 @@ #include #include #include +#include +#include /** \brief Main namespace for MoveIt */ namespace moveit From 4ba40c8b35fd076a467de46517f5e37ecb7db6e0 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 14:09:13 -0600 Subject: [PATCH 14/43] removed reliance on indirect includes --- .../include/moveit/collision_detection/occupancy_map.h | 1 + .../include/moveit/collision_detection/world.h | 1 + moveit_core/collision_detection_fcl/src/collision_common.cpp | 1 + .../collision_distance_field/collision_env_distance_field.h | 1 + .../moveit/collision_distance_field/collision_env_hybrid.h | 2 ++ .../src/collision_common_distance_field.cpp | 1 + .../include/moveit/kinematics_base/kinematics_base.h | 1 + moveit_core/planning_interface/src/planning_interface.cpp | 1 + .../moveit/planning_request_adapter/planning_request_adapter.h | 1 + .../include/moveit/planning_scene/planning_scene.h | 1 + moveit_core/planning_scene/test/test_collision_objects.cpp | 1 + moveit_core/planning_scene/test/test_planning_scene.cpp | 1 + .../robot_model/include/moveit/robot_model/joint_model_group.h | 1 + moveit_core/robot_model/test/test.cpp | 1 + .../robot_state/include/moveit/robot_state/attached_body.h | 1 + moveit_core/robot_state/test/test_aabb.cpp | 1 + moveit_core/robot_state/test/test_kinematic_complex.cpp | 1 + .../v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp | 3 +++ .../include/moveit/kinematics_cache/kinematics_cache.h | 2 ++ .../kinematics_constraint_aware/kinematics_constraint_aware.h | 3 +++ .../kinematics_constraint_aware/kinematics_request_response.h | 3 +++ moveit_planners/ompl/ompl_interface/test/test_state_space.cpp | 1 + .../pilz_industrial_motion_planner.h | 1 + .../src/pilz_industrial_motion_planner.cpp | 2 ++ .../test/unit_tests/src/unittest_planning_context_loaders.cpp | 2 ++ .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 1 + .../include/moveit/pick_place/manipulation_pipeline.h | 2 ++ moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp | 1 + .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 1 + moveit_ros/perception/mesh_filter/src/gl_renderer.cpp | 1 + .../include/moveit/point_containment_filter/shape_mask.h | 1 + .../include/moveit/semantic_world/semantic_world.h | 1 + .../moveit/kinematics_plugin_loader/kinematics_plugin_loader.h | 1 + .../kinematics_plugin_loader/src/kinematics_plugin_loader.cpp | 1 + .../include/moveit/plan_execution/plan_representation.h | 1 + .../src/evaluate_collision_checking_speed.cpp | 1 + .../moveit/planning_scene_monitor/current_state_monitor.h | 2 ++ .../moveit/planning_scene_monitor/planning_scene_monitor.h | 3 +++ .../include/moveit/planning_scene_monitor/trajectory_monitor.h | 1 + .../trajectory_execution_manager.h | 1 + .../src/wrap_python_planning_scene_interface.cpp | 2 ++ .../py_bindings_tools/src/roscpp_initializer.cpp | 1 + .../include/moveit/robot_interaction/interaction.h | 2 ++ .../include/moveit/robot_interaction/kinematic_options_map.h | 2 ++ .../include/moveit/robot_interaction/locked_robot_state.h | 3 +++ .../include/moveit/robot_interaction/robot_interaction.h | 2 ++ .../moveit/rviz_plugin_render_tools/trajectory_visualization.h | 1 + .../src/tools/compute_default_collisions.cpp | 1 + .../src/widgets/configuration_files_widget.cpp | 1 + moveit_setup_assistant/src/widgets/default_collisions_widget.h | 2 ++ moveit_setup_assistant/src/widgets/setup_assistant_widget.h | 1 + moveit_setup_assistant/src/widgets/start_screen_widget.cpp | 1 + 52 files changed, 73 insertions(+) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h index 746b9d2b0b..514cd5a061 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/occupancy_map.h @@ -42,6 +42,7 @@ #include #include #include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 6c20fbe7d4..92799537c5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index 72957d76d8..0176c6dd7c 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -49,6 +49,7 @@ #include #include +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index f66db3c555..411cecd9bc 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -42,6 +42,7 @@ #include #include #include "rclcpp/rclcpp.hpp" +#include namespace collision_detection { diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 6e8dd80fd3..da088bda6b 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -41,6 +41,8 @@ #include #include +#include + namespace collision_detection { /** \brief This hybrid collision environment combines FCL and a distance field. Both can be used to calculate diff --git a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp index f66e5e9777..859e8243ef 100644 --- a/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_common_distance_field.cpp @@ -42,6 +42,7 @@ #include #endif #include +#include namespace collision_detection { diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index d2d674c816..a80d1e4486 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -41,6 +41,7 @@ #include #include "rclcpp/rclcpp.hpp" #include +#include #include "moveit_kinematics_base_export.h" diff --git a/moveit_core/planning_interface/src/planning_interface.cpp b/moveit_core/planning_interface/src/planning_interface.cpp index dde2cf4ac3..b156560bd8 100644 --- a/moveit_core/planning_interface/src/planning_interface.cpp +++ b/moveit_core/planning_interface/src/planning_interface.cpp @@ -35,6 +35,7 @@ /* Author: Ioan Sucan */ #include +#include #include namespace planning_interface diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index f9e513c097..0804e893ac 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -39,6 +39,7 @@ #include #include #include +#include /** \brief Generic interface to adapting motion planning requests */ namespace planning_request_adapter diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 446803e73c..49d49a4ed1 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -54,6 +54,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include "moveit_planning_scene_export.h" diff --git a/moveit_core/planning_scene/test/test_collision_objects.cpp b/moveit_core/planning_scene/test/test_collision_objects.cpp index 362bb3f553..1e18bf26a3 100644 --- a/moveit_core/planning_scene/test/test_collision_objects.cpp +++ b/moveit_core/planning_scene/test/test_collision_objects.cpp @@ -42,6 +42,7 @@ #include #include #include +#include #if __has_include() #include diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index 5394ff119c..bffffd4c87 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index 2d811091fa..c7a1759bfb 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -41,6 +41,7 @@ #include #include #include +#include #include namespace moveit diff --git a/moveit_core/robot_model/test/test.cpp b/moveit_core/robot_model/test/test.cpp index bed167fbea..6f7297cabc 100644 --- a/moveit_core/robot_model/test/test.cpp +++ b/moveit_core/robot_model/test/test.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 9f3410ebf0..33aa9e535d 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -42,6 +42,7 @@ #include #include #include +#include namespace moveit { diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index bcb9889a9c..33d732d9bd 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #if __has_include() #include diff --git a/moveit_core/robot_state/test/test_kinematic_complex.cpp b/moveit_core/robot_state/test/test_kinematic_complex.cpp index 2c5e64dd91..b7090b56e7 100644 --- a/moveit_core/robot_state/test/test_kinematic_complex.cpp +++ b/moveit_core/robot_state/test/test_kinematic_complex.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp index bde5c831f1..211a2df183 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp @@ -44,6 +44,9 @@ #include #include +// std +#include + namespace kinematics_cache_ros { bool KinematicsCacheROS::init(const kinematics_cache::KinematicsCache::Options& opt, diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h index 4db845c015..6bead430f3 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h @@ -41,6 +41,8 @@ #include #include +#include + namespace kinematics_cache { class KinematicsCache diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index e1aaad147c..b90178585f 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -54,6 +54,9 @@ #include #include +// std +#include + namespace kinematics_constraint_aware { class KinematicsConstraintAware; diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h index aeb1cef0e0..a4b98045d6 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h @@ -47,6 +47,9 @@ #include #include +// std +#include + namespace kinematics_constraint_aware { /** diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp index 5e54df17d3..8fe430fcf2 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp @@ -46,6 +46,7 @@ #include #include #include +#include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_state_space"); diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h index 62745d4587..cf73ddda43 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/pilz_industrial_motion_planner.h @@ -43,6 +43,7 @@ #include #include +#include namespace pilz_industrial_motion_planner { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp index be641ddeec..6336d54bee 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/pilz_industrial_motion_planner.cpp @@ -47,6 +47,8 @@ #include +#include + namespace pilz_industrial_motion_planner { static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning"; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index 9c99e13fac..e91bd458f2 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -45,6 +45,8 @@ #include "rclcpp/rclcpp.hpp" +#include + static const rclcpp::Logger LOGGER = rclcpp::get_logger("unittest_planning_context_loader"); class PlanningContextLoadersTest : public ::testing::TestWithParam> diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 3db074c46f..6dfe568d7f 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -52,6 +52,7 @@ #include #include #include +#include namespace moveit_ros_benchmarks { diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index fa646b6900..f3471f54ba 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -39,6 +39,8 @@ #include #include #include +#include +#include namespace pick_place { diff --git a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp index e89a0e9c8c..06a55673c4 100644 --- a/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp +++ b/moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include "unit_test_servo_calcs.hpp" diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index d423f814d0..429000b63a 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -47,6 +47,7 @@ #include #include +#include namespace occupancy_map_monitor { diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index c2ba57239e..68d8fa5525 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -47,6 +47,7 @@ #include #include #include +#include #include using namespace std; diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 2a40d94491..d77d8dfe63 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -42,6 +42,7 @@ #include #include #include +#include namespace point_containment_filter { diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index 082afcf729..a6b6f983e4 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -41,6 +41,7 @@ #include #include #include +#include namespace shapes { diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 204ab9f8fa..a6488b8878 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -39,6 +39,7 @@ #include #include #include +#include namespace kinematics_plugin_loader { diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index ec269a3fb3..2b13bcb16f 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" namespace kinematics_plugin_loader diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index 985ea001dd..e2a1c49484 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -39,6 +39,7 @@ #include #include #include +#include namespace plan_execution { diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index 745fdca10c..23d3e0d9b1 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -38,6 +38,7 @@ #include #include #include +#include using namespace std::chrono_literals; diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 27011bfc12..30b09e2148 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -39,6 +39,8 @@ #include #include #include +#include +#include #include diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 063fcd7aa2..15c5bcd60a 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -49,6 +49,9 @@ #include #include #include +#include +#include +#include #include "moveit_planning_scene_monitor_export.h" diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 727e437acd..d5e55feadc 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -43,6 +43,7 @@ #include #include #include +#include namespace planning_scene_monitor { diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index e411727bcc..0234052acd 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -48,6 +48,7 @@ #include #include +#include #include "moveit_trajectory_execution_manager_export.h" diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp index 5455bf1ff1..0520727d5f 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp @@ -42,6 +42,8 @@ #include #include +#include + /** @cond IGNORE */ namespace bp = boost::python; diff --git a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp index fc7f87c3e5..20fd57fc9d 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp +++ b/moveit_ros/planning_interface/py_bindings_tools/src/roscpp_initializer.cpp @@ -38,6 +38,7 @@ #include "moveit/py_bindings_tools/py_conversions.h" #include #include +#include static std::vector& ROScppArgs() { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 18544702cc..9f7fd9a197 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -40,6 +40,8 @@ #include #include #include +#include +#include namespace moveit { diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 22bae5cf09..edd6f880a5 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -37,6 +37,8 @@ #pragma once #include +#include +#include #include "moveit_robot_interaction_export.h" diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index eeb5d31365..2e00e47e08 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -40,6 +40,9 @@ #include #include +#include +#include + namespace robot_interaction { MOVEIT_CLASS_FORWARD(LockedRobotState); // Defines LockedRobotStatePtr, ConstPtr, WeakPtr... etc diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index 925e92fd37..0ae3ae2041 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -43,6 +43,8 @@ #include #include #include +#include +#include // This is needed for legacy code that includes robot_interaction.h but not // interaction_handler.h diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 566898301e..05632800e7 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -41,6 +41,7 @@ #include #include #include +#include #ifndef Q_MOC_RUN #include diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 7a9990263c..11a8cbacec 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -39,6 +39,7 @@ #include // for statistics at end #include #include +#include namespace moveit_setup_assistant { diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index 642c3ff3d1..23d84033c5 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -56,6 +56,7 @@ // Read write files #include // For writing yaml and launch files #include +#include namespace moveit_setup_assistant { diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.h b/moveit_setup_assistant/src/widgets/default_collisions_widget.h index cc4db24aaa..4eb4ae8e53 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.h +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.h @@ -55,6 +55,8 @@ class QTableView; class QVBoxLayout; #ifndef Q_MOC_RUN +#include +#include #include #endif diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h index a212661d28..d855d79781 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h @@ -59,6 +59,7 @@ class QSplitter; // Other #include // for parsing input arguments +#include #endif // Forward declarations diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index d621c6f1c7..51d42f31b5 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -57,6 +57,7 @@ // C #include // for reading in urdf #include +#include // MoveIt #include From d3983861c9ebcbb2e392122126f51030d4d56993 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 17:35:48 -0600 Subject: [PATCH 15/43] final changes, removing unnecessary boost includes from CMakeLists --- moveit_core/collision_detection/src/collision_matrix.cpp | 2 +- moveit_core/collision_detection_bullet/CMakeLists.txt | 1 - moveit_core/collision_detection_fcl/CMakeLists.txt | 1 - moveit_core/collision_distance_field/CMakeLists.txt | 1 - moveit_core/kinematics_base/CMakeLists.txt | 1 - .../kinematics_cache/v2/kinematics_cache/CMakeLists.txt | 2 +- moveit_experimental/kinematics_constraint_aware/CMakeLists.txt | 2 +- moveit_ros/occupancy_map_monitor/CMakeLists.txt | 3 --- moveit_ros/occupancy_map_monitor/ConfigExtras.cmake | 3 --- moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt | 1 - moveit_ros/perception/point_containment_filter/CMakeLists.txt | 1 - moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt | 1 - moveit_ros/planning/rdf_loader/CMakeLists.txt | 3 +-- moveit_ros/planning/rdf_loader/src/rdf_loader.cpp | 1 - .../planning/trajectory_execution_manager/CMakeLists.txt | 1 - 15 files changed, 4 insertions(+), 20 deletions(-) delete mode 100644 moveit_ros/occupancy_map_monitor/ConfigExtras.cmake diff --git a/moveit_core/collision_detection/src/collision_matrix.cpp b/moveit_core/collision_detection/src/collision_matrix.cpp index 33b0d3c482..6b20537874 100644 --- a/moveit_core/collision_detection/src/collision_matrix.cpp +++ b/moveit_core/collision_detection/src/collision_matrix.cpp @@ -146,7 +146,7 @@ void AllowedCollisionMatrix::setEntry(const std::string& name1, const std::strin const AllowedCollision::Type v = allowed ? AllowedCollision::ALWAYS : AllowedCollision::NEVER; entries_[name1][name2] = entries_[name2][name1] = v; - // remove boost::function pointers, if any + // remove function pointers, if any auto it = allowed_contacts_.find(name1); if (it != allowed_contacts_.end()) { diff --git a/moveit_core/collision_detection_bullet/CMakeLists.txt b/moveit_core/collision_detection_bullet/CMakeLists.txt index c922f3ead4..d261a45ba0 100644 --- a/moveit_core/collision_detection_bullet/CMakeLists.txt +++ b/moveit_core/collision_detection_bullet/CMakeLists.txt @@ -22,7 +22,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdf urdfdom urdfdom_headers - Boost visualization_msgs octomap_msgs ) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 32002955a7..4dd696f975 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -15,7 +15,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} urdfdom urdfdom_headers LIBFCL - Boost visualization_msgs ) target_link_libraries(${MOVEIT_LIB_NAME} diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index e46787ae8f..fd0dae0199 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -35,7 +35,6 @@ if(BUILD_TESTING) ament_add_gtest(test_collision_distance_field test/test_collision_distance_field.cpp) ament_target_dependencies(test_collision_distance_field - Boost geometric_shapes OCTOMAP srdfdom diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index d3b38ba32d..0776cdeb97 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -15,7 +15,6 @@ ament_target_dependencies( srdfdom moveit_msgs geometric_shapes geometry_msgs - Boost ) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt index 5500762e58..450aabc75f 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt @@ -7,7 +7,7 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V # This line is needed to ensure that messages are done being built before this is built add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt index b2bbaa553f..30de4f603d 100644 --- a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt +++ b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt @@ -5,7 +5,7 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V # This line is needed to ensure that messages are done being built before this is built add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 110eee2150..ad8975adc8 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -24,8 +24,6 @@ find_package(octomap REQUIRED) find_package(geometric_shapes REQUIRED) find_package(tf2_ros REQUIRED) -# Finds Boost Components -include(ConfigExtras.cmake) include_directories(include) include_directories(SYSTEM @@ -40,7 +38,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS pluginlib octomap geometric_shapes - Boost ) add_library(${MOVEIT_LIB_NAME} SHARED diff --git a/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake b/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake deleted file mode 100644 index 837e37df5e..0000000000 --- a/moveit_ros/occupancy_map_monitor/ConfigExtras.cmake +++ /dev/null @@ -1,3 +0,0 @@ -# Extras module needed for dependencies to find boost components - -find_package(Boost REQUIRED thread) diff --git a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt index 98dbb81058..f2dfdb4734 100644 --- a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt +++ b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt @@ -10,7 +10,6 @@ endif() ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_ros_occupancy_map_monitor - Boost sensor_msgs ) diff --git a/moveit_ros/perception/point_containment_filter/CMakeLists.txt b/moveit_ros/perception/point_containment_filter/CMakeLists.txt index 7c1dd5cc94..362e87d94d 100644 --- a/moveit_ros/perception/point_containment_filter/CMakeLists.txt +++ b/moveit_ros/perception/point_containment_filter/CMakeLists.txt @@ -8,7 +8,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp sensor_msgs geometric_shapes - Boost ) install(DIRECTORY include/ DESTINATION include) diff --git a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt index ee1b58e883..d489eca982 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt @@ -8,7 +8,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} pluginlib class_loader moveit_core - Boost ) target_link_libraries(${MOVEIT_LIB_NAME} moveit_rdf_loader diff --git a/moveit_ros/planning/rdf_loader/CMakeLists.txt b/moveit_ros/planning/rdf_loader/CMakeLists.txt index e470ac3552..982c909389 100644 --- a/moveit_ros/planning/rdf_loader/CMakeLists.txt +++ b/moveit_ros/planning/rdf_loader/CMakeLists.txt @@ -7,8 +7,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} ament_index_cpp urdf srdfdom - moveit_core - Boost) + moveit_core) install(DIRECTORY include/ DESTINATION include) install(DIRECTORY diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index 758b1463aa..49f34fd6c6 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -219,7 +219,6 @@ bool RDFLoader::loadPkgFileToString(std::string& buffer, const std::string& pack } std::filesystem::path path(package_path); - // Use boost to cross-platform combine paths path = path / relative_path; return loadXmlFileToString(buffer, path.string(), xacro_args); diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index 95db3085ab..670f856627 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -9,7 +9,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core moveit_ros_occupancy_map_monitor rclcpp - Boost pluginlib std_msgs sensor_msgs From ee04b2c9f424c522ce5e436b6094092f4b262fc9 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 09:19:43 -0600 Subject: [PATCH 16/43] removed now-unnecessary package --- moveit_ros/occupancy_map_monitor/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index ad8975adc8..1069c83146 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -93,5 +93,3 @@ if(BUILD_TESTING) ${MOVEIT_LIB_NAME} ) endif() - -ament_package(CONFIG_EXTRAS ConfigExtras.cmake) From dd4cda6a7799b1f2a3bcb9a16e4cf9fcbf848cb6 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 09:33:26 -0600 Subject: [PATCH 17/43] added direct includes --- .../include/moveit/collision_detection/collision_common.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index c08342a360..8c14ea803b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -36,6 +36,8 @@ #pragma once +#include +#include #include #include #include From 97dd35f7cd6d19b9fe9f6722b6b426444e10323f Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 09:38:17 -0600 Subject: [PATCH 18/43] fixed formatting --- moveit_setup_assistant/src/tools/moveit_config_data.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 8a00d682f4..3d84e0a8fe 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -41,7 +41,7 @@ #include #include #include -#include // for creating folders/files +#include // for creating folders/files #include // for getting file path for loading images // OMPL version #include From 051cc11aac46caaf8e8f25914ff63011d7a6880c Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 11:27:41 -0600 Subject: [PATCH 19/43] added back mistakenly removed cmake command --- moveit_ros/occupancy_map_monitor/CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 1069c83146..c01ae8e3a5 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -38,6 +38,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS pluginlib octomap geometric_shapes + Boost ) add_library(${MOVEIT_LIB_NAME} SHARED @@ -93,3 +94,5 @@ if(BUILD_TESTING) ${MOVEIT_LIB_NAME} ) endif() + +ament_package() From 2f3c9dd4481320a2f7e9a558e44b6313073524f3 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 16:04:37 -0600 Subject: [PATCH 20/43] removing unnecessary includes thanks to Abi's review --- .../moveit/collision_distance_field/collision_env_hybrid.h | 2 -- moveit_core/kinematics_metrics/src/kinematics_metrics.cpp | 1 + moveit_core/planning_scene/test/test_collision_objects.cpp | 1 - moveit_core/planning_scene/test/test_planning_scene.cpp | 1 - .../robot_model/include/moveit/robot_model/robot_model.h | 2 -- moveit_core/robot_model/test/test.cpp | 1 - moveit_core/robot_state/test/test_aabb.cpp | 1 - moveit_core/robot_state/test/test_kinematic_complex.cpp | 1 - .../kinematics_constraint_aware/kinematics_constraint_aware.h | 3 --- moveit_planners/ompl/ompl_interface/test/test_state_space.cpp | 1 - .../test/unit_tests/src/unittest_planning_context_loaders.cpp | 2 -- .../moveit/kinematics_plugin_loader/kinematics_plugin_loader.h | 1 - .../src/wrap_python_planning_scene_interface.cpp | 2 -- .../include/moveit/robot_interaction/kinematic_options_map.h | 2 +- 14 files changed, 2 insertions(+), 19 deletions(-) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index da088bda6b..6e8dd80fd3 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -41,8 +41,6 @@ #include #include -#include - namespace collision_detection { /** \brief This hybrid collision environment combines FCL and a distance field. Both can be used to calculate diff --git a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp index 28828278cf..4c482af055 100644 --- a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp +++ b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp @@ -40,6 +40,7 @@ #include #include #include +#include namespace kinematics_metrics { diff --git a/moveit_core/planning_scene/test/test_collision_objects.cpp b/moveit_core/planning_scene/test/test_collision_objects.cpp index 1e18bf26a3..362bb3f553 100644 --- a/moveit_core/planning_scene/test/test_collision_objects.cpp +++ b/moveit_core/planning_scene/test/test_collision_objects.cpp @@ -42,7 +42,6 @@ #include #include #include -#include #if __has_include() #include diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index bffffd4c87..5394ff119c 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -43,7 +43,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 8804880840..7f5e387412 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -51,8 +51,6 @@ #include #include #include -#include -#include /** \brief Main namespace for MoveIt */ namespace moveit diff --git a/moveit_core/robot_model/test/test.cpp b/moveit_core/robot_model/test/test.cpp index 6f7297cabc..bed167fbea 100644 --- a/moveit_core/robot_model/test/test.cpp +++ b/moveit_core/robot_model/test/test.cpp @@ -37,7 +37,6 @@ #include #include #include -#include #include #include diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index 33d732d9bd..bcb9889a9c 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #if __has_include() #include diff --git a/moveit_core/robot_state/test/test_kinematic_complex.cpp b/moveit_core/robot_state/test/test_kinematic_complex.cpp index b7090b56e7..2c5e64dd91 100644 --- a/moveit_core/robot_state/test/test_kinematic_complex.cpp +++ b/moveit_core/robot_state/test/test_kinematic_complex.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #include diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index b90178585f..e1aaad147c 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -54,9 +54,6 @@ #include #include -// std -#include - namespace kinematics_constraint_aware { class KinematicsConstraintAware; diff --git a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp index 8fe430fcf2..5e54df17d3 100644 --- a/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/test/test_state_space.cpp @@ -46,7 +46,6 @@ #include #include #include -#include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_state_space"); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp index e91bd458f2..9c99e13fac 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_planning_context_loaders.cpp @@ -45,8 +45,6 @@ #include "rclcpp/rclcpp.hpp" -#include - static const rclcpp::Logger LOGGER = rclcpp::get_logger("unittest_planning_context_loader"); class PlanningContextLoadersTest : public ::testing::TestWithParam> diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index a6488b8878..204ab9f8fa 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -39,7 +39,6 @@ #include #include #include -#include namespace kinematics_plugin_loader { diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp index 0520727d5f..5455bf1ff1 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/wrap_python_planning_scene_interface.cpp @@ -42,8 +42,6 @@ #include #include -#include - /** @cond IGNORE */ namespace bp = boost::python; diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index edd6f880a5..890cda5664 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include #include #include "moveit_robot_interaction_export.h" From 6499df1fa3cb39fce95bc66ec5e9aaf64f5547e3 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 09:44:55 -0600 Subject: [PATCH 21/43] resolved rebase conflicts --- .../moveit/planning_scene/planning_scene.h | 15 +++- .../moveit/robot_model/joint_model_group.h | 1 + .../robot_model/src/joint_model_group.cpp | 7 +- moveit_core/robot_state/src/conversions.cpp | 4 +- moveit_core/robot_state/test/test_aabb.cpp | 3 +- .../include/moveit/transforms/transforms.h | 13 +++- .../command_list_manager.h | 4 +- .../cartesianconfiguration.h | 14 ++-- .../sequence.h | 5 +- .../benchmarks/src/benchmark_execution.cpp | 69 ++++++++++--------- .../benchmarks/src/BenchmarkExecutor.cpp | 6 +- .../include/moveit/pick_place/pick_place.h | 13 +++- .../pick_place/src/pick_place.cpp | 3 +- .../include/moveit_servo/pose_tracking.h | 2 +- .../planning_scene_monitor.h | 13 +++- .../src/wrap_python_move_group.cpp | 1 + .../src/interaction_handler.cpp | 2 +- .../src/robot_interaction.cpp | 4 +- .../background_processing.hpp | 13 +++- .../src/mesh_shape.cpp | 7 +- .../src/render_shapes.cpp | 2 +- .../src/trajectory_visualization.cpp | 11 +-- .../warehouse/src/save_to_warehouse.cpp | 4 +- .../src/tools/compute_default_collisions.cpp | 18 ++--- .../src/widgets/planning_groups_widget.cpp | 8 +-- 25 files changed, 142 insertions(+), 100 deletions(-) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 49d49a4ed1..7e17a04874 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -51,10 +51,10 @@ #include #include #include -#include #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include "moveit_planning_scene_export.h" @@ -86,10 +86,19 @@ using ObjectTypeMap = std::map +class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_from_this { public: + /** + * @brief PlanningScene cannot be copy-constructed + */ + PlanningScene(const PlanningScene&) = delete; + + /** + * @brief PlanningScene cannot be copy-assigned + */ + PlanningScene& operator=(const PlanningScene&) = delete; + /** \brief construct using an existing RobotModel */ PlanningScene(const moveit::core::RobotModelConstPtr& robot_model, const collision_detection::WorldPtr& world = std::make_shared()); diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index c7a1759bfb..617adf3304 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -43,6 +43,7 @@ #include #include #include +#include namespace moveit { diff --git a/moveit_core/robot_model/src/joint_model_group.cpp b/moveit_core/robot_model/src/joint_model_group.cpp index 808025517e..dd0db3c36d 100644 --- a/moveit_core/robot_model/src/joint_model_group.cpp +++ b/moveit_core/robot_model/src/joint_model_group.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #include #include @@ -369,9 +368,9 @@ void JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNum { assert(active_joint_bounds.size() == active_joint_model_vector_.size()); if (distances.size() != active_joint_model_vector_.size()) - throw Exception("When sampling random values nearby for group '" + name_ + "', distances vector should be of size " + - boost::lexical_cast(active_joint_model_vector_.size()) + ", but it is of size " + - boost::lexical_cast(distances.size())); + throw Exception("When sampling random values nearby for group '" + name_ + + "', distances vector should be of size " + std::to_string(active_joint_model_vector_.size()) + + ", but it is of size " + std::to_string(distances.size())); for (std::size_t i = 0; i < active_joint_model_vector_.size(); ++i) active_joint_model_vector_[i]->getVariableRandomPositionsNearBy(rng, values + active_joint_model_start_index_[i], *active_joint_bounds[i], diff --git a/moveit_core/robot_state/src/conversions.cpp b/moveit_core/robot_state/src/conversions.cpp index 3217b550cd..708857948b 100644 --- a/moveit_core/robot_state/src/conversions.cpp +++ b/moveit_core/robot_state/src/conversions.cpp @@ -45,6 +45,8 @@ #include #endif #include +#include +#include "rclcpp/rclcpp.hpp" namespace moveit { @@ -560,7 +562,7 @@ void streamToRobotState(RobotState& state, const std::string& line, const std::s // Get a variable if (!std::getline(line_stream, cell, separator[0])) RCLCPP_ERROR(LOGGER, "Missing variable %s", state.getVariableNames()[i].c_str()); - state.getVariablePositions()[i] = boost::lexical_cast(cell.c_str()); + state.getVariablePositions()[i] = std::stod(cell); } } diff --git a/moveit_core/robot_state/test/test_aabb.cpp b/moveit_core/robot_state/test/test_aabb.cpp index bcb9889a9c..09fb10b4b7 100644 --- a/moveit_core/robot_state/test/test_aabb.cpp +++ b/moveit_core/robot_state/test/test_aabb.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #if __has_include() #include @@ -240,7 +241,7 @@ TEST_F(TestAABB, TestPR2) aabb.extendWithTransformedBox(transforms[i], extents); // Publish AABB - msg->ns = (*it)->getName() + boost::lexical_cast(i); + msg->ns = (*it)->getName() + std::to_string(i); msg->pose.position.x = transforms[i].translation()[0]; msg->pose.position.y = transforms[i].translation()[1]; msg->pose.position.z = transforms[i].translation()[2]; diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 2f586616d1..7b31fbb4f4 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -38,7 +38,6 @@ #include #include -#include #include #include @@ -56,9 +55,19 @@ using FixedTransformsMap = std::map -#include +#include #include #include @@ -107,7 +107,7 @@ class CommandListManager private: using MotionResponseCont = std::vector; - using RobotState_OptRef = boost::optional; + using RobotState_OptRef = std::optional; using RadiiCont = std::vector; using GroupNamesCont = std::vector; diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 50edfc3291..5076547887 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -81,10 +81,10 @@ class CartesianConfiguration : public RobotConfiguration bool hasSeed() const; void setPoseTolerance(const double tol); - const boost::optional getPoseTolerance() const; + const std::optional getPoseTolerance() const; void setAngleTolerance(const double tol); - const boost::optional getAngleTolerance() const; + const std::optional getAngleTolerance() const; private: static geometry_msgs::msg::Pose toPose(const std::vector& pose); @@ -96,14 +96,14 @@ class CartesianConfiguration : public RobotConfiguration //! @brief The dimensions of the sphere associated with the target region //! of the position constraint. - boost::optional tolerance_pose_{ boost::none }; + std::optional tolerance_pose_; //! @brief The value to assign to the absolute tolerances of the //! orientation constraint. - boost::optional tolerance_angle_{ boost::none }; + std::optional tolerance_angle_; //! @brief The seed for computing the IK solution of the cartesian configuration. - boost::optional seed_{ boost::none }; + std::optional seed_; }; std::ostream& operator<<(std::ostream& /*os*/, const CartesianConfiguration& /*obj*/); @@ -166,7 +166,7 @@ inline void CartesianConfiguration::setPoseTolerance(const double tol) tolerance_pose_ = tol; } -inline const boost::optional CartesianConfiguration::getPoseTolerance() const +inline const std::optional CartesianConfiguration::getPoseTolerance() const { return tolerance_pose_; } @@ -176,7 +176,7 @@ inline void CartesianConfiguration::setAngleTolerance(const double tol) tolerance_angle_ = tol; } -inline const boost::optional CartesianConfiguration::getAngleTolerance() const +inline const std::optional CartesianConfiguration::getAngleTolerance() const { return tolerance_angle_; } diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index 79ef318f81..1ffad86ccc 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -43,6 +43,7 @@ #include "command_types_typedef.h" #include "motioncmd.h" +#include namespace pilz_industrial_motion_planner_testutils { @@ -112,13 +113,13 @@ inline size_t Sequence::size() const template inline T& Sequence::getCmd(const size_t index_cmd) { - return boost::get(cmds_.at(index_cmd).first); + return std::get(cmds_.at(index_cmd).first); } template inline const T& Sequence::getCmd(const size_t index_cmd) const { - return boost::get(cmds_.at(index_cmd).first); + return std::get(cmds_.at(index_cmd).first); } inline double Sequence::getBlendRadius(const size_t index_cmd) const diff --git a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp index b888540769..91e42928bb 100644 --- a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp +++ b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp @@ -61,6 +61,8 @@ #include #include +#include +#include namespace moveit_benchmarks { @@ -307,7 +309,7 @@ void moveit_benchmarks::BenchmarkExecution::runAllBenchmarks(BenchmarkType type) // update request given .cfg options if (start_state_to_use) req.motion_plan_request.start_state = *start_state_to_use; - req.filename = options_.output + "." + boost::lexical_cast(++n_call) + ".log"; + req.filename = options_.output + "." + std::to_string(++n_call) + ".log"; if (!options_.group_override.empty()) req.motion_plan_request.group_name = options_.group_override; @@ -404,7 +406,7 @@ void moveit_benchmarks::BenchmarkExecution::runAllBenchmarks(BenchmarkType type) checkConstrainedLink(req.motion_plan_request.goal_constraints[0], options_.default_constrained_link); if (!options_.planning_frame.empty()) checkHeader(req.motion_plan_request.goal_constraints[0], options_.planning_frame); - req.filename = options_.output + "." + boost::lexical_cast(++n_call) + ".log"; + req.filename = options_.output + "." + std::to_string(++n_call) + ".log"; ROS_INFO("Benchmarking goal '%s' (%d of %d)", cnames[i].c_str(), static_cast(i) + 1, static_cast(cnames.size())); @@ -493,7 +495,7 @@ void moveit_benchmarks::BenchmarkExecution::runAllBenchmarks(BenchmarkType type) req.motion_plan_request.group_name = options_.group_override; if (options_.timeout > 0.0) req.motion_plan_request.allowed_planning_time = options_.timeout; - req.filename = options_.output + ".trajectory." + boost::lexical_cast(i + 1) + ".log"; + req.filename = options_.output + ".trajectory." + std::to_string(i + 1) + ".log"; ROS_INFO("Benchmarking trajectory '%s' (%d of %d)", cnames[i].c_str(), static_cast(i) + 1, static_cast(cnames.size())); @@ -565,19 +567,19 @@ bool moveit_benchmarks::BenchmarkExecution::readOptions(const std::string& filen { memset(options_.offsets, 0, 6 * sizeof(double)); if (!declared_options["scene.goal_offset_x"].empty()) - options_.offsets[0] = boost::lexical_cast(declared_options["scene.goal_offset_x"]); + options_.offsets[0] = std::stod(declared_options["scene.goal_offset_x"]); if (!declared_options["scene.goal_offset_y"].empty()) - options_.offsets[1] = boost::lexical_cast(declared_options["scene.goal_offset_y"]); + options_.offsets[1] = std::stod(declared_options["scene.goal_offset_y"]); if (!declared_options["scene.goal_offset_z"].empty()) - options_.offsets[2] = boost::lexical_cast(declared_options["scene.goal_offset_z"]); + options_.offsets[2] = std::stod(declared_options["scene.goal_offset_z"]); if (!declared_options["scene.goal_offset_roll"].empty()) - options_.offsets[3] = boost::lexical_cast(declared_options["scene.goal_offset_roll"]); + options_.offsets[3] = std::stod(declared_options["scene.goal_offset_roll"]); if (!declared_options["scene.goal_offset_pitch"].empty()) - options_.offsets[4] = boost::lexical_cast(declared_options["scene.goal_offset_pitch"]); + options_.offsets[4] = std::stod(declared_options["scene.goal_offset_pitch"]); if (!declared_options["scene.goal_offset_yaw"].empty()) - options_.offsets[5] = boost::lexical_cast(declared_options["scene.goal_offset_yaw"]); + options_.offsets[5] = std::stod(declared_options["scene.goal_offset_yaw"]); } - catch (boost::bad_lexical_cast& ex) + catch (std::invalid_argument& ex) { ROS_WARN("%s", ex.what()); } @@ -603,14 +605,14 @@ bool moveit_benchmarks::BenchmarkExecution::readOptions(const std::string& filen // add workspace bounds if specified in the .cfg file options_.workspace_parameters.header.frame_id = declared_options["scene.workspace_frame"]; options_.workspace_parameters.header.stamp = ros::Time::now(); - options_.workspace_parameters.min_corner.x = boost::lexical_cast(strings[0]); - options_.workspace_parameters.min_corner.y = boost::lexical_cast(strings[1]); - options_.workspace_parameters.min_corner.z = boost::lexical_cast(strings[2]); - options_.workspace_parameters.max_corner.x = boost::lexical_cast(strings[3]); - options_.workspace_parameters.max_corner.y = boost::lexical_cast(strings[4]); - options_.workspace_parameters.max_corner.z = boost::lexical_cast(strings[5]); + options_.workspace_parameters.min_corner.x = std::stod(strings[0]); + options_.workspace_parameters.min_corner.y = std::stod(strings[1]); + options_.workspace_parameters.min_corner.z = std::stod(strings[2]); + options_.workspace_parameters.max_corner.x = std::stod(strings[3]); + options_.workspace_parameters.max_corner.y = std::stod(strings[4]); + options_.workspace_parameters.max_corner.z = std::stod(strings[5]); } - catch (boost::bad_lexical_cast& ex) + catch (std::invalid_argument& ex) { ROS_WARN("%s", ex.what()); } @@ -645,9 +647,9 @@ bool moveit_benchmarks::BenchmarkExecution::readOptions(const std::string& filen { try { - options_.timeout = boost::lexical_cast(declared_options["scene.timeout"]); + options_.timeout = std::stod(declared_options["scene.timeout"]); } - catch (boost::bad_lexical_cast& ex) + catch (std::invalid_argument& ex) { ROS_WARN("%s", ex.what()); } @@ -725,16 +727,16 @@ bool moveit_benchmarks::BenchmarkExecution::readOptions(const std::string& filen new_sweep.is_sweep = true; // not a fractional factorial analaysis try { - new_sweep.start = boost::lexical_cast(strings[0]); - new_sweep.step_size = boost::lexical_cast(strings[1]); - new_sweep.end = boost::lexical_cast(strings[2]); + new_sweep.start = std::stod(strings[0]); + new_sweep.step_size = std::stod(strings[1]); + new_sweep.end = std::stod(strings[2]); new_sweep.key = sweep_var; // for logging to file: std::ostringstream ss; ss << "param_" << sweep_var << " REAL"; new_sweep.log_key = ss.str(); } - catch (boost::bad_lexical_cast& ex) + catch (std::invalid_argument& ex) { ROS_WARN("%s", ex.what()); } @@ -804,8 +806,8 @@ void moveit_benchmarks::BenchmarkExecution::collectMetrics(RunData& rundata, const planning_interface::MotionPlanDetailedResponse& mp_res, bool solved, double total_time) { - rundata["total_time REAL"] = boost::lexical_cast(total_time); - rundata["solved BOOLEAN"] = boost::lexical_cast(solved); + rundata["total_time REAL"] = std::to_string(total_time); + rundata["solved BOOLEAN"] = solved ? "true" : "false"; double L = 0.0; double clearance = 0.0; double smoothness = 0.0; @@ -872,17 +874,16 @@ void moveit_benchmarks::BenchmarkExecution::collectMetrics(RunData& rundata, } smoothness /= (double)p.getWayPointCount(); } - rundata["path_" + mp_res.description_[j] + "_correct BOOLEAN"] = boost::lexical_cast(correct); - rundata["path_" + mp_res.description_[j] + "_length REAL"] = boost::lexical_cast(L); - rundata["path_" + mp_res.description_[j] + "_clearance REAL"] = boost::lexical_cast(clearance); - rundata["path_" + mp_res.description_[j] + "_smoothness REAL"] = boost::lexical_cast(smoothness); - rundata["path_" + mp_res.description_[j] + "_time REAL"] = - boost::lexical_cast(mp_res.processing_time_[j]); + rundata["path_" + mp_res.description_[j] + "_correct BOOLEAN"] = correct ? "true" : "false"; + rundata["path_" + mp_res.description_[j] + "_length REAL"] = std::to_string(L); + rundata["path_" + mp_res.description_[j] + "_clearance REAL"] = std::to_string(clearance); + rundata["path_" + mp_res.description_[j] + "_smoothness REAL"] = std::to_string(smoothness); + rundata["path_" + mp_res.description_[j] + "_time REAL"] = std::to_string(mp_res.processing_time_[j]); process_time -= mp_res.processing_time_[j]; } if (process_time <= 0.0) process_time = 0.0; - rundata["process_time REAL"] = boost::lexical_cast(process_time); + rundata["process_time REAL"] = std::to_string(process_time); } } @@ -1425,9 +1426,9 @@ void moveit_benchmarks::BenchmarkExecution::modifyPlannerConfiguration(planning_ try { double value = param_combinations_[param_combinations_id_][param_options_[i].key]; - str_parameter_value = boost::lexical_cast(value); + str_parameter_value = std::to_string(value); } - catch (boost::bad_lexical_cast& ex) + catch (std::bad_alloc& ex) { ROS_WARN("%s", ex.what()); } diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 5019d02770..575b33ae7d 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -874,7 +874,7 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, double total_time) { metrics["time REAL"] = moveit::core::toString(total_time); - metrics["solved BOOLEAN"] = boost::lexical_cast(solved); + metrics["solved BOOLEAN"] = solved ? "true" : "false"; if (solved) { @@ -945,7 +945,7 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, } smoothness /= (double)p.getWayPointCount(); } - metrics["path_" + mp_res.description_[j] + "_correct BOOLEAN"] = boost::lexical_cast(correct); + metrics["path_" + mp_res.description_[j] + "_correct BOOLEAN"] = correct ? "true" : "false"; metrics["path_" + mp_res.description_[j] + "_length REAL"] = moveit::core::toString(traj_len); metrics["path_" + mp_res.description_[j] + "_clearance REAL"] = moveit::core::toString(clearance); metrics["path_" + mp_res.description_[j] + "_smoothness REAL"] = moveit::core::toString(smoothness); @@ -953,7 +953,7 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, if (j == mp_res.trajectory_.size() - 1) { - metrics["final_path_correct BOOLEAN"] = boost::lexical_cast(correct); + metrics["final_path_correct BOOLEAN"] = correct ? "true" : "false"; metrics["final_path_length REAL"] = moveit::core::toString(traj_len); metrics["final_path_clearance REAL"] = moveit::core::toString(clearance); metrics["final_path_smoothness REAL"] = moveit::core::toString(smoothness); diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index 30fd775408..1acff73cce 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -43,7 +43,6 @@ #include #include #include -#include #include namespace pick_place @@ -110,9 +109,19 @@ class PlacePlan : public PickPlacePlanBase bool plan(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::action::PlaceGoal& goal); }; -class PickPlace : private boost::noncopyable, public std::enable_shared_from_this +class PickPlace : public std::enable_shared_from_this { public: + /** + * @brief PickPlace cannot be copy-constructed + */ + PickPlace(const PickPlace&) = delete; + + /** + * @brief PickPlace cannot be copy-assigned + */ + PickPlace& operator=(const PickPlace&) = delete; + static const std::string DISPLAY_PATH_TOPIC; static const std::string DISPLAY_GRASP_TOPIC; diff --git a/moveit_ros/manipulation/pick_place/src/pick_place.cpp b/moveit_ros/manipulation/pick_place/src/pick_place.cpp index a633749f63..544523af61 100644 --- a/moveit_ros/manipulation/pick_place/src/pick_place.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick_place.cpp @@ -191,8 +191,7 @@ void PickPlace::visualizeGrasps(const std::vector& plans) c unsigned int type = std::min(plan->processing_stage_, colors.size() - 1); state.updateStateWithLinkAt(plan->shared_data_->ik_link_, plan->transformed_goal_pose_); state.getRobotMarkers(ma, jmg->getLinkModelNames(), colors[type], - "moveit_grasps:stage_" + boost::lexical_cast(plan->processing_stage_), - ros::Duration(60)); + "moveit_grasps:stage_" + std::to_string(plan->processing_stage_), ros::Duration(60)); } } diff --git a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h index 1a2abe1e34..2dd27e7c2e 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h @@ -191,7 +191,7 @@ class PoseTracking // Flag that a different thread has requested a stop. std::atomic stop_requested_; - boost::optional angular_error_; + std::optional angular_error_; }; // using alias diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 15c5bcd60a..f1dce98563 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -46,7 +46,6 @@ #include #include #include -#include #include #include #include @@ -62,9 +61,19 @@ MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, /** * @brief PlanningSceneMonitor * Subscribes to the topic \e planning_scene */ -class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost::noncopyable +class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor { public: + /** + * @brief PlanningSceneMonitor cannot be copy-constructed + */ + PlanningSceneMonitor(const PlanningSceneMonitor&) = delete; + + /** + * @brief PlanningSceneMonitor cannot be copy-assigned + */ + PlanningSceneMonitor& operator=(const PlanningSceneMonitor&) = delete; + enum SceneUpdateType { /** \brief No update */ diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index 452edfea60..599b17d802 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -58,6 +58,7 @@ #include #include +#include #include #include #include diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index a492bcd04b..e0ae1a39cf 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -54,9 +54,9 @@ #else #include #endif -#include #include #include +#include #include #include diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 0caebce02b..1315ff38b6 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -53,12 +53,12 @@ #include #endif #include -#include #include #include #include #include +#include #include #include @@ -120,7 +120,7 @@ void RobotInteraction::addActiveComponent(const InteractiveMarkerConstructorFn& g.update_pose = update; g.process_feedback = process; // compute the suffix that will be added to the generated markers - g.marker_name_suffix = "_" + name + "_" + boost::lexical_cast(active_generic_.size()); + g.marker_name_suffix = "_" + name + "_" + std::to_string(active_generic_.size()); active_generic_.push_back(g); } diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp index f2d1491305..7f47a3331e 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/background_processing.hpp @@ -38,7 +38,6 @@ #include #include -#include #include #include #include @@ -54,9 +53,19 @@ namespace tools /** \brief This class provides simple API for executing background jobs. A queue of jobs is created and the specified jobs are executed in order, one at a time. */ -class BackgroundProcessing : private boost::noncopyable +class BackgroundProcessing { public: + /** + * @brief BackgroundProcessing cannot be copy-constructed + */ + BackgroundProcessing(const BackgroundProcessing&) = delete; + + /** + * @brief BackgroundProcessing cannot be copy-assigned + */ + BackgroundProcessing& operator=(const BackgroundProcessing&) = delete; + /** \brief Events for jobs */ enum JobEvent { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/mesh_shape.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/mesh_shape.cpp index 06384107eb..40afa630c6 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/mesh_shape.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/mesh_shape.cpp @@ -37,8 +37,8 @@ #include #include -#include #include +#include namespace rviz_rendering { @@ -46,8 +46,7 @@ MeshShape::MeshShape(Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_ : Shape(Shape::Mesh, scene_manager, parent_node), started_(false) { static uint32_t count = 0; - manual_object_ = - scene_manager->createManualObject("MeshShape_ManualObject" + boost::lexical_cast(count++)); + manual_object_ = scene_manager->createManualObject("MeshShape_ManualObject" + std::to_string(count++)); material_->setCullingMode(Ogre::CULL_NONE); } @@ -121,7 +120,7 @@ void MeshShape::endTriangles() started_ = false; manual_object_->end(); static uint32_t count = 0; - std::string name = "ConvertedMeshShape@" + boost::lexical_cast(count++); + std::string name = "ConvertedMeshShape@" + std::to_string(count++); manual_object_->convertToMesh(name); entity_ = scene_manager_->createEntity(name); if (entity_) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp index a27b38b0cc..45029d5724 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp @@ -48,10 +48,10 @@ #include #include -#include #include #include +#include namespace moveit_rviz_plugin { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index 7610776fbc..c94ce94d09 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -36,7 +36,6 @@ #include #include -#include #include @@ -57,6 +56,8 @@ #include #include +#include + using namespace std::placeholders; namespace moveit_rviz_plugin @@ -259,8 +260,8 @@ void TrajectoryVisualization::changedShowTrail() for (std::size_t i = 0; i < trajectory_trail_.size(); ++i) { int waypoint_i = std::min(i * stepsize, t->getWayPointCount() - 1); // limit to last trajectory point - auto r = std::make_unique(scene_node_, context_, - "Trail Robot " + boost::lexical_cast(i), nullptr); + auto r = + std::make_unique(scene_node_, context_, "Trail Robot " + std::to_string(i), nullptr); r->load(*robot_model_->getURDF()); r->setVisualVisible(display_path_visual_enabled_property_->getBool()); r->setCollisionVisible(display_path_collision_enabled_property_->getBool()); @@ -392,9 +393,9 @@ float TrajectoryVisualization::getStateDisplayTime() float value; try { - value = boost::lexical_cast(tm); + value = std::stof(tm); } - catch (const boost::bad_lexical_cast& ex) + catch (const std::invalid_argument& ex) { state_display_time_property_->setStdString(default_time_string); return default_time_value; diff --git a/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp b/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp index 6d392cf23b..5ed6e68984 100644 --- a/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp +++ b/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp @@ -116,9 +116,9 @@ void onRobotState(const moveit_msgs::msg::RobotState& msg, moveit_warehouse::Rob rs.getKnownRobotStates(names); std::set names_set(names.begin(), names.end()); std::size_t n = names.size(); - while (names_set.find("S" + boost::lexical_cast(n)) != names_set.end()) + while (names_set.find("S" + std::to_string(n)) != names_set.end()) n++; - std::string name = "S" + boost::lexical_cast(n); + std::string name = "S" + std::to_string(n); RCLCPP_INFO(LOGGER, "Adding robot state '%s'", name.c_str()); rs.addRobotState(msg, name); } diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 11a8cbacec..86b0f110c1 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -554,9 +554,8 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce StringPairSet& links_seen_colliding, unsigned int* progress) { unsigned int num_disabled = 0; - - boost::thread_group bgroup; // create a group of threads - std::mutex lock; // used for sharing the same data structures + std::vector bgroup; + std::mutex lock; // used for sharing the same data structures int num_threads = std::thread::hardware_concurrency(); // how many cores does this computer have? // RCLCPP_INFO_STREAM_STREAM(LOGGER, "Performing " << num_trials << " trials for 'always in collision' checking on " << @@ -565,19 +564,12 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce for (int i = 0; i < num_threads; ++i) { ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress); - bgroup.create_thread([tc] { return disableNeverInCollisionThread(tc); }); + bgroup.push_back(std::thread([tc] { return disableNeverInCollisionThread(tc); })); } - try - { - bgroup.join_all(); // wait for all threads to finish - } - catch (boost::thread_interrupted) + for (auto& thread : bgroup) { - RCLCPP_WARN_STREAM(LOGGER, "disableNeverInCollision interrupted"); - bgroup.interrupt_all(); - bgroup.join_all(); // wait for all threads to interrupt - throw; + thread.join(); } // Loop through every possible link pair and check if it has ever been seen in collision diff --git a/moveit_setup_assistant/src/widgets/planning_groups_widget.cpp b/moveit_setup_assistant/src/widgets/planning_groups_widget.cpp index 4fd262dae7..be7b6bf5a5 100644 --- a/moveit_setup_assistant/src/widgets/planning_groups_widget.cpp +++ b/moveit_setup_assistant/src/widgets/planning_groups_widget.cpp @@ -1093,9 +1093,9 @@ bool PlanningGroupsWidget::saveGroupScreen() double kinematics_resolution_double; try { - kinematics_resolution_double = boost::lexical_cast(kinematics_resolution); + kinematics_resolution_double = std::stod(kinematics_resolution); } - catch (boost::bad_lexical_cast&) + catch (std::invalid_argument&) { QMessageBox::warning(this, "Error Saving", "Unable to convert kinematics resolution to a double number."); return false; @@ -1105,9 +1105,9 @@ bool PlanningGroupsWidget::saveGroupScreen() double kinematics_timeout_double; try { - kinematics_timeout_double = boost::lexical_cast(kinematics_timeout); + kinematics_timeout_double = std::stod(kinematics_timeout); } - catch (boost::bad_lexical_cast&) + catch (std::invalid_argument&) { QMessageBox::warning(this, "Error Saving", "Unable to convert kinematics solver timeout to a double number."); return false; From da13641d6513f31872fba66f5e85255f5c6ff2c8 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 14:37:03 -0600 Subject: [PATCH 22/43] updated std::optional usage --- .../cartesianconfiguration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 5076547887..847ee256c6 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -158,7 +158,7 @@ inline const JointConfiguration& CartesianConfiguration::getSeed() const inline bool CartesianConfiguration::hasSeed() const { - return seed_.is_initialized(); + return seed_.has_value(); } inline void CartesianConfiguration::setPoseTolerance(const double tol) From 0a22f2d6dc6b1e17cf91f2466aac3074e76caeb4 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Mon, 13 Jun 2022 16:38:10 -0600 Subject: [PATCH 23/43] changing variant usage to be consistent with std --- .../pilz_industrial_motion_planner/command_list_manager.h | 5 +++-- .../src/command_list_manager.cpp | 4 ++-- .../command_types_typedef.h | 8 ++++---- .../pilz_industrial_motion_planner_testutils/sequence.h | 2 +- moveit_ros/moveit_servo/src/pose_tracking.cpp | 1 - 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h index 911ba05c49..638b63c986 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/command_list_manager.h @@ -36,7 +36,8 @@ #include -#include +#include +#include #include #include @@ -107,7 +108,7 @@ class CommandListManager private: using MotionResponseCont = std::vector; - using RobotState_OptRef = std::optional; + using RobotState_OptRef = const std::optional>; using RadiiCont = std::vector; using GroupNamesCont = std::vector; diff --git a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp index 34f41d206d..8702caac22 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp @@ -161,10 +161,10 @@ CommandListManager::getPreviousEndState(const MotionResponseCont& motion_plan_re { if (it->trajectory_->getGroupName() == group_name) { - return it->trajectory_->getLastWayPoint(); + return std::reference_wrapper(it->trajectory_->getLastWayPoint()); } } - return boost::none; + return {}; } void CommandListManager::setStartState(const MotionResponseCont& motion_plan_responses, const std::string& group_name, diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h index dcf2cab731..697cc5781f 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/command_types_typedef.h @@ -34,8 +34,6 @@ #pragma once -#include - #include "ptp.h" #include "lin.h" #include "circ.h" @@ -44,6 +42,8 @@ #include "cartesianconfiguration.h" #include "circ_auxiliary_types.h" +#include + namespace pilz_industrial_motion_planner_testutils { typedef Ptp PtpJoint; @@ -60,7 +60,7 @@ typedef Circ C typedef Circ CircJointCenterCart; typedef Circ CircJointInterimCart; -typedef boost::variant +typedef std::variant CmdVariant; } // namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h index 1ffad86ccc..e18d517080 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/sequence.h @@ -140,6 +140,6 @@ inline void Sequence::setAllBlendRadiiToZero() template inline bool Sequence::cmdIsOfType(const size_t index_cmd) const { - return cmds_.at(index_cmd).first.type() == typeid(T); + return std::holds_alternative(cmds_.at(index_cmd).first); } } // namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_ros/moveit_servo/src/pose_tracking.cpp b/moveit_ros/moveit_servo/src/pose_tracking.cpp index ee13f15272..cd6a1b44f5 100644 --- a/moveit_ros/moveit_servo/src/pose_tracking.cpp +++ b/moveit_ros/moveit_servo/src/pose_tracking.cpp @@ -81,7 +81,6 @@ PoseTracking::PoseTracking(const rclcpp::Node::SharedPtr& node, const ServoParam , transform_buffer_(node_->get_clock()) , transform_listener_(transform_buffer_) , stop_requested_(false) - , angular_error_(boost::none) { readROSParams(); From 03fada229dab87a8dc05c4c9998b97d189496c2b Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 12:36:20 -0600 Subject: [PATCH 24/43] fixed outdated calls to boost --- .../src/sequence.cpp | 9 ++++----- moveit_ros/moveit_servo/src/pose_tracking.cpp | 2 +- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp index e6b3043314..4f4554196a 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/sequence.cpp @@ -35,14 +35,13 @@ #include "pilz_industrial_motion_planner_testutils/sequence.h" #include -#include namespace pilz_industrial_motion_planner_testutils { /** * @brief Visitor transforming the stored command into a MotionPlanRequest. */ -class ToReqVisitor : public boost::static_visitor +class ToReqVisitor { public: template @@ -55,7 +54,7 @@ class ToReqVisitor : public boost::static_visitor +class ToBaseVisitor { public: template @@ -73,7 +72,7 @@ moveit_msgs::msg::MotionSequenceRequest Sequence::toRequest() const for (const auto& cmd : cmds_) { moveit_msgs::msg::MotionSequenceItem item; - item.req = boost::apply_visitor(ToReqVisitor(), cmd.first); + item.req = std::visit(ToReqVisitor(), cmd.first); if (std::find(group_names.begin(), group_names.end(), item.req.group_name) != group_names.end()) { @@ -114,7 +113,7 @@ void Sequence::erase(const size_t start, const size_t end) MotionCmd& Sequence::getCmd(const size_t index_cmd) { - return boost::apply_visitor(ToBaseVisitor(), cmds_.at(index_cmd).first); + return std::visit(ToBaseVisitor(), cmds_.at(index_cmd).first); } } // namespace pilz_industrial_motion_planner_testutils diff --git a/moveit_ros/moveit_servo/src/pose_tracking.cpp b/moveit_ros/moveit_servo/src/pose_tracking.cpp index cd6a1b44f5..fed500dfad 100644 --- a/moveit_ros/moveit_servo/src/pose_tracking.cpp +++ b/moveit_ros/moveit_servo/src/pose_tracking.cpp @@ -345,7 +345,7 @@ void PoseTracking::doPostMotionReset() { stopMotion(); stop_requested_ = false; - angular_error_ = boost::none; + angular_error_ = {}; // Reset error integrals and previous errors of PID controllers cartesian_position_pids_[0].reset(); From bff3698c71c6169deb6484926b7ab9514249e82e Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 13:56:56 -0600 Subject: [PATCH 25/43] updating comments and adding/removing includes --- moveit_core/collision_detection/src/collision_matrix.cpp | 2 +- moveit_core/collision_detection/src/world.cpp | 2 +- .../cartesianconfiguration.h | 2 +- .../src/xml_testdata_loader.cpp | 1 - moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h | 2 +- 5 files changed, 4 insertions(+), 5 deletions(-) diff --git a/moveit_core/collision_detection/src/collision_matrix.cpp b/moveit_core/collision_detection/src/collision_matrix.cpp index 77e601640e..8de60b1f96 100644 --- a/moveit_core/collision_detection/src/collision_matrix.cpp +++ b/moveit_core/collision_detection/src/collision_matrix.cpp @@ -368,7 +368,7 @@ void AllowedCollisionMatrix::getMessage(moveit_msgs::msg::AllowedCollisionMatrix for (std::size_t i = 0; i < msg.entry_names.size(); ++i) msg.entry_values[i].enabled.resize(msg.entry_names.size(), false); - // there is an approximation here: if we use a boost function to decide + // there is an approximation here: if we use a function to decide // whether a collision is allowed or not, we just assume the collision is not allowed. for (std::size_t i = 0; i < msg.entry_names.size(); ++i) { diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 1cb5baa66d..8afc6657ab 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -175,7 +175,7 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram for (const std::pair& object : objects_) { // if "object name/" matches start of object_id, we found the matching object - // name.rfind is in service of removing the call to boost::starts_with and does the same thing + // rfind searches name for object.first in the first index (returns 0 if found) if (name.rfind(object.first, 0) == 0 && name[object.first.length()] == '/') { auto it = object.second->global_subframe_poses_.find(name.substr(object.first.length() + 1)); diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h index 847ee256c6..b6057abdb3 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/cartesianconfiguration.h @@ -36,8 +36,8 @@ #include #include +#include -#include #include #include #include diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp index 3fef3967ed..4a6c9f8ab1 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp @@ -38,7 +38,6 @@ #include #include -#include #include "pilz_industrial_motion_planner_testutils/default_values.h" #include "pilz_industrial_motion_planner_testutils/exception_types.h" diff --git a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h index 2dd27e7c2e..b7d805a1c7 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h @@ -39,7 +39,7 @@ #pragma once #include -#include +#include #include #include #include From 4a1605a9cd6ee4df52a66cdeb88602e7fb5b3d1a Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 14:48:58 -0600 Subject: [PATCH 26/43] added commit and removed comment --- .../include/moveit/ompl_interface/detail/constraints_library.h | 2 +- .../include/moveit/semantic_world/semantic_world.h | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index fcfdc9bdb0..df22d88607 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -36,11 +36,11 @@ #pragma once +#include #include #include #include #include -#include namespace ompl_interface { diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index a6b6f983e4..66d4eda184 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -150,8 +150,6 @@ class SemanticWorld std::map current_tables_in_collision_world_; - // boost::mutex table_lock_; - rclcpp::Subscription::SharedPtr table_subscriber_; rclcpp::Publisher::SharedPtr visualization_publisher_; From e63795576214b6ab54422c2510b55907bc510d6f Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 15:36:55 -0600 Subject: [PATCH 27/43] change to std asserts --- .../perception/mesh_filter/test/mesh_filter_test.cpp | 4 ++-- moveit_ros/robot_interaction/src/kinematic_options.cpp | 9 ++++----- 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp index 46acbcd874..a8ee7b9086 100644 --- a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp +++ b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp @@ -79,8 +79,8 @@ class FilterTraits template class MeshFilterTest : public testing::TestWithParam { - BOOST_STATIC_ASSERT_MSG(FilterTraits::FILTER_GL_TYPE != GL_ZERO, "Only \"float\" and \"unsigned short int\" " - "are allowed."); + static_assert(FilterTraits::FILTER_GL_TYPE != GL_ZERO, "Only \"float\" and \"unsigned short int\" " + "are allowed."); public: MeshFilterTest(unsigned width = 500, unsigned height = 500, double near = 0.5, double far = 5.0, double shadow = 0.1, diff --git a/moveit_ros/robot_interaction/src/kinematic_options.cpp b/moveit_ros/robot_interaction/src/kinematic_options.cpp index 357e9516aa..ea03b44119 100644 --- a/moveit_ros/robot_interaction/src/kinematic_options.cpp +++ b/moveit_ros/robot_interaction/src/kinematic_options.cpp @@ -35,7 +35,6 @@ /* Author: Acorn Pooley */ #include -#include #include static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_robot_interaction.kinematic_options"); @@ -85,7 +84,7 @@ void robot_interaction::KinematicOptions::setOptions(const KinematicOptions& sou F(::kinematics::DiscretizationMethods::DiscretizationMethod, discretization_method, DISCRETIZATION_METHOD) // This structure should be identical to kinematics::KinematicsQueryOptions - // This is only used in the BOOST_STATIC_ASSERT below. + // This is only used in the static_assert below. struct DummyKinematicsQueryOptions { #define F(type, member, enumval) type member; @@ -93,7 +92,7 @@ void robot_interaction::KinematicOptions::setOptions(const KinematicOptions& sou #undef F }; // This structure should be identical to robot_interaction::KinematicOptions - // This is only used in the BOOST_STATIC_ASSERT below. + // This is only used in the static_assert below. struct DummyKinematicOptions { #define F(type, member, enumval) type member; @@ -106,8 +105,8 @@ void robot_interaction::KinematicOptions::setOptions(const KinematicOptions& sou // kinematics::KinematicsQueryOptions or robot_interaction::KinematicOptions // and not added to the O_FIELDS and QO_FIELDS definitions above. To fix add // any new fields to the definitions above. - BOOST_STATIC_ASSERT(sizeof(kinematics::KinematicsQueryOptions) == sizeof(DummyKinematicsQueryOptions)); - BOOST_STATIC_ASSERT(sizeof(KinematicOptions) == sizeof(DummyKinematicOptions)); + static_assert(sizeof(kinematics::KinematicsQueryOptions) == sizeof(DummyKinematicsQueryOptions)); + static_assert(sizeof(KinematicOptions) == sizeof(DummyKinematicOptions)); // copy fields from other to this if its bit is set in fields #define F(type, member, enumval) \ From 9780359302bc63cc04780262a29ceb267ed81254 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 15:57:23 -0600 Subject: [PATCH 28/43] removing unnecessary boost usage --- .../include/moveit/planning_scene/planning_scene.h | 1 + .../include/moveit/robot_state/robot_state.h | 7 +++---- moveit_core/robot_state/src/robot_state.cpp | 11 ++++++----- moveit_core/utils/src/robot_model_test_utils.cpp | 2 +- .../detail/GreedyKCenters.h | 2 +- .../chomp_motion_planner/multivariate_gaussian.h | 2 +- 6 files changed, 13 insertions(+), 12 deletions(-) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 7e17a04874..d6c4dc9752 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -55,6 +55,7 @@ #include #include #include +#include #include "rclcpp/rclcpp.hpp" #include "moveit_planning_scene_export.h" diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 7b108e63ca..44e0877b1b 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -46,7 +46,6 @@ #include #include -#include #include /* Terminology @@ -1356,7 +1355,7 @@ class RobotState { throw Exception("Invalid link"); } - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); return global_link_transforms_[link->getLinkIndex()]; } @@ -1388,7 +1387,7 @@ class RobotState const Eigen::Isometry3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const { - BOOST_VERIFY(checkCollisionTransforms()); + assert(checkCollisionTransforms()); return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index]; } @@ -1416,7 +1415,7 @@ class RobotState const Eigen::Isometry3d& getJointTransform(const JointModel* joint) const { - BOOST_VERIFY(checkJointTransforms(joint)); + assert(checkJointTransforms(joint)); return variable_joint_transforms_[joint->getJointIndex()]; } diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index 4a9022a497..e0eeca7510 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -52,6 +52,7 @@ #include #include #include +#include namespace moveit { @@ -1132,7 +1133,7 @@ const Eigen::Isometry3d& RobotState::getFrameInfo(const std::string& frame_id, c } if ((robot_link = robot_model_->getLinkModel(frame_id, &frame_found))) { - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); return global_link_transforms_[robot_link->getLinkIndex()]; } robot_link = nullptr; @@ -1144,7 +1145,7 @@ const Eigen::Isometry3d& RobotState::getFrameInfo(const std::string& frame_id, c const Eigen::Isometry3d& transform = jt->second->getGlobalPose(); robot_link = jt->second->getAttachedLink(); frame_found = true; - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); return transform; } @@ -1155,7 +1156,7 @@ const Eigen::Isometry3d& RobotState::getFrameInfo(const std::string& frame_id, c if (frame_found) { robot_link = body.second->getAttachedLink(); - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); return transform; } } @@ -1284,7 +1285,7 @@ bool RobotState::getJacobian(const JointModelGroup* group, const LinkModel* link const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian, bool use_quaternion_representation) const { - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); if (!group->isChain()) { @@ -2049,7 +2050,7 @@ double RobotState::computeCartesianPath(const JointModelGroup* group, std::vecto void RobotState::computeAABB(std::vector& aabb) const { - BOOST_VERIFY(checkLinkTransforms()); + assert(checkLinkTransforms()); core::AABB bounding_box; std::vector links = robot_model_->getLinkModelsWithCollisionGeometry(); diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 4521525c64..ea0fb92c43 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -34,7 +34,7 @@ /* Author: Bryce Willey */ -#include +#include // TODO #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index 1c4eef699f..b17526c346 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -54,7 +54,7 @@ class GreedyKCenters /** \brief The definition of a distance function */ using DistanceFunction = std::function; /** \brief A matrix type for storing distances between points and centers */ - using Matrix = boost::numeric::ublas::matrix; + using Matrix = boost::numeric::ublas::matrix; // TODO GreedyKCenters() = default; diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 23ae0b135f..bbbafef3b8 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -63,7 +63,7 @@ class MultivariateGaussian Eigen::MatrixXd covariance_cholesky_; /**< Cholesky decomposition (LL^T) of the covariance */ int size_; - boost::mt19937 rng_; + boost::mt19937 rng_; // TODO boost::normal_distribution<> normal_dist_; boost::variate_generator > gaussian_; }; From a23aff03e5acc946473377793a6b52be3e03b9ea Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Tue, 14 Jun 2022 17:08:57 -0600 Subject: [PATCH 29/43] removed boost regex --- moveit_core/utils/src/robot_model_test_utils.cpp | 6 ++++-- .../benchmarks/benchmarks/src/benchmark_execution.cpp | 8 ++++---- moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 6 +++--- .../warehouse/warehouse/src/moveit_message_storage.cpp | 8 ++++---- .../warehouse/warehouse/src/planning_scene_storage.cpp | 8 ++++---- 5 files changed, 19 insertions(+), 17 deletions(-) diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index ea0fb92c43..5840d74237 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -117,8 +117,10 @@ RobotModelBuilder::RobotModelBuilder(const std::string& name, const std::string& void RobotModelBuilder::addChain(const std::string& section, const std::string& type, const std::vector& joint_origins, urdf::Vector3 joint_axis) { - std::vector link_names; - boost::split_regex(link_names, section, boost::regex("->")); + // https://stackoverflow.com/questions/53849/how-do-i-tokenize-a-string-in-c + auto const link_names = std::vector( + std::sregex_token_iterator{ begin(str), end(str), std::regex{ "->" }, -1 }, std::sregex_token_iterator{}); + if (link_names.empty()) { RCLCPP_ERROR(LOGGER, "No links specified (empty section?)"); diff --git a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp index 91e42928bb..0172c80556 100644 --- a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp +++ b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp @@ -40,7 +40,6 @@ #include #include -#include #include #include #include @@ -63,6 +62,7 @@ #include #include #include +#include namespace moveit_benchmarks { @@ -231,13 +231,13 @@ void moveit_benchmarks::BenchmarkExecution::runAllBenchmarks(BenchmarkType type) std::vector start_states; if (!options_.start_regex.empty()) { - boost::regex start_regex(options_.start_regex); + std::regex start_regex(options_.start_regex); std::vector state_names; rs_.getKnownRobotStates(state_names); for (std::size_t i = 0; i < state_names.size(); ++i) { - boost::cmatch match; - if (boost::regex_match(state_names[i].c_str(), match, start_regex)) + std::smatch match; + if (std::regex_match(state_names[i], match, start_regex)) start_states.push_back(state_names[i]); } if (start_states.empty()) diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 575b33ae7d..b9184d8125 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -674,13 +674,13 @@ bool BenchmarkExecutor::loadStates(const std::string& regex, std::vector state_names; rs_->getKnownRobotStates(state_names); for (const std::string& state_name : state_names) { - boost::cmatch match; - if (boost::regex_match(state_name.c_str(), match, start_regex)) + std::smatch match; + if (std::regex_match(state_name, match, start_regex)) { moveit_warehouse::RobotStateWithMetadata robot_state; try diff --git a/moveit_ros/warehouse/warehouse/src/moveit_message_storage.cpp b/moveit_ros/warehouse/warehouse/src/moveit_message_storage.cpp index 6b5f793fa6..634074ef87 100644 --- a/moveit_ros/warehouse/warehouse/src/moveit_message_storage.cpp +++ b/moveit_ros/warehouse/warehouse/src/moveit_message_storage.cpp @@ -36,9 +36,9 @@ #include #include -#include #include #include +#include moveit_warehouse::MoveItMessageStorage::MoveItMessageStorage(warehouse_ros::DatabaseConnection::Ptr conn) : conn_(std::move(conn)) @@ -50,11 +50,11 @@ void moveit_warehouse::MoveItMessageStorage::filterNames(const std::string& rege if (!regex.empty()) { std::vector fnames; - boost::regex r(regex); + std::regex r(regex); for (std::string& name : names) { - boost::cmatch match; - if (boost::regex_match(name.c_str(), match, r)) + std::smatch match; + if (std::regex_match(name, match, r)) fnames.push_back(name); } names.swap(fnames); diff --git a/moveit_ros/warehouse/warehouse/src/planning_scene_storage.cpp b/moveit_ros/warehouse/warehouse/src/planning_scene_storage.cpp index 0e8d97348f..158459c0f0 100644 --- a/moveit_ros/warehouse/warehouse/src/planning_scene_storage.cpp +++ b/moveit_ros/warehouse/warehouse/src/planning_scene_storage.cpp @@ -35,9 +35,9 @@ /* Author: Ioan Sucan */ #include -#include #include #include +#include const std::string moveit_warehouse::PlanningSceneStorage::DATABASE_NAME = "moveit_planning_scenes"; @@ -286,11 +286,11 @@ void moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames(const std:: if (!regex.empty()) { std::vector fnames; - boost::regex r(regex); + std::regex r(regex); for (const std::string& query_name : query_names) { - boost::cmatch match; - if (boost::regex_match(query_name.c_str(), match, r)) + std::smatch match; + if (std::regex_match(query_name, match, r)) { fnames.push_back(query_name); } From d4d3c60d92c3ec882800b8b56339195c29f28ff6 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 15 Jun 2022 10:19:00 -0600 Subject: [PATCH 30/43] fixed bug in string tokenizing --- moveit_core/utils/src/robot_model_test_utils.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 5840d74237..5162fd1f0e 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -43,6 +43,7 @@ #include #include #include +#include namespace moveit { @@ -118,8 +119,9 @@ void RobotModelBuilder::addChain(const std::string& section, const std::string& const std::vector& joint_origins, urdf::Vector3 joint_axis) { // https://stackoverflow.com/questions/53849/how-do-i-tokenize-a-string-in-c - auto const link_names = std::vector( - std::sregex_token_iterator{ begin(str), end(str), std::regex{ "->" }, -1 }, std::sregex_token_iterator{}); + std::regex re("->"); + auto const link_names = std::vector(std::sregex_token_iterator{ begin(section), end(section), re, -1 }, + std::sregex_token_iterator{}); if (link_names.empty()) { From c6bb633414f0e7acc3a94b93510db39a3d13e964 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 15 Jun 2022 11:00:52 -0600 Subject: [PATCH 31/43] re-adding boost serializer --- .../include/moveit/ompl_interface/detail/constraints_library.h | 1 + 1 file changed, 1 insertion(+) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h index df22d88607..7893627c11 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraints_library.h @@ -41,6 +41,7 @@ #include #include #include +#include namespace ompl_interface { From 9d587a92b43f5d987730ba4f29d39b781c72dadd Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 15 Jun 2022 14:19:13 -0600 Subject: [PATCH 32/43] further boost removal --- .../utils/src/robot_model_test_utils.cpp | 1 - .../detail/GreedyKCenters.h | 3 ++- .../multivariate_gaussian.h | 18 +++++++----------- 3 files changed, 9 insertions(+), 13 deletions(-) diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 5162fd1f0e..dde9818be0 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -34,7 +34,6 @@ /* Author: Bryce Willey */ -#include // TODO #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index b17526c346..ee44ed9f00 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -41,6 +41,7 @@ #include #include #include +#include namespace cached_ik_kinematics_plugin { @@ -54,7 +55,7 @@ class GreedyKCenters /** \brief The definition of a distance function */ using DistanceFunction = std::function; /** \brief A matrix type for storing distances between points and centers */ - using Matrix = boost::numeric::ublas::matrix; // TODO + using Matrix = Eigen::Matrix; GreedyKCenters() = default; diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index bbbafef3b8..ae6cf5b296 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -36,6 +36,7 @@ #pragma once +#include #include #include #include @@ -63,9 +64,9 @@ class MultivariateGaussian Eigen::MatrixXd covariance_cholesky_; /**< Cholesky decomposition (LL^T) of the covariance */ int size_; - boost::mt19937 rng_; // TODO - boost::normal_distribution<> normal_dist_; - boost::variate_generator > gaussian_; + std::random_device rd; + std::mt19937 rng_; + std::normal_distribution gaussian_; }; //////////////////////// template function definitions follow ////////////////////////////// @@ -73,14 +74,9 @@ class MultivariateGaussian template MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase& mean, const Eigen::MatrixBase& covariance) - : mean_(mean) - , covariance_(covariance) - , covariance_cholesky_(covariance_.llt().matrixL()) - , rng_() - , normal_dist_(0.0, 1.0) - , gaussian_(rng_, normal_dist_) + : mean_(mean), covariance_(covariance), covariance_cholesky_(covariance_.llt().matrixL()), rd(), gaussian_(0.0, 1.0) { - rng_.seed(rand()); + rng_ = std::mt19937(rd()); size_ = mean.rows(); } @@ -88,7 +84,7 @@ template void MultivariateGaussian::sample(Eigen::MatrixBase& output) { for (int i = 0; i < size_; ++i) - output(i) = gaussian_(); + output(i) = gaussian_(rng_); output = mean_ + covariance_cholesky_ * output; } } // namespace chomp From 98385294257ed40ed9c9e6046e3fc6fc11064ffd Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 15 Jun 2022 14:32:21 -0600 Subject: [PATCH 33/43] switching to eigen --- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index ee44ed9f00..b9829e80e0 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -41,7 +41,7 @@ #include #include #include -#include +#include namespace cached_ik_kinematics_plugin { @@ -55,7 +55,7 @@ class GreedyKCenters /** \brief The definition of a distance function */ using DistanceFunction = std::function; /** \brief A matrix type for storing distances between points and centers */ - using Matrix = Eigen::Matrix; + using Matrix = Eigen::MatrixXd; GreedyKCenters() = default; @@ -89,8 +89,8 @@ class GreedyKCenters centers.clear(); centers.reserve(k); - if (dists.size1() < data.size() || dists.size2() < k) - dists.resize(std::max(2 * dists.size1() + 1, data.size()), k, false); + if (dists.rows() < data.size() || dists.cols() < k) + dists.resize(std::max(2 * dists.rows() + 1, data.size()), k, false); // first center is picked randomly centers.push_back(std::uniform_int_distribution{ 0, data.size() - 1 }(generator_)); for (unsigned i = 1; i < k; ++i) From c73ec20acb78d26df36f822f89d08d4cfb763612 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Wed, 15 Jun 2022 15:23:42 -0600 Subject: [PATCH 34/43] fixing std rng usage --- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 4 ++-- .../include/chomp_motion_planner/multivariate_gaussian.h | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index b9829e80e0..de0794689b 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -89,8 +89,8 @@ class GreedyKCenters centers.clear(); centers.reserve(k); - if (dists.rows() < data.size() || dists.cols() < k) - dists.resize(std::max(2 * dists.rows() + 1, data.size()), k, false); + if (((long unsigned int)dists.rows()) < data.size() || ((long unsigned int)dists.cols()) < k) + dists.resize(std::max(2 * ((long unsigned int)dists.rows()) + 1, data.size()), k); // first center is picked randomly centers.push_back(std::uniform_int_distribution{ 0, data.size() - 1 }(generator_)); for (unsigned i = 1; i < k; ++i) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index ae6cf5b296..34308958a9 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -64,7 +64,6 @@ class MultivariateGaussian Eigen::MatrixXd covariance_cholesky_; /**< Cholesky decomposition (LL^T) of the covariance */ int size_; - std::random_device rd; std::mt19937 rng_; std::normal_distribution gaussian_; }; @@ -74,9 +73,9 @@ class MultivariateGaussian template MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase& mean, const Eigen::MatrixBase& covariance) - : mean_(mean), covariance_(covariance), covariance_cholesky_(covariance_.llt().matrixL()), rd(), gaussian_(0.0, 1.0) + : mean_(mean), covariance_(covariance), covariance_cholesky_(covariance_.llt().matrixL()), gaussian_(0.0, 1.0) { - rng_ = std::mt19937(rd()); + rng_ = std::mt19937(std::random_device{}()); size_ = mean.rows(); } From 366db23de31f56223dca7fbd673db65b751f3606 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:29:32 -0600 Subject: [PATCH 35/43] removing unnecessary includes --- moveit_core/collision_detection/CMakeLists.txt | 1 - moveit_core/collision_detection/src/world.cpp | 1 - .../include/moveit/robot_state/cartesian_interpolator.h | 2 -- moveit_core/robot_state/src/attached_body.cpp | 1 - moveit_core/robot_state/src/conversions.cpp | 2 -- moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt | 3 --- .../moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 1 - .../cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h | 1 + .../include/chomp_motion_planner/multivariate_gaussian.h | 3 --- .../move_group_interface/src/wrap_python_move_group.cpp | 1 - 10 files changed, 1 insertion(+), 15 deletions(-) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index 73685def49..60ae3c713c 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -24,7 +24,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} visualization_msgs tf2_eigen geometric_shapes - Boost OCTOMAP ) diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 8afc6657ab..713b2997ab 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -36,7 +36,6 @@ #include #include -#include #include #include diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index f5b549d245..edd14535e3 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -40,8 +40,6 @@ #include -#include - namespace moveit { namespace core diff --git a/moveit_core/robot_state/src/attached_body.cpp b/moveit_core/robot_state/src/attached_body.cpp index 829776fee1..58611f33c2 100644 --- a/moveit_core/robot_state/src/attached_body.cpp +++ b/moveit_core/robot_state/src/attached_body.cpp @@ -37,7 +37,6 @@ #include #include #include -#include namespace moveit { diff --git a/moveit_core/robot_state/src/conversions.cpp b/moveit_core/robot_state/src/conversions.cpp index 708857948b..5db0b68747 100644 --- a/moveit_core/robot_state/src/conversions.cpp +++ b/moveit_core/robot_state/src/conversions.cpp @@ -44,9 +44,7 @@ #else #include #endif -#include #include -#include "rclcpp/rclcpp.hpp" namespace moveit { diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index 9263b4aabc..e78ee06f0a 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -1,8 +1,6 @@ find_package(trac_ik_kinematics_plugin QUIET) find_package(ur_kinematics QUIET) -find_package(Boost COMPONENTS filesystem program_options REQUIRED) - set(MOVEIT_LIB_NAME moveit_cached_ik_kinematics_base) add_library(${MOVEIT_LIB_NAME} SHARED src/ik_cache.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") @@ -10,7 +8,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp moveit_core moveit_msgs - Boost ) if(trac_ik_kinematics_plugin_FOUND) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h index de0794689b..b1120c3864 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/GreedyKCenters.h @@ -38,7 +38,6 @@ #pragma once -#include #include #include #include diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 495cf2d7c3..431d8b47e6 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -45,6 +45,7 @@ #include #include "GreedyKCenters.h" #include "NearestNeighbors.h" +#include namespace cached_ik_kinematics_plugin { diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index 34308958a9..d9affb9b6a 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -37,9 +37,6 @@ #pragma once #include -#include -#include -#include #include #include #include diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index 599b17d802..452edfea60 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -58,7 +58,6 @@ #include #include -#include #include #include #include From 9d00f996f4d6323118f474fb5f312b9a1b18ab92 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:32:35 -0600 Subject: [PATCH 36/43] re-adding removed include --- .../move_group_interface/src/wrap_python_move_group.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index 452edfea60..599b17d802 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -58,6 +58,7 @@ #include #include +#include #include #include #include From 3fdf34bf45945fc28dea3bfc8444d077eb2947b8 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:39:58 -0600 Subject: [PATCH 37/43] removing more includes --- moveit_ros/manipulation/CMakeLists.txt | 2 -- .../move_group_pick_place_capability/CMakeLists.txt | 2 +- moveit_ros/manipulation/pick_place/CMakeLists.txt | 2 +- .../perception/depth_image_octomap_updater/CMakeLists.txt | 2 -- moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt | 2 -- 5 files changed, 2 insertions(+), 8 deletions(-) diff --git a/moveit_ros/manipulation/CMakeLists.txt b/moveit_ros/manipulation/CMakeLists.txt index 022bc76e91..4ec24aeb89 100644 --- a/moveit_ros/manipulation/CMakeLists.txt +++ b/moveit_ros/manipulation/CMakeLists.txt @@ -25,7 +25,6 @@ find_package(catkin REQUIRED COMPONENTS ) find_package(Eigen3 REQUIRED) -find_package(Boost REQUIRED thread system filesystem date_time program_options) generate_dynamic_reconfigure_options("pick_place/cfg/PickPlaceDynamicReconfigure.cfg") @@ -51,7 +50,6 @@ include_directories(move_group_pick_place_capability/include) include_directories(SYSTEM ${catkin_INCLUDE_DIRS} - ${Boost_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS}) add_subdirectory(pick_place) diff --git a/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt b/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt index fc1cb27f0e..91d8a4e01d 100644 --- a/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt +++ b/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt @@ -7,7 +7,7 @@ add_library(${MOVEIT_LIB_NAME} ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_link_libraries(${MOVEIT_LIB_NAME} moveit_pick_place_planner ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} moveit_pick_place_planner ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_ros/manipulation/pick_place/CMakeLists.txt b/moveit_ros/manipulation/pick_place/CMakeLists.txt index c2e8edc6ee..f612a3fdb0 100644 --- a/moveit_ros/manipulation/pick_place/CMakeLists.txt +++ b/moveit_ros/manipulation/pick_place/CMakeLists.txt @@ -12,7 +12,7 @@ add_library(${MOVEIT_LIB_NAME} ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) install(TARGETS ${MOVEIT_LIB_NAME} EXPORT ${MOVEIT_LIB_NAME} diff --git a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt index 0146061207..013044d7e6 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt +++ b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt @@ -11,7 +11,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core tf2_geometry_msgs geometric_shapes moveit_ros_occupancy_map_monitor - Boost ) target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_lazy_free_space_updater moveit_mesh_filter) @@ -26,7 +25,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} tf2_geometry_msgs geometric_shapes moveit_ros_occupancy_map_monitor - Boost pluginlib ) target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core) diff --git a/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt b/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt index 067554aafd..c6d1330808 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt +++ b/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt @@ -11,7 +11,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core moveit_ros_occupancy_map_monitor tf2_geometry_msgs tf2 - Boost ) target_link_libraries(${MOVEIT_LIB_NAME}_core moveit_point_containment_filter) set_target_properties(${MOVEIT_LIB_NAME}_core PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") @@ -28,7 +27,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_ros_occupancy_map_monitor tf2_geometry_msgs tf2 - Boost pluginlib ) target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core) From 23dcfa0465aaa7929b78755666adcecf8206c2fc Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:43:15 -0600 Subject: [PATCH 38/43] removing more includes --- moveit_ros/perception/mesh_filter/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 54b973d317..d6b0916001 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -16,7 +16,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} moveit_core geometric_shapes Eigen3 - Boost ) target_link_libraries(${MOVEIT_LIB_NAME} ${gl_LIBS} ${SYSTEM_GL_LIBRARIES}) From 52a8e1ea61268623759fcd16e8b669dd12263302 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:46:41 -0600 Subject: [PATCH 39/43] removing unnecessary includes --- moveit_ros/robot_interaction/src/interaction_handler.cpp | 1 - moveit_ros/robot_interaction/src/robot_interaction.cpp | 2 -- 2 files changed, 3 deletions(-) diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index e0ae1a39cf..e4a59cb68e 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -54,7 +54,6 @@ #else #include #endif -#include #include #include diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 1315ff38b6..5e464e0203 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -53,8 +53,6 @@ #include #endif #include -#include -#include #include #include From 405be90c912c5d10c85649762f8dd15c52e86a4f Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Thu, 16 Jun 2022 11:50:27 -0600 Subject: [PATCH 40/43] removing unnecessary includes --- .../visualization/planning_scene_rviz_plugin/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 858e5958c5..f71a603caa 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -16,7 +16,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core moveit_ros_planning moveit_msgs pluginlib - Boost rviz_ogre_vendor ) target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/include") From 68c31b79364cf2c60f6d7881467999242e2b2de5 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Fri, 17 Jun 2022 09:19:02 -0600 Subject: [PATCH 41/43] switched back to boost version --- moveit_core/utils/src/robot_model_test_utils.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index dde9818be0..4521525c64 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -34,6 +34,7 @@ /* Author: Bryce Willey */ +#include #include #include #include @@ -42,7 +43,6 @@ #include #include #include -#include namespace moveit { @@ -117,11 +117,8 @@ RobotModelBuilder::RobotModelBuilder(const std::string& name, const std::string& void RobotModelBuilder::addChain(const std::string& section, const std::string& type, const std::vector& joint_origins, urdf::Vector3 joint_axis) { - // https://stackoverflow.com/questions/53849/how-do-i-tokenize-a-string-in-c - std::regex re("->"); - auto const link_names = std::vector(std::sregex_token_iterator{ begin(section), end(section), re, -1 }, - std::sregex_token_iterator{}); - + std::vector link_names; + boost::split_regex(link_names, section, boost::regex("->")); if (link_names.empty()) { RCLCPP_ERROR(LOGGER, "No links specified (empty section?)"); From 669f474f4f1a705d261d1781550fe4d35d5e68af Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Fri, 17 Jun 2022 09:21:53 -0600 Subject: [PATCH 42/43] sorting includes alphabetically --- moveit_core/robot_state/src/robot_state.cpp | 10 +++++----- .../benchmarks/benchmarks/src/benchmark_execution.cpp | 4 ++-- .../moveit_servo/include/moveit_servo/pose_tracking.h | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index e0eeca7510..61934fea29 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -35,11 +35,11 @@ /* Author: Ioan Sucan, Sachin Chitta, Acorn Pooley, Mario Prats, Dave Coleman */ -#include -#include -#include #include #include +#include +#include +#include #include #include #include @@ -49,10 +49,10 @@ #else #include #endif -#include +#include #include +#include #include -#include namespace moveit { diff --git a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp index 0172c80556..c077866aa4 100644 --- a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp +++ b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp @@ -60,9 +60,9 @@ #include #include -#include -#include #include +#include +#include namespace moveit_benchmarks { diff --git a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h index b7d805a1c7..4b4484ac3a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/pose_tracking.h @@ -39,11 +39,11 @@ #pragma once #include -#include #include #include -#include #include +#include +#include #if __has_include() #include #else From 7f1822bdee2b22dfe2652410da868aa9334bb9d7 Mon Sep 17 00:00:00 2001 From: Henry Moore Date: Fri, 17 Jun 2022 10:10:08 -0600 Subject: [PATCH 43/43] changing to cmath constants instead of boost constants --- .../src/kinematic_constraint.cpp | 22 ++++----- .../test/test_constraints.cpp | 4 +- .../test/test_orientation_constraints.cpp | 32 ++++++------- .../src/kinematics_metrics.cpp | 13 +++-- moveit_core/robot_model/CMakeLists.txt | 1 - .../robot_model/src/floating_joint_model.cpp | 11 ++--- .../robot_model/src/planar_joint_model.cpp | 48 +++++++++---------- .../robot_model/src/revolute_joint_model.cpp | 39 ++++++++------- moveit_core/robot_model/src/robot_model.cpp | 1 - moveit_core/robot_trajectory/CMakeLists.txt | 1 - .../robot_trajectory/src/robot_trajectory.cpp | 18 +++---- .../utils/src/robot_model_test_utils.cpp | 5 +- .../benchmarks/src/benchmark_execution.cpp | 4 +- .../benchmarks/src/BenchmarkExecutor.cpp | 4 +- moveit_ros/robot_interaction/CMakeLists.txt | 7 +-- .../robot_interaction/ConfigExtras.cmake | 3 -- .../src/interactive_marker_helpers.cpp | 7 ++- .../src/render_shapes.cpp | 6 +-- .../warehouse/src/initialize_demo_db.cpp | 4 +- 19 files changed, 105 insertions(+), 125 deletions(-) delete mode 100644 moveit_ros/robot_interaction/ConfigExtras.cmake diff --git a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp index a36d7038b4..35263f059b 100644 --- a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp +++ b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include #include @@ -51,6 +50,7 @@ #endif #include #include +#include #include #include @@ -64,11 +64,11 @@ static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematic_constr static double normalizeAngle(double angle) { - double v = fmod(angle, 2.0 * boost::math::constants::pi()); - if (v < -boost::math::constants::pi()) - v += 2.0 * boost::math::constants::pi(); - else if (v > boost::math::constants::pi()) - v -= 2.0 * boost::math::constants::pi(); + double v = fmod(angle, 2.0 * M_PI); + if (v < -M_PI) + v += 2.0 * M_PI; + else if (v > M_PI) + v -= 2.0 * M_PI; return v; } @@ -287,10 +287,10 @@ ConstraintEvaluationResult JointConstraint::decide(const moveit::core::RobotStat { dif = normalizeAngle(current_joint_position) - joint_position_; - if (dif > boost::math::constants::pi()) - dif = 2.0 * boost::math::constants::pi() - dif; - else if (dif < -boost::math::constants::pi()) - dif += 2.0 * boost::math::constants::pi(); // we include a sign change to have dif > 0 + if (dif > M_PI) + dif = 2.0 * M_PI - dif; + else if (dif < -M_PI) + dif += 2.0 * M_PI; // we include a sign change to have dif > 0 } else dif = current_joint_position - joint_position_; @@ -803,7 +803,7 @@ bool VisibilityConstraint::configure(const moveit_msgs::msg::VisibilityConstrain // compute the points on the base circle of the cone that make up the cone sides points_.clear(); - double delta = 2.0 * boost::math::constants::pi() / (double)cone_sides_; + double delta = 2.0 * M_PI / (double)cone_sides_; double a = 0.0; for (unsigned int i = 0; i < cone_sides_; ++i, a += delta) { diff --git a/moveit_core/kinematic_constraints/test/test_constraints.cpp b/moveit_core/kinematic_constraints/test/test_constraints.cpp index c0535f233c..8ee047a45c 100644 --- a/moveit_core/kinematic_constraints/test/test_constraints.cpp +++ b/moveit_core/kinematic_constraints/test/test_constraints.cpp @@ -43,8 +43,8 @@ #else #include #endif +#include #include -#include class LoadPlanningModelsPr2 : public testing::Test { @@ -659,7 +659,7 @@ TEST_F(LoadPlanningModelsPr2, OrientationConstraintsSimple) EXPECT_FALSE(oc.decide(robot_state).satisfied); // rotation by pi does not wrap to zero - jvals["r_wrist_roll_joint"] = boost::math::constants::pi(); + jvals["r_wrist_roll_joint"] = M_PI; robot_state.setVariablePositions(jvals); robot_state.update(); EXPECT_FALSE(oc.decide(robot_state).satisfied); diff --git a/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp b/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp index 2eac084246..5cd7c02923 100644 --- a/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp +++ b/moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp @@ -45,7 +45,7 @@ #include #include #endif -#include +#include #include @@ -202,24 +202,24 @@ TEST_F(SphericalRobot, Test2) moveit::core::RobotState robot_state(robot_model_); // Singularity: roll + yaw = theta // These violate either absolute_x_axis_tolerance or absolute_z_axis_tolerance - robot_state.setVariablePositions(getJointValues(0.15, boost::math::constants::half_pi(), 0.15)); + robot_state.setVariablePositions(getJointValues(0.15, M_PI_2, 0.15)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.21, boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.21, M_PI_2, 0.0)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.0, boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.0, M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); // Singularity: roll - yaw = theta // This's identical to -pi/2 pitch rotation - robot_state.setVariablePositions(getJointValues(0.15, -boost::math::constants::half_pi(), 0.15)); + robot_state.setVariablePositions(getJointValues(0.15, -M_PI_2, 0.15)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); @@ -248,12 +248,12 @@ TEST_F(SphericalRobot, Test3) // Singularity: roll + yaw = theta // These tests violate absolute_x_axis_tolerance - robot_state.setVariablePositions(getJointValues(0.21, boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.21, M_PI_2, 0.0)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.0, boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.0, M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); @@ -263,12 +263,12 @@ TEST_F(SphericalRobot, Test3) ocm.absolute_z_axis_tolerance = 0.2; // These tests violate absolute_z_axis_tolerance - robot_state.setVariablePositions(getJointValues(0.21, boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.21, M_PI_2, 0.0)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.0, boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.0, M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); @@ -296,12 +296,12 @@ TEST_F(SphericalRobot, Test4) // Singularity: roll + yaw = theta // These tests violate absolute_x_axis_tolerance - robot_state.setVariablePositions(getJointValues(0.21, -boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.21, -M_PI_2, 0.0)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.0, -boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.0, -M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); @@ -311,17 +311,17 @@ TEST_F(SphericalRobot, Test4) ocm.absolute_z_axis_tolerance = 0.2; // These tests violate absolute_z_axis_tolerance - robot_state.setVariablePositions(getJointValues(0.21, -boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.21, -M_PI_2, 0.0)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.0, -boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.0, -M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); - robot_state.setVariablePositions(getJointValues(0.5, -boost::math::constants::half_pi(), 0.21)); + robot_state.setVariablePositions(getJointValues(0.5, -M_PI_2, 0.21)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); EXPECT_FALSE(oc.decide(robot_state).satisfied); @@ -336,7 +336,7 @@ TEST_F(SphericalRobot, Test5) moveit_msgs::msg::OrientationConstraint ocm; moveit::core::RobotState robot_state(robot_model_); - robot_state.setVariablePositions(getJointValues(0.0, boost::math::constants::half_pi(), 0.0)); + robot_state.setVariablePositions(getJointValues(0.0, M_PI_2, 0.0)); robot_state.update(); ocm.link_name = "yaw"; @@ -347,7 +347,7 @@ TEST_F(SphericalRobot, Test5) ocm.absolute_z_axis_tolerance = 1.0; ocm.weight = 1.0; - robot_state.setVariablePositions(getJointValues(0.2, boost::math::constants::half_pi(), 0.3)); + robot_state.setVariablePositions(getJointValues(0.2, M_PI_2, 0.3)); robot_state.update(); EXPECT_TRUE(oc.configure(ocm, tf)); diff --git a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp index 4c482af055..a45829a177 100644 --- a/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp +++ b/moveit_core/kinematics_metrics/src/kinematics_metrics.cpp @@ -34,13 +34,13 @@ /* Author: Sachin Chitta */ -#include -#include -#include #include #include -#include #include +#include +#include +#include +#include namespace kinematics_metrics { @@ -68,9 +68,8 @@ double KinematicsMetrics::getJointLimitsPenalty(const moveit::core::RobotState& if (bounds[0].min_position_ == -std::numeric_limits::max() || bounds[0].max_position_ == std::numeric_limits::max() || bounds[1].min_position_ == -std::numeric_limits::max() || - bounds[1].max_position_ == std::numeric_limits::max() || - bounds[2].min_position_ == -boost::math::constants::pi() || - bounds[2].max_position_ == boost::math::constants::pi()) + bounds[1].max_position_ == std::numeric_limits::max() || bounds[2].min_position_ == -M_PI || + bounds[2].max_position_ == M_PI) continue; } if (joint_model->getType() == moveit::core::JointModel::FLOATING) diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index 1980af2635..05da550fd6 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -34,7 +34,6 @@ if(BUILD_TESTING) ament_add_gtest(test_robot_model test/test.cpp) ament_target_dependencies(test_robot_model rclcpp - Boost ) target_link_libraries(test_robot_model moveit_test_utils ${MOVEIT_LIB_NAME}) endif() diff --git a/moveit_core/robot_model/src/floating_joint_model.cpp b/moveit_core/robot_model/src/floating_joint_model.cpp index 8bbe43c654..f44a6e663f 100644 --- a/moveit_core/robot_model/src/floating_joint_model.cpp +++ b/moveit_core/robot_model/src/floating_joint_model.cpp @@ -35,13 +35,12 @@ /* Author: Ioan Sucan */ -#include +#include #include -#include +#include +#include #include #include -#include -#include namespace moveit { @@ -104,7 +103,7 @@ double FloatingJointModel::getMaximumExtent(const Bounds& other_bounds) const double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_; double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_; double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_; - return sqrt(dx * dx + dy * dy + dz * dz) + boost::math::constants::pi() * 0.5 * angular_distance_weight_; + return sqrt(dx * dx + dy * dy + dz * dz) + M_PI * 0.5 * angular_distance_weight_; } double FloatingJointModel::distance(const double* values1, const double* values2) const @@ -312,7 +311,7 @@ void FloatingJointModel::getVariableRandomPositionsNearBy(random_numbers::Random std::min(bounds[2].max_position_, near[2] + distance)); double da = angular_distance_weight_ * distance; - if (da >= .25 * boost::math::constants::pi()) + if (da >= .25 * M_PI) { double q[4]; rng.quaternion(q); diff --git a/moveit_core/robot_model/src/planar_joint_model.cpp b/moveit_core/robot_model/src/planar_joint_model.cpp index 46784b5ed3..8815c2fef3 100644 --- a/moveit_core/robot_model/src/planar_joint_model.cpp +++ b/moveit_core/robot_model/src/planar_joint_model.cpp @@ -35,12 +35,11 @@ /* Author: Ioan Sucan */ -#include -#include #include -#include -#include #include +#include +#include +#include namespace moveit { @@ -72,8 +71,8 @@ PlanarJointModel::PlanarJointModel(const std::string& name, size_t joint_index, variable_bounds_[0].max_position_ = std::numeric_limits::infinity(); variable_bounds_[1].min_position_ = -std::numeric_limits::infinity(); variable_bounds_[1].max_position_ = std::numeric_limits::infinity(); - variable_bounds_[2].min_position_ = -boost::math::constants::pi(); - variable_bounds_[2].max_position_ = boost::math::constants::pi(); + variable_bounds_[2].min_position_ = -M_PI; + variable_bounds_[2].max_position_ = M_PI; computeVariableBoundsMsg(); } @@ -87,7 +86,7 @@ double PlanarJointModel::getMaximumExtent(const Bounds& other_bounds) const { double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_; double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_; - return sqrt(dx * dx + dy * dy) + boost::math::constants::pi() * angular_distance_weight_; + return sqrt(dx * dx + dy * dy) + M_PI * angular_distance_weight_; } void PlanarJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const @@ -138,8 +137,8 @@ void PlanarJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNu double da = angular_distance_weight_ * distance; // limit the sampling range to 2pi to work correctly even if the distance is very large - if (da > boost::math::constants::pi()) - da = boost::math::constants::pi(); + if (da > M_PI) + da = M_PI; values[2] = rng.uniformReal(near[2] - da, near[2] + da); normalizeRotation(values); } @@ -162,8 +161,7 @@ void computeTurnDriveTurnGeometry(const double* from, const double* to, const do const double angle_straight_diff = std::hypot(dx, dy) > min_translational_distance ? angles::shortest_angular_distance(from[2], std::atan2(dy, dx)) : 0.0; - const double angle_backward_diff = - angles::normalize_angle(angle_straight_diff - boost::math::constants::pi()); + const double angle_backward_diff = angles::normalize_angle(angle_straight_diff - M_PI); const double move_straight_cost = std::abs(angle_straight_diff) + std::abs(angles::shortest_angular_distance(from[2] + angle_straight_diff, to[2])); const double move_backward_cost = @@ -190,20 +188,20 @@ void PlanarJointModel::interpolate(const double* from, const double* to, const d // interpolate angle double diff = to[2] - from[2]; - if (fabs(diff) <= boost::math::constants::pi()) + if (fabs(diff) <= M_PI) state[2] = from[2] + diff * t; else { if (diff > 0.0) - diff = 2.0 * boost::math::constants::pi() - diff; + diff = 2.0 * M_PI - diff; else - diff = -2.0 * boost::math::constants::pi() - diff; + diff = -2.0 * M_PI - diff; state[2] = from[2] - diff * t; // input states are within bounds, so the following check is sufficient - if (state[2] > boost::math::constants::pi()) - state[2] -= 2.0 * boost::math::constants::pi(); - else if (state[2] < -boost::math::constants::pi()) - state[2] += 2.0 * boost::math::constants::pi(); + if (state[2] > M_PI) + state[2] -= 2.0 * M_PI; + else if (state[2] < -M_PI) + state[2] += 2.0 * M_PI; } } else if (motion_model_ == DIFF_DRIVE) @@ -254,7 +252,7 @@ double PlanarJointModel::distance(const double* values1, const double* values2) double dy = values1[1] - values2[1]; double d = fabs(values1[2] - values2[2]); - d = (d > boost::math::constants::pi()) ? 2.0 * boost::math::constants::pi() - d : d; + d = (d > M_PI) ? 2.0 * M_PI - d : d; return sqrt(dx * dx + dy * dy) + angular_distance_weight_ * d; } else if (motion_model_ == DIFF_DRIVE) @@ -279,13 +277,13 @@ bool PlanarJointModel::satisfiesPositionBounds(const double* values, const Bound bool PlanarJointModel::normalizeRotation(double* values) const { double& v = values[2]; - if (v >= -boost::math::constants::pi() && v <= boost::math::constants::pi()) + if (v >= -M_PI && v <= M_PI) return false; - v = fmod(v, 2.0 * boost::math::constants::pi()); - if (v < -boost::math::constants::pi()) - v += 2.0 * boost::math::constants::pi(); - else if (v > boost::math::constants::pi()) - v -= 2.0 * boost::math::constants::pi(); + v = fmod(v, 2.0 * M_PI); + if (v < -M_PI) + v += 2.0 * M_PI; + else if (v > M_PI) + v -= 2.0 * M_PI; return true; } diff --git a/moveit_core/robot_model/src/revolute_joint_model.cpp b/moveit_core/robot_model/src/revolute_joint_model.cpp index bc0a8320ad..90fba07d90 100644 --- a/moveit_core/robot_model/src/revolute_joint_model.cpp +++ b/moveit_core/robot_model/src/revolute_joint_model.cpp @@ -37,7 +37,6 @@ #include #include -#include #include #include @@ -60,8 +59,8 @@ RevoluteJointModel::RevoluteJointModel(const std::string& name, size_t joint_ind variable_names_.push_back(getName()); variable_bounds_.resize(1); variable_bounds_[0].position_bounded_ = true; - variable_bounds_[0].min_position_ = -boost::math::constants::pi(); - variable_bounds_[0].max_position_ = boost::math::constants::pi(); + variable_bounds_[0].min_position_ = -M_PI; + variable_bounds_[0].max_position_ = M_PI; variable_index_map_[getName()] = 0; computeVariableBoundsMsg(); } @@ -88,8 +87,8 @@ void RevoluteJointModel::setContinuous(bool flag) if (flag) { variable_bounds_[0].position_bounded_ = false; - variable_bounds_[0].min_position_ = -boost::math::constants::pi(); - variable_bounds_[0].max_position_ = boost::math::constants::pi(); + variable_bounds_[0].min_position_ = -M_PI; + variable_bounds_[0].max_position_ = M_PI; } else variable_bounds_[0].position_bounded_ = true; @@ -135,20 +134,20 @@ void RevoluteJointModel::interpolate(const double* from, const double* to, const if (continuous_) { double diff = to[0] - from[0]; - if (fabs(diff) <= boost::math::constants::pi()) + if (fabs(diff) <= M_PI) state[0] = from[0] + diff * t; else { if (diff > 0.0) - diff = 2.0 * boost::math::constants::pi() - diff; + diff = 2.0 * M_PI - diff; else - diff = -2.0 * boost::math::constants::pi() - diff; + diff = -2.0 * M_PI - diff; state[0] = from[0] - diff * t; // input states are within bounds, so the following check is sufficient - if (state[0] > boost::math::constants::pi()) - state[0] -= 2.0 * boost::math::constants::pi(); - else if (state[0] < -boost::math::constants::pi()) - state[0] += 2.0 * boost::math::constants::pi(); + if (state[0] > M_PI) + state[0] -= 2.0 * M_PI; + else if (state[0] < -M_PI) + state[0] += 2.0 * M_PI; } } else @@ -159,8 +158,8 @@ double RevoluteJointModel::distance(const double* values1, const double* values2 { if (continuous_) { - double d = fmod(fabs(values1[0] - values2[0]), 2.0 * boost::math::constants::pi()); - return (d > boost::math::constants::pi()) ? 2.0 * boost::math::constants::pi() - d : d; + double d = fmod(fabs(values1[0] - values2[0]), 2.0 * M_PI); + return (d > M_PI) ? 2.0 * M_PI - d : d; } else return fabs(values1[0] - values2[0]); @@ -203,13 +202,13 @@ bool RevoluteJointModel::enforcePositionBounds(double* values, const Bounds& bou if (continuous_) { double& v = values[0]; - if (v <= -boost::math::constants::pi() || v > boost::math::constants::pi()) + if (v <= -M_PI || v > M_PI) { - v = fmod(v, 2.0 * boost::math::constants::pi()); - if (v <= -boost::math::constants::pi()) - v += 2.0 * boost::math::constants::pi(); - else if (v > boost::math::constants::pi()) - v -= 2.0 * boost::math::constants::pi(); + v = fmod(v, 2.0 * M_PI); + if (v <= -M_PI) + v += 2.0 * M_PI; + else if (v > M_PI) + v -= 2.0 * M_PI; return true; } } diff --git a/moveit_core/robot_model/src/robot_model.cpp b/moveit_core/robot_model/src/robot_model.cpp index 9c0ad5780f..fa22ee7389 100644 --- a/moveit_core/robot_model/src/robot_model.cpp +++ b/moveit_core/robot_model/src/robot_model.cpp @@ -37,7 +37,6 @@ #include #include -#include #include #include #include diff --git a/moveit_core/robot_trajectory/CMakeLists.txt b/moveit_core/robot_trajectory/CMakeLists.txt index b0c07c0896..03aaad5dc3 100644 --- a/moveit_core/robot_trajectory/CMakeLists.txt +++ b/moveit_core/robot_trajectory/CMakeLists.txt @@ -6,7 +6,6 @@ ament_target_dependencies(${MOVEIT_LIB_NAME} rclcpp urdfdom urdfdom_headers - Boost ) target_link_libraries(${MOVEIT_LIB_NAME} diff --git a/moveit_core/robot_trajectory/src/robot_trajectory.cpp b/moveit_core/robot_trajectory/src/robot_trajectory.cpp index fb1d19a570..8bd38e05c8 100644 --- a/moveit_core/robot_trajectory/src/robot_trajectory.cpp +++ b/moveit_core/robot_trajectory/src/robot_trajectory.cpp @@ -34,6 +34,7 @@ /* Author: Ioan Sucan, Adam Leeper */ +#include #include #include #include @@ -45,7 +46,6 @@ #else #include #endif -#include #include namespace robot_trajectory @@ -175,10 +175,10 @@ RobotTrajectory& RobotTrajectory::unwind() for (std::size_t j = 1; j < waypoints_.size(); ++j) { double current_value = waypoints_[j]->getJointPositions(cont_joint)[0]; - if (last_value > current_value + boost::math::constants::pi()) - running_offset += 2.0 * boost::math::constants::pi(); - else if (current_value > last_value + boost::math::constants::pi()) - running_offset -= 2.0 * boost::math::constants::pi(); + if (last_value > current_value + M_PI) + running_offset += 2.0 * M_PI; + else if (current_value > last_value + M_PI) + running_offset -= 2.0 * M_PI; last_value = current_value; if (running_offset > std::numeric_limits::epsilon() || @@ -223,10 +223,10 @@ RobotTrajectory& RobotTrajectory::unwind(const moveit::core::RobotState& state) for (std::size_t j = 1; j < waypoints_.size(); ++j) { double current_value = waypoints_[j]->getJointPositions(cont_joint)[0]; - if (last_value > current_value + boost::math::constants::pi()) - running_offset += 2.0 * boost::math::constants::pi(); - else if (current_value > last_value + boost::math::constants::pi()) - running_offset -= 2.0 * boost::math::constants::pi(); + if (last_value > current_value + M_PI) + running_offset += 2.0 * M_PI; + else if (current_value > last_value + M_PI) + running_offset -= 2.0 * M_PI; last_value = current_value; if (running_offset > std::numeric_limits::epsilon() || diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 4521525c64..8043329abc 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -35,7 +35,6 @@ /* Author: Bryce Willey */ #include -#include #include #include #include @@ -191,8 +190,8 @@ void RobotModelBuilder::addChain(const std::string& section, const std::string& if (joint->type == urdf::Joint::REVOLUTE || joint->type == urdf::Joint::PRISMATIC) { auto limits = std::make_shared(); - limits->lower = -boost::math::constants::pi(); - limits->upper = boost::math::constants::pi(); + limits->lower = -M_PI; + limits->upper = M_PI; joint->limits = limits; } diff --git a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp index c077866aa4..b32c0a5471 100644 --- a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp +++ b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp @@ -46,7 +46,6 @@ #include #include #include -#include #include #include @@ -59,6 +58,7 @@ #include #include +#include #include #include #include @@ -864,7 +864,7 @@ void moveit_benchmarks::BenchmarkExecution::collectMetrics(RunData& rundata, if (acosValue > -1.0 && acosValue < 1.0) { // the smoothness is actually the outside angle of the one we compute - double angle = (boost::math::constants::pi() - acos(acosValue)); + double angle = (M_PI - acos(acosValue)); // and we normalize by the length of the segments double u = 2.0 * angle; /// (a + b); diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index b9184d8125..dcf9df540b 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -50,8 +50,8 @@ #include #include #undef BOOST_ALLOW_DEPRECATED_HEADERS -#include #include +#include #include #include #ifndef _WIN32 @@ -935,7 +935,7 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, if (acos_value > -1.0 && acos_value < 1.0) { // the smoothness is actually the outside angle of the one we compute - double angle = (boost::math::constants::pi() - acos(acos_value)); + double angle = (M_PI - acos(acos_value)); // and we normalize by the length of the segments double u = 2.0 * angle; /// (a + b); diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index e70b425cd0..c3a8bb35ca 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -13,13 +13,10 @@ find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(rclcpp REQUIRED) -# Finds Boost Components -include(ConfigExtras.cmake) set(MOVEIT_LIB_NAME moveit_robot_interaction) set(THIS_PACKAGE_INCLUDE_DEPENDS - Boost moveit_ros_planning interactive_markers tf2_geometry_msgs @@ -45,8 +42,6 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(locked_robot_state_test test/locked_robot_state_test.cpp) target_link_libraries(locked_robot_state_test ${MOVEIT_LIB_NAME}) - ament_target_dependencies(locked_robot_state_test - Boost) endif() install( @@ -78,4 +73,4 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() -ament_package(CONFIG_EXTRAS ConfigExtras.cmake) +ament_package() diff --git a/moveit_ros/robot_interaction/ConfigExtras.cmake b/moveit_ros/robot_interaction/ConfigExtras.cmake deleted file mode 100644 index 837e37df5e..0000000000 --- a/moveit_ros/robot_interaction/ConfigExtras.cmake +++ /dev/null @@ -1,3 +0,0 @@ -# Extras module needed for dependencies to find boost components - -find_package(Boost REQUIRED thread) diff --git a/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp b/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp index 5b39aab24b..98041c461b 100644 --- a/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp +++ b/moveit_ros/robot_interaction/src/interactive_marker_helpers.cpp @@ -34,6 +34,7 @@ /* Author: Ioan Sucan, Acorn Pooley, Adam Leeper */ +#include #include #include #if __has_include() @@ -42,8 +43,6 @@ #include #endif -#include - namespace robot_interaction { visualization_msgs::msg::InteractiveMarker @@ -73,7 +72,7 @@ void addTArrowMarker(visualization_msgs::msg::InteractiveMarker& im) // Arrow points along Z tf2::Quaternion imq, tmq; tf2::fromMsg(m.pose.orientation, imq); - tmq.setRPY(0, -boost::math::constants::pi() / 2.0, 0); + tmq.setRPY(0, -M_PI / 2.0, 0); imq = imq * tmq; m.pose.orientation = tf2::toMsg(imq); m.color.r = 0.0f; @@ -93,7 +92,7 @@ void addTArrowMarker(visualization_msgs::msg::InteractiveMarker& im) mc.pose = im.pose; // Cylinder points along Y tf2::fromMsg(mc.pose.orientation, imq); - tmq.setRPY(boost::math::constants::pi() / 2.0, 0, 0); + tmq.setRPY(M_PI / 2.0, 0, 0); imq = imq * tmq; mc.pose.orientation = tf2::toMsg(imq); mc.pose.position.x -= 0.04; diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp index 45029d5724..379d468f8e 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp @@ -48,8 +48,7 @@ #include #include -#include - +#include #include #include @@ -179,8 +178,7 @@ void RenderShapes::renderShape(Ogre::SceneNode* node, const shapes::Shape* s, co { // in geometric shapes, the z axis of the cylinder is its height; // for the rviz shape, the y axis is the height; we add a transform to fix this - static Ogre::Quaternion fix(Ogre::Radian(boost::math::constants::pi() / 2.0), - Ogre::Vector3(1.0, 0.0, 0.0)); + static Ogre::Quaternion fix(Ogre::Radian(M_PI / 2.0), Ogre::Vector3(1.0, 0.0, 0.0)); orientation = orientation * fix; } diff --git a/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp b/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp index a3bfdedeba..3123e48428 100644 --- a/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp +++ b/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp @@ -34,6 +34,7 @@ /* Author: Ioan Sucan */ +#include #include #include #include @@ -45,7 +46,6 @@ #include #include #include -#include #include #include #include @@ -132,7 +132,7 @@ int main(int argc, char** argv) ocm.orientation.w = 1.0; ocm.absolute_x_axis_tolerance = 0.1; ocm.absolute_y_axis_tolerance = 0.1; - ocm.absolute_z_axis_tolerance = boost::math::constants::pi(); + ocm.absolute_z_axis_tolerance = M_PI; ocm.weight = 1.0; moveit_msgs::msg::Constraints cmsg; cmsg.orientation_constraints.resize(1, ocm);